From 0cef943b16e660f24024bde795b42c7b54e1139e Mon Sep 17 00:00:00 2001 From: Vladyslav Usenko Date: Sun, 14 Apr 2019 21:07:42 +0200 Subject: [PATCH] Initial commit --- .clang-format | 6 + .gitignore | 7 + .gitlab-ci.yml | 76 + .gitmodules | 21 + CMakeLists.txt | 210 +++ LICENSE | 29 + README.md | 62 + cmake_modules/FindEigen3.cmake | 83 + cmake_modules/FindOpenGV.cmake | 85 + cmake_modules/FindTBB.cmake | 283 +++ data/euroc_config.json | 30 + data/euroc_ds_calib.json | 213 +++ data/euroc_eucm_calib.json | 213 +++ data/tumvi_512_config.json | 30 + data/tumvi_512_ds_calib.json | 381 ++++ data/tumvi_512_eucm_calib.json | 381 ++++ doc/Calibration.md | 117 ++ doc/Simulation.md | 50 + doc/VioMapping.md | 86 + doc/img/MH_05_MAPPING.png | Bin 0 -> 416348 bytes doc/img/MH_05_OPT_FLOW.png | Bin 0 -> 555738 bytes doc/img/MH_05_VIO.png | Bin 0 -> 342089 bytes doc/img/SIM_MAPPER.png | Bin 0 -> 47281 bytes doc/img/SIM_VIO.png | Bin 0 -> 143023 bytes doc/img/euroc_cam_calib.png | Bin 0 -> 423200 bytes doc/img/euroc_imu_calib.png | Bin 0 -> 615342 bytes doc/img/teaser.png | Bin 0 -> 275281 bytes doc/img/tumvi_cam_calib.png | Bin 0 -> 374119 bytes doc/img/tumvi_imu_calib.png | Bin 0 -> 410254 bytes docker/b_image/Dockerfile | 3 + docker/b_image_xenial/Dockerfile | 17 + include/basalt/calibration/aprilgrid.h | 137 ++ .../basalt/calibration/calibration_helper.h | 116 ++ include/basalt/calibration/cam_calib.h | 165 ++ include/basalt/calibration/cam_imu_calib.h | 180 ++ include/basalt/calibration/vignette.h | 87 + include/basalt/io/dataset_io.h | 247 +++ include/basalt/io/dataset_io_euroc.h | 248 +++ include/basalt/io/dataset_io_rosbag.h | 375 ++++ include/basalt/io/marg_data_io.h | 76 + .../frame_to_frame_optical_flow.h | 382 ++++ include/basalt/optical_flow/optical_flow.h | 85 + include/basalt/optical_flow/patch.h | 177 ++ .../basalt/optical_flow/patch_optical_flow.h | 376 ++++ include/basalt/optical_flow/patterns.h | 171 ++ include/basalt/optimization/accumulator.h | 336 ++++ include/basalt/optimization/linearize.h | 187 ++ include/basalt/optimization/poses_linearize.h | 180 ++ include/basalt/optimization/poses_optimize.h | 259 +++ .../basalt/optimization/spline_linearize.h | 635 +++++++ include/basalt/optimization/spline_optimize.h | 488 ++++++ include/basalt/utils/common_types.h | 254 +++ include/basalt/utils/image.h | 711 ++++++++ include/basalt/utils/imu_types.h | 270 +++ include/basalt/utils/keypoints.h | 111 ++ include/basalt/utils/nfr.h | 120 ++ include/basalt/utils/sim_utils.h | 55 + include/basalt/utils/system_utils.h | 52 + include/basalt/utils/test_utils.h | 77 + include/basalt/utils/tracks.h | 225 +++ include/basalt/utils/union_find.h | 94 + include/basalt/utils/vio_config.h | 75 + include/basalt/utils/vis_utils.h | 106 ++ include/basalt/vi_estimator/ba_base.h | 372 ++++ include/basalt/vi_estimator/keypoint_vio.h | 229 +++ include/basalt/vi_estimator/nfr_mapper.h | 218 +++ include/basalt/vi_estimator/vio_estimator.h | 102 ++ scripts/eval_full/gen_results.py | 39 + scripts/eval_full/run_evaluations.sh | 26 + scripts/install_deps.sh | 9 + scripts/install_mac_os_deps.sh | 4 + scripts/install_ubuntu_deps.sh | 4 + scripts/update_submodules.sh | 7 + src/calibrate.cpp | 82 + src/calibrate_imu.cpp | 94 + src/calibration/calibraiton_helper.cpp | 361 ++++ src/calibration/cam_calib.cpp | 798 +++++++++ src/calibration/cam_imu_calib.cpp | 1054 +++++++++++ src/calibration/vignette.cpp | 306 ++++ src/io/dataset_io.cpp | 57 + src/io/marg_data_io.cpp | 228 +++ src/mapper.cpp | 647 +++++++ src/mapper_sim.cpp | 595 +++++++ src/mapper_sim_naive.cpp | 751 ++++++++ src/opt_flow.cpp | 342 ++++ src/optical_flow/optical_flow.cpp | 101 ++ src/utils/keypoints.cpp | 420 +++++ src/utils/vio_config.cpp | 130 ++ src/vi_estimator/ba_base.cpp | 525 ++++++ src/vi_estimator/keypoint_vio.cpp | 1054 +++++++++++ src/vi_estimator/keypoint_vio_linearize.cpp | 266 +++ src/vi_estimator/nfr_mapper.cpp | 675 +++++++ src/vi_estimator/vio_estimator.cpp | 153 ++ src/vio.cpp | 682 ++++++++ src/vio_sim.cpp | 900 ++++++++++ test/CMakeLists.txt | 31 + test/src/test_image.cpp | 127 ++ test/src/test_nfr.cpp | 137 ++ test/src/test_spline_opt.cpp | 109 ++ test/src/test_vio.cpp | 408 +++++ thirdparty/CLI11 | 1 + thirdparty/DBoW3/CMakeLists.txt | 15 + thirdparty/DBoW3/LICENSE.txt | 44 + thirdparty/DBoW3/README.txt | 7 + thirdparty/DBoW3/src/BowVector.cpp | 136 ++ thirdparty/DBoW3/src/BowVector.h | 117 ++ thirdparty/DBoW3/src/CMakeLists.txt | 20 + thirdparty/DBoW3/src/DBoW3.h | 68 + thirdparty/DBoW3/src/Database.cpp | 855 +++++++++ thirdparty/DBoW3/src/Database.h | 354 ++++ thirdparty/DBoW3/src/DescManip.cpp | 239 +++ thirdparty/DBoW3/src/DescManip.h | 99 ++ thirdparty/DBoW3/src/FeatureVector.cpp | 85 + thirdparty/DBoW3/src/FeatureVector.h | 55 + thirdparty/DBoW3/src/QueryResults.cpp | 63 + thirdparty/DBoW3/src/QueryResults.h | 205 +++ thirdparty/DBoW3/src/ScoringObject.cpp | 315 ++++ thirdparty/DBoW3/src/ScoringObject.h | 95 + thirdparty/DBoW3/src/Vocabulary.cpp | 1558 +++++++++++++++++ thirdparty/DBoW3/src/Vocabulary.h | 468 +++++ thirdparty/DBoW3/src/exports.h | 51 + thirdparty/DBoW3/src/quicklz.c | 848 +++++++++ thirdparty/DBoW3/src/quicklz.h | 150 ++ thirdparty/DBoW3/src/timers.h | 159 ++ thirdparty/Pangolin | 1 + thirdparty/apriltag/CMakeLists.txt | 25 + .../apriltag/ethz_apriltag2/CMakeLists.txt | 35 + thirdparty/apriltag/ethz_apriltag2/LICENSE | 34 + .../ethz_apriltag2/include/apriltags/Edge.h | 59 + .../include/apriltags/FloatImage.h | 61 + .../include/apriltags/GLine2D.h | 74 + .../include/apriltags/GLineSegment2D.h | 31 + .../include/apriltags/Gaussian.h | 37 + .../include/apriltags/GrayModel.h | 46 + .../include/apriltags/Gridder.h | 180 ++ .../include/apriltags/Homography33.h | 77 + .../include/apriltags/MathUtil.h | 69 + .../ethz_apriltag2/include/apriltags/Quad.h | 72 + .../include/apriltags/Segment.h | 56 + .../include/apriltags/Tag16h5.h | 41 + .../include/apriltags/Tag16h5_other.h | 17 + .../include/apriltags/Tag25h7.h | 51 + .../include/apriltags/Tag25h9.h | 52 + .../include/apriltags/Tag36h11.h | 64 + .../include/apriltags/Tag36h11_other.h | 88 + .../include/apriltags/Tag36h9.h | 63 + .../include/apriltags/TagDetection.h | 99 ++ .../include/apriltags/TagDetector.h | 29 + .../include/apriltags/TagFamily.h | 106 ++ .../include/apriltags/UnionFindSimple.h | 41 + .../include/apriltags/XYWeight.h | 19 + .../ethz_apriltag2/include/apriltags/pch.h | 17 + .../apriltag/ethz_apriltag2/package.xml | 13 + .../apriltag/ethz_apriltag2/src/Edge.cc | 119 ++ .../apriltag/ethz_apriltag2/src/FloatImage.cc | 77 + .../apriltag/ethz_apriltag2/src/GLine2D.cc | 109 ++ .../ethz_apriltag2/src/GLineSegment2D.cc | 26 + .../apriltag/ethz_apriltag2/src/Gaussian.cc | 71 + .../apriltag/ethz_apriltag2/src/GrayModel.cc | 81 + .../ethz_apriltag2/src/Homography33.cc | 216 +++ .../apriltag/ethz_apriltag2/src/MathUtil.cc | 11 + .../apriltag/ethz_apriltag2/src/Quad.cc | 159 ++ .../apriltag/ethz_apriltag2/src/Segment.cc | 21 + .../ethz_apriltag2/src/TagDetection.cc | 161 ++ .../ethz_apriltag2/src/TagDetector.cc | 613 +++++++ .../apriltag/ethz_apriltag2/src/TagFamily.cc | 138 ++ .../ethz_apriltag2/src/UnionFindSimple.cc | 54 + .../ethz_apriltag2/src/example/CMakeLists.txt | 9 + .../ethz_apriltag2/src/example/Serial.cpp | 113 ++ .../ethz_apriltag2/src/example/Serial.h | 41 + .../src/example/apriltags_demo.cpp | 453 +++++ .../src/example/arduino_tags/arduino_tags.ino | 40 + .../ethz_apriltag2/src/example/imu.cpp | 64 + .../apriltag/include/basalt/utils/apriltag.h | 30 + thirdparty/apriltag/src/apriltag.cpp | 249 +++ thirdparty/basalt-headers | 1 + thirdparty/opengv | 1 + thirdparty/ros/CMakeLists.txt | 33 + thirdparty/ros/console_bridge | 1 + .../ros/include/console_bridge_export.h | 41 + thirdparty/ros/include/geometry_msgs/Accel.h | 214 +++ .../ros/include/geometry_msgs/AccelStamped.h | 238 +++ .../geometry_msgs/AccelWithCovariance.h | 230 +++ .../AccelWithCovarianceStamped.h | 250 +++ .../ros/include/geometry_msgs/Inertia.h | 273 +++ .../include/geometry_msgs/InertiaStamped.h | 250 +++ thirdparty/ros/include/geometry_msgs/Point.h | 206 +++ .../ros/include/geometry_msgs/Point32.h | 213 +++ .../ros/include/geometry_msgs/PointStamped.h | 226 +++ .../ros/include/geometry_msgs/Polygon.h | 209 +++ .../include/geometry_msgs/PolygonStamped.h | 238 +++ thirdparty/ros/include/geometry_msgs/Pose.h | 217 +++ thirdparty/ros/include/geometry_msgs/Pose2D.h | 207 +++ .../ros/include/geometry_msgs/PoseArray.h | 248 +++ .../ros/include/geometry_msgs/PoseStamped.h | 241 +++ .../geometry_msgs/PoseWithCovariance.h | 233 +++ .../geometry_msgs/PoseWithCovarianceStamped.h | 254 +++ .../ros/include/geometry_msgs/Quaternion.h | 216 +++ .../include/geometry_msgs/QuaternionStamped.h | 229 +++ .../ros/include/geometry_msgs/Transform.h | 223 +++ .../include/geometry_msgs/TransformStamped.h | 262 +++ thirdparty/ros/include/geometry_msgs/Twist.h | 214 +++ .../ros/include/geometry_msgs/TwistStamped.h | 238 +++ .../geometry_msgs/TwistWithCovariance.h | 230 +++ .../TwistWithCovarianceStamped.h | 250 +++ .../ros/include/geometry_msgs/Vector3.h | 212 +++ .../include/geometry_msgs/Vector3Stamped.h | 232 +++ thirdparty/ros/include/geometry_msgs/Wrench.h | 215 +++ .../ros/include/geometry_msgs/WrenchStamped.h | 239 +++ .../ros/include/sensor_msgs/BatteryState.h | 428 +++++ .../ros/include/sensor_msgs/CameraInfo.h | 467 +++++ .../ros/include/sensor_msgs/ChannelFloat32.h | 222 +++ .../ros/include/sensor_msgs/CompressedImage.h | 239 +++ .../ros/include/sensor_msgs/FluidPressure.h | 233 +++ .../ros/include/sensor_msgs/Illuminance.h | 242 +++ thirdparty/ros/include/sensor_msgs/Image.h | 285 +++ thirdparty/ros/include/sensor_msgs/Imu.h | 328 ++++ .../ros/include/sensor_msgs/JointState.h | 280 +++ thirdparty/ros/include/sensor_msgs/Joy.h | 234 +++ .../ros/include/sensor_msgs/JoyFeedback.h | 228 +++ .../include/sensor_msgs/JoyFeedbackArray.h | 212 +++ .../ros/include/sensor_msgs/LaserEcho.h | 195 +++ .../ros/include/sensor_msgs/LaserScan.h | 315 ++++ .../ros/include/sensor_msgs/MagneticField.h | 264 +++ .../include/sensor_msgs/MultiDOFJointState.h | 330 ++++ .../include/sensor_msgs/MultiEchoLaserScan.h | 330 ++++ .../ros/include/sensor_msgs/NavSatFix.h | 347 ++++ .../ros/include/sensor_msgs/NavSatStatus.h | 242 +++ .../ros/include/sensor_msgs/PointCloud.h | 290 +++ .../ros/include/sensor_msgs/PointCloud2.h | 326 ++++ .../ros/include/sensor_msgs/PointField.h | 251 +++ thirdparty/ros/include/sensor_msgs/Range.h | 293 ++++ .../include/sensor_msgs/RegionOfInterest.h | 237 +++ .../include/sensor_msgs/RelativeHumidity.h | 233 +++ .../ros/include/sensor_msgs/SetCameraInfo.h | 123 ++ .../sensor_msgs/SetCameraInfoRequest.h | 371 ++++ .../sensor_msgs/SetCameraInfoResponse.h | 197 +++ .../ros/include/sensor_msgs/Temperature.h | 229 +++ .../ros/include/sensor_msgs/TimeReference.h | 229 +++ .../include/sensor_msgs/distortion_models.h | 50 + .../ros/include/sensor_msgs/fill_image.h | 70 + .../ros/include/sensor_msgs/image_encodings.h | 232 +++ .../sensor_msgs/point_cloud2_iterator.h | 302 ++++ .../sensor_msgs/point_cloud_conversion.h | 169 ++ .../sensor_msgs/point_field_conversion.h | 178 ++ thirdparty/ros/include/std_msgs/Bool.h | 187 ++ thirdparty/ros/include/std_msgs/Byte.h | 187 ++ .../ros/include/std_msgs/ByteMultiArray.h | 241 +++ thirdparty/ros/include/std_msgs/Char.h | 187 ++ thirdparty/ros/include/std_msgs/ColorRGBA.h | 214 +++ thirdparty/ros/include/std_msgs/Duration.h | 187 ++ thirdparty/ros/include/std_msgs/Empty.h | 179 ++ thirdparty/ros/include/std_msgs/Float32.h | 187 ++ .../ros/include/std_msgs/Float32MultiArray.h | 241 +++ thirdparty/ros/include/std_msgs/Float64.h | 187 ++ .../ros/include/std_msgs/Float64MultiArray.h | 241 +++ thirdparty/ros/include/std_msgs/Header.h | 217 +++ thirdparty/ros/include/std_msgs/Int16.h | 187 ++ .../ros/include/std_msgs/Int16MultiArray.h | 241 +++ thirdparty/ros/include/std_msgs/Int32.h | 187 ++ .../ros/include/std_msgs/Int32MultiArray.h | 241 +++ thirdparty/ros/include/std_msgs/Int64.h | 187 ++ .../ros/include/std_msgs/Int64MultiArray.h | 241 +++ thirdparty/ros/include/std_msgs/Int8.h | 187 ++ .../ros/include/std_msgs/Int8MultiArray.h | 241 +++ .../include/std_msgs/MultiArrayDimension.h | 205 +++ .../ros/include/std_msgs/MultiArrayLayout.h | 233 +++ thirdparty/ros/include/std_msgs/String.h | 187 ++ thirdparty/ros/include/std_msgs/Time.h | 187 ++ thirdparty/ros/include/std_msgs/UInt16.h | 187 ++ .../ros/include/std_msgs/UInt16MultiArray.h | 241 +++ thirdparty/ros/include/std_msgs/UInt32.h | 187 ++ .../ros/include/std_msgs/UInt32MultiArray.h | 241 +++ thirdparty/ros/include/std_msgs/UInt64.h | 187 ++ .../ros/include/std_msgs/UInt64MultiArray.h | 241 +++ thirdparty/ros/include/std_msgs/UInt8.h | 187 ++ .../ros/include/std_msgs/UInt8MultiArray.h | 241 +++ .../ros/include/std_msgs/builtin_bool.h | 36 + .../ros/include/std_msgs/builtin_double.h | 36 + .../ros/include/std_msgs/builtin_float.h | 36 + .../ros/include/std_msgs/builtin_int16.h | 36 + .../ros/include/std_msgs/builtin_int32.h | 36 + .../ros/include/std_msgs/builtin_int64.h | 36 + .../ros/include/std_msgs/builtin_int8.h | 36 + .../ros/include/std_msgs/builtin_string.h | 86 + .../ros/include/std_msgs/builtin_uint16.h | 36 + .../ros/include/std_msgs/builtin_uint32.h | 36 + .../ros/include/std_msgs/builtin_uint64.h | 36 + .../ros/include/std_msgs/builtin_uint8.h | 36 + .../include/std_msgs/header_deprecated_def.h | 249 +++ .../ros/include/std_msgs/trait_macros.h | 80 + thirdparty/ros/ros_comm | 1 + thirdparty/ros/roscpp_core | 1 + 293 files changed, 55391 insertions(+) create mode 100644 .clang-format create mode 100644 .gitignore create mode 100644 .gitlab-ci.yml create mode 100644 .gitmodules create mode 100644 CMakeLists.txt create mode 100644 LICENSE create mode 100644 README.md create mode 100644 cmake_modules/FindEigen3.cmake create mode 100644 cmake_modules/FindOpenGV.cmake create mode 100644 cmake_modules/FindTBB.cmake create mode 100644 data/euroc_config.json create mode 100644 data/euroc_ds_calib.json create mode 100644 data/euroc_eucm_calib.json create mode 100644 data/tumvi_512_config.json create mode 100644 data/tumvi_512_ds_calib.json create mode 100644 data/tumvi_512_eucm_calib.json create mode 100644 doc/Calibration.md create mode 100644 doc/Simulation.md create mode 100644 doc/VioMapping.md create mode 100644 doc/img/MH_05_MAPPING.png create mode 100644 doc/img/MH_05_OPT_FLOW.png create mode 100644 doc/img/MH_05_VIO.png create mode 100644 doc/img/SIM_MAPPER.png create mode 100644 doc/img/SIM_VIO.png create mode 100644 doc/img/euroc_cam_calib.png create mode 100644 doc/img/euroc_imu_calib.png create mode 100644 doc/img/teaser.png create mode 100644 doc/img/tumvi_cam_calib.png create mode 100644 doc/img/tumvi_imu_calib.png create mode 100644 docker/b_image/Dockerfile create mode 100644 docker/b_image_xenial/Dockerfile create mode 100644 include/basalt/calibration/aprilgrid.h create mode 100644 include/basalt/calibration/calibration_helper.h create mode 100644 include/basalt/calibration/cam_calib.h create mode 100644 include/basalt/calibration/cam_imu_calib.h create mode 100644 include/basalt/calibration/vignette.h create mode 100644 include/basalt/io/dataset_io.h create mode 100644 include/basalt/io/dataset_io_euroc.h create mode 100644 include/basalt/io/dataset_io_rosbag.h create mode 100644 include/basalt/io/marg_data_io.h create mode 100644 include/basalt/optical_flow/frame_to_frame_optical_flow.h create mode 100644 include/basalt/optical_flow/optical_flow.h create mode 100644 include/basalt/optical_flow/patch.h create mode 100644 include/basalt/optical_flow/patch_optical_flow.h create mode 100644 include/basalt/optical_flow/patterns.h create mode 100644 include/basalt/optimization/accumulator.h create mode 100644 include/basalt/optimization/linearize.h create mode 100644 include/basalt/optimization/poses_linearize.h create mode 100644 include/basalt/optimization/poses_optimize.h create mode 100644 include/basalt/optimization/spline_linearize.h create mode 100644 include/basalt/optimization/spline_optimize.h create mode 100644 include/basalt/utils/common_types.h create mode 100644 include/basalt/utils/image.h create mode 100644 include/basalt/utils/imu_types.h create mode 100644 include/basalt/utils/keypoints.h create mode 100644 include/basalt/utils/nfr.h create mode 100644 include/basalt/utils/sim_utils.h create mode 100644 include/basalt/utils/system_utils.h create mode 100644 include/basalt/utils/test_utils.h create mode 100644 include/basalt/utils/tracks.h create mode 100644 include/basalt/utils/union_find.h create mode 100644 include/basalt/utils/vio_config.h create mode 100644 include/basalt/utils/vis_utils.h create mode 100644 include/basalt/vi_estimator/ba_base.h create mode 100644 include/basalt/vi_estimator/keypoint_vio.h create mode 100644 include/basalt/vi_estimator/nfr_mapper.h create mode 100644 include/basalt/vi_estimator/vio_estimator.h create mode 100755 scripts/eval_full/gen_results.py create mode 100755 scripts/eval_full/run_evaluations.sh create mode 100755 scripts/install_deps.sh create mode 100755 scripts/install_mac_os_deps.sh create mode 100755 scripts/install_ubuntu_deps.sh create mode 100755 scripts/update_submodules.sh create mode 100644 src/calibrate.cpp create mode 100644 src/calibrate_imu.cpp create mode 100644 src/calibration/calibraiton_helper.cpp create mode 100644 src/calibration/cam_calib.cpp create mode 100644 src/calibration/cam_imu_calib.cpp create mode 100644 src/calibration/vignette.cpp create mode 100644 src/io/dataset_io.cpp create mode 100644 src/io/marg_data_io.cpp create mode 100644 src/mapper.cpp create mode 100644 src/mapper_sim.cpp create mode 100644 src/mapper_sim_naive.cpp create mode 100644 src/opt_flow.cpp create mode 100644 src/optical_flow/optical_flow.cpp create mode 100644 src/utils/keypoints.cpp create mode 100644 src/utils/vio_config.cpp create mode 100644 src/vi_estimator/ba_base.cpp create mode 100644 src/vi_estimator/keypoint_vio.cpp create mode 100644 src/vi_estimator/keypoint_vio_linearize.cpp create mode 100644 src/vi_estimator/nfr_mapper.cpp create mode 100644 src/vi_estimator/vio_estimator.cpp create mode 100644 src/vio.cpp create mode 100644 src/vio_sim.cpp create mode 100644 test/CMakeLists.txt create mode 100644 test/src/test_image.cpp create mode 100644 test/src/test_nfr.cpp create mode 100644 test/src/test_spline_opt.cpp create mode 100644 test/src/test_vio.cpp create mode 160000 thirdparty/CLI11 create mode 100644 thirdparty/DBoW3/CMakeLists.txt create mode 100644 thirdparty/DBoW3/LICENSE.txt create mode 100644 thirdparty/DBoW3/README.txt create mode 100644 thirdparty/DBoW3/src/BowVector.cpp create mode 100644 thirdparty/DBoW3/src/BowVector.h create mode 100644 thirdparty/DBoW3/src/CMakeLists.txt create mode 100644 thirdparty/DBoW3/src/DBoW3.h create mode 100644 thirdparty/DBoW3/src/Database.cpp create mode 100644 thirdparty/DBoW3/src/Database.h create mode 100644 thirdparty/DBoW3/src/DescManip.cpp create mode 100644 thirdparty/DBoW3/src/DescManip.h create mode 100644 thirdparty/DBoW3/src/FeatureVector.cpp create mode 100644 thirdparty/DBoW3/src/FeatureVector.h create mode 100644 thirdparty/DBoW3/src/QueryResults.cpp create mode 100644 thirdparty/DBoW3/src/QueryResults.h create mode 100644 thirdparty/DBoW3/src/ScoringObject.cpp create mode 100644 thirdparty/DBoW3/src/ScoringObject.h create mode 100644 thirdparty/DBoW3/src/Vocabulary.cpp create mode 100644 thirdparty/DBoW3/src/Vocabulary.h create mode 100644 thirdparty/DBoW3/src/exports.h create mode 100644 thirdparty/DBoW3/src/quicklz.c create mode 100644 thirdparty/DBoW3/src/quicklz.h create mode 100644 thirdparty/DBoW3/src/timers.h create mode 160000 thirdparty/Pangolin create mode 100644 thirdparty/apriltag/CMakeLists.txt create mode 100644 thirdparty/apriltag/ethz_apriltag2/CMakeLists.txt create mode 100644 thirdparty/apriltag/ethz_apriltag2/LICENSE create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Edge.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/FloatImage.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/GLine2D.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/GLineSegment2D.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Gaussian.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/GrayModel.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Gridder.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Homography33.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/MathUtil.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Quad.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Segment.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag16h5.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag16h5_other.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag25h7.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag25h9.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h11.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h11_other.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h9.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/TagDetection.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/TagDetector.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/TagFamily.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/UnionFindSimple.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/XYWeight.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/include/apriltags/pch.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/package.xml create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/Edge.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/FloatImage.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/GLine2D.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/GLineSegment2D.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/Gaussian.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/GrayModel.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/Homography33.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/MathUtil.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/Quad.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/Segment.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/TagDetection.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/TagDetector.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/TagFamily.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/UnionFindSimple.cc create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/example/CMakeLists.txt create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/example/Serial.cpp create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/example/Serial.h create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/example/apriltags_demo.cpp create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/example/arduino_tags/arduino_tags.ino create mode 100644 thirdparty/apriltag/ethz_apriltag2/src/example/imu.cpp create mode 100644 thirdparty/apriltag/include/basalt/utils/apriltag.h create mode 100644 thirdparty/apriltag/src/apriltag.cpp create mode 160000 thirdparty/basalt-headers create mode 160000 thirdparty/opengv create mode 100644 thirdparty/ros/CMakeLists.txt create mode 160000 thirdparty/ros/console_bridge create mode 100644 thirdparty/ros/include/console_bridge_export.h create mode 100644 thirdparty/ros/include/geometry_msgs/Accel.h create mode 100644 thirdparty/ros/include/geometry_msgs/AccelStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/AccelWithCovariance.h create mode 100644 thirdparty/ros/include/geometry_msgs/AccelWithCovarianceStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/Inertia.h create mode 100644 thirdparty/ros/include/geometry_msgs/InertiaStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/Point.h create mode 100644 thirdparty/ros/include/geometry_msgs/Point32.h create mode 100644 thirdparty/ros/include/geometry_msgs/PointStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/Polygon.h create mode 100644 thirdparty/ros/include/geometry_msgs/PolygonStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/Pose.h create mode 100644 thirdparty/ros/include/geometry_msgs/Pose2D.h create mode 100644 thirdparty/ros/include/geometry_msgs/PoseArray.h create mode 100644 thirdparty/ros/include/geometry_msgs/PoseStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/PoseWithCovariance.h create mode 100644 thirdparty/ros/include/geometry_msgs/PoseWithCovarianceStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/Quaternion.h create mode 100644 thirdparty/ros/include/geometry_msgs/QuaternionStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/Transform.h create mode 100644 thirdparty/ros/include/geometry_msgs/TransformStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/Twist.h create mode 100644 thirdparty/ros/include/geometry_msgs/TwistStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/TwistWithCovariance.h create mode 100644 thirdparty/ros/include/geometry_msgs/TwistWithCovarianceStamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/Vector3.h create mode 100644 thirdparty/ros/include/geometry_msgs/Vector3Stamped.h create mode 100644 thirdparty/ros/include/geometry_msgs/Wrench.h create mode 100644 thirdparty/ros/include/geometry_msgs/WrenchStamped.h create mode 100644 thirdparty/ros/include/sensor_msgs/BatteryState.h create mode 100644 thirdparty/ros/include/sensor_msgs/CameraInfo.h create mode 100644 thirdparty/ros/include/sensor_msgs/ChannelFloat32.h create mode 100644 thirdparty/ros/include/sensor_msgs/CompressedImage.h create mode 100644 thirdparty/ros/include/sensor_msgs/FluidPressure.h create mode 100644 thirdparty/ros/include/sensor_msgs/Illuminance.h create mode 100644 thirdparty/ros/include/sensor_msgs/Image.h create mode 100644 thirdparty/ros/include/sensor_msgs/Imu.h create mode 100644 thirdparty/ros/include/sensor_msgs/JointState.h create mode 100644 thirdparty/ros/include/sensor_msgs/Joy.h create mode 100644 thirdparty/ros/include/sensor_msgs/JoyFeedback.h create mode 100644 thirdparty/ros/include/sensor_msgs/JoyFeedbackArray.h create mode 100644 thirdparty/ros/include/sensor_msgs/LaserEcho.h create mode 100644 thirdparty/ros/include/sensor_msgs/LaserScan.h create mode 100644 thirdparty/ros/include/sensor_msgs/MagneticField.h create mode 100644 thirdparty/ros/include/sensor_msgs/MultiDOFJointState.h create mode 100644 thirdparty/ros/include/sensor_msgs/MultiEchoLaserScan.h create mode 100644 thirdparty/ros/include/sensor_msgs/NavSatFix.h create mode 100644 thirdparty/ros/include/sensor_msgs/NavSatStatus.h create mode 100644 thirdparty/ros/include/sensor_msgs/PointCloud.h create mode 100644 thirdparty/ros/include/sensor_msgs/PointCloud2.h create mode 100644 thirdparty/ros/include/sensor_msgs/PointField.h create mode 100644 thirdparty/ros/include/sensor_msgs/Range.h create mode 100644 thirdparty/ros/include/sensor_msgs/RegionOfInterest.h create mode 100644 thirdparty/ros/include/sensor_msgs/RelativeHumidity.h create mode 100644 thirdparty/ros/include/sensor_msgs/SetCameraInfo.h create mode 100644 thirdparty/ros/include/sensor_msgs/SetCameraInfoRequest.h create mode 100644 thirdparty/ros/include/sensor_msgs/SetCameraInfoResponse.h create mode 100644 thirdparty/ros/include/sensor_msgs/Temperature.h create mode 100644 thirdparty/ros/include/sensor_msgs/TimeReference.h create mode 100644 thirdparty/ros/include/sensor_msgs/distortion_models.h create mode 100644 thirdparty/ros/include/sensor_msgs/fill_image.h create mode 100644 thirdparty/ros/include/sensor_msgs/image_encodings.h create mode 100644 thirdparty/ros/include/sensor_msgs/point_cloud2_iterator.h create mode 100644 thirdparty/ros/include/sensor_msgs/point_cloud_conversion.h create mode 100644 thirdparty/ros/include/sensor_msgs/point_field_conversion.h create mode 100644 thirdparty/ros/include/std_msgs/Bool.h create mode 100644 thirdparty/ros/include/std_msgs/Byte.h create mode 100644 thirdparty/ros/include/std_msgs/ByteMultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/Char.h create mode 100644 thirdparty/ros/include/std_msgs/ColorRGBA.h create mode 100644 thirdparty/ros/include/std_msgs/Duration.h create mode 100644 thirdparty/ros/include/std_msgs/Empty.h create mode 100644 thirdparty/ros/include/std_msgs/Float32.h create mode 100644 thirdparty/ros/include/std_msgs/Float32MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/Float64.h create mode 100644 thirdparty/ros/include/std_msgs/Float64MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/Header.h create mode 100644 thirdparty/ros/include/std_msgs/Int16.h create mode 100644 thirdparty/ros/include/std_msgs/Int16MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/Int32.h create mode 100644 thirdparty/ros/include/std_msgs/Int32MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/Int64.h create mode 100644 thirdparty/ros/include/std_msgs/Int64MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/Int8.h create mode 100644 thirdparty/ros/include/std_msgs/Int8MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/MultiArrayDimension.h create mode 100644 thirdparty/ros/include/std_msgs/MultiArrayLayout.h create mode 100644 thirdparty/ros/include/std_msgs/String.h create mode 100644 thirdparty/ros/include/std_msgs/Time.h create mode 100644 thirdparty/ros/include/std_msgs/UInt16.h create mode 100644 thirdparty/ros/include/std_msgs/UInt16MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/UInt32.h create mode 100644 thirdparty/ros/include/std_msgs/UInt32MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/UInt64.h create mode 100644 thirdparty/ros/include/std_msgs/UInt64MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/UInt8.h create mode 100644 thirdparty/ros/include/std_msgs/UInt8MultiArray.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_bool.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_double.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_float.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_int16.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_int32.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_int64.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_int8.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_string.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_uint16.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_uint32.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_uint64.h create mode 100644 thirdparty/ros/include/std_msgs/builtin_uint8.h create mode 100644 thirdparty/ros/include/std_msgs/header_deprecated_def.h create mode 100644 thirdparty/ros/include/std_msgs/trait_macros.h create mode 160000 thirdparty/ros/ros_comm create mode 160000 thirdparty/ros/roscpp_core diff --git a/.clang-format b/.clang-format new file mode 100644 index 0000000..dc0134c --- /dev/null +++ b/.clang-format @@ -0,0 +1,6 @@ +--- +Language: Cpp +BasedOnStyle: Google +IndentWidth: 2 +... + diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..51704a2 --- /dev/null +++ b/.gitignore @@ -0,0 +1,7 @@ +cmake-build* +.idea +CMakeLists.txt.user +build +thirdparty/build-* +scripts/eval/eval_* +scripts/eval_full/eval_* diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml new file mode 100644 index 0000000..d38d87c --- /dev/null +++ b/.gitlab-ci.yml @@ -0,0 +1,76 @@ +image: vladyslavusenko/b_image:latest + +compile: + stage: build + variables: + CXX_MARCH: 'corei7-avx' + before_script: + - mkdir -p ccache + - export CCACHE_BASEDIR=${PWD} + - export CCACHE_DIR=${PWD}/ccache + cache: + paths: + - ccache/ + script: + - ./scripts/update_submodules.sh + - mkdir build + - cd build + - cmake .. -DCMAKE_BUILD_TYPE=Release -DCXX_MARCH=${CXX_MARCH} -DCMAKE_INSTALL_PREFIX=/usr/ + - make -j3 + - make package + - cd test/ + - ctest -V + - cd ../../ + - mkdir deb_bionic + - cp build/*.deb deb_bionic/ + artifacts: + paths: + - deb_bionic/*.deb + expire_in: 1 week + +compile_16_04: + stage: build + before_script: + - mkdir -p ccache + - export CCACHE_BASEDIR=${PWD} + - export CCACHE_DIR=${PWD}/ccache + cache: + paths: + - ccache/ + script: + - ./scripts/update_submodules.sh + - mkdir build + - cd build + - cmake .. -DCMAKE_BUILD_TYPE=Release -DCXX_MARCH=${CXX_MARCH} -DCMAKE_INSTALL_PREFIX=/usr/ + - make -j3 + - make package + - cd test/ + - ctest -V + - cd ../../ + - mkdir deb_xenial + - cp build/*.deb deb_xenial/ + artifacts: + paths: + - deb_xenial/*.deb + expire_in: 1 week + only: + - master + image: vladyslavusenko/b_image_xenial:latest + +deploy: + stage: deploy + before_script: + - eval $(ssh-agent -s) + - echo "$SSH_PRIVATE_KEY" | tr -d '\r' | ssh-add - > /dev/null + - mkdir -p ~/.ssh + - chmod 700 ~/.ssh + - echo "$SSH_KNOWN_HOSTS" > ~/.ssh/known_hosts + - chmod 644 ~/.ssh/known_hosts + variables: + GIT_STRATEGY: none + only: + - master + script: + - scp deb_xenial/*.deb $REPOSITORY_URL/xenial/ + - scp deb_bionic/*.deb $REPOSITORY_URL/bionic/ + diff --git a/.gitmodules b/.gitmodules new file mode 100644 index 0000000..b1d0363 --- /dev/null +++ b/.gitmodules @@ -0,0 +1,21 @@ +[submodule "thirdparty/CLI11"] + path = thirdparty/CLI11 + url = https://github.com/CLIUtils/CLI11.git +[submodule "thirdparty/opengv"] + path = thirdparty/opengv + url = https://github.com/laurentkneip/opengv.git +[submodule "thirdparty/Pangolin"] + path = thirdparty/Pangolin + url = https://github.com/stevenlovegrove/Pangolin.git +[submodule "thirdparty/ros_comm"] + path = thirdparty/ros/ros_comm + url = https://github.com/ros/ros_comm.git +[submodule "thirdparty/roscpp_core"] + path = thirdparty/ros/roscpp_core + url = https://github.com/ros/roscpp_core.git +[submodule "thirdparty/console_bridge"] + path = thirdparty/ros/console_bridge + url = https://github.com/ros/console_bridge.git +[submodule "thirdparty/basalt-headers"] + path = thirdparty/basalt-headers + url = https://gitlab.com/VladyslavUsenko/basalt-headers.git diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..5bbdc53 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,210 @@ +cmake_minimum_required(VERSION 3.8) +project(basalt) + +set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake_modules/" ${CMAKE_MODULE_PATH}) + +set(EIGEN_ROOT "${CMAKE_CURRENT_SOURCE_DIR}/thirdparty/basalt-headers/thirdparty/eigen") + +string(TOLOWER "${PROJECT_NAME}" PROJECT_NAME_LOWERCASE) +find_program(DPKG_PROGRAM dpkg DOC "dpkg program of Debian-based systems") +if(DPKG_PROGRAM) + execute_process( + COMMAND ${DPKG_PROGRAM} --print-architecture + OUTPUT_VARIABLE CPACK_DEBIAN_PACKAGE_ARCHITECTURE + OUTPUT_STRIP_TRAILING_WHITESPACE + ) +endif(DPKG_PROGRAM) + + +find_program(LSB_RELEASE_PROGRAM lsb_release DOC "lsb_release program of Debian-based systems") +if(LSB_RELEASE_PROGRAM) +execute_process(COMMAND ${LSB_RELEASE_PROGRAM} -rs + OUTPUT_VARIABLE LSB_RELEASE_ID_SHORT + OUTPUT_STRIP_TRAILING_WHITESPACE +) + +if(${LSB_RELEASE_ID_SHORT} EQUAL "18.04") + set(DEBIAN_DEPENDS "libtbb2, liblz4-1, libbz2-1.0, libboost-filesystem1.65.1, libboost-date-time1.65.1, libboost-program-options1.65.1, libboost-regex1.65.1, libopencv-dev, libglew2.0, libjpeg8, libpng16-16") +elseif(${LSB_RELEASE_ID_SHORT} EQUAL "16.04") + set(DEBIAN_DEPENDS "libtbb2, liblz4-1, libbz2-1.0, libboost-filesystem1.58.0, libboost-date-time1.58.0, libboost-program-options1.58.0, libboost-regex1.58.0, libopencv-dev, libglew1.13, libjpeg8, libpng12-0") +endif(${LSB_RELEASE_ID_SHORT} EQUAL "18.04") + +endif(LSB_RELEASE_PROGRAM) + +string(TIMESTAMP PROJECT_VERSION_REVISION "%Y%m%d%H%M") + +SET(CPACK_GENERATOR "DEB") +SET(CPACK_DEBIAN_PACKAGE_MAINTAINER "Vladyslav Usenko ") +SET(CPACK_PACKAGE_VERSION_MAJOR "0") +SET(CPACK_PACKAGE_VERSION_MINOR "1") +SET(CPACK_PACKAGE_VERSION_PATCH "0-${PROJECT_VERSION_REVISION}~${LSB_RELEASE_ID_SHORT}") +SET(CPACK_DEBIAN_PACKAGE_DEPENDS ${DEBIAN_DEPENDS}) +SET(CPACK_PACKAGE_FILE_NAME "${PROJECT_NAME_LOWERCASE}_${CPACK_PACKAGE_VERSION_MAJOR}.${CPACK_PACKAGE_VERSION_MINOR}.${CPACK_PACKAGE_VERSION_PATCH}_${CPACK_DEBIAN_PACKAGE_ARCHITECTURE}") +SET(CPACK_RESOURCE_FILE_LICENSE "${CMAKE_CURRENT_SOURCE_DIR}/LICENSE") +include(CPack) + + +# Configure CCache if available +find_program(CCACHE_PROGRAM ccache) +if(CCACHE_PROGRAM) + message(STATUS "Found ccache: ${CCACHE_PROGRAM}") + set(CMAKE_C_COMPILER_LAUNCHER ${CCACHE_PROGRAM}) + set(CMAKE_CXX_COMPILER_LAUNCHER ${CCACHE_PROGRAM}) +endif(CCACHE_PROGRAM) + +IF( NOT CMAKE_BUILD_TYPE ) + SET( CMAKE_BUILD_TYPE Release) +ENDIF() + +IF(NOT CXX_MARCH) + SET(CXX_MARCH native) +ENDIF() + +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) +set(CMAKE_CXX_EXTENSIONS OFF) +set(CMAKE_POSITION_INDEPENDENT_CODE ON) + +# Flags used for CHECK_CXX_SOURCE_COMPILES +set(CMAKE_REQUIRED_FLAGS "-Wno-unused-variable -Wno-unused-value") + + +IF("${CMAKE_CXX_COMPILER_ID}" STREQUAL "Clang") + SET(CMAKE_CXX_FLAGS_DEBUG "-O0 -g") + SET(CMAKE_CXX_FLAGS_RELEASE "-O3 -ftree-vectorize -march=${CXX_MARCH}") + SET(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-O3 -g -ftree-vectorize -march=${CXX_MARCH}") + SET(CMAKE_CXX_FLAGS "-Wall -Werror -Wextra -Wno-deprecated-register -Qunused-arguments -fcolor-diagnostics -fopenmp") +ELSEIF("${CMAKE_CXX_COMPILER_ID}" STREQUAL "AppleClang") + SET(CMAKE_CXX_FLAGS_DEBUG "-O0 -g") + SET(CMAKE_CXX_FLAGS_RELEASE "-O3 -ftree-vectorize -march=${CXX_MARCH}") + SET(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-O3 -g -ftree-vectorize -march=${CXX_MARCH}") + SET(CMAKE_CXX_FLAGS "-Wall -Wextra -Wno-deprecated-register -Wno-deprecated-declarations -Wno-sign-compare -Wno-exceptions -Wno-missing-field-initializers -Wno-unused-parameter -Wno-unused-private-field -Qunused-arguments -fcolor-diagnostics -nostdinc++") + include_directories(/usr/local/opt/llvm/include/c++/v1) + link_directories(/usr/local/opt/llvm/lib) + SET(STD_CXX_FS c++fs) +ELSEIF("${CMAKE_CXX_COMPILER_ID}" STREQUAL "GNU") + SET(CMAKE_CXX_FLAGS_DEBUG "-O0 -g") + SET(CMAKE_CXX_FLAGS_RELEASE "-O3 -ftree-vectorize -march=${CXX_MARCH}") + SET(CMAKE_CXX_FLAGS_RELWITHDEBINFO "-O3 -g -ftree-vectorize -march=${CXX_MARCH}") + SET(CMAKE_CXX_FLAGS "-Wall -Werror -Wextra -std=c++11 -Wno-misleading-indentation -Wno-sign-compare -Wno-maybe-uninitialized -Wno-int-in-bool-context -Wno-implicit-fallthrough -Wno-unused-parameter -Wno-deprecated-declarations -ftemplate-backtrace-limit=0 -fopenmp") + SET(STD_CXX_FS stdc++fs) +ENDIF() + +set(EIGEN_INCLUDE_DIR_HINTS ${EIGEN_ROOT}) +find_package(Eigen3 3.3.7 REQUIRED) +include_directories(${EIGEN3_INCLUDE_DIR}) +message(STATUS "Found Eigen headers in: ${EIGEN3_INCLUDE_DIR}") + +find_package(TBB REQUIRED) +include_directories(${TBB_INCLUDE_DIR}) + +find_package(OpenCV REQUIRED core imgproc calib3d) +include_directories(${OpenCV_INCLUDE_DIR}) +message(STATUS "Found OpenCV headers in: ${OpenCV_INCLUDE_DIR}") +message(STATUS "Found OpenCV_LIBS: ${OpenCV_LIBS}") + +add_subdirectory(thirdparty/ros) +add_subdirectory(thirdparty/apriltag) +add_subdirectory(thirdparty/DBoW3) + + +set(BUILD_SHARED_LIBS OFF CACHE BOOL "Enable BUILD_SHARED_LIBS") +set(BUILD_TESTS OFF CACHE BOOL "Enable BUILD_TESTS") + +set(BUILD_PANGOLIN_LIBOPENEXR OFF CACHE BOOL "Enable BUILD_PANGOLIN_LIBOPENEXR") +set(BUILD_PANGOLIN_PYTHON OFF CACHE BOOL "Enable BUILD_PANGOLIN_PYTHON") +set(BUILD_EXAMPLES OFF CACHE BOOL "Enable BUILD_EXAMPLES") +add_subdirectory(thirdparty/opengv EXCLUDE_FROM_ALL) + +# Hack to disable CPack in Pangolin. +macro(include) + if(NOT ${ARGV0} STREQUAL "CPack") + _include(${ARGN}) + endif() +endmacro() +add_subdirectory(thirdparty/Pangolin EXCLUDE_FROM_ALL) + +include_directories(thirdparty/basalt-headers/thirdparty/Sophus) +include_directories(thirdparty/basalt-headers/thirdparty/cereal/include) +include_directories(thirdparty/basalt-headers/include) +include_directories(thirdparty/CLI11/include) +include_directories(thirdparty/fast/include) +include_directories(thirdparty/DBoW3/src/) + +include_directories(include) + + +add_library(basalt SHARED + src/io/dataset_io.cpp + src/io/marg_data_io.cpp + src/calibration/cam_calib.cpp + src/calibration/cam_imu_calib.cpp + src/calibration/calibraiton_helper.cpp + src/calibration/vignette.cpp + src/utils/vio_config.cpp + src/optical_flow/optical_flow.cpp + src/vi_estimator/keypoint_vio.cpp + src/vi_estimator/keypoint_vio_linearize.cpp + src/vi_estimator/vio_estimator.cpp + src/vi_estimator/ba_base.cpp + src/vi_estimator/nfr_mapper.cpp + src/utils/keypoints.cpp) + + +target_link_libraries(basalt rosbag pangolin apriltag ${OPENGV_LIBS} ${TBB_LIBRARIES} ${OpenCV_LIBS} opengv ${STD_CXX_FS} DBoW3) + + +add_executable(basalt_calibrate src/calibrate.cpp) +target_link_libraries(basalt_calibrate ${Pangolin_LIBRARIES} apriltag ${OPENGV_LIBS} ${TBB_LIBRARIES} ${rosbag_LIBRARIES} basalt) + +add_executable(basalt_calibrate_imu src/calibrate_imu.cpp) +target_link_libraries(basalt_calibrate_imu ${Pangolin_LIBRARIES} apriltag ${OPENGV_LIBS} ${TBB_LIBRARIES} ${rosbag_LIBRARIES} basalt) + + +add_executable(basalt_vio_sim src/vio_sim.cpp ) +target_link_libraries(basalt_vio_sim ${Pangolin_LIBRARIES} opengv ${STD_CXX_FS} ${TBB_LIBRARIES} basalt) + +add_executable(basalt_mapper_sim src/mapper_sim.cpp ) +target_link_libraries(basalt_mapper_sim ${Pangolin_LIBRARIES} opengv ${TBB_LIBRARIES} basalt) + +add_executable(basalt_mapper_sim_naive src/mapper_sim_naive.cpp) +target_link_libraries(basalt_mapper_sim_naive ${Pangolin_LIBRARIES} opengv ${TBB_LIBRARIES} basalt) + +add_executable(basalt_mapper src/mapper.cpp) +target_link_libraries(basalt_mapper ${Pangolin_LIBRARIES} opengv ${STD_CXX_FS} ${TBB_LIBRARIES} basalt) + + +add_executable(basalt_opt_flow src/opt_flow.cpp) +target_link_libraries(basalt_opt_flow ${Pangolin_LIBRARIES} opengv ${STD_CXX_FS} basalt) + +add_executable(basalt_vio src/vio.cpp) +target_link_libraries(basalt_vio ${Pangolin_LIBRARIES} opengv ${STD_CXX_FS} basalt) + + + +install(TARGETS basalt_calibrate basalt_calibrate_imu basalt_vio_sim basalt_mapper_sim basalt_mapper_sim_naive basalt_mapper basalt_opt_flow basalt_vio basalt + EXPORT BasaltTargets + RUNTIME DESTINATION ${CMAKE_INSTALL_PREFIX}/bin + LIBRARY DESTINATION ${CMAKE_INSTALL_PREFIX}/lib + ARCHIVE DESTINATION ${CMAKE_INSTALL_PREFIX}/lib +) + +file(GLOB CONFIG_FILES "${CMAKE_CURRENT_SOURCE_DIR}/data/*.json") +INSTALL(FILES ${CONFIG_FILES} ${CMAKE_CURRENT_SOURCE_DIR}/thirdparty/DBoW3/vocab/orbvoc.dbow3 + DESTINATION ${CMAKE_INSTALL_PREFIX}/etc/basalt +) + + +# Replace install() to do-nothing macro. +macro(install) +endmacro() +# Include subproject (or any other CMake code) with "disabled" install(). +add_subdirectory(thirdparty/basalt-headers/test) +add_subdirectory(test) +# Restore original install() behavior. +macro(install) + _install(${ARGN}) +endmacro() + + + diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..03fd6f3 --- /dev/null +++ b/LICENSE @@ -0,0 +1,29 @@ +BSD 3-Clause License + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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/README.md b/README.md new file mode 100644 index 0000000..8dc7987 --- /dev/null +++ b/README.md @@ -0,0 +1,62 @@ +## Basalt +For more information see https://vision.in.tum.de/research/vslam/basalt + +![teaser](doc/img/teaser.png) + +This project contains tools for: +* Camera, IMU and motion capture calibration. +* Visual-inertial odometry and mapping. +* Simulated environment to test different components of the system. + + +## Related Publications +Visual-Inertial Odometry and Mapping: +* **Visual-Inertial Mapping with Non-Linear Factor Recovery**, V. Usenko, N. Demmel, D. Schubert, J. Stückler, D. Cremers, In [[arXiv:]](https://arxiv.org/abs/). + +Calibration (explains implemented camera models): +* **The Double Sphere Camera Model**, V. Usenko and N. Demmel and D. Cremers, In 2018 International Conference on 3D Vision (3DV), [[DOI:10.1109/3DV.2018.00069]](https://doi.org/10.1109/3DV.2018.00069), [[arXiv:1807.08957]](https://arxiv.org/abs/1807.08957). + +Calibration (demonstrates how these tools can be used for dataset calibration): +* **The TUM VI Benchmark for Evaluating Visual-Inertial Odometry**, D. Schubert, T. Goll, N. Demmel, V. Usenko, J. Stückler, D. Cremers, In 2018 International Conference on Intelligent Robots and Systems (IROS), [[DOI:10.1109/IROS.2018.8593419]](https://doi.org/10.1109/IROS.2018.8593419), [[arXiv:1804.06120]](https://arxiv.org/abs/1804.06120). + + +## Installation +### APT installation for Ubuntu 16.04 and 18.04 (Fast) +Set up keys +``` +sudo apt-key adv --keyserver keyserver.ubuntu.com --recv-keys 0D97B6C9 +``` +Add the repository to the sources list. On **Ubuntu 18.04** run: +``` +sudo sh -c 'echo "deb [arch=amd64] http://packages.usenko.eu/ubuntu bionic main" > /etc/apt/sources.list.d/basalt.list' +``` +On **Ubuntu 16.04** run: +``` +sudo sh -c 'echo "deb [arch=amd64] http://packages.usenko.eu/ubuntu xenial main" > /etc/apt/sources.list.d/basalt.list' +``` +Update the Ubuntu package index and install Basalt: +``` +sudo apt-get update +sudo apt-get install basalt +``` +### Source installation for Ubuntu 18.04 and MacOS 10.14 Mojave +Clone the source code for the project +``` +git clone --recursive https://gitlab.com/VladyslavUsenko/basalt.git +cd basalt +./scripts/install_deps.sh +mkdir build +cd build +cmake .. -DCMAKE_BUILD_TYPE=RelWithDebInfo +make -j8 +``` +NOTE: It is possible to compile the code on Ubuntu 16.04, but you need to install cmake-3.10 and gcc-7. See corresponding [Dockerfile](docker/b_image_xenial/Dockerfile) as an example. + +## Usage +* [Camera, IMU and Mocap calibration.](doc/Calibration.md) +* [Visual-inertial odometry and mapping.](doc/VioMapping.md) +* [Simulation tools to test different components of the system.](doc/Simulation.md) + +## Licence +The code for this practical course is provided under a BSD 3-clause license. See the LICENSE file for details. +Note also the different licenses of thirdparty submodules. diff --git a/cmake_modules/FindEigen3.cmake b/cmake_modules/FindEigen3.cmake new file mode 100644 index 0000000..9c44084 --- /dev/null +++ b/cmake_modules/FindEigen3.cmake @@ -0,0 +1,83 @@ +# - Try to find Eigen3 lib +# +# This module supports requiring a minimum version, e.g. you can do +# find_package(Eigen3 3.1.2) +# to require version 3.1.2 or newer of Eigen3. +# +# Once done this will define +# +# EIGEN3_FOUND - system has eigen lib with correct version +# EIGEN3_INCLUDE_DIR - the eigen include directory +# EIGEN3_VERSION - eigen version + +# Copyright (c) 2006, 2007 Montel Laurent, +# Copyright (c) 2008, 2009 Gael Guennebaud, +# Copyright (c) 2009 Benoit Jacob +# Redistribution and use is allowed according to the terms of the 2-clause BSD license. + +if(NOT Eigen3_FIND_VERSION) + if(NOT Eigen3_FIND_VERSION_MAJOR) + set(Eigen3_FIND_VERSION_MAJOR 2) + endif(NOT Eigen3_FIND_VERSION_MAJOR) + if(NOT Eigen3_FIND_VERSION_MINOR) + set(Eigen3_FIND_VERSION_MINOR 91) + endif(NOT Eigen3_FIND_VERSION_MINOR) + if(NOT Eigen3_FIND_VERSION_PATCH) + set(Eigen3_FIND_VERSION_PATCH 0) + endif(NOT Eigen3_FIND_VERSION_PATCH) + + set(Eigen3_FIND_VERSION "${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}") +endif(NOT Eigen3_FIND_VERSION) + +macro(_eigen3_check_version) + file(READ "${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h" _eigen3_version_header) + + string(REGEX MATCH "define[ \t]+EIGEN_WORLD_VERSION[ \t]+([0-9]+)" _eigen3_world_version_match "${_eigen3_version_header}") + set(EIGEN3_WORLD_VERSION "${CMAKE_MATCH_1}") + string(REGEX MATCH "define[ \t]+EIGEN_MAJOR_VERSION[ \t]+([0-9]+)" _eigen3_major_version_match "${_eigen3_version_header}") + set(EIGEN3_MAJOR_VERSION "${CMAKE_MATCH_1}") + string(REGEX MATCH "define[ \t]+EIGEN_MINOR_VERSION[ \t]+([0-9]+)" _eigen3_minor_version_match "${_eigen3_version_header}") + set(EIGEN3_MINOR_VERSION "${CMAKE_MATCH_1}") + + set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION}) + if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + set(EIGEN3_VERSION_OK FALSE) + else(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + set(EIGEN3_VERSION_OK TRUE) + endif(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION}) + + if(NOT EIGEN3_VERSION_OK) + + message(STATUS "Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, " + "but at least version ${Eigen3_FIND_VERSION} is required") + endif(NOT EIGEN3_VERSION_OK) +endmacro(_eigen3_check_version) + +if (EIGEN3_INCLUDE_DIR) + + # in cache already + _eigen3_check_version() + set(EIGEN3_FOUND ${EIGEN3_VERSION_OK}) + +else (EIGEN3_INCLUDE_DIR) + + find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library + HINTS ${EIGEN_INCLUDE_DIR_HINTS} + PATHS + /usr/local/include + /opt/local/include + ${CMAKE_INSTALL_PREFIX}/include + ${KDE4_INCLUDE_DIR} + PATH_SUFFIXES eigen3 eigen + ) + + if(EIGEN3_INCLUDE_DIR) + _eigen3_check_version() + endif(EIGEN3_INCLUDE_DIR) + + include(FindPackageHandleStandardArgs) + find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK) + + mark_as_advanced(EIGEN3_INCLUDE_DIR) + +endif(EIGEN3_INCLUDE_DIR) diff --git a/cmake_modules/FindOpenGV.cmake b/cmake_modules/FindOpenGV.cmake new file mode 100644 index 0000000..ad244c6 --- /dev/null +++ b/cmake_modules/FindOpenGV.cmake @@ -0,0 +1,85 @@ + +# This is FindOPENGV.cmake +# CMake module to locate the OPENGV package +# +# The following cache variables may be set before calling this script: +# +# OPENGV_DIR (or OPENGV_ROOT): (Optional) The install prefix OR source tree of opengv (e.g. /usr/local or src/opengv) +# OPENGV_BUILD_NAME: (Optional) If compiling against a source tree, the name of the build directory +# within it (e.g build-debug). Without this defined, this script tries to +# intelligently find the build directory based on the project's build directory name +# or based on the build type (Debug/Release/etc). +# +# The following variables will be defined: +# +# OPENGV_FOUND : TRUE if the package has been successfully found +# OPENGV_INCLUDE_DIR : paths to OPENGV's INCLUDE directories +# OPENGV_LIBS : paths to OPENGV's libraries +# +# NOTES on compiling against an uninstalled OPENGV build tree: +# - A OPENGV source tree will be automatically searched for in the directory +# 'opengv' next to your project directory, after searching +# CMAKE_INSTALL_PREFIX and $HOME, but before searching /usr/local and /usr. +# - The build directory will be searched first with the same name as your +# project's build directory, e.g. if you build from 'MyProject/build-optimized', +# 'opengv/build-optimized' will be searched first. Next, a build directory for +# your project's build type, e.g. if CMAKE_BUILD_TYPE in your project is +# 'Release', then 'opengv/build-release' will be searched next. Finally, plain +# 'opengv/build' will be searched. +# - You can control the opengv build directory name directly by defining the CMake +# cache variable 'OPENGV_BUILD_NAME', then only 'opengv/${OPENGV_BUILD_NAME} will +# be searched. +# - Use the standard CMAKE_PREFIX_PATH, or OPENGV_DIR, to find a specific opengv +# directory. + +# Get path suffixes to help look for opengv +if(OPENGV_BUILD_NAME) + set(opengv_build_names "${OPENGV_BUILD_NAME}/opengv") +else() + # lowercase build type + string(TOLOWER "${CMAKE_BUILD_TYPE}" build_type_suffix) + # build suffix of this project + get_filename_component(my_build_name "${CMAKE_BINARY_DIR}" NAME) + + set(opengv_build_names "${my_build_name}/opengv" "build-${build_type_suffix}/opengv" "build/opengv" "build/lib") +endif() + +# Use OPENGV_ROOT or OPENGV_DIR equivalently +if(OPENGV_ROOT AND NOT OPENGV_DIR) + set(OPENGV_DIR "${OPENGV_ROOT}") +endif() + +if(OPENGV_DIR) + # Find include dirs + find_path(OPENGV_INCLUDE_DIR opengv/types.hpp + PATHS "${OPENGV_DIR}/include" "${OPENGV_DIR}" NO_DEFAULT_PATH + DOC "OPENGV include directories") + + # Find libraries + find_library(OPENGV_LIBS NAMES opengv + HINTS "${OPENGV_DIR}/lib" "${OPENGV_DIR}" NO_DEFAULT_PATH + PATH_SUFFIXES ${opengv_build_names} + DOC "OPENGV libraries") +else() + # Find include dirs + set(extra_include_paths ${CMAKE_INSTALL_PREFIX}/include "$ENV{HOME}/include" "${PROJECT_SOURCE_DIR}/../opengv" /usr/local/include /usr/include) + find_path(OPENGV_INCLUDE_DIR opengv/types.hpp + PATHS ${extra_include_paths} + DOC "OPENGV include directories") + if(NOT OPENGV_INCLUDE_DIR) + message(STATUS "Searched for opengv headers in default paths plus ${extra_include_paths}") + endif() + + # Find libraries + find_library(OPENGV_LIBS NAMES opengv + HINTS ${CMAKE_INSTALL_PREFIX}/lib "$ENV{HOME}/lib" "${PROJECT_SOURCE_DIR}/../opengv" /usr/local/lib /usr/lib + PATH_SUFFIXES ${opengv_build_names} + DOC "OPENGV libraries") +endif() + +# handle the QUIETLY and REQUIRED arguments and set OPENGV_FOUND to TRUE +# if all listed variables are TRUE +include(FindPackageHandleStandardArgs) +find_package_handle_standard_args(OPENGV DEFAULT_MSG + OPENGV_LIBS OPENGV_INCLUDE_DIR) + diff --git a/cmake_modules/FindTBB.cmake b/cmake_modules/FindTBB.cmake new file mode 100644 index 0000000..f9e3e0f --- /dev/null +++ b/cmake_modules/FindTBB.cmake @@ -0,0 +1,283 @@ +# Locate Intel Threading Building Blocks include paths and libraries +# FindTBB.cmake can be found at https://code.google.com/p/findtbb/ +# Written by Hannes Hofmann +# Improvements by Gino van den Bergen , +# Florian Uhlig , +# Jiri Marsik + +# The MIT License +# +# Copyright (c) 2011 Hannes Hofmann +# +# Permission is hereby granted, free of charge, to any person obtaining a copy +# of this software and associated documentation files (the "Software"), to deal +# in the Software without restriction, including without limitation the rights +# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +# copies of the Software, and to permit persons to whom the Software is +# furnished to do so, subject to the following conditions: +# +# The above copyright notice and this permission notice shall be included in +# all copies or substantial portions of the Software. +# +# THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +# IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +# FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +# AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +# LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +# OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN +# THE SOFTWARE. + +# GvdB: This module uses the environment variable TBB_ARCH_PLATFORM which defines architecture and compiler. +# e.g. "ia32/vc8" or "em64t/cc4.1.0_libc2.4_kernel2.6.16.21" +# TBB_ARCH_PLATFORM is set by the build script tbbvars[.bat|.sh|.csh], which can be found +# in the TBB installation directory (TBB_INSTALL_DIR). +# +# GvdB: Mac OS X distribution places libraries directly in lib directory. +# +# For backwards compatibility, you may explicitely set the CMake variables TBB_ARCHITECTURE and TBB_COMPILER. +# TBB_ARCHITECTURE [ ia32 | em64t | itanium ] +# which architecture to use +# TBB_COMPILER e.g. vc9 or cc3.2.3_libc2.3.2_kernel2.4.21 or cc4.0.1_os10.4.9 +# which compiler to use (detected automatically on Windows) + +# This module respects +# TBB_INSTALL_DIR or $ENV{TBB21_INSTALL_DIR} or $ENV{TBB_INSTALL_DIR} + +# This module defines +# TBB_INCLUDE_DIRS, where to find task_scheduler_init.h, etc. +# TBB_LIBRARY_DIRS, where to find libtbb, libtbbmalloc +# TBB_DEBUG_LIBRARY_DIRS, where to find libtbb_debug, libtbbmalloc_debug +# TBB_INSTALL_DIR, the base TBB install directory +# TBB_LIBRARIES, the libraries to link against to use TBB. +# TBB_DEBUG_LIBRARIES, the libraries to link against to use TBB with debug symbols. +# TBB_FOUND, If false, don't try to use TBB. +# TBB_INTERFACE_VERSION, as defined in tbb/tbb_stddef.h + + +if (WIN32) + # has em64t/vc8 em64t/vc9 + # has ia32/vc7.1 ia32/vc8 ia32/vc9 + set(_TBB_DEFAULT_INSTALL_DIR "C:/Program Files/Intel/TBB" "C:/Program Files (x86)/Intel/TBB") + set(_TBB_LIB_NAME "tbb") + set(_TBB_LIB_MALLOC_NAME "${_TBB_LIB_NAME}malloc") + set(_TBB_LIB_DEBUG_NAME "${_TBB_LIB_NAME}_debug") + set(_TBB_LIB_MALLOC_DEBUG_NAME "${_TBB_LIB_MALLOC_NAME}_debug") + if (MSVC71) + set (_TBB_COMPILER "vc7.1") + endif(MSVC71) + if (MSVC80) + set(_TBB_COMPILER "vc8") + endif(MSVC80) + if (MSVC90) + set(_TBB_COMPILER "vc9") + endif(MSVC90) + if(MSVC10) + set(_TBB_COMPILER "vc10") + endif(MSVC10) + # Todo: add other Windows compilers such as ICL. + set(_TBB_ARCHITECTURE ${TBB_ARCHITECTURE}) +endif (WIN32) + +if (UNIX) + if (APPLE) + # MAC + set(_TBB_DEFAULT_INSTALL_DIR "/Library/Frameworks/Intel_TBB.framework/Versions") + # libs: libtbb.dylib, libtbbmalloc.dylib, *_debug + set(_TBB_LIB_NAME "tbb") + set(_TBB_LIB_MALLOC_NAME "${_TBB_LIB_NAME}malloc") + set(_TBB_LIB_DEBUG_NAME "${_TBB_LIB_NAME}_debug") + set(_TBB_LIB_MALLOC_DEBUG_NAME "${_TBB_LIB_MALLOC_NAME}_debug") + # default flavor on apple: ia32/cc4.0.1_os10.4.9 + # Jiri: There is no reason to presume there is only one flavor and + # that user's setting of variables should be ignored. + if(NOT TBB_COMPILER) + set(_TBB_COMPILER "cc4.0.1_os10.4.9") + elseif (NOT TBB_COMPILER) + set(_TBB_COMPILER ${TBB_COMPILER}) + endif(NOT TBB_COMPILER) + if(NOT TBB_ARCHITECTURE) + set(_TBB_ARCHITECTURE "ia32") + elseif(NOT TBB_ARCHITECTURE) + set(_TBB_ARCHITECTURE ${TBB_ARCHITECTURE}) + endif(NOT TBB_ARCHITECTURE) + else (APPLE) + # LINUX + set(_TBB_DEFAULT_INSTALL_DIR "/opt/intel/tbb" "/usr/local/include" "/usr/include") + set(_TBB_LIB_NAME "tbb") + set(_TBB_LIB_MALLOC_NAME "${_TBB_LIB_NAME}malloc") + set(_TBB_LIB_DEBUG_NAME "${_TBB_LIB_NAME}_debug") + set(_TBB_LIB_MALLOC_DEBUG_NAME "${_TBB_LIB_MALLOC_NAME}_debug") + # has em64t/cc3.2.3_libc2.3.2_kernel2.4.21 em64t/cc3.3.3_libc2.3.3_kernel2.6.5 em64t/cc3.4.3_libc2.3.4_kernel2.6.9 em64t/cc4.1.0_libc2.4_kernel2.6.16.21 + # has ia32/* + # has itanium/* + set(_TBB_COMPILER ${TBB_COMPILER}) + set(_TBB_ARCHITECTURE ${TBB_ARCHITECTURE}) + endif (APPLE) +endif (UNIX) + +if (CMAKE_SYSTEM MATCHES "SunOS.*") +# SUN +# not yet supported +# has em64t/cc3.4.3_kernel5.10 +# has ia32/* +endif (CMAKE_SYSTEM MATCHES "SunOS.*") + + +#-- Clear the public variables +set (TBB_FOUND "NO") + + +#-- Find TBB install dir and set ${_TBB_INSTALL_DIR} and cached ${TBB_INSTALL_DIR} +# first: use CMake variable TBB_INSTALL_DIR +if (TBB_INSTALL_DIR) + set (_TBB_INSTALL_DIR ${TBB_INSTALL_DIR}) +endif (TBB_INSTALL_DIR) +# second: use environment variable +if (NOT _TBB_INSTALL_DIR) + if (NOT "$ENV{TBB_INSTALL_DIR}" STREQUAL "") + set (_TBB_INSTALL_DIR $ENV{TBB_INSTALL_DIR}) + endif (NOT "$ENV{TBB_INSTALL_DIR}" STREQUAL "") + # Intel recommends setting TBB21_INSTALL_DIR + if (NOT "$ENV{TBB21_INSTALL_DIR}" STREQUAL "") + set (_TBB_INSTALL_DIR $ENV{TBB21_INSTALL_DIR}) + endif (NOT "$ENV{TBB21_INSTALL_DIR}" STREQUAL "") + if (NOT "$ENV{TBB22_INSTALL_DIR}" STREQUAL "") + set (_TBB_INSTALL_DIR $ENV{TBB22_INSTALL_DIR}) + endif (NOT "$ENV{TBB22_INSTALL_DIR}" STREQUAL "") + if (NOT "$ENV{TBB30_INSTALL_DIR}" STREQUAL "") + set (_TBB_INSTALL_DIR $ENV{TBB30_INSTALL_DIR}) + endif (NOT "$ENV{TBB30_INSTALL_DIR}" STREQUAL "") +endif (NOT _TBB_INSTALL_DIR) +# third: try to find path automatically +if (NOT _TBB_INSTALL_DIR) + if (_TBB_DEFAULT_INSTALL_DIR) + set (_TBB_INSTALL_DIR ${_TBB_DEFAULT_INSTALL_DIR}) + endif (_TBB_DEFAULT_INSTALL_DIR) +endif (NOT _TBB_INSTALL_DIR) +# sanity check +if (NOT _TBB_INSTALL_DIR) + message ("ERROR: Unable to find Intel TBB install directory. ${_TBB_INSTALL_DIR}") +else (NOT _TBB_INSTALL_DIR) +# finally: set the cached CMake variable TBB_INSTALL_DIR +if (NOT TBB_INSTALL_DIR) + set (TBB_INSTALL_DIR ${_TBB_INSTALL_DIR} CACHE PATH "Intel TBB install directory") + mark_as_advanced(TBB_INSTALL_DIR) +endif (NOT TBB_INSTALL_DIR) + + +#-- A macro to rewrite the paths of the library. This is necessary, because +# find_library() always found the em64t/vc9 version of the TBB libs +macro(TBB_CORRECT_LIB_DIR var_name) +# if (NOT "${_TBB_ARCHITECTURE}" STREQUAL "em64t") + string(REPLACE em64t "${_TBB_ARCHITECTURE}" ${var_name} ${${var_name}}) +# endif (NOT "${_TBB_ARCHITECTURE}" STREQUAL "em64t") + string(REPLACE ia32 "${_TBB_ARCHITECTURE}" ${var_name} ${${var_name}}) + string(REPLACE vc7.1 "${_TBB_COMPILER}" ${var_name} ${${var_name}}) + string(REPLACE vc8 "${_TBB_COMPILER}" ${var_name} ${${var_name}}) + string(REPLACE vc9 "${_TBB_COMPILER}" ${var_name} ${${var_name}}) + string(REPLACE vc10 "${_TBB_COMPILER}" ${var_name} ${${var_name}}) +endmacro(TBB_CORRECT_LIB_DIR var_content) + + +#-- Look for include directory and set ${TBB_INCLUDE_DIR} +set (TBB_INC_SEARCH_DIR ${_TBB_INSTALL_DIR}/include) +# Jiri: tbbvars now sets the CPATH environment variable to the directory +# containing the headers. +find_path(TBB_INCLUDE_DIR + tbb/task_scheduler_init.h + PATHS ${TBB_INC_SEARCH_DIR} ENV CPATH +) +mark_as_advanced(TBB_INCLUDE_DIR) + + +#-- Look for libraries +# GvdB: $ENV{TBB_ARCH_PLATFORM} is set by the build script tbbvars[.bat|.sh|.csh] +if (NOT $ENV{TBB_ARCH_PLATFORM} STREQUAL "") + set (_TBB_LIBRARY_DIR + ${_TBB_INSTALL_DIR}/lib/$ENV{TBB_ARCH_PLATFORM} + ${_TBB_INSTALL_DIR}/$ENV{TBB_ARCH_PLATFORM}/lib + ) +endif (NOT $ENV{TBB_ARCH_PLATFORM} STREQUAL "") +# Jiri: This block isn't mutually exclusive with the previous one +# (hence no else), instead I test if the user really specified +# the variables in question. +if ((NOT ${TBB_ARCHITECTURE} STREQUAL "") AND (NOT ${TBB_COMPILER} STREQUAL "")) + # HH: deprecated + message(STATUS "[Warning] FindTBB.cmake: The use of TBB_ARCHITECTURE and TBB_COMPILER is deprecated and may not be supported in future versions. Please set \$ENV{TBB_ARCH_PLATFORM} (using tbbvars.[bat|csh|sh]).") + # Jiri: It doesn't hurt to look in more places, so I store the hints from + # ENV{TBB_ARCH_PLATFORM} and the TBB_ARCHITECTURE and TBB_COMPILER + # variables and search them both. + set (_TBB_LIBRARY_DIR "${_TBB_INSTALL_DIR}/${_TBB_ARCHITECTURE}/${_TBB_COMPILER}/lib" ${_TBB_LIBRARY_DIR}) +endif ((NOT ${TBB_ARCHITECTURE} STREQUAL "") AND (NOT ${TBB_COMPILER} STREQUAL "")) + +# GvdB: Mac OS X distribution places libraries directly in lib directory. +list(APPEND _TBB_LIBRARY_DIR ${_TBB_INSTALL_DIR}/lib) + +# Jiri: No reason not to check the default paths. From recent versions, +# tbbvars has started exporting the LIBRARY_PATH and LD_LIBRARY_PATH +# variables, which now point to the directories of the lib files. +# It all makes more sense to use the ${_TBB_LIBRARY_DIR} as a HINTS +# argument instead of the implicit PATHS as it isn't hard-coded +# but computed by system introspection. Searching the LIBRARY_PATH +# and LD_LIBRARY_PATH environment variables is now even more important +# that tbbvars doesn't export TBB_ARCH_PLATFORM and it facilitates +# the use of TBB built from sources. +find_library(TBB_LIBRARY ${_TBB_LIB_NAME} HINTS ${_TBB_LIBRARY_DIR} + PATHS ENV LIBRARY_PATH ENV LD_LIBRARY_PATH) +find_library(TBB_MALLOC_LIBRARY ${_TBB_LIB_MALLOC_NAME} HINTS ${_TBB_LIBRARY_DIR} + PATHS ENV LIBRARY_PATH ENV LD_LIBRARY_PATH) + +#Extract path from TBB_LIBRARY name +get_filename_component(TBB_LIBRARY_DIR ${TBB_LIBRARY} PATH) + +#TBB_CORRECT_LIB_DIR(TBB_LIBRARY) +#TBB_CORRECT_LIB_DIR(TBB_MALLOC_LIBRARY) +mark_as_advanced(TBB_LIBRARY TBB_MALLOC_LIBRARY) + +#-- Look for debug libraries +# Jiri: Changed the same way as for the release libraries. +find_library(TBB_LIBRARY_DEBUG ${_TBB_LIB_DEBUG_NAME} HINTS ${_TBB_LIBRARY_DIR} + PATHS ENV LIBRARY_PATH ENV LD_LIBRARY_PATH) +find_library(TBB_MALLOC_LIBRARY_DEBUG ${_TBB_LIB_MALLOC_DEBUG_NAME} HINTS ${_TBB_LIBRARY_DIR} + PATHS ENV LIBRARY_PATH ENV LD_LIBRARY_PATH) + +# Jiri: Self-built TBB stores the debug libraries in a separate directory. +# Extract path from TBB_LIBRARY_DEBUG name +get_filename_component(TBB_LIBRARY_DEBUG_DIR ${TBB_LIBRARY_DEBUG} PATH) + +#TBB_CORRECT_LIB_DIR(TBB_LIBRARY_DEBUG) +#TBB_CORRECT_LIB_DIR(TBB_MALLOC_LIBRARY_DEBUG) +mark_as_advanced(TBB_LIBRARY_DEBUG TBB_MALLOC_LIBRARY_DEBUG) + + +if (TBB_INCLUDE_DIR) + if (TBB_LIBRARY) + set (TBB_FOUND "YES") + set (TBB_LIBRARIES ${TBB_LIBRARY} ${TBB_MALLOC_LIBRARY} ${TBB_LIBRARIES}) + set (TBB_DEBUG_LIBRARIES ${TBB_LIBRARY_DEBUG} ${TBB_MALLOC_LIBRARY_DEBUG} ${TBB_DEBUG_LIBRARIES}) + set (TBB_INCLUDE_DIRS ${TBB_INCLUDE_DIR} CACHE PATH "TBB include directory" FORCE) + set (TBB_LIBRARY_DIRS ${TBB_LIBRARY_DIR} CACHE PATH "TBB library directory" FORCE) + # Jiri: Self-built TBB stores the debug libraries in a separate directory. + set (TBB_DEBUG_LIBRARY_DIRS ${TBB_LIBRARY_DEBUG_DIR} CACHE PATH "TBB debug library directory" FORCE) + mark_as_advanced(TBB_INCLUDE_DIRS TBB_LIBRARY_DIRS TBB_DEBUG_LIBRARY_DIRS TBB_LIBRARIES TBB_DEBUG_LIBRARIES) + message(STATUS "Found Intel TBB") + endif (TBB_LIBRARY) +endif (TBB_INCLUDE_DIR) + +if (NOT TBB_FOUND) + message("ERROR: Intel TBB NOT found!") + message(STATUS "Looked for Threading Building Blocks in ${_TBB_INSTALL_DIR}") + # do only throw fatal, if this pkg is REQUIRED + if (TBB_FIND_REQUIRED) + message(FATAL_ERROR "Could NOT find TBB library.") + endif (TBB_FIND_REQUIRED) +endif (NOT TBB_FOUND) + +endif (NOT _TBB_INSTALL_DIR) + +if (TBB_FOUND) + set(TBB_INTERFACE_VERSION 0) + FILE(READ "${TBB_INCLUDE_DIRS}/tbb/tbb_stddef.h" _TBB_VERSION_CONTENTS) + STRING(REGEX REPLACE ".*#define TBB_INTERFACE_VERSION ([0-9]+).*" "\\1" TBB_INTERFACE_VERSION "${_TBB_VERSION_CONTENTS}") + set(TBB_INTERFACE_VERSION "${TBB_INTERFACE_VERSION}") +endif (TBB_FOUND) diff --git a/data/euroc_config.json b/data/euroc_config.json new file mode 100644 index 0000000..22949a6 --- /dev/null +++ b/data/euroc_config.json @@ -0,0 +1,30 @@ +{ + "value0": { + "config.optical_flow_type": "frame_to_frame", + "config.optical_flow_detection_grid_size": 50, + "config.optical_flow_max_recovered_dist2": 0.04, + "config.optical_flow_pattern": 51, + "config.optical_flow_max_iterations": 5, + "config.optical_flow_epipolar_error": 0.005, + "config.optical_flow_levels": 3, + "config.vio_max_states": 3, + "config.vio_max_kfs": 7, + "config.vio_min_frames_after_kf": 5, + "config.vio_new_kf_keypoints_thresh": 0.7, + "config.vio_max_iterations": 5, + "config.vio_debug": false, + "config.vio_obs_std_dev": 0.5, + "config.vio_obs_huber_thresh": 1.0, + + "config.mapper_obs_std_dev": 0.25, + "config.mapper_obs_huber_thresh": 1.5, + "config.mapper_detection_num_points": 800, + "config.mapper_num_frames_to_match": 30, + "config.mapper_frames_to_match_threshold": 0.3, + "config.mapper_min_matches": 20, + "config.mapper_ransac_threshold": 5e-5, + "config.mapper_min_track_length": 5, + "config.mapper_max_hamming_distance": 70, + "config.mapper_second_best_test_ratio": 1.2 + } +} diff --git a/data/euroc_ds_calib.json b/data/euroc_ds_calib.json new file mode 100644 index 0000000..83e1872 --- /dev/null +++ b/data/euroc_ds_calib.json @@ -0,0 +1,213 @@ +{ + "value0": { + "T_imu_cam": [ + { + "px": -0.016774788924641534, + "py": -0.068938940687127, + "pz": 0.005139123188382424, + "qx": -0.007239825785317818, + "qy": 0.007541278561558601, + "qz": 0.7017845426564943, + "qw": 0.7123125505904486 + }, + { + "px": -0.01507436282032619, + "py": 0.0412627204046637, + "pz": 0.00316287258752953, + "qx": -0.0023360576185881625, + "qy": 0.013000769689092388, + "qz": 0.7024677108343111, + "qw": 0.7115930283929829 + } + ], + "intrinsics": [ + { + "camera_type": "ds", + "intrinsics": { + "fx": 349.7560023050409, + "fy": 348.72454229977037, + "cx": 365.89440762590149, + "cy": 249.32995565708704, + "xi": -0.2409573942178872, + "alpha": 0.566996899163044 + } + }, + { + "camera_type": "ds", + "intrinsics": { + "fx": 361.6713883800533, + "fy": 360.5856493689301, + "cx": 379.40818394080869, + "cy": 255.9772968522045, + "xi": -0.21300835384809328, + "alpha": 0.5767008625037023 + } + } + ], + "resolution": [ + [ + 752, + 480 + ], + [ + 752, + 480 + ] + ], + "vignette": [ + { + "value0": 0, + "value1": 50000000000, + "value2": [ + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 0.977014799737916 + ], + [ + 0.963099657065011 + ], + [ + 0.922192868484681 + ], + [ + 0.854947649264748 + ], + [ + 0.775979681731632 + ], + [ + 0.722888431826212 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ] + ] + }, + { + "value0": 0, + "value1": 50000000000, + "value2": [ + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 0.977014799737916 + ], + [ + 0.963099657065011 + ], + [ + 0.922192868484681 + ], + [ + 0.854947649264748 + ], + [ + 0.775979681731632 + ], + [ + 0.722888431826212 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ] + ] + } + ], + "calib_accel_bias": [ + 0.001725405479279035, + 0.1500005286487319, + 0.06708820471592454, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "calib_gyro_bias": [ + -0.002186848441668376, + 0.024427823167917037, + 0.07668367023977922, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "imu_update_rate": 200.0, + "accel_noise_std": 0.016, + "gyro_noise_std": 0.000282, + "accel_bias_std": 0.001, + "gyro_bias_std": 0.0001, + "T_mocap_world": { + "px": 0.0, + "py": 0.0, + "pz": 0.0, + "qx": 0.0, + "qy": 0.0, + "qz": 0.0, + "qw": 1.0 + }, + "T_imu_marker": { + "px": 0.0, + "py": 0.0, + "pz": 0.0, + "qx": 0.0, + "qy": 0.0, + "qz": 0.0, + "qw": 1.0 + }, + "mocap_time_offset_ns": 0, + "mocap_to_imu_offset_ns": 140763258159875, + "cam_time_offset_ns": 0 + } +} diff --git a/data/euroc_eucm_calib.json b/data/euroc_eucm_calib.json new file mode 100644 index 0000000..9973a89 --- /dev/null +++ b/data/euroc_eucm_calib.json @@ -0,0 +1,213 @@ +{ + "value0": { + "T_imu_cam": [ + { + "px": -0.016774788924641534, + "py": -0.068938940687127, + "pz": 0.005139123188382424, + "qx": -0.007239825785317818, + "qy": 0.007541278561558601, + "qz": 0.7017845426564943, + "qw": 0.7123125505904486 + }, + { + "px": -0.01507436282032619, + "py": 0.0412627204046637, + "pz": 0.00316287258752953, + "qx": -0.0023360576185881625, + "qy": 0.013000769689092388, + "qz": 0.7024677108343111, + "qw": 0.7115930283929829 + } + ], + "intrinsics": [ + { + "camera_type": "eucm", + "intrinsics": { + "fx": 460.76484651566468, + "fy": 459.4051018049483, + "cx": 365.8937161309615, + "cy": 249.33499869752445, + "alpha": 0.5903365915227143, + "beta": 1.127468196965374 + } + }, + { + "camera_type": "eucm", + "intrinsics": { + "fx": 459.55216904505178, + "fy": 458.17181312352059, + "cx": 379.4066773637502, + "cy": 255.98301446219285, + "alpha": 0.6049889282227827, + "beta": 1.0907289821146678 + } + } + ], + "resolution": [ + [ + 752, + 480 + ], + [ + 752, + 480 + ] + ], + "vignette": [ + { + "value0": 0, + "value1": 50000000000, + "value2": [ + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 0.977014799737916 + ], + [ + 0.963099657065011 + ], + [ + 0.922192868484681 + ], + [ + 0.854947649264748 + ], + [ + 0.775979681731632 + ], + [ + 0.722888431826212 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ] + ] + }, + { + "value0": 0, + "value1": 50000000000, + "value2": [ + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 1.0 + ], + [ + 0.977014799737916 + ], + [ + 0.963099657065011 + ], + [ + 0.922192868484681 + ], + [ + 0.854947649264748 + ], + [ + 0.775979681731632 + ], + [ + 0.722888431826212 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ], + [ + 0.0686113338332548 + ] + ] + } + ], + "calib_accel_bias": [ + 0.001725405479279035, + 0.1500005286487319, + 0.06708820471592454, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "calib_gyro_bias": [ + -0.002186848441668376, + 0.024427823167917037, + 0.07668367023977922, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "imu_update_rate": 200.0, + "accel_noise_std": 0.016, + "gyro_noise_std": 0.000282, + "accel_bias_std": 0.001, + "gyro_bias_std": 0.0001, + "T_mocap_world": { + "px": 0.0, + "py": 0.0, + "pz": 0.0, + "qx": 0.0, + "qy": 0.0, + "qz": 0.0, + "qw": 1.0 + }, + "T_imu_marker": { + "px": 0.0, + "py": 0.0, + "pz": 0.0, + "qx": 0.0, + "qy": 0.0, + "qz": 0.0, + "qw": 1.0 + }, + "mocap_time_offset_ns": 0, + "mocap_to_imu_offset_ns": 140763258159875, + "cam_time_offset_ns": 0 + } +} diff --git a/data/tumvi_512_config.json b/data/tumvi_512_config.json new file mode 100644 index 0000000..5f189c4 --- /dev/null +++ b/data/tumvi_512_config.json @@ -0,0 +1,30 @@ +{ + "value0": { + "config.optical_flow_type": "frame_to_frame", + "config.optical_flow_detection_grid_size": 40, + "config.optical_flow_max_recovered_dist2": 0.04, + "config.optical_flow_pattern": 51, + "config.optical_flow_max_iterations": 5, + "config.optical_flow_epipolar_error": 0.005, + "config.optical_flow_levels": 3, + "config.vio_max_states": 3, + "config.vio_max_kfs": 7, + "config.vio_min_frames_after_kf": 5, + "config.vio_new_kf_keypoints_thresh": 0.7, + "config.vio_max_iterations": 5, + "config.vio_debug": false, + "config.vio_obs_std_dev": 0.5, + "config.vio_obs_huber_thresh": 1.0, + + "config.mapper_obs_std_dev": 0.25, + "config.mapper_obs_huber_thresh": 1.5, + "config.mapper_detection_num_points": 800, + "config.mapper_num_frames_to_match": 30, + "config.mapper_frames_to_match_threshold": 0.3, + "config.mapper_min_matches": 20, + "config.mapper_ransac_threshold": 5e-5, + "config.mapper_min_track_length": 5, + "config.mapper_max_hamming_distance": 70, + "config.mapper_second_best_test_ratio": 1.2 + } +} diff --git a/data/tumvi_512_ds_calib.json b/data/tumvi_512_ds_calib.json new file mode 100644 index 0000000..1f5d4b8 --- /dev/null +++ b/data/tumvi_512_ds_calib.json @@ -0,0 +1,381 @@ +{ + "value0": { + "T_imu_cam": [ + { + "px": 0.04548094812071685, + "py": -0.07145370002838907, + "pz": -0.046315428444919249, + "qx": -0.013392900690257393, + "qy": -0.6945866755293793, + "qz": 0.7192437840259219, + "qw": 0.007639340823570553 + }, + { + "px": -0.05546984222234079, + "py": -0.06999334244486549, + "pz": -0.049092582974927929, + "qx": -0.01340980138125811, + "qy": -0.7115668842588793, + "qz": 0.7024477338114514, + "qw": 0.007741299385907546 + } + ], + "intrinsics": [ + { + "camera_type": "ds", + "intrinsics": { + "fx": 158.28600034966977, + "fy": 158.2743455478755, + "cx": 254.96116578191653, + "cy": 256.8894394501779, + "xi": -0.17213086034353243, + "alpha": 0.5931177593944744 + } + }, + { + "camera_type": "ds", + "intrinsics": { + "fx": 157.91830144176309, + "fy": 157.8901286125632, + "cx": 252.56547609702953, + "cy": 255.02489416194656, + "xi": -0.17114780716007858, + "alpha": 0.5925543396658507 + } + } + ], + "resolution": [ + [ + 512, + 512 + ], + [ + 512, + 512 + ] + ], + "calib_accel_bias": [ + -0.0011791549110128743, + -0.007714616665106584, + 0.00006733124206236036, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "calib_gyro_bias": [ + -0.00007403817898158015, + 0.0000024090695654577384, + -0.00001847724206614636, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "imu_update_rate": 200.0, + "accel_noise_std": 0.016, + "gyro_noise_std": 0.000282, + "accel_bias_std": 0.001, + "gyro_bias_std": 0.0001, + "T_mocap_world": { + "px": 0.0, + "py": 0.0, + "pz": 0.0, + "qx": 0.0, + "qy": 0.0, + "qz": 0.0, + "qw": 1.0 + }, + "T_imu_marker": { + "px": 0.0, + "py": 0.0, + "pz": 0.0, + "qx": 0.0, + "qy": 0.0, + "qz": 0.0, + "qw": 1.0 + }, + "mocap_time_offset_ns": 0, + "mocap_to_imu_offset_ns": 0, + "cam_time_offset_ns": 0, + "vignette": [ + { + "value0": 0, + "value1": 10000000000, + "value2": [ + [ + 0.9899372881888493 + ], + [ + 0.9931178795891834 + ], + [ + 0.9984407803536122 + ], + [ + 0.996964178110498 + ], + [ + 0.9956605833036875 + ], + [ + 0.9973489553595134 + ], + [ + 0.9985691891331739 + ], + [ + 1.0 + ], + [ + 0.9966866746094087 + ], + [ + 0.9958706368580655 + ], + [ + 0.9957807702286541 + ], + [ + 0.9927911027519979 + ], + [ + 0.9838733297580375 + ], + [ + 0.9719198145611155 + ], + [ + 0.9566058020047663 + ], + [ + 0.9378032130699772 + ], + [ + 0.9194004905192558 + ], + [ + 0.9024065312353705 + ], + [ + 0.8845584821495792 + ], + [ + 0.8624817202873822 + ], + [ + 0.8449163722596605 + ], + [ + 0.8239771250783265 + ], + [ + 0.802936456716557 + ], + [ + 0.7811632337206126 + ], + [ + 0.758539495055499 + ], + [ + 0.7341063700839284 + ], + [ + 0.7100276770866111 + ], + [ + 0.6874554816035845 + ], + [ + 0.6641863547515791 + ], + [ + 0.6412571843680321 + ], + [ + 0.6228323769487529 + ], + [ + 0.6030940673078892 + ], + [ + 0.5598212055840929 + ], + [ + 0.4377741720108287 + ], + [ + 0.24026566347390075 + ], + [ + 0.08222347033252997 + ], + [ + 0.03489917830551274 + ], + [ + 0.029153547460757366 + ], + [ + 0.030477276736751079 + ], + [ + 0.01 + ], + [ + 0.01 + ], + [ + 0.01 + ], + [ + 0.01 + ] + ] + }, + { + "value0": 0, + "value1": 10000000000, + "value2": [ + [ + 0.9982144512705363 + ], + [ + 0.9961165266369948 + ], + [ + 0.9892083034957775 + ], + [ + 0.9870647327777502 + ], + [ + 0.9863145153017516 + ], + [ + 0.9847218081828388 + ], + [ + 0.9828536767530198 + ], + [ + 0.9808724309018916 + ], + [ + 0.9797280962140972 + ], + [ + 0.9784762156394231 + ], + [ + 0.9771015659455632 + ], + [ + 0.9730709135912151 + ], + [ + 0.9650117828320545 + ], + [ + 0.9512319166574508 + ], + [ + 0.9346333455674182 + ], + [ + 0.9182278021221385 + ], + [ + 0.9025351121100457 + ], + [ + 0.8845788263796353 + ], + [ + 0.8668369304290567 + ], + [ + 0.8469326512989164 + ], + [ + 0.8280417962134851 + ], + [ + 0.8072181976634909 + ], + [ + 0.788496496511515 + ], + [ + 0.7691952807935 + ], + [ + 0.7459299901795546 + ], + [ + 0.7240742868053557 + ], + [ + 0.7009088004583106 + ], + [ + 0.6799474150660547 + ], + [ + 0.6586062723412073 + ], + [ + 0.6406388063878976 + ], + [ + 0.6239758367746359 + ], + [ + 0.6026729560290718 + ], + [ + 0.5455288113795859 + ], + [ + 0.3945979030583888 + ], + [ + 0.1981919324270445 + ], + [ + 0.06754460426558173 + ], + [ + 0.028910567836990938 + ], + [ + 0.02842995279817033 + ], + [ + 0.0299618927515648 + ], + [ + 0.01 + ], + [ + 0.01 + ], + [ + 0.01 + ], + [ + 0.01 + ] + ] + } + ] + } +} diff --git a/data/tumvi_512_eucm_calib.json b/data/tumvi_512_eucm_calib.json new file mode 100644 index 0000000..50010a8 --- /dev/null +++ b/data/tumvi_512_eucm_calib.json @@ -0,0 +1,381 @@ +{ + "value0": { + "T_imu_cam": [ + { + "px": 0.04548094812071685, + "py": -0.07145370002838907, + "pz": -0.046315428444919249, + "qx": -0.013392900690257393, + "qy": -0.6945866755293793, + "qz": 0.7192437840259219, + "qw": 0.007639340823570553 + }, + { + "px": -0.05546984222234079, + "py": -0.06999334244486549, + "pz": -0.049092582974927929, + "qx": -0.01340980138125811, + "qy": -0.7115668842588793, + "qz": 0.7024477338114514, + "qw": 0.007741299385907546 + } + ], + "intrinsics": [ + { + "camera_type": "eucm", + "intrinsics": { + "fx": 191.14799836282189, + "fy": 191.13150963902818, + "cx": 254.9585771534443, + "cy": 256.88154645599448, + "alpha": 0.6291060881178562, + "beta": 1.0418067381860868 + } + }, + { + "camera_type": "eucm", + "intrinsics": { + "fx": 190.47905769226575, + "fy": 190.44567561523216, + "cx": 252.55882115024333, + "cy": 255.02104780344699, + "alpha": 0.6281040684983363, + "beta": 1.041250259119081 + } + } + ], + "resolution": [ + [ + 512, + 512 + ], + [ + 512, + 512 + ] + ], + "calib_accel_bias": [ + -0.0011791549110128743, + -0.007714616665106584, + 0.00006733124206236036, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "calib_gyro_bias": [ + -0.00007403817898158015, + 0.0000024090695654577384, + -0.00001847724206614636, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0 + ], + "imu_update_rate": 200.0, + "accel_noise_std": 0.016, + "gyro_noise_std": 0.000282, + "accel_bias_std": 0.001, + "gyro_bias_std": 0.0001, + "T_mocap_world": { + "px": 0.0, + "py": 0.0, + "pz": 0.0, + "qx": 0.0, + "qy": 0.0, + "qz": 0.0, + "qw": 1.0 + }, + "T_imu_marker": { + "px": 0.0, + "py": 0.0, + "pz": 0.0, + "qx": 0.0, + "qy": 0.0, + "qz": 0.0, + "qw": 1.0 + }, + "mocap_time_offset_ns": 0, + "mocap_to_imu_offset_ns": 0, + "cam_time_offset_ns": 0, + "vignette": [ + { + "value0": 0, + "value1": 10000000000, + "value2": [ + [ + 0.9899372881888493 + ], + [ + 0.9931178795891834 + ], + [ + 0.9984407803536122 + ], + [ + 0.996964178110498 + ], + [ + 0.9956605833036875 + ], + [ + 0.9973489553595134 + ], + [ + 0.9985691891331739 + ], + [ + 1.0 + ], + [ + 0.9966866746094087 + ], + [ + 0.9958706368580655 + ], + [ + 0.9957807702286541 + ], + [ + 0.9927911027519979 + ], + [ + 0.9838733297580375 + ], + [ + 0.9719198145611155 + ], + [ + 0.9566058020047663 + ], + [ + 0.9378032130699772 + ], + [ + 0.9194004905192558 + ], + [ + 0.9024065312353705 + ], + [ + 0.8845584821495792 + ], + [ + 0.8624817202873822 + ], + [ + 0.8449163722596605 + ], + [ + 0.8239771250783265 + ], + [ + 0.802936456716557 + ], + [ + 0.7811632337206126 + ], + [ + 0.758539495055499 + ], + [ + 0.7341063700839284 + ], + [ + 0.7100276770866111 + ], + [ + 0.6874554816035845 + ], + [ + 0.6641863547515791 + ], + [ + 0.6412571843680321 + ], + [ + 0.6228323769487529 + ], + [ + 0.6030940673078892 + ], + [ + 0.5598212055840929 + ], + [ + 0.4377741720108287 + ], + [ + 0.24026566347390075 + ], + [ + 0.08222347033252997 + ], + [ + 0.03489917830551274 + ], + [ + 0.029153547460757366 + ], + [ + 0.030477276736751079 + ], + [ + 0.01 + ], + [ + 0.01 + ], + [ + 0.01 + ], + [ + 0.01 + ] + ] + }, + { + "value0": 0, + "value1": 10000000000, + "value2": [ + [ + 0.9982144512705363 + ], + [ + 0.9961165266369948 + ], + [ + 0.9892083034957775 + ], + [ + 0.9870647327777502 + ], + [ + 0.9863145153017516 + ], + [ + 0.9847218081828388 + ], + [ + 0.9828536767530198 + ], + [ + 0.9808724309018916 + ], + [ + 0.9797280962140972 + ], + [ + 0.9784762156394231 + ], + [ + 0.9771015659455632 + ], + [ + 0.9730709135912151 + ], + [ + 0.9650117828320545 + ], + [ + 0.9512319166574508 + ], + [ + 0.9346333455674182 + ], + [ + 0.9182278021221385 + ], + [ + 0.9025351121100457 + ], + [ + 0.8845788263796353 + ], + [ + 0.8668369304290567 + ], + [ + 0.8469326512989164 + ], + [ + 0.8280417962134851 + ], + [ + 0.8072181976634909 + ], + [ + 0.788496496511515 + ], + [ + 0.7691952807935 + ], + [ + 0.7459299901795546 + ], + [ + 0.7240742868053557 + ], + [ + 0.7009088004583106 + ], + [ + 0.6799474150660547 + ], + [ + 0.6586062723412073 + ], + [ + 0.6406388063878976 + ], + [ + 0.6239758367746359 + ], + [ + 0.6026729560290718 + ], + [ + 0.5455288113795859 + ], + [ + 0.3945979030583888 + ], + [ + 0.1981919324270445 + ], + [ + 0.06754460426558173 + ], + [ + 0.028910567836990938 + ], + [ + 0.02842995279817033 + ], + [ + 0.0299618927515648 + ], + [ + 0.01 + ], + [ + 0.01 + ], + [ + 0.01 + ], + [ + 0.01 + ] + ] + } + ] + } +} diff --git a/doc/Calibration.md b/doc/Calibration.md new file mode 100644 index 0000000..617e153 --- /dev/null +++ b/doc/Calibration.md @@ -0,0 +1,117 @@ +# Calibration + +Here, we explain how to use the calibration tools with [TUM-VI](https://vision.in.tum.de/data/datasets/visual-inertial-dataset) and [EuRoC](https://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) datasets as an example. + + +## TUM-VI dataset +Download the datasets for camera and camera-IMU calibration: +``` +mkdir ~/tumvi_calib_data +cd ~/tumvi_calib_data +wget http://vision.in.tum.de/tumvi/calibrated/512_16/dataset-calib-cam3_512_16.bag +wget http://vision.in.tum.de/tumvi/calibrated/512_16/dataset-calib-imu1_512_16.bag +``` + +### Camera calibration +Run the camera calibration: +``` +basalt_calibrate --dataset-path ~/tumvi_calib_data/dataset-calib-cam3_512_16.bag --dataset-type bag --result-path ~/tumvi_calib_result/ --cam-types ds ds +``` +The command line options have the following meaning: +* `--dataset-path` path to the dataset. +* `--dataset-type` type of the datset. Currently only `bag` and `euroc` formats of the datasets are supported. +* `--result-path` path to the folder where the resulting calibration and intermediate results will be stored. +* `--cam-types` camera models for the image streams in the dataset. For more detais see [arXiv:1807.08957](https://arxiv.org/abs/1807.08957). + +After that, you should see the calibration GUI: +![tumvi_cam_calib](doc/img/tumvi_cam_calib.png) + +The buttons in the GUI are located in the order which you should follow to calibrate the camera: +* `load_dataset` loads the dataset. +* `detect_corners` starts corner detection in the backround thread. Since it is the most time consuming part of the calibration process, the detected corners are cached and loaded if you run the executable again pointing to the same result folder path. +* `init_cam_intr` computes an initial guess for camera intrinsics. +* `init_cam_poses` computes an initial guess for camera poses given the current intrinsics. +* `init_cam_extr` computes an initial transformation between the cameras. +* `init_opt` initializes optimization and shows the projected points given the current calibration and camera poses. +* `optimize` runs an iteration of the optimization and visualizes the result. You should press this button until the error printed in the console output stops decreasing and the optimization converges. +* `save_calib` saves the current calibration as `calibration.json` in the result folder. +* `compute_vign` **(Experimental)** computes a radially-symmetric vignetting for the cameras. For the algorithm to work, **the calibration pattern should be static (and camera moving around it) and have a constant lighting throughout the calibration sequence**. If you run `compute_vign` you should press `save_calib` afterwards. The png images with vignetting will also be stored in the result folder. + +You can also control the process using the following buttons: +* `show_frame` slider to switch between the frames in the sequence. +* `show_corners` toggles the visibility of the detected corners shown in red. +* `show_corners_rejected` toggles the visibility of rejected corners. +* `show_init_reproj` shows the initial reprojections computed by the `init_cam_poses` step. +* `show_opt` shows reprojected corners with the current estimate of the intrinsics and poses. +* `show_vign` toggles the visibility of the points used for vignetting estimation. The points are distributed across white areas of the pattern. +* `show_ids` toggles the ID visualization for every point. +* `huber_thresh` controls the threshold for the huber norm in pixels for the optimization. +* `opt_intr` controls if the optimization can change the intrinsics. For some datasets it might be helpful to disable this option for several first iterations of the optimization. + +### Camera + IMU + Mocap calibration +After calibrating the camera you can run the camera + IMU + Mocap calibration. The result path should point to the **same folder as before**: +``` +basalt_calibrate_imu --dataset-path ~/tumvi_calib_data/dataset-calib-imu1_512_16.bag --dataset-type bag --result-path ~/tumvi_calib_result/ --gyro-noise-std 0.000282 --accel-noise-std 0.016 --gyro-bias-std 0.0001 --accel-bias-std 0.001 +``` +The command line options for the IMU noise are continous-time and defined as in [Kalibr](https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model): +* `--gyro-noise-std` gyroscope white noise. +* `--accel-noise-std` accelerometer white noise. +* `--gyro-bias-std` gyroscope random walk. +* `--accel-bias-std` accelerometer random walk. + +![tumvi_imu_calib](doc/img/tumvi_imu_calib.png) + +The buttons in the GUI are located in the order which you need to follow to calibrate the camera-IMU setup: +* `load_dataset`, `detect_corners`, `init_cam_poses` same as above. +* `init_cam_imu` initializes the rotation between camera and IMU by aligning rotation velocities of the camera to the gyro data. +* `init_opt` initializes the optimization. Shows reprojected corners in magenta and the estimated values from the spline as solid lines below. +* `optimize` runs an iteration of the optimization. You should press it several times until convergence before proceeding to next steps. +* `init_mocap` initializes the transformation from the Aprilgrid calibration pattern to the Mocap coordinate system. **Currently we assume that the orientation of the Mocap marker frame is approximately aligned with IMU axes**. +* `save_calib` save the current calibration as `calibration.json` in the result folder. +* `save_mocap_calib` save the current Mocap to IMU calibration as `mocap_calibration.json` in the result folder. + +You can also control the visualization using the following buttons: +* `show_frame` - `show_ids` the same as above. +* `show_spline` toggles the visibility of enabled measurements (accel, gyro, position, velocity) generated from the spline that we optimize. +* `show_data` toggles the visibility of raw data containted in the dataset. +* `show_accel` shows accelerometer data. +* `show_gyro` shows gyroscope data. +* `show_pos` shows the position data. +* `show_mocap` shows the mocap marker position transformed to the IMU frame. +* `show_mocap_rot_error` shows rotation between the spline and Mocap measurements. +* `show_mocap_rot_vel` shows the rotation velocity computed from the Mocap. + +The following options control the optimization process: +* `opt_intr` enables optimization of intrinsics. Usually should be disabled for the camera-IMU calibration. +* `opt_poses` enables optimization based camera pose initialization. Sometimes helps to better initialize the spline before running optimization with `opt_corners`. +* `opt_corners` enables optimization based on reprojection corner positions **(should be used by default)**. +* `opt_cam_time_offset` computes the time offset between camera and the IMU. This option should be used only for refinement when the optimization already converged. +* `opt_imu_scale` enables IMU axis scaling, rotation and mislignment calibration. This option should be used only for refinement when the optimization already converged. +* `opt_mocap` enables Mocap optimization. You should run it only after pressing `init_mocap`. +* `huber_thresh` controls the threshold for the huber norm in pixels for the optimization. + + +**NOTE:** In this case the we use pre-calibrated sequence, so most of refinements or Mocap to IMU calibration will not have any visible effect. If you want to test this functionality use the "raw" sequences, for example `http://vision.in.tum.de/tumvi/raw/dataset-calib-cam3.bag` and `http://vision.in.tum.de/tumvi/raw/dataset-calib-imu1.bag`. + +## EuRoC dataset +Download the datasets for camera and camera-IMU calibration: +``` +mkdir ~/euroc_calib_data +cd ~/euroc_calib_data +wget http://robotics.ethz.ch/~asl-datasets/ijrr_euroc_mav_dataset/calibration_datasets/cam_april/cam_april.bag +wget http://robotics.ethz.ch/~asl-datasets/ijrr_euroc_mav_dataset/calibration_datasets/imu_april/imu_april.bag +``` + +### Camera calibration +Run the camera calibration: +``` +basalt_calibrate --dataset-path ~/euroc_calib_data/cam_april.bag --dataset-type bag --result-path ~/euroc_calib_result/ --cam-types ds ds +``` +![euroc_cam_calib](doc/img/euroc_cam_calib.png) + +### Camera + IMU calibration +After calibrating the camera you can run the camera + IMU calibration. The result-path should point to the same folder as before: +``` +basalt_calibrate_imu --dataset-path ~/euroc_calib_data/imu_april.bag --dataset-type bag --result-path ~/euroc_calib_result/ --gyro-noise-std 0.000282 --accel-noise-std 0.016 --gyro-bias-std 0.0001 --accel-bias-std 0.001 +``` +![euroc_imu_calib](doc/img/euroc_imu_calib.png) diff --git a/doc/Simulation.md b/doc/Simulation.md new file mode 100644 index 0000000..fa63ad7 --- /dev/null +++ b/doc/Simulation.md @@ -0,0 +1,50 @@ +## Simulator + +For better evaluation of the system we use the simulated environment where the optical flow and IMU data is generated from the ground truth by adding noise. + +**Note:** The path to calibration and configuration files used here works for the APT installation. If you compile from source specify the appropriate path to the files in [data folder](data/). + + +### Visual-inertial odometry simulator +``` +basalt_vio_sim --cam-calib /usr/etc/basalt/euroc_ds_calib.json --marg-data sim_marg_data --show-gui 1 +``` + +The command line options have the following meaning: +* `--cam-calib` path to camera calibration file. Check [calibration instructions](doc/Calibration.md) to see how the calibration was generated. +* `--marg-data` folder where the data from keyframe marginalization will be stored. This data can be later used for visual-inertial mapping simulator. +* `--show-gui` enables or disables GUI. + +This opens the GUI and runs the sequence. +![SIM_VIO](doc/img/SIM_VIO.png) + +The buttons in the GUI have the following meaning: +* `show_obs` toggles the visibility the ground-truth landmarks in the image view. +* `show_noisy` toggles the visibility the noisy landmarks in the image view. +* `show_vio` toggles the visibility the landmarks estimated by VIO in the image view. +* `show_ids` toggles the IDs of the landmarks. +* `show_accel` shows noisy accelerometer measurements generated from ground truth spline. +* `show_gyro` shows noisy gyroscope measurements generated from ground truth spline. +* `show_gt_...` shows ground truth position, velocity and biases. +* `show_est_...` shows VIO estimates of the position, velocity and biases. +* `next_step` proceeds to next frame. +* `continue` plays the sequence. +* `align_button` performs SE(3) alignment with ground-truth trajectory and prints the RMS ATE to the console. + + +### Visual-inertial mapping simulator +``` +basalt_mapper_sim --cam-calib /usr/etc/basalt/euroc_ds_calib.json --marg-data sim_marg_data --show-gui 1 +``` +The command line arguments are the same as above. + +This opens the GUI where the map can be processed. +![SIM_MAPPER](doc/img/SIM_MAPPER.png) + +The system processes the marginalization data and extracts the non-linear factors from them. Roll-pitch and relative-pose factors are initially added to the system. One way to verify that they result in gravity-aligned map is the following +* `optimize` runs the optimization +* `rand_inc` applies a random increment to all frames of the system. If you run the `optimize` until convergence afterwards, and press `align_svd` the alignment transformation should only contain the rotation around Z axis. +* `rand_yaw` applies an increment in yaw to all poses. This should not change the error of the optimization once is have converged. +* `setup_points` triangulates the points and adds them to optimization. You should optimize the system again after adding the points. + +For comparison we also provide the `basalt_mapper_sim_naive` executable that has the same parameters. It runs a global bundle-adjustment on keyframe data and inserts pre-integrated IMU measurements between keyframes. This executable is included for comparison only. \ No newline at end of file diff --git a/doc/VioMapping.md b/doc/VioMapping.md new file mode 100644 index 0000000..3e0c958 --- /dev/null +++ b/doc/VioMapping.md @@ -0,0 +1,86 @@ +## EuRoC dataset + +We demonstrate the usage of the system with the `MH_05_difficult` sequence of the [EuRoC dataset](https://projects.asl.ethz.ch/datasets/doku.php?id=kmavvisualinertialdatasets) as an example. + +**Note:** The path to calibration and configuration files used here works for the APT installation. If you compile from source specify the appropriate path to the files in [data folder](data/). + +Download the sequence from the dataset and extract it. +``` +mkdir euroc_data +cd euroc_data +wget http://robotics.ethz.ch/~asl-datasets/ijrr_euroc_mav_dataset/machine_hall/MH_05_difficult/MH_05_difficult.zip +mkdir MH_05_difficult +cd MH_05_difficult +unzip ../MH_05_difficult.zip +cd ../ +``` + +### Visual-inertial odometry +To run the visual-inertial odometry execute the following command in `euroc_data` folder where you downloaded the dataset. +``` +basalt_vio --dataset-path MH_05_difficult/ --cam-calib /usr/etc/basalt/euroc_ds_calib.json --dataset-type euroc --config-path /usr/etc/basalt/euroc_config.json --marg-data euroc_marg_data --show-gui 1 +``` +The command line options have the following meaning: +* `--dataset-path` path to the dataset. +* `--dataset-type` type of the datset. Currently only `bag` and `euroc` formats of the datasets are supported. +* `--cam-calib` path to camera calibration file. Check [calibration instructions](doc/Calibration.md) to see how the calibration was generated. +* `--marg-data` folder where the data from keyframe marginalization will be stored. This data can be later used for visual-inertial mapping. +* `--show-gui` enables or disables GUI. + +This opens the GUI and runs the sequence. The processing happens in the background as fast as possible, and the visualization results are saved in GUI and can be analysed offline. +![MH_05_VIO](doc/img/MH_05_VIO.png) + +The buttons in the GUI have the following meaning: +* `show_obs` toggles the visibility the tracked landmarks in the image view. +* `show_ids` toggles the IDs of the points. +* `show_est_pos` shows the plot of the estimated position. +* `show_est_vel` shows the plot of the estimated velocity. +* `show_est_bg` shows the plot of the estimated gyro bias. +* `show_est_ba` shows the plot of the estimated accel bias. +* `show_ge` shows ground-truth trajectory in the 3D view. + +By default the system starts with `continue_fast` enabled. This option visualizes the latest processed frame until the end of the sequence. Alternatively, the `continue_btn` visualizes every frame without skipping. If both options are disabled the system shows the frame that is selected with `show_frame` slider and user can move forward and backward with `next_step` and `prev_step` buttons. The `follow` button changes between the static camera and the camera attached to the current frame. + +For evaluation the button `align_svd` is used. It aligns the GT trajectory with the current estimate with SE(3) transformation and prints the transformation and the root-mean-squared absolute trajectory error (RMS ATE). + +### Visual-inertial mapping +To run the mapping tool execute the following command: +``` +basalt_mapper --cam-calib /usr/etc/basalt/euroc_ds_calib.json --marg-data euroc_marg_data --vocabulary /usr/etc/basalt/orbvoc.dbow3 +``` +Here `--marg-data` is the folder with the results from VIO and `--vocabulary` is the path to DBoW3 vocabulary. + +This opens the GUI and extracts non-linear factors from the marginalization data. +![MH_05_MAPPING](doc/img/MH_05_MAPPING.png) + +The buttons in the GUI have the following meaning: +* `show_frame1`, `show_cam1`, `show_frame2`, `show_cam2` allows you to assign images to image view 1 and 2 from different timestamps and cameras. +* `show_detected` shows the detected keypoints in the image view window. +* `show_matches` shows feature matching results. +* `show_inliers` shows inlier matches after geometric verification. +* `show_ids` prints point IDs. Can be used to find the same point in two views to check matches and inliers. +* `show_gt` shows the ground-truth trajectory. +* `show_edges` shows the edges from the factors. Relative-pose factors in red, roll-pitch factors in magenta and bundle adjustment co-visibility edges in green. +* `show_points` shows 3D landmarks. + +The workflow for the mapping is the following: +* `detect` detect the keypoints in the keyframe images. +* `match` run the geometric 2D to 2D matching between image frames. +* `tracks` build tracks from 2D matches and triangulate the points. +* `optimize` run the optimization +* `align_svd` align ground-truth trajectory in SE(3) and print the transformation and the error. + +For more systematic evaulation see the evaluation scripts in `scripts/eval_full` folder. + +**NOTE: It appears that only the datasets in ASL Dataset Format (`euroc` dataset type in our notation) contain ground truth that is time-aligned to the IMU and camera images. It is located in `state_groundtruth_estimate0` folder. Bag files have raw Mocap measurements that are not time aligned and should not be used for evaluations.** + + + +### Optical Flow +The visual-inertial odometry relies on the optical flow results. To enable a better analysis of the system we also provide a separate optical flow executable +``` +basalt_opt_flow --dataset-path MH_05_difficult/ --cam-calib /usr/etc/basalt/euroc_ds_calib.json --dataset-type euroc --config-path /usr/etc/basalt/euroc_config.json --show-gui 1 +``` + +This will run the GUI and print an average track length after the dataset is processed. +![MH_05_OPT_FLOW](doc/img/MH_05_OPT_FLOW.png) \ No newline at end of file diff --git a/doc/img/MH_05_MAPPING.png b/doc/img/MH_05_MAPPING.png new file mode 100644 index 0000000000000000000000000000000000000000..bc7bd1e1e948abf1460bd15daade29a9aaa15981 GIT binary patch literal 416348 zcmZU*1yq~c)-?=;0>!Pxp#_RVahKu_MG6$x;1b*dEv~_ey97#cf_rg_l_J5lkW$;9x}?hSja~pmUR>g%1abwIcZ(roc&y%43qb*k5Z1!(*Rz+OhytJ83IC; zFDfYI$}iutguEn^CPk+*Anep9d|u0LdUCp+%A_q<_pU^?gsl8YAE|pZ6o7{fnY#zwE*Pah1h4+d=^r2+V;m-nLtridflF4YM=t)71V{B_2ZL-XE0z?7zpu3OTMR%bYs) zF6POSa99hS!>$qlLk}H&e~AAq0$B44aV9hRQAJ?HPkw1^nJX9=`#(byh6QV8Wl@yi z#T8nujSag|m+iupdkrHZ?1vm(R6g?X{u~^*U4zBrR#amc7V-V}ya~}aR)&q@zxN38 zaAQ1G$BQ#0jhOCV|Hw$etKgKCL4nezj(sM2@1(6of!3Enwih#3n?GIi^uMkhIiKsR z?W&SA2RT3n43~nu31~q@3EoO%jK0V%FXxf_3c#3GP=LYz6Lm30ViqQM#g1@kyAUZdp= z?@Fa$gkL{!nVUC_(`>M&rYpz6hH%mYXmVx7ZT){&if~ok4o{hwM4o5Cn4KAPr#t8! zKLB)?qN?5#EE3)~q>N`t*d9%@CrO>!*W%-IAfh09yh?~JqOaZ~4hJ$6{m-SMTja91 zeGc85E#eA%GekCdtH~>kF{I^~NpXorN?U1CDQ3dJF!ju5%?}fDiqZww=F)$h?R)V* z7r7D=5thLMJ^>|Y`y~b(b!E%iPK5PKmv69^IZev2R-pKv6|D&{FhpCK`q>EP?Gfrh z6e9j_?qEGqTL|=?nLIpPEsP2OB6O2}jji-fC5chMsxN~Qg|-$v9G8_;xQC(GYK#t1 zZYW9p-__1%jAZPJ>2$)1k@jp2@jSiiZ1CPsI$QqtV#Kv_eoRkCZrwUTFXo&YrVQL~#8DuYNf6ca)2rYy=_|aStE(}4 zqL0a!*wv$2My_LAR$}C-lPI-c4K`XKE6XQ~mi}v%5_rlhE!+_pDuu-1+Kz}9w7}Hy;giD@-INt!Ou7BO34Unt=?(X5CZTmr!E#iQ=@Zwz$ z>f6FZ+id41z|Rur%=^vJj=S%par@+-jshMd4=#XrCF;UKOYtMWv1k+t@t$xC?$vJT z{d?F>P2Ty@B7x@( zr}jsG3dRNLJe96aU2bKL6+LUUvJ(u=tVB!7nq&LA{3Ihi$KVlk_aV$|RShwPul`j} z`;?Ny4h8P_d29#<slsI&>*BsPVEAmoSfn}Gbx^6Co}dZn>6;WUUX*nJumj9 znx0G4X8F<__^F(na4Paj9s#GO&wlUk+ff!43NS`1l$TflScdEa0k8=>Llk493qD5P zzcXT0igCcy-}{=n`(|Imcgnc>v4+kqxUmyp_dD@$mO_wAgiurKS&@il?T!OQOV?bh{%}<9y2|-`d7P|R{?l={IqrG{Ji)doJ#eg(n zu+ACtXTC8gN>)jxrLT3w+{{mn=*+*@>d3DMO9A|+N2}m&Tx5TkCd2Duub&3B&7gm6 z%evHczvzc&+-{iNb3?Juh}+++3UbjH)E#OOb3}gFK@mit1h?55_x*(jj4P=MiYdzJ z?$U&B4r;myPxPx5yC83kzR5b_|Gz-nxK|)oU>UL)SN)0a`VKh#R(yq0F9V$ml^ z5tAV~!_q8V9bY2W*<)vUsDJD$hvsb8HVC5+>LNh-kjsR zjV3?O5wedRPNgb3eoPgT3q9MXZDyFRVqUwZl3>0$Ag5u#=|wMseYRk;?@&v(~j zHj*fQE09K*;C28Ul%Bf%t7`eWrV#EvajwFa@9hXU3}HyHf`iKHN5{L%Yz8syG}AnW z4&Kx)J=58BaE82RK5rm3xXymu{N*TasL+t?xD-E`6D*!GYcgwtaZOz7D| zyW8()MBxW~VKpn0D{rhb>GZz5N!=de!O_Fs3hjv9269@#Pf>{X`<(>V6h}Ye70} zr}EW;1%u&|kyiX;@ZaB!cq&gGVRs1Zv{kM_?iThj}>Jmdx@BGPwM@5>DkA}S4sZ@-(JMiAuZC_*M^3t@eS`V zscRqoCwKSus`B^VQFCkvYcQM^eh4_8qvxBOU5#;<(>p7-Od3%vCcfLcbCdI8K_=^L;@O*(dZS#*7tM7|)B8s~JS1|8p;>tCWYQk}*9~ zRphrg0u$TKL^5=Iuzs-9!K-amg@eLlFmkBFb5xh+c}Pj+&SuEkj7DQRKJ9LveFi_Q zXV@r$sbR7*AHNm4ej2=zL{WL5nlU*BwauTe)NVNliTVemEQr;U$CKWpyqaYb4vH9C zUb@*$u+(K5jfyL(q12A&w}$?z#~*8r&Nn4-`x%$JUV9PAqox&p|fv zX)wXRfCv<^C(QEHwWBTrxFu-lD*D9&-pYkT#wEjgY&?7I;|aYiRm-ejZ9-DPxuw;Q zB*&5OpD}x)C|3o~hS%UbGW?YZM@^!?fm>|p$$Qh5jj#gcCYG}tLC=|v)|x$*n5eBV zVQ^GY6gO^kQ3f}5bZ;Uz?#)R;cjT6^tNoL|TNvN;WZm6^YQjxzyU7%fZ0cf$+jdpm z270lg@E2wzsqDCE3`GXTsN2FVNGN?RTQGKl-`e!#snEr0=ofw^O&;l|9~7EyiBtbo zk2{W(h{xC8CIP7uiaR@<4XR=R!eCh+%{Qv)9EIA%>;Autdd`cANbY@F6;1j z5cCGnJ^vy2lg)eT{1Jt=il(YT5Uk~!$>E&oC6FZ=RCV@k^aXjU$(q2wu6Cm{zL@kT zFzvN!+B>#X3IPXehJ%!;gM%w%;FynR(PD>FgS8#+#cp%$-lR{Sj?x;u3r}dkPlmYI zk-sTiHKj;6@bbh+ayD`&MKC}QUCs`KyeBFqPWTlm+h z2=XrO?(P;gHl_x0#qPmM?u6r5UZ|cE;1+x?dN*A3*|6fpfY^emVE)!&{b=97M^OE1 zZ`|*mZ2~%0Ui+squSXeDspXjq-eJuxnbzltQrIIq-nV@xwN$^)@$@<>O%T;%4g(3lE>c_L(|7oVAubB;MGA-I)B0Eh|z(mds*hh(QHGbK9 z$vG$JcK7j*%l{QWDq0ZL?H`3SMK019kXnI()O4wOACS7Ot!>_}INtYUfb3>S>OtDf zj82QR@Usl-(;vQqQtu$7hK`@LTdHIC+U%;7lS`($wuIxY#%}W9cw&QID+=u@<%1$S zfgV+i%9IEFKsD;2c<+#x<_Qv)>pxZBKx%3d=pL_!#E*N>K96oIWaq)B78XVdBWb^* zVp8|e2JF|(1%6g}Jt4e>d)Rqp`gN8KNKL@LYBgwnwRV_~9Lle5$fYZG%XdDoG=UE! z;9(DLggb1-3+;3v4vXKhBr-lzr12uvl)CraqTE>qoMkX7TRn`|NfYwl8kFls?M*rD z@bP(9d0DNhBQ9I^Ddm-u`47`?R?Wex37isd03FK7>up>rtbz;HBre_e-h=T}m_6Sx z>Bi0`rPhR353?m|N=?pMj}X7yTNT#EKquk^Ygf@*Ej*HZm=@&3@>*Ly775Q^#uPQq zMN?FCM*OrAaLzaz;p3|$1}!qG7Logq+Y3i2IktU9H&vwB8#efVPQ2+2JLW#WgEgy34wU2R(b->*#lwx9on zY~{K|hE>E7uToXQkwtJTgC&M?OQ^fMT&L{k^mJe42Pio;wUgn}_lK2?tLnW?gd}np zW3I>}M7$q2j336A5n%afI!;*!UugH&Vt2R8YEdDYci-bQsHVtQ4Z6T(c|UthUU7D{k#Qlh%;2?M5CHeW*w49T82 zL;GF;oeSrqX1N*r7mG59{6LTlZMGy-+A%nlLIlyPPZ3JFBi58p8i~r|Sz3KhEUVl8 zu+16!v&IJIb4uP>%uFegJe8IuG^w{%E`BT}0B;q1JOPf4Ii!v!hmjelFG(ci-Cm?> zxAc?(#|mfJ(ygI=Y8k@d1p#H@HbV%zvhT#%wJeunvv$};5M?2MOp!%tC`JBm3I$Z1 zFSIAeb~1RepmwQAoxtdKBOVsaE0RL_vTnyW;9+0DJX`ScwhrMkCwJ>%CFh$bv~Re_ zi~DnrO@g^eE9pgf{5$8hc8A8cIj@70?6ZTQc?{#*jPtwstM7s@#U~vduopdS&DbTF zJj|dA91IF^=F2TWwJiSV;snVoLCeI=$qz9L|F>q(%82KIt_hXCfGBV5l1k;Tl%~X>8 ztx)_`T&Z~Y&@IsF9A?=rxzeX@#BrLIlV1=5GPj)?A1?gh`XIrrQzaJ-fEZ5S|P@N}%A5*siXb>hyKqKi;N z#?JP0eYXpBp}ORaDa>7(bH-=w@AIv;5k@45Qr`138~9O(#BdmdIrX_aKPGCxh`AZVb#58$_W4M^9YM+5ooc@ zPa=8m^BDWSoIPO;+0TN`*+=^#N{SsV)k{(HwXiIS=3S3zqG#T^2`f!U2y|&~j zO{h}3Cx6TlB92xfi$qgAX?MDe54b5eC!fs7VNm;Vh%Pv%{je?eIlJCFu5>C7n=vMm zRC9WUxM#L=;WQ)WH8{u{bTMh_ad{6_o-DI(Hs%tlb`By#)(&GXMOD>NZs>q1`|euG zjkt3)rOx1;a~*?V+>J$z>RIl+kla7m6m}(K3Bc;b=*7Cn5fdv{%NvuGkht?4zz+Jc zGX7zfZLRtUyLp-f;xjEoLOESjd9&Oh^rVc4JR7oIH~l12vfrPjGnPo&1ol_R^;=un zmFUPU!152;oc4s{60BlELviQey;zG1`}|K%TNpRcfMaNRLjqn58$r;eu7~~C&vZ63 zG*d?_m7+)N#znSy%bsJ8U5fWIZrm7y)4oaLbEUV6Vnxsq^x>k3)%SoEc%IbX=OVi- zg!PeJvs6OS7Ymh4?}N{(0DPyyh2>_?hR|<<68i#)FAxWk*;`}y!BD_hC;w(6O{ztL z5T|xoG2>WWQ>_b~>s$or@!+%k<*mBe+F6H!?kDHkg|j4$PC&JdqBzC=FeyVa)ft;} z2|r(2R_1#Z)}X8QwK`-atMOXHz`#IO$&&W=Y$}(QPpuyCdcZhkFSnDN%sc?>Oqw~P zu_N@1f0aslEpA$n`oOQTxN%={37&c3M3rj~)pS&cXcuai|A4_@27Smo_7ZCt#?Yqr zD++Wpy;JxBvD3Abq_k_7*>Gc1Bv5cErmV>IAKL@R51WrmV;MrOv~N1ke@6U{ec8dD zA>sj;o^-B*zH%4CZ?=WrX$DKJQSgKagGD%Eu7CBQWDoLyRDfPwL-~9Zw~agVj2qpz zh!Oj7EeP>z^Ry!mXUWOsw)NId?Hq35;UEjFp1!V0fmZ688%gEl+N3SF{T>v$YTe_H zFq8DM!2G9qL%9naS5=1ciplFwFjG}@Q#Z+4se`|ieLN9Q=uG2ymBAC5ghO_E@d?$C zI?~7_-2nu21oBAu!r1*x2TCF0!M^b)m6BoYx)CT1Gsf!Xrryf5dLRKCuJ z10(l->S!8y*p&C<1IH3VKc?($g=LwGX*kN5=V|L!@f&GgOP1-e8Jo~W5-A?=%U)KW zj93iY?o28kv@lphh1(CmPvN|%Rd9UK&tv2`J`x(buTx&|vHK}1j1*hk$n|K|X7sm@ z$>H$!4;A3~`b&}Z1ZU^FHfRd8z1?r|EQ3^DjgFcT!)188MKT@DLFOWk`&Y^~Z#E3p zTNCopDCA?%(8h0vRH(}9ymRq9jLRQctiUmLaG&1-hiU`Bf!f26ygqYI?n0z>0(i}r zXt3GE$-i_3`5>3@p?lDp=M11|K0n2#fFe|$wBJT&|7khL5odQ0r9PfFAic}^$HGpG zvvo;ur1z~r!K(~JSGV4y8dZ}>ilF?yQUXhi@cKtIay|eqgCf`(Ixbj@q|i@sUi?^E zQZ+EEVT$<%mgKHE`2C#En@I{pTrE0X+Sn;(&=neP*eT(t3%_W@KDJtuLtXYKszGg(Uort zl5VVk@JLt6_8gsqTgYxPa;glvNf`8A+x&IS6hTuG2ynTdTq_s8 zBcVtAQ?!w^%{#p__Q}Y_!u)K!^`T)}_yR0O&O+M4kZ*hBp83d<+QOO-ryVL(cYJ^v zFj^fnX~2?epZ=n*)u-OlV-w$K6Nmfl(+wGu${T+ntr5c~xRx{<1yB@w^^I}UUpf>N z2v9(dIX;0t&&6p%-tdaGPj6l_^_-xg-GTNE&bJa|>#)`yC6}r`gq8`UB!?xWs+{}M z@`;H$oM~5`mVZL!8ii*b_~mfBGv>3T&NmzHxMt$gQSe2~d$GrG5yd(Jhn?Ynq3&xU)WRW4Ua+C946vT#L#0{*JEpy^nB zDc+Scy1^zd0v6#`7G{ZQ8M|tgWu=D9bAjz=DXB4;Q@w}H$I!$YGoy2qV8nF{(Q(7w zlCKt4Q(YHpb%-+sENT)wXFh`Rv*aV@+wTt67H^Ai$BurM2-WKdEkq=APGmtS_&m1# zXxa6vt!KZ!AIlc1;nDA@ZLObXT(H9KBZQEqs@P;qrD;@H-`XX-ilGl&b0z1qXXrhw z_?AKD9m7weY(1IY%DlVCeMy}O%mm`%;|q2PCA}H+tabFsShEtP$-1w_gS^C|>^8AF z&p6q3ZyhwwJo(RxxLW4tLLyDLDkx2eyL9jD%}pSRkESxUBOKVEy|Jhk0XIp1$7GxAL;XLO?VwU6dR{qKi1~2GlAQBK85NHTcQP9;Nou(h%qROk1d_ z1q){eQZw6}qoJW8#eN#{(hh3_xtl2mXjg~wt-Z)`w)zHsQCm#tl(eh?`89h467@>W zeevDYQE)sC*NPkum*wAH08;F5uhLExSQ$60L7i?|N=K+jyZkR!WM85J(cXeu)+zn} zO^tTBE~S0R*!*}K|H1s3t<=6qV?2I}%UIk1n7Q4Er5&u*gGCs^>)BU6LZb}}1; z-19rXxR^q+=cpgG>Wm22(A?y4muc`5p8SA3Skx09jL2y15Bf34xcXZ~AY2Vl8vm=Q z@$~ZAxVYLvNZtf?B~1ruQ|tW566l&lQXH|+(69l^Epdo|#0AaKCHS{6IGTd^)C6WD zmwY_skQ!RKa)SMZWq=_M6D%7!H)dt0e?2lXA#b+h>|cA?nD5 zi*q3rRy{F%*A_0iFJu)FxA-@@UuhVOgT&IeI<%v^aq+cvV|d-XnEH6U_|PN5T+UYW zmWT{>-p5E*T>G3B5&*Zto^c>M#!GMN+vG6RN!eMSI3Gv#W^JbwMggFqBSymxD>9Ib zX`93(v7Xc~a4h8ni7rtC(S`BF_G{6CrT(xis=WUGR-gPd{?MgsFcIYlrBjboHJS0Q z4`@)LTRa#|F=>^jXzD0Q6>-O{{97wV(IkECRuY*s(X^&?{WHw9)99H^Y^m5?N7IXo zD*F0lMlP+dTaCf;u`lY(zdgag#Dsl?uOosOZim6NwKbU!6Z-`|CO#R;=4)06>N5)d zH|8!l7o{d*MZH~D0L~0MqUk2k+WwWdTvRST8x6=Z#(U}Lpf0Ov+VKZCQRzy+*|cP+ z_%nU>I5GOST1xu87^OPL;0(tS$K?5L9V_~*z3hu*F6{in6c9MmYVC?jAwE-4hoL_Y zbIFspG}hU3{%SIAU@Vu$*$Pbd?{Goi=#0#u2&w(la=GYeFLkDtM23mOus-CcJk;sO;X+$%g4R29$^h_=ooA9p6{34*59QNSPI5^NXDPHjr zN<=OJ`Hed0Fiz#A_2a>mRldkkfSG!4v1@LhatMi496lxw_3*qL_i1(9uvhTFZT7J& zfmrQwbY+=@twdGgdM}=}>Y;+hh_>|%4NU9)2^aHE+70&O^=;%?sO~)^iStUEHZpdrFmiiIjVlErwOh1!c7`n|z(;WRNMZg6Xve5JD z>em>t$$oFoHAkJP}pq^ z)N1iZcLG~BEjN%CDYR|1jtjx^D5yQ4k3GMG?AM6Z0KHfURG5i<;DQ9l+tojxm#Ha zr9{RS;Fu!&bHGe7j>|Ya^Yl*zw=KR!s~Yi8U}a4L>&2I7MTrCg-3m2qSta5@G%-aY znly6zqsoYl@E|fj+8Xu&poLOb9+$m#@^K;eFD>@6F2B1Am-sH}>4gPlWX={VCX`k* zrqWPjPF}GBc-2tB__8h&+Yu0!ClMFlI)d@$g>e_WX4$^zp}r%K=tr&4o62Gw^P!em z|E=;ABG9G1uUA#C)A+sEt8V#4$@C_4p~|eP8Lt2^UgR}Kj$Z{MYGJ?<=D=OxQa)}N z)QU-XUlHGXcsUW&9@R?Z!OZ-OuP-r4Sw@-F)XOB#&14RRqAK#)Olk0?#^a#I%?Ic^ za364pc2t%?YAjOf&f?C$|9b|Hm7TqPp<$IaTPjPc%I8s=@7uhy4vi;m1{_Gyjv+UB zF3X`<Z4Fd+fZnm~YH>r}6%SsQXJ~;*(to)*O(&S1=c{Z;aEjAR83SxQvfZ2J_a1 zgRE#XdRI%=o9~^S;b^H@~eJ={E5iAZ

YdaWZ${9R+odXf8R+Wwmp zbW~g@7R=*Z1|Ophb*5ibNV&gy6;m`QTCZcX0Bbt>L}O!FW8)zK%?n&JbIkpRorfH+ zzNP<5lmTw1>bqZ`ZpYpI(a+rQLkdY2KN-)r(><<<6y1d1A<^U}_vpCJ{&Cc`^s=_3 zGae|>x&MchvK@}x_PX+;McM&!-m@Y5wRB8WRq=#yWtnxqz*fWU6bq#{KPpJOC#(&0 z5@K5B&aSn|PuF`;9H}vpDSQSpt-|@Fm3;hV>-fvwseu_?MXF`EcA!W;vodiIZ1MXc z2~+L;SY|^4<-pa>#P$@+=G^U-k2REZGs6`RKN)qgp%hE}4}uY>maHOcb@Wym>$?g)BgCIlamdPp*% z1${mNfjspp&e;dZjEp{fKhE85%CL`}@t}@ucNdv3ZY6GnnXU`B&NR{r9xKR3pxV?24X!>;Dm#Ep;@M916xi!-9G5V%E=S_|`rNbOY zhGg!(B!au*-TJL%5(zIwz2RA`WfCf6*kL@jden!PBAIdHT6kw^fd0d}mBp}6VE!6H z5+bZHJLKU;dNM9tYFC8zam|kwnkrN0Ey@&1^oW`vNdpIq3GbGqte;OuR_($}1LCJO z#Nv@^pO7Tf=QvwXT`q!iutxK^Dg4mW1kc*m^Oc~6rlmdB3tUHubHki^QPL>HT-9b z;$=tsjT9f>q3^BzBKA}71xuXM%(2H=8<;XOavsRce(f;l6%<3l>2d;3yW3RpHiZGJ z9e&G!XX81b%Z0~3haJqmo6*cI54U?CI{gI#4jRewult#iN%>)~C6!&@9U0X1lah#9 z#9@1iAC==pFV34^aA)WJ$GU{NEwI?>dMH8tZfSPCtKjHwcwTW;ReYV*5bs04+SU>E zunCC0^(1^C?s0UW;}+q%xH|Si?_I89t`IEh07WJ5x3EFlFky3i>FhpnRN=kB{CahN(qE zz%NX);SuePJC$k?Y%xD)h##TnianY8T?>b5E1qma)E>B3Yr#@Jce|S6XUiUAW_2O% zkdSKKp2bw>*eZn%fsg~VOkDP+m9+NYD=|0fqQE>weBqDQ1K9NI7L!}iO@gODHIzy% zSugg6xqSl`{z0_HMP~5p`n;*1G6BI-id@FSr8;GExKWcJ@CsMUN8b@*Hxp#jbiAh) zk)$O@FcTBN{?yQ;_{hV`XsOn62=Ci6(02iN9RlC5ACF@Erb^sK6Y1_?Qu@?hY&%)I zQIxHE%T2ha^GXohet)?ng4l;5@8|`0(h@CHqT8FT0>GNKZ-;pX61_gT+w_#7JDuhn8zf$lKhw7p1a)KyoN2e(!y5pafEY{b{x^CAFJH<&7SB z-zh;GuzV@n49imfWF32aN!j2ymvMHmmnov5sLZJRlRS8_zxGIZ5uF<@q}puL)yxo* zWwP|JEIBF2z268}b8V-)G;EN9>S!(OsEeMKWU{6*nXpLa{!#sh`G@(CJ=y{Wt!lcy z59a1N30d@ZFORY4R|Fy=s507}DDuV5-w9Gk+?p-s^AA`iQMq;`tvxl% z8eZeO%E>aT^SH{aeECZ9Tre_G`c31mMTDxWWwUV4926REC&+j-dIFRvrvBl{Wz(is?acBKOcDtiG-| zC$81%rve1&Tox&H^;XA0xW<4w&+k>&YCIb>MW3eUerI1HXuk(+L3NZN2&*+QMAlB; zfM6<60c?fdmO;kVU@X4Sfu zH-^k=Sq-1_@*o@rZZB3=@&Wx(TT}k5hK@+yjrKM`QS3hWcNwHHTuD*yHuHpWgqEcd z+qakp+~8{~DKxojm6eGl@ag%cuWfS4^Qt2wRi#GxM*w}<{X3NngvS>>9|mwULpF%K zDi*I$FgK!fE<%$$D2!X2cCDKN))_A>8K<%>Yt3t0(5On9D@O_nQ`;#+ubM7j?qKEq zbd-nCITy*YGwhGL!z$&=y>C0Tn#$QFE#utzL-xkHVj((v3%CICRKXRLOuo@wno+j-|zi$7x7Gf=Xb7k z`lh2NOMnhNZKLf?jYpZUX!yIuxVmWphz@xs3mQUlk%*n?JF58{$G}Wm5^(mtKJeiN zKE1ZKHm~JMcHiU!TN-FO5P`yfYM5EyCWFtp@0G7eUSd57d0EienX4|e@)@a?hD%&6 zr=SstyH(v}ogu5-ws0Kg!|L4N$p!t1!m*H5lcPTQzNcQ3Z#P%UfJTzdT!gdTLQ%Jb zU;s@uJN-ajnI~!3Zke*c`zpOiiuac%_Bwqf5Ea;vLHe^~K?dAiQL0M`P1tBHtg;mo ziPtx(RAk=qxaJ1^aVym#WgnI<7x|738Z5`v2>+u+dAOf92Mm5+HSM~sFgy9pUb8NW z-vtN$c4-Gr0Eeak2SMGNc>yhmRya9Js<3}er?A(pr>K$96cP%_OxI5X4mSpF&PJ{! z71c9)nM*Znijx>_E-F8qr>o?Mf<$463A8{#fze`Z*bt zHc+AOv4Te6hM3lb);Fj3oCyPvv$9#_A4GD^{iirB{&O6Lf(z)b=XQciPJAxy2ZDkt zo;qC*7d6wXs}sH9IIWv8>@C}AMp%7`1cB>lIet4x07e|5v5H z)t}1_*AESLM44)(7S`nW;>T~fT7M-+WYz`VxN~)$Yj>T*ySj}F!0vQlyhTQ~a2fAK zG5_$prQ>L*UYt|JWE5#pA0TH9< z?vp!QxfBiwaDlf)liWxL3gVFI`R-(bPCC{$5ko>@dI5R3_MtC1Etiro8);4)ai#%f z9Sirg@he_M#pBX%N zr3SyQ{nZm+O^+iz2?{`OhCkVU^+(d8{@?NfJQDU>P0~M^(=|&L_dMkC$9}I>7lwAJ z)tz}3dLdlp{HvA*1`Y!3x?KScC67%dLsR=lYJ6vXhxzuC539zLhsgc^Iyi%KU={np z=hpnowY78KtjDVV@Y-ywMdJYgfe*ot>CQt5@Ke6Yejk&VRBYI4uoQ*sZ(<+GGhEF5 z7KZNoKl&6L=^{5sM45DMvdBMZhF_ND?_4EFeh1Rs66yz^#Ga?B1YQkNwIY-4uMFE{ zv{*gez5|_D=4J9lI*{@Ne0!4S?URBN(!4x*l;=sDpCOvsha?nbTy0q7#9^+ISH{(C zN0KhVe^_7Cn2y`zKZE=y=n8DjprHDwRje?D-0_@$?P^eGiQKK?Kym1uzk%mZCMnX6 zAXP(dUGf`eOPo;vrf+hXHMDtp`V1P8sZ~DqGDd?zSrEMKc)}UO@b{z7k9ZG)g`+dR!5#Z5$NoKAQ}{;0CDUe*QtZ>C3P3{8`BB zk49wgM}1eF*iu8k=(=F6e`l}m&u(NU(c2#}m)-(B5|?WF=H0JmLS1( zT!1D-;CoIDNeS994vjH$ky;#wy*VN##-2o;-n~`Lw;ZN{qQ|nyB{JlPs^ocZsa;X+ zsNt@@t8Y&3ZIQ<+w0B(^4pI2E&Uro?stY1iL)O8A2BX^vKb8>o_@Z|Fbaw@ogP~?+ z;iwbl_=-30T}}%PC6ZV~39F2bJEXP{Fv6jVKlCT2pGV6GhuTrziytwCtT*>iv7|DC z2}%s_Nex{w_#m@b23AEjyMt8H5rKnaV-Xg+T9GEedzsV2Y0aKJ9a`zn`~!c z>*keV3{6?DZBx zSS1PXNxk&jcVwl!T?ueu4#UnY53oeqvtoq}mf0^Sbp!KtWAk46OmUP0=B;X6Sn~lt z8T~OZS>HSO-3n1iWD%(4sr@CLJ2yVpDOI!I&ja0G!2UX;@>j9k-QO=kddD*PYih=RY)*q%VF%vLCScsnTB{#@}C$)ZBpw$U}8pFqPM9p3~~OY|rsUei1G% zEj{i!LY@jT4BPN(7GEe8v1pRgXprZH!0$i4oPR!v;L!5qHKfxby9rVx3`~95l4g9! zM~aQuLafm%n^xd>ERo2Up{!g#e6r?ML_rJNAp7C(X>u)=#JG^Gw!>Y&00OR1A=6hW zSumOLTf6O>^BJp=Q$k<^P5a^P)28K93Zw_|_g?n*7N9MUMXyxLV-Qk0Fuhzpqr63E zmKjUdx?t?fw%+jsJ}MX*T`}iNJ%hYRV$2*ACzt+N{e0ce6y$T~UcWGU-0`igXFhxm zfx>Xy0h?;0sxnd{h7rHWZByn$p3|XNScn$eTWVRBxsZBsVoiD)D5$E5%iJPs__cK5n2F10e@-Z+yNd5HnVv%p~Z^`6 zW5qZ!r(40iDSRL|Wg52O8TiPH9lm03zko9-MhDSLWSpvHp)<xV^nak}8&%h*|K*jf>|$r=DAo zg z?}fRwDvm^G=;yvfVddXW&NMG<>J~D1bo&xlze)c^Lj#%m)^^6NtR306#Kinu4vhyJ z8hI?xV4WHDBo>aplIb3rm59c4W^WhShG9&?(2a! zC@sH>Vu#^p#%|x9`sNKGU4q})YdU)O7oayA1i{y7HC8xH;H?jqmQpHs1v6MhztP2y z9E`90Hd|t}C%1&tiR7o{jTLOrRNBkqXJTo`~?7obV7An5@JQ*-=Omq!EcaG+^wO|qu_|A zI87KY^9hh1;nxj~CPSAik;n1B6aa&KZYzq%_ljCyL$)ekV&&1t2)f7t=0nPf@DGe{ zWkYN+Xa6W7#fg#aF6HFUz!gd3D~hkPZ#EHRNsKX!3pw24Pu%{{?2eqGBOdWdW?Ylx{&K~xI5fdQFIa(>615`B^J3knRq=#|?MDNfw!_<9 zG1{@^dNfEi$M_-E%I{ zYdJ(wc9#GKG6KcBf;w@3D3ID9ImD13Z9(3lgD)GSQOW(!EP=btZ(_@kaX@rS`o*r zp|CHzDKtFhFmG-v^)jXUr#>Du)255)^))G7bl!{2fZeQpEA@Wlc}k?Q6rxSxttKkd zpXY-hpT=x=y$sCknjb2KTbjVLY)ODAf{{+e-wtitFrp=VE^PteEP1_*t?~PFao2hO z+N11Tl~LN}-B>xhe|9Q*yUD1=#^%2ihdNG*;(WAOS@{by*Sa<^dWBtPpmyWiluK11 zI)8fs1|!r5&wlhEp^kLO*Ne#B3(2L|nDa+|%&uxkrfgi;jLsvE#F8&feN)#I|As1d z*zzsbw|V#ooI-~vU`Tln@_4RO)_LbNA@TmAcz$fwyVNMXXdk`?9Gz z<;9wsVFmXxWfe}3d$Kh(@J{yY#f*&r_2)knO-73vv(`s(b8YdAH{`Q_3g>RHSxC?m z=GGGWfiDU^D^s0eR3pyX3ck1zOul0?9ru6^x^40?*SjstfXR*crVm>&@kPG?tm9~K z#Ey&$%HWaLpimCLa~(`fkz{WdcF!$8`3615XEn9nhrtZgivR`cW@34|S23l@BZ1kB zeh@B=%f!+9MD1Piud~d^;DgM~Ouv~uRIa=BGQL8}j7Qq4XS(cmwDMv+!4Cu?M;&J^ z*PF4KJXRRCIY12VwB;#9KJN{gqG^rL*C_8B@L5SoIXNjOq48;YMRpiyXk`UnVm~71 zI4^>hf9iHL%I`1w&p(0PV=5D)HBP>vzMu*+Vw27}#)J(Zg8%u?4*8%z=gPy3DT)1I z^o*X>>#4MOWODXwQK(78&wp8R6-m_ZI3K-VZJf)4-vq5~O30I5;6I~i1fe*~X{k}WO1Itt z*-}aVTwvcm|p(q6N zesD4tQUDaV#XVI8FX=qEpmadhEK93*tg|B)i=kH$O0~;}O-vb4kINhPUrpT8!n3kI zo-F5xI6d~!)$die*SoB=G5%oyTMfq3h~>~e`-4tO(foqQsZd7SW>;6%J(p?efM2~S zahioQwFewnJAh>pSu{ntz}j&xd|r`wz9{LRdyahVmBlPZS)6oitvEj~6V-Vo-;=Iu zY}k`LOeUtSIBC}0S`M7=jbBYaHKo^Y;C{U|Ba`#O$ji*X8vnl^kJR%{mV-CVD}#kd z7BN$2MS)D1c`$y^#c^MyKI2KLdECazlFO)-YTEI{Gm?3aCFgQ-Y5@UaZ@RAOgRlGOginVVkVN!O5&!X#18J-^X!B&9F4HVS64SrT z?SJu9@w?+bl>NFPS})k+Evy@`*kI4l^_X8U(y7Lj;`QO#>OQ=&g9))vD`?uemJoj_Oxz0Hk zXXoMLc3W)K6MG5Or^us8T$^=;K`9XHwY~d4Df`4;iWb{mI}JAR1?nxWHKP&jC(tS=vA7PlBqQZb36zUeV`0?V-&~=_F|6`#9 z56cf7ugg^(@7q&HN5_Br%|ekXslD;7jf0y=KUT<9i^5J6jC>3%fAQAdb*2%To1i$8gdP8POv=FYa-@;)q_` zMQgc*Y^>aEFQ=4b)5)&g)em`B(S%|F*;qxomGS8N-ci|ij)aty2MT)`!bzsKQO~Wc z09HV|sSf$O&1Fcib@V#`-7P~oj{v_xbqIY9d@2Z};S)Q-Z4upm zldF>aQ!>`WvgP)ot<-yH^?X(W+tJ0DQ~zXxkHuIqO)&035n$tejo2yccm~9rL<{Fh zJQhS05>~)@;D74Cg}bxb2k?H*84=C}6OILC-<1+ac2Vj?1* zt^G|?aBy&#b5aq#q<;wKKu@_6uWh{u>O{pS)h(o^Y9(tNsktrprl4nH$Pi0o50lNY zeu?p{E0H)jt0&MuG!kWiJ$LdGIUB=|h|WY7pMchM|3y)#8lS=7vHxPa zH2-`W)69!MWH4dmPWE69ZTy~lpLLNy4w!+WBsm+c`vRO}I)#M&gF9rQ z=f`txfSA^@=f=G*xgZImdPeZ_@y*IhF@}bLNdAowZGqdIgwIm(uYaR2yRj`^V})ed zNud3f2qPu>*2zd0()%W^Umvy2$Eb3lGchkD%X-OG*sjq|R?(C;qCqzAUXdIJKX9K8 z<1DAnEuW;y?YpB^Y+rZEj;*>g>+FC(0f1BHdWL%NUzae=P@9Yp#O6d5VjGu6OQ9g4_g=UU$>%; zAV#5RWfErlBy;ejps4ANM^%qCfnfBbBn69+>At(q*&f`&5{rcQ@{Obye2P`C>F$Hx zu4i0(Ia;@~lih9L)34YvCY&TvCl*IKokTRhtum#rMr-`FZc{CJQwBdE79vbd>EBEZ zkD%G>W)rG769(StT7Jv(8#RQB`{|A8mvhT@>&rN9@LK7s?oBLpf5F$^ft}UMONPz! zX_b`);3uVEu+h?USr~tbfnqX~U@W_EH2+>(qFz|tPkuci$t_(ea_ELuk?JZNN7Ez~Y&cxQ_r*H37^ za`SrSI0N}{5pCCf_rHIak|Tsax?E!A(_}MkUByebs-wC2V(z2~=6FXpO)!1aHntmx z4Ex{W8R{{_xeJ@I#W62lb{BhT{kjl{#r12iRho8)T!?F4u9~gmLhUvc96Y+T1Y6B)1^LA4C zM-*a812xnd&Prr0Lp`NRI`gsSd(Q5wg50X$TrAIRH|`go=glyWr81A$w+X0Q@Hf&=H;)pP!?MGFtU^ev0kWks*)Fa$nJEPkSsUvaP>%)k$WNZMpJ6Zy>Mb zr^mou=YBBeGtA(chyx;5sI`K=yCO?Phj;w=39NmQ^04#!`0`il0bCmrMruFIMasL>4q)v9pyKBbp_|#cN#Pq^# zYe1xaqgF{!;rh}e{h>C!-*$iE{3Ki2zk#ufk0EfXJy7R$sWZ2qau2j+tf1a;+=s~2 zzD`HY52ztj#cFgd^<@@JWW>1fJ$Gsxp;B~sG6<+@ah%e$)|XOvHxUw9aVEt`=6W_< z9x*WwsSzRn?=>%K>CCab+gWsb25AWTci>IZO(K6C7u+69F}d@0;kT$B|1#RrG=~zE zwJ+b6TnoRR9AVei@q3?nOuU^(^IP~Mul+FVa^)KNBiN0Xaeeqw`@iw;M$kl{bL7%z zlQqLbL!3i?J#B2b;*coFY$N2kA zx!Y1Thp~{vVIXaRi8{1YmSB%mt+7CM>`*B&$2kA7gs1xpx!18n#IsM9T~Fts`O=?sqsfs+;#204SK#&y!j)C&cM<6a1~N^NQqWN+ z-mm;mJ&D4jK==#UqhOI14q zrsQig(a3LSnCv@9EzS0UCHb|MLI)Y@2Kznl5nJjXy%hB-B|8oV^5{Ek!f%5id0(Ys<(@Y3bG8el` ziHKmqnT|QZGV6EfcQPuwF=P9xMExWXOCu!^*~e?bC|y^mRk?$9Sntf41+7r2nPfAuRVG{gmC0Zfv`EYI_)SF%kFPBV+vAtHuTQi%-{`6N#>ciDd#%caOLe z0kev{Z-@KmeK+hVe(wcJd^rM-yyN7)q%*qMM~r*E;#}za*R-T6+N_uw9*f*Mqps5& zi@c~$5~CNrwzD+t@k3=XE-1uIuE7Y-IlN62NHZ@UIc`{Bq}!Eybv52j7|?{3IMK14 zJ+?em13w#+tO}EZG;e#FM1H`+6L%fBka}>Icw4QdWJ$Lh{FbJsEHr8$V|+TQd8L6G zV@uYc>7^v<2xKZ^Ey}_P)sMw;3OUN^lUv5XYK(^ADAD^`Sb!;fDX_`=RPdI8^GodM z6~qclse8bs;_poSQBxR8n(|9XomxQ{$#U-BYNAKnRjt1=GlXhv-)9K2mJnEnaX`m5 z@sQ)E#%sc>is3qWezDg^dS`m&Qu)%zf&15VlVcH_6^IGv;WJ0u|6Hz+GEG`8R?Tt) z2kzri6q87AO~n*mtJoH^ibAd8m?7g3zr>p~x5xQQ=Wh5a4ttE|C5qX%xe8<51!9e;L@x6(~D;jeVHIaabuqZ%u5A zEGZ*ZO>jr+8tHz(=~@fXpek->3T{d~h{ElUx>9|zpR135H{sIMkIm%=*U~dw)+EDp zpgA1k&?}I>_;_BRCQ>ec@)u*w;urDF`YoPs2yTKZ;l!w*6rStXACLF#7+N(975i|L zFa&9?&VvW}EQ}!I{Sg(lwZm*jlj|<~{9cEO?MxaM zn*8foN0e(%VqVJ`_qEaaqJu}oZToFtY1)pehc{m3}Jo z(a5}yD5UV(;3&R+D2kCZkoQDO?u)PZnSQye#hJ?cPn#aFogZ2svXebsRHd1KeK@2% zl@*Dmy{V0|h2h$i%bdN|Tw3Kgyf$Ed`62jaPvY>`_!nyMyo3Gx5Q!R@rl@AMvA6r5 z5Dg+fXh*^5*eMQ;)Awgk{*XR%%9y|FVDrNT?cUGhZu^-#N; zNS=&gsB_q|xV9XylVKaHpg6R7kG?GO$HjKzv!No$AT;D9QM=9yw#Pes#W9kK@fUg0 z_Z&0Qb(_Q{7u~P*nnsYWy}>9LcNWo+Y96d@0G{-5^QV#>Q0vu$Ckn=I79;*WbC%m} zx8tMgDXz3(m`h>wge2RxL~Ru@C#7&1t(hDMiaZt-d;61u@kzh|p^ZIFOg2+HWQgwg zSaC=%oyHU=`0NLGVOPo}5sTwx7%pFre@{Rsfnh~Pzgm5o{|xH=%BA*aWX1KYLG$Ld=a2K}9O-SH9cF3163Fc;{!s6z?)zAkKT5Kf z*WYehdm6gwP7AgAOAdOYzV0L4GiMBX8=D_Geh4<{)L8h$;9&OHA+OCf&{PYx7&nOH zu{v=kGLPyz)F0xRQDM4SJSQ`oz0b;XennI3BRX85=orsRRo|l zWxT*73!j->j^h4yX5((NeMa$r$_dIpjhN4#rQnH|ePDk6BtSg;&35VS2=Yi#@Oa!S zHI>hx}xzl z+cWuIzt%?dZX=oRBt$oZMiVP&^zfENmKKXClFq*n#PjN7;MN5CQ$536Aczs*^ZRs4 zjr9io2`=Sx{5|{_5xNvfr{PEQWR(86!#l#H4=;51bGfh`?-yNb$@yYjn>=e6r-_=B{W#g=Y2`yHZ(%BxjnW*yeb#) z>PD)%N_(-HX3<9CcT35nWawX#d+UsGD)q!x+yny><~W0jzP3s>@c4r=FgK&<6+K%+;g===#J&iO?op8^U6F>I*FZp zYP_deOj!j5m<#8xh(euceMH1Wlv5nxhB3}o@4A$=$4yzCs{+$gnv9bV62x@RrDS4z zodn}zSx7c6<+eCPz6j|i-|E#`AY^LUHul9b#21Oc)K&s0(3F&vj5w2waJD?@3x4g~ zj+)x^eO_^A5uMuHgW`mck8B&tq;umR{r6Om-w7PBeL$LRTg-R_a{0h2{!ww`honER zN+uLZs0dPtTLpeo`l26Rk+4zHP6|s%E(>B*J?eRuqm56({>{(LHTe4;YW#0Pky5gY z#VB-vk>Eq~NE>WPZE4}#g1qSw1fC)Gc5`DybDQW=wM6G;BF4QcRjId8#I3a1=bb8U z%*EMfZ9ynm=Tb(^$v(t^)}LjHox3w>79Y`U5{yaONpiE$vi5W;7-rewP2A_>Qxe3a zrFCiVs_-McSz8RXM!L7(hVYp5*KmWc`Er}2E=HejCpP+7g-`u2l z_0nu`JMdr4_x`XaNEB%lI_Ew3T^g;C_XKyY>1`(@YB)LUd?a36Z2lyG-90#9#Q!F? z?cCFvIU$LIy|ppoS^6i`Dh$l<#=lnhh=|@{14%lAsWV%+=d@%4s~T%(ebj_A_jkrJ zeg1$rWtp513pbWHdAc>4_Mlk=6RmhCDklzw9h8pG5h|bd-FWB|Ozx~8Y^)|p87;2Q z2#knxefkb)Q?jiEon)nqb$@9Zkra{|*|S z*|4N0F8(V^`X$#QpA+Ls`suz&-u>MRWcEVr`2fmUUdk^jao zjQtNdHr42qs6psPDud#9S@FTH?qTN(l*S*5n`I9+zwZ>iDe_HB{0jd*uKudgbSm@< zwNdq17+m1^k#Y5q@2&n4G~`5YLBUux&@z=_EVTfy#5j?CX#KeQ^78FtX1##5wKYK% zxBTZ6&#-82b6bop0x?dQx{ElCO8TRk=oA|5E-3eFlA}fpv_2pId(qw`kwrnr`7W@@ zc&F>e?f7zcui<$Ae7573ZLgJ2^!Y)_x6tYB;55w!xYlE3(y!Za`0=`}AR>qc#-gVv z^NAQH+L-xQ)K~Kt#g<@>>&HNt3h~WgxqF^myqIop{zUxArs}T&gys8xiyHpMQ(LoK za&le*|2G8od~r%6*Nb{rD!X|Hv0D8Fcw12_Cu#&bNXS{KBtQP8a+f-Va-xwT)E4DiZQDj@x<5^np?tMAS1+CYOo9dLD z!#lL*u#@rZCv#&f#nepZ^QU?e@+{(@WwAs3?X#@C;QZo`7(z};zvJ6~6T-c&BZEQ3 zegA@r_Mntp{#K)8ntDoznxCfiJ|F`+R&md*nFd>bMfjvcs_!}AR&CA|CIHr}iOEaA zk&}wyd=p{Fxrq&A!`ys)>P&>D=H|3<@+0Hpk`4}B;Hyl{w*ZR`* z+w?VaOEm|*_m3!@2X?!m@RuVxW{kb!^@XA9L~M`EH=RaxbzO^#J)D>(2+iN*s1+zH z4vYUJ!mQf(C9-~6$k@)qJzdhYN*28sbJxpQvHAgv%~|q$U|Nj4KQCzui>oO&{^t`2 zh19Pelf3xR`u;x`puy`_@G-i{`#0?~)fSqy))b%w`UOnm49XLsD6a{h^pTodSSYBe<&16C zbL-ap%h@%Q>Dmx5gYcQl__IU2O-IZfBuxez_V=yZ+y3{pcu#+~*Bb`>yemvcvW7T_ z(1Y%uUu684XA`yK$TL>{cJTe(Z?;cn_x3{b9+AHbV(LYueuiU|JTu25RBHA11MqJ* z>!V{K32q_UD+5%Kf4VDpEoy~v;67w=(fP(A4|Z$qVmlPj=n+d`&reW}km4OKa}=R* zezoR0Ag`VwqjAM?lk^VD7ga6Rt$cE$ZebQv0XH^Vs87S$Khv*Q;!{xhB7f<_xzL9tfgP&s=lF!pl`1H=NBa)zDs;n_`InmWa@!~Mb)m-tESR#E@G;!kbeki4? zjlWB@%*ATdk>RRV`95QBYAnrZ45r1L~--4no=VPajbxtA0NDMBB`vg-U{Zj za4xr>Y&=3tT+ZGQ71n2~v9CHiiO;U2|-Ozqw|iN8su&{(cGBs8f6PwB)u~;PO`Xl z#rA21#1#H~>rFniz<3$dnUh$pYf%@mjg(kn`vkUAj>D$p@!cEpCNcvO92by>u^bh` zr?k>2BGzTc_Gb0Yr8(Aif*A;Rh*c6>dEj~}MI+w(6<7$(Z3fDlnU6;e$_r3Az10!zS1l8CuTD0Q}mTeliPyiw6npjxnnq(j`WdA{uZONMD!;-GbKl9 z&>t0Je0_zw1ntTpj8?L@kpQ`?g){VjRUbAqB|QCF>cjGp2j6mMTze)kTgE%-?ygd^ zftT?Ib=n=Zoeo*HR+vRxQPf^(^%WOvf#DA!eDK-1B-OIjEBM z&HqIUwhvrFNkfTP9!%d-3_*^)Kl!r~qriKa!Vy>lt11W5I)|&xyyHPGm~F>Xz6Tqi zuEO!)@~NnL{s5N{8Ggae6A~sAj*eHsOC%1VZ2*K@H&8TV5`XunKByHk<@b?VN@*}S z$RF8Y@O9w0_hj(VABI4l@hlFKy^ccHgL~>b>99W1&tI-txM@^*3}&A$U##M_&{GmP zT;?P=%&o%90mDISD4ZEuDj$3QEj^#B9h+pyCz1bmPE&a{jXwrxj2IPHvW=9g+EUa|Z&wWV5QLOqp*MOvD!nOYkGeDO4A7}>vTn-TTv9B8h zoV&I$6|te8AkUcoj>|Q1S^Q^GsN>oeuya1O_mi1{GVPY>+ROe+2{7f$b9Z-bDvg|^ zQ9DBkB5xlrP}eN``Y1z{-U%omrppx1L zL=wApYZ?D1h{E}E&vtgjPHf$MaV$zslLpy3Yjvz=^>^*}^tc-k%jk9@!zx>93tA^l z;I#oj-5j;Fp{ifB=R7Y`?q-=pezG_N=0_86c-C7~C8dnqQX7T`hslmtl`Dd2$QHJ? z?3)T|s$iVOuuMoJ?H@#q5xkrTFtVMmFqwVrYeAOzkTQm082#;=O9kJNl(w+j`x3-| zyTLnH`^2EF?FBkDwgk|+VW{!aocZBa+V?6X2Pa-}v)YlvB_r_rY(|yEd95u|W5ptZ zo_xjW?7R)f?DhXgUZk7n?e{{?lvd)?xYXYjX;&^tx{O9Rdtp$p`Z69Q9P@*jHYzd= zC6A>q7fl3R@JA_0Nhh=@{lsD8)!rIO;eyH#T3d@w^Pl7I^D9FhkT*e`Ge^O++3jml zfX)|$W{m`2_-iRWX*h7?T*nxcmw1m6!rV#nk!6$DnI68++tQ2@sVsG& zz8M5+c}W+|fD=J@XO_)#<`lPcxmk7G&(qmb zd|uQ++v#h zdfAyv%RKw}jlE-L)XA4OMBB2SAs?q~_Z}1JRt1A%yH4kU^0@}%;o5AJ(>2Z z?*AeZ^P>D59c}tt?PoI+D@jUQX1?!(rImzve<+)-6uhC&WmG1^E13z^fn*JMivQd? z%VGj1KM@yt-Aq;=3nv1Niinu2e(6I@2ZW6jXVi5epApfxHShHiVi6XXCk#qIG1!ip z7zY_{KY;4gOCfK}soi%;mG-5=Z*S%_odht?+YmK6AceZ}V5Yf89g zR9Z@09hi3CE(VQ|L3!~0H3&n;TX&@uGTW3oEr`>dqaa<=Tdmg<=5eYSWKx;$f5G;% zb8-TP{lk*P0(TBI^&qD_HRgyPATgcGGn_$|FfTS_LI5LcZ;=w|s&p^UMVd|5uz`v2 zN%a+Dx=gheL(0%7C;(0;nK?L$Gfaz9g67#cWy)Ko6!&*QX*?wbxj|SINZ~elHSasL zZcPkQaRsUi30)o^!?>LKf7Ul;1#~JhqG0D;R|J&kuzn&I$-%Ui>tL|3%rFsRN!;0` z#*iNWI$RUwNe}O>n?&}j$sr;*z7$p^WN`Xy`Dl1gCKScp>cp*5O5?h58}j1$Qv5M% zS3?)8;6#$7NpNsB%%3tNqG&`_1bC_9T^QYOtp6b5v|JR=lN>t_VKS7dnS!ysH27~P z*m!Ge5a`!o?912{a4`u@BqH9~czme`xgT(uks#Y@N~xBmhHqowASAR2+??x~Qlg$` zX+aJVW|`cN3M^ilmRea+rQlYn51K}cM}Fykl|DUF<9tQs7IzNN5ZZq|U9{KtdoDNA z<1*h@j@^LY%ci4Xoyrb%^oygsfG6eficjXR(ixS~H9j=}Fa3$=e67#GI@!(23h72a zFYQ-eUPYh%vU{xq8C5L?ueecyu#}W7`J+!Ss+t(G zz5a8aN>H$u)p7s-@FC9ru@G?WH6AO^%*;%EOV9-;)#gL34c685b=`jRHE3d&zN0*I zZ3tREU_3Y)U^@oF2H*8`NW`4WLK<-Mh+wIiS}HY{kmaH2^+yWQ&-xH7NW)T%&OIJ` zkW6nai9GWv;*`JN>5;@*8zY~R_?7I_RE2ha8Nv5XL(7d~<&Hk9hv^4sZ zjKAbPN%W-o^y`6*^o607QpL5!Pn5Vx+R+d38XhIIlPermc-#3crqj^XTi{#i3I)jXUg#8w*5y z%X`CMBzYs=Zf0Gv8wBw!TKALY8W>a(KbT2>-%co|C%u+PWW`>D&|A)`2r)}jArGKi&YMOc z$Gz1(G!R<9&7H9(EY2KT&|r?E&r!M6a`k_!NfwMt(DO<{`B=IZje>(}_(wm*YHA%&!sj7!PEOGPO*P_tDhK0_s4Len z=xzne3?c4`KsD|p$^7=5xZdsJFz6A9kh7&O1*TAi6ePv_UzEg!xC#!=UNteXQsUc` zf(iS44Q4rWO4xCt)6N^c>lKTz>*+sQk4(M){HiQ!!R_qvUb=v)v=lhs>+#K@wr-1E zJX!`86iw*pms6oshEnEeJsvwGrev&>tcLMCp2jUE|B@DY;!a0YpC#+SE$E_Iky)bp z(#OxrFb%a=FnqsbF892&Ai|OA-Z=Y4Q3>jzk5h(aXm!%4e~1`YywYgpCHBSe)GVW= zN}C3CQSpVurDlF=m~A?;(B=Yb=b||MjMpsf(-4(To^l^$i@a+adfqLQ=!mZ|`#Vfr zo*6~qk_vtNyUtE4adQzhwP7D*!c8+}X{~?VU7Cu?RQ<~g5HR}!WKHG&jqLn4hKr+$ zR>lt=@w2YW;SYBIJN4ToHs`kF^Qg^7ai#ymcLmNzPrrlWG871h4?3vsqV_%3g>336 z4(EyA(Se9OVU8Pvy%lPY*wnDB7&)V@>GRUY9Y!^x8&x9s?flbExl7{>(W9-=6H_&f zb2`d-HCQWS*zQmDv(J|0()X;;C7a(LMEQ+WHf^j458G%O7@$q^i#a`Rhd`JEBK*{O zLEgnX2d!ZZ=bOj6zAEjp~gRcqMcXtytz?knXaCdHL0UACc z#=(r%49a@~q-(J%Zv&xeDrciGMgtJpiIq}i)zt}N1%+Zyqw0(*HIq|PKsq!k?N=Mp zh-G>){d(Fm{#(Z9?xy{^1h59-P|#Oz&9?oe=sTeN`Xh1SKn1*+dZJ}<_F9R`F#vO2&MwCn2I@E58R{tm-tJgNN=z!{wT{7F zQgj)}DE3a*q8YKI%Oc!|s%(og=xQiVv@Ex#xBgGQi0m>Z-~x*ZI+9G%`y_Bgey)&+ zUHtPC*ewaM-YL8*z8%6~VuRp)7nTDINYoio9nqLo7pqt?8#px?7+n z?|^;~MfYJ373`1Q@}H}%La>Br8Ayy*k}XQ~L4EvSrS;%^a=Hz7=q5F}i8L(wSg7ML z#G~W77yybiFa^=(bXZdaFl>?tgqN-5hLc#&mFB^J2?YfO6bYi2eJY$5lW)MCduaJ1 zg^w^`V)w#eEd{!tpWk4bPy%rCh>BGaP2!t(^)rkV0ZM{A@QQ;&-?W0fsUOlG$Zi*B zwJm8L=ePUb8Ni%(F_7$znL`2+w(Te;o@?g&{LX%c@UmHT>xGcuJBTp?wQyJ8GS)tM z_UBzYJ5;NfQPP<)mh>I|lQve#x>PqIbMd_Va*?^}^C~6DZH#Az*e#gI2f~jZqnlZo z6?m3BP4;Pf_e5fZEpcAD1 zB#GSg@&*`&91!dMs&MC72VgcFE(0DCeG*Q7epx~(;E`DFb?aW=JQkp7HPsqee;coy zM+#c^(o(Qjqi@w-Zp3O6aelj^Gj$EsVFho^-i|dtUkX^h02!xu9yRmX38tAwso*;$ zC7@}Gcw82;rO2qBz&Ny57#)=lSIzj;#77q5!&&n1h}`|S>C*!Wy&&cjYsa2CC^o0|~jj-19GVG#a&rr5P-LP4V7i;hZ&(SecRaCL{3ZDw?&% zN6)IV{Zpg<4@3IwYvqS3VUW<0`0Z$6BIo1}CkHqp0D??B42*ohT9bJI%*3ri(xs-W56%z^}D6CkK1Tpq7i zf?XQcb*n@rjYsm7uKyk(0Rz^Dw~%;nqR?|=C~dhDe3@#CtdPJ8_D3X$XSVV+A3g

AK-Lalr~8NT|dIQfdz^9iw6ge=moXQoD*^3$71tDPBZmkRIfUn$N9(H zLHeVL-jk(E#k0Yw)tF<_s1|fEbEQ2VTEkUJrCEh1DFELIllz+YV|3TF)Z_Nn#`n8W zQI#MkW1Wm8!$OYQD=jfdu$%OLf{=-pkZE+9JmLcKbj%XL3p0ztKy=*FSZ|#`kuXwBD+NeJAQD0 z1g7c_n8s#3fZXQh<{msc&BvK0J?$x8i&a;!7AF!O$D8^C_hA6_Azq6=%NyH->V7X^ zQQs7(LI2vRW$M#If^t5uaMw%6k=`>8DjniaMZdsb?L*A!!}AcFN}?BEq3vSF1qEkv6yLO7g%vy;|};y4R3Q-shASF5emWoC#uuLRtB#8hc> zifU`bh@Nn%@AEX_oH)G2Dsb05(Lx~G(LEaY4+zz^SlnYAItUhQ`S?6~*f!(h!Us@Q z6|bXMCpb`xKNGvLm5!tw0?uXAko_h%fLcHN`*6ai9bh5?8^8Q|SM9+!DhsRAfW!In!!isONew!8ii3otuyP+ZF z?(S~r+s7bpb`YMExXtjpNgf^<>!#C>4-0;N)#L&2D#m$zh&sYz)AvW00Y#f7B+J6a zYPYGFj$?-@Ov#OZU_VAw215>k@K&c!Wr^x_1%yqY7p013mWz!^W=F%v{}3D0@$uzj{hz==6ip=cIHS&lJ%OJY2B?w7%GRJ~B-CqkC7rI(t;2jdamHy+9pd2vqmr zfC9X{;%F-Frym&mT}%wM7)+K|x-Jvg;I2u?>xUH7swj=hV76JW9}$BF_OJWlo8~4@ zmVVQ<4lbEs;-mTVTY7usf4aatjVmuzd}}igbicW|jFTn01HLlE2`vOCt+D+T_-`5!sQevnIseE(CKYz{1z)maEihc<@iF*rSGw$zn!8k6j>^HCDTM zMSP_wpP`noyYGO<|1G@w&&%DuN{Kw8*xnrJ&2;XzlFaL2-%yUg|1tWOKPwpL$J;nN zy_^sa*R^Q}AXE8=F9_2n`iggXp)oZll*8@8>6IAYoSB(ejHV3yPfV~H+#_X&Vx?iq zc*;;VQip6)>}#R_@MzJ4YKc-=n&0N0sBYYI6((8Kd%Q4D(G&7FIQq6ot-OoYY<1E;J`&~OCjQV z*uDhB!VN19AOlur+`h@n@Nz%82AakJp!kOk0@({Fa_Vl51~gl|Jm&y5@?&kyI5|0a zt5-be-jjsSntULhWf{E0a*P7&;-t0>Kncoi7sWY~2EVWvVVE(R`O{0q-eA&To}yV- zf2w_ZKOYPolPudsE0LR)7Wj7xK^#+I!tVF8)3KpsC92ERlX=)b@!;lRns z85&+z$I0bkw77sW7NStcs#>^z*qU)LZG>`OQUVPA!w$!7RDm#LHE;KjN~>y5-+Qhh7(ngo%j>KB?`&XpYCtDSUhF6~ufysCMn@ ziw>;(-t!FsYerNQ{I#-9TbEc%q5^9(RGA;^41x1KX#QHy`OkqkpuUAXoXpZMDliv| z5sERF#AmI)xjr&DJoWt!qM%Bo@OcE?5A#Q_#mf|QQH63M(*)&0H3id>N=`HPqw9Wb z&}Zp`-W;GCa$V5#=3r*p8aHzo(v8`oI3?u9j`DsiBj#Q%roBL`crtp9R#8^f4zdsu z1xPp;Pb>0vl5z0m^zTbDL+(99RWje_E1*wc9EC-h(u5p6j2S>*0P5BsU9=PCJa}#= zbv0<8S;(iHKCie?9A=6kOjNGQ5ak&xT7>0Nx@69XqcaYPC;1h}(#RkMDG?`Rcu>%tr79ZYEG5T9^e%zsUAkNa1d{p;obQWXUlAu5fd&JBc-^RsYtr@~f zC3d&0<2f-g=w;43ZOLn9@%1ax_ig8fXRJP+RI>@I89INjsocc$nro;^=1u%yWmUnH6{V5~*~<<8zM@2a78=@03Qmw^Ui0m zb`bdHjBRJV;6*dU-Uqvt+OY29>c4K57xtvjc#&- zxy8!}LlA1`$4Mdux0wD4ZWqxvfvLxuFBa>+5g95pb9$f&w2Xy*dFadd7Cb5y$WGa? zVaNQtRb#!zm7uyn^18oXI0iLE>irGu{-$sSKk|+p8+3>YYK&&$p9r$q-@Kpd{B>3j z@4T~m*V_7z+68H7Xb6b0>8pvgw6)DFK(dq2lhx4G(29+o5z^{y0Ek|JM*D+lsG>N= zOu$e;*#v4{RK^kdum%%*X>mB%3ncR_jg6%@_+@o^?NmoZRg@O8c-fP>SMY=fqgVWQ zxM8xdjUY}6<<5s%k;_`{#m&vl&|gmFpB2|wN-LZV)Jans(Gwjf=tckh^Rv7-c`SN# zA!B+k1<@7p(_rrEt5jKQm3d|aQug$cj5hmX4CbKcxel)eFVaC~k7(!CM4@J#Jp+KK ze}Zmq{dLK|{=L1TPt!Q~Jely%ShN-Q4EVA;r55tIQiB#Y>n1t)jIlI;-;|`N zmJMEo6I9xuPy}mt!R|*W3(ej)?D`TZ85#74ZmyM;~Wh7YQ*06i3@Nt~}%b zT1s$@fMEy;c0`a6(0mfJsCF&bUY}Am5q$FZ{}i^nZN^}KGUp-+)df=eItO44=y_d! zdoTcLJ}tIsD&Q5p8i`aZ{`g?9s8X%<4PXou&Qm@D4r}b74yB)v2c>W z<*u{sf0Z{3RxU;e?ezlP>E}x0r`Nl+RC%fPPmnUMXV>|GTXINNuzbz~t6&=RdiTFI zB+lm{Y{WXY{{uI4lMu1#4Z5^k&q0-gI>e}eBWp*!)Ap2I4~3bH%{nkPU)El@B0{Hd z9R4y9f$R8i_qqd$ushgkKJc{VHH}oSSF)J<>-SQqqSldLH*f2DIDGxC4LsPLoxv`Z z7=zXrW$9oQr2{F|pSZ{P9~Ry8)D|Q#Wb&iOfhWoX$nIv1g1Py$!wC(wd0)NwBSEQ| z5-Y5Koixl)cmOed7ByLRyo4pk{OY^E@T8fkqX>4IuiQ++osoxqOEAAU(e~`sQnYS? z27Zhth9gTA2F)AajgtjMDx#lSw?^J?1WYkM?Yr|J0f4|2JouhoR7fvjqDgntx8#)v zBsJH!&ck{s*Wgi?(9bWs!L*p9cZjL3l1c|%V^n3Hr~|Wus1W-1KDbgh>`LyDV|h+` zG@URE4r@`G2)Fz1^!lR55V#+J18nk_{Ncc~wju%h z&aZ=s997R&`_W(gcmW_Pxp@#2jA7|Rm@iXXuTHmt%QT=I!lS8Pra9t+54EF9U}SBh z3o*&?JPQ^DH|Jqbg&)-oHE8y1Jh!zyb}habf^AU1yMUL54e24;gA(__%^j?}o1B~! z%rpXKq00034`v|qUx1yelVL^A>H+MjA@+Kz!?T5(H9i1bpe^@A-Z#v|E=`J)nBy!+ zL#e~w@D|ee-=O>W%NxLX|qltL(rguvFy}Eu(ZhoDBiAKxJ^*5a|THpSr=%?uc6Yb zk{;7duQH z6g+kOGN;QoPq8_h`?+jNjvt_Jz{9tLH^>8YwtV_NDVK@ zp&j_GVK5q$mL*%7IrSlSOi(InzLNJ5TLBDOR;OeQ?jFGRKEGki3a(Nw&`4zW5(eoD z==`4O%d#dIo@|UbnN)s$qsBytf7DP{mjsx~{us4#5JT($aT>fbC`%Jn^;6W*j0pai zW5X~xb6)_6!i!T_Q;T~trH~qMe5S-h3EU~Q*hkhiP)RhglJdr%#BAVt&VTzW*p=$_ zaeDuomlib2jW?MrD!2|1dnGsALWWSCJA=mwqdB&is%y!P_sG1&4DV}g$p1?jw_)Jb z2K$u&?x$^4JpuI7U_~Y=*V==A`sb^s2!uiC|0C-wpsHNEZa3Xsn}!VvBGTPml2Rfi zDM)vBmvo3UNQqL?-6ldTWv50rQ<7Flqq6{$cPg|Pv zN+Q~eiwPEoUNw&IC60>sd-46u;>I=dKX zePiK}{+%C7s?wn1lbQ;Y3^~RM73`Qxm|9V{5x-hX3IdCLWMSj9r;jPf~pr~ z#JlnOYP?@gYJUavzsb47KD@jWo;mlJcWxETVOn}%jCdx1y@Wl@KCxb*TF9`ZI9CDu z@iJ=LUri5v?!68cy>}U<kCYFJpU8A_(=kWIBY~{Qf0uF z4Btwga^Wfw`0`Q0*1ak=t}@6DYlIy}_iGe@=VEu)N#9%X={^$#2?` z)z$A8!Xx*v^c7^l3pac zWa6hWqYTwm7UH}5)a!l~b)SFQK|o(VU`n*;jvVvOcig;Cg=fw>w#YvCasQb?T|~>D z!f9!u!pzb-2C1)kF2C%jk7osQ!+x!lOa=^ldE`cHc^TA=XhVE$R|YbiZ-{?h?fyni z2{HDLT2g(Vgn#s2`7wF=9({J&*4H1Oj-3Ue{O=wv`q-TpL9j(d?jg9ttq7{O?gGx+ zMOw>GUOoJ}!M+(K$1stjN>Kdz3PmPBqE|exg>tAQejm%{X$%>Q96|-vF_GN68wNe&pL(;Bp$p#n9T#3Fj9Il8{9oGqz-qlV ztm$vrG1F=S2pvmrXf2+n!ndBP{yfd3`HmW0iABcg$;yCXeAQS)d0@o}l}|9<+(P@0oIhRe|g5ha^jte;+K@ge9ft0x-6_O>ZhF;6t-Z+p4m z6?s0}DWbDG>Ly38IZDyB5t()c$OpOUwkhoUr2Pc5r;43i=mX;u$wW8z)pO0=827`` zeeYXms)=c>L|X9{`5p9=R?WdoIqQ}}$JOHTZz(s80@}*;5g<#mjRYSJaHm0{P4pg^4FUWRkd8@qUAyY- zvVE+e5>2tDTo{mHnh1{j9G|20Km?NN;jKQbtW#Eu_8e6y;$QN})h19DpU@amVjq#y zke|5&V*3p7c7nL=)5vpJzmqEoe$3=iKn)V|>k)$><>lpCk5QTC%Q8ehzsXmZU?r7? zC93n8-U@!)!)=(y8L45(c|(|MJFinMBO_|@IuRp5 zVA*bB>DEZ-GdqU0s+>y8x|b* z`be0>?u95s%+kIoRhh4=CeuW(^Br}1LHj+yg6pY@=i$u7>n7H$8}Thz`pAqpK;1GcPMFYd?fw_NX# zt9*ZJDf_OVRAdR(p0?vq9(5z2b=I(^a=y-dymO zXp$#@kNoUR6q%l|a{Vsls;6@8jzIF@;^rwA)u3g}e4UfYySco*M{JOz_TVnM?iCKe z?WAlF`@PX4<$52>f=`Q%tX1LSl!%P|-Z%NoZpaL(Pwxx z&jULk?TULq_W65_&cl^MsK01X4(0nMx+Rp`w(g7ULxz2#x+fPw0rI3#<9}UYfGr+ zf||_4#8JcCL;@yTu7sJ>wREe`z2PqT(yzW8%^}GY5x$oXr88v5N;>5vI3Ba}3AF#f z!W1MomPizEE5rBjj@8;q#Jo%<@655~m%@V>4i>3_@h)kk!X^E22$sy$W0Jzhl619n zA#X}V=bO?_g;6pZ7AX)LZiq4-k1sAFPqxx_E$>CwTN(J?-mZh!;A_2VPX^~m>TB-H z>Mry!DfEaQh4)V&5}?6^EdOAL@1@=So$x`78sZ2KMDRSyk8qp_BU`PAqclk$nIXq5 z)MBAeR4Da_zv`f=vNPa*gIjMq8yt4A6h9p=j7vo84}B2WqH5)NOT1vHM_6ySmfo=R zjutrB7lrOzMR;794GdSYqp*@j$2Ocr_v)ExnmW7o^8_Y7e6vhcV8q9b_>tq%oiV^i zmSgoy@EE=pLFTeqa?}*r71OPGjuiDMrx z;6vrnp+xq{j6;Uk--e9s+oXO9tT?{RzO84)>Uxb&6JH|bnI|T2H8^Cyh<4G3_foP zK8MBFQ)59|8?jd*&a*MHF^>@-;dsWe&a*OZZgng=qjt`XP}$uEx2Fk8yerEg#t3b% zcG|UA!fg3s4A>$}tI^X(!v21w$q(1MP$PC*iElpV6?%<_W5UOCe|9p&9qD3~<@yjw z$T}RBC0H8|#aN*N_*jP>w3XC8tp5Dw=tk`;;i|{QF^whdpgM2foi_kwF^C}UoUXVj zPqqMw$@|Ltqyl4(o2`C=!h(zZWg1E@e0mLBiV1>EZ1bt6Xb#etj^AHJi8Bzt*?wii zMrxZ|Pu)X?Cy(){NYgsBJ0BAvu#@|hmB_5E4hA)k5h(D#c?UJ`zY+&^CLej@Acv53 z^B5`_tj<1db*RZNsCbfz*M|l-O*GpIE+p1%^z6Nmv5XuXCAcy|%v&THGOvkHAIY^Y z;oZ=q5Wxzq>DcCe^~Q)cbO0xihI5B8;TT$YzTGy!{j(IOUB@T7eROpEU(aQMWDGe4 zg&(pi4QY%lW3r;`%=29muer=*mp?tvK1AlN>!@YXG1B_6l@4kSE>yM~9I!?jYHNQ) ze*q(ZHX_Ax_S|;q;Dy;T(?r?hK+R&r2A3q1nx;XiyNN~t^519P2wIjI8O2dE!BDV= z012=B!zYu6+3-VQG3}WTTtc3A2wuT7kcAHSwXy(_uqWaf!As&NJ_gtKADLT5F2AS$ zM6&A5k6`N?PSu>4a>Wkx2Fq!SUOeG-{~aI0TW@DJoKj}x&_PNQA0!!aAeX<~Go1Pq zLBaxk{FP^$(Zb|-pwE~X<(BQGQh0GCugUNQ7y`|o*F-@3Ybne} zPn6LzX+J+}$Xe@uZnv*}fW|7vO#A{CHog0~3YEbrDwKP8IL`xBG)Ck@ z%+J8-_2omzed|QdafcTwT5j%w@$ZlZmFY=nQ)%Z#miUr{2Or93K{E3qE7`R~QnRUs z`TZ}<=I}lYwx34@W@%;hhoI376JDBEfe8C0Fsn2T z**5vcXs4s_GJz>Piglfw`XoiFYU;1`_aG;5sHi}t^WN`1? zJu@|e1=Tjokg|;(-6-1Tp9_*JGL3khqa>ynbS~@Bwe}B)@gIcrv9s%(<~XflH@2_8 z=u5Kpi|k~Cz28*pEt=l#^MK#6`MVufI(A1BajZHpEQ{qQ|LFjU+0|aBme^3or^6P{ z6RWjKz@G-gN7q89SSYrhsWNu`_7u5?gTwP^8B;Q1H3-uyUFi`k6(6>xE`h7P-lNai zrR>oJ4fAn_SuUz?P!p_ID{v?|sz2cl*flJcUvsMvX--#k&3K(cAY{IWK9J^^#L3G` zF=uCyT=*x^nd-H-=Cvs6r-3F^C83zA?nvseVKYP6xR)V0o3Fiyy|qYIMe(6|9GN{q zZ@_503d>J0%}^`|kJvEkDx64k`h`~Bq4hhNnwvZE z&dXy)^h_m#V^5Jt8Q9y_ukDON6yf=ptuCB_o6Ov;MU7q40FHnC!X+I1rLbw-L*&aw zOJMIyf6*ueS85ECKNTYv^l@P^PksIWh+>HOcI=4moL)_dY1m;m=Wa^-jF=^!N9OQ) z>)ap;aZCT}F@xv#fyyt2$i&J09vig5Z{NOMKD}ZYlm;cfNQ|9LMTVYC3^NQ7mKa%+ zyHfIF#|U-<5?1;yZc})>IIv~IGmE3vvlX$gj`35J9#!aZ|6NHgYTOaNti)VrSkCsENV4kXB~OL_?S%U^7^PFs`qyD z$&$>7#WP4AYpcRbI;j+*?62)#aTyb!;X$+p_aS4N(>ETud>5V~rJp}*uYb0i2M`_D z5UT7bfxc@|o8b4N$)I0;=^7pBkP;p8`_=V3)yYY*#5+|0uz}H~{L`nWzd5z$2;Abc zdvR%)7!?c}?I>UCH6Djk9<2$wIF6QUThWNV(i4r#=EpnrztOjy`-zhC7{o&S`By~`$&)Y@U!>RIx<>lmkrbG(|9o_XEU;1UpQBp8Y2VP(-Rk7X*ruVe% z@Qh)h{-BC7D4r=kyVk6ZEM`L}`eH-7J$vlk#v*5R@O4_XUWpiw80o#ToJGmFqJR8A zi2vO+J(p1MWvhUa9LCCFn8u#2*10K<9N{YSZlGz-VQQ@K?})?fWGfjT335Y`k?0r{ za211whbCUvTx2ko_&)2D)6prheM`^ennL zkR~I5$*zOFzaamZJ;;!xZL4H(a)$?a@_ogO8~QZJ5a5bDFybhIq7FZ?+_&-5PnVgJ zn|QGx7HZOF%fWI@26FfJBBqn3kU#_^w9a}v-^Od{y#`P53Qs?jbHi444xE=A_e@aU zw-{sM0S~HNlUqp2M78DRRrI8q=X&-Hl>QyY7Fzf_Ojucy&{vgKeU$PYK|Sd-?>@@2 z_cf?J@L`4p!>)tulM+>RPqE`)l!dNbU>}aYKqsCO5TS{$kx#1EV{9Jp@H$5o7gW>H z%2!t)L3k{cHZ28VdG^Ntba!d_ayot>*oSPn^%Sl-O=zvs%aeF6lj7ZG^arS01{ z;hydgg5jD#t~k7KgcgJT_^r_{O5+EiSSw=v2Kz9(c`G|R6i9_}2TjA>DjCZ=Kwm9- ze?s`c=LPDTAXMzuoh_kO5Z#s(ywLG^F}CjQThdht{A0Wg@bvDY|UcH4kcPtG6~t ze0JR$$xJ;P&MRp$h?-*ePzZ-pcPQrf%$!I5O1U*KX4Gx&8pcmIl7??uwcHk^;e;5k z!lV$QWDq~T!0_*&4U>9vJ7J)J&80#FUNFOSKvCqF%<1Pm>dduP?I%jab&VEe?4M`} zJ6C$;thkc&#`c&Mga(hs<{uB&H(GTr@j|A!yNCS6)VzN-4JM9kRQcVwhf2{SBL-o9 zVy1X%Olkl0G57T4Z6hxwnb{?;NJz|utdIOz{JKvnaIfD4%CO~FuZOnPm3{v=c7d5y z_JIh90NO1a=s20#)kRkZXJ;fq?gcZ?JsC&9{jE{Q+AK-2H4v!ER~Ka7PFkD7SfU2g ze+tUboKleAuJij@LQxNt7&%J5sOl9E$H?-gf%Ea21AUUGdSgppz2-TT*PB?!uL|>h z1lJ%eCOn-I-xUP`lB;}&EKlvm!)Mow+msdOv?eAaCQcka5>{q2Z7Mx&fCn7#m`;JY zFtp~O6M#=&vI2)I7DOQ}3EJ){P(P>dwEbPWdZXak%+{ix7Udu5k|S#xnN^qXiO2|( zJWtWJVDCC=EOBs+8u1Z}G&J55< zfdSj6)nDJsKN+x@4SW;k@I7{Hjqz~$ZCzq|Z+6OQbIzJNBvHf~v{$823QJ^2RiaNH z>DoFiYi9iVE-SWJbd%JaEgcJQ>gVbr3YL%=VrK{vTKAsNm8z4pR6nKhO(rZ=l!pIH z^IPV3qV9j^LvWSfb7|{YpB*mIcD+_7xPTl*h*RM}pyKxzM^~f_#J{IQtaM~rr(>+= z8$48Rd+@4lyOFW&tklCkS>vS%Uvm7f7Xav!zGAdFqPLD&sj6mutzK4NK8LM1n{);u zTn?epLV_Tc+3x?e1{N`-D^=2XeJR?Xsyt^nSOrcLTJLX`);<|uVFDrrKTd99VgjLZ zIwsr2!*n*q0@`ND)BgbXOf{7LDM`)mz8vy|b~&&QE$>?Xhp6h|WG(Cd*U}usaXm5_ zOu`8(EzyWS%IerIK}q*%^~wh7V3{;aaugSL(vW#PHjOu*6?;~%1RI^8p4_pZi)7@0 zScBPWH$#ILI;=6X>9TnO-4ctb1weQefPDxY1~p!B*KDoioHrTZ_L&mY^4rVQyzDJ2$qF7IV?(z5)_s?c zFLu4nU~%gDYb;w}FJ!Fxbr)jm&6u!blflcnx2dnh=QNE5dO5HysCCYISZ>!2A394P z6&_uh#jou;_)-T+Nc@na?KdvEP#!IV*F3g%{JL*%_BZmi za!;wikM`RsO_He0A#=yK9Oyk9K+r{KJsoQSFeRGI7@4j0NJ>`8M}+3mR}2&<+1nh~ z@6N6F*XlFpVo=`S)a$3>pQ}oT&AF5~u6TJ08erwIxrBB}eL5TDqdTyb}N+Wm95(YfiFa z4F*ey>_Tc|OP-x^8D^tF7w=Vt8D8y97q_B9wjU<%U!M1KDGNC#!J3=g2rJ1Xs};$i zj4#G(Ro+t(w}|+ArV$3st54j(vQ>47KRiy#4pk&X`&dWXvG`;@xI?p1L9PI~L9h_c ztaEiC;t~p{-X>ib6pHC+X{75Okjy3878XNmf9HJ5XnTT9oO9KG5r5H>>m8`cP5qJ|v#&WFsrQ;m5-$+u9_M1YMp zaTw^Yu#hcrhVmoZRKkq_+(Bhpm^-c%5^v2^p4oh_8ZgfsWJ`~ zqPy#}9$>jzac?2OM%CtY?pQL`*y`Cj1@+X;|GWn6kouAa^8;o^>`-ZQDQ3N0PYtWv ziw}dZY0zW{HTRC@n6hH;mt>l3dw2#Apb@e$fyKp|Q=ZI7GN#`duWit6N?Pm@*`2dT zHc|$8T4KJIoIn3a2sB&JlX{~r-Ys4TUGOA#rIu-VtZbwkb+22D9389q2M6`R#;64e zKQXEHrszAMKztpqHU!+Jm}Lt}UOZ_f@kwCS+}7mPF~g%9&`(aztaXE4KOuEO3CayndH_PmE>XppRhz z(1FCG_o^2sqAN>CrF45cG!*;~vDa(lj8n929|nzL=RPi_fNbAqm1R=XqM0KIhP$rr z%vvT`vinEJr^ik{&t5(Cj!)`j=^I$gDO}`wad~~r%1kK7OcXvnzwFb8qJ!x0{NISv z44(H-w}MQ@xOyxA*s=26PPHAvM8yjQA1Ir<<9Et!MilA%1lWBs=sHL~@R;EDPT?h95iExMvuQf)m4HD>^a44HG z{=`v^lI;{=?t>^9DLo4(EPB|{6ML^j zo1FZWKhlS2)_uK0-thxS;9vc0R}Ju>$r`L_CYb}e=*%KSAz1QU(ji|yLYHUBM3N)t zNi|YZ){1AyoK!s>+Smv7woep&qQ2qnAo64f)mY0v3$|86vAZU zjX0!naT157?Td_^3i%P6YWpL~`0X7F#W9B=^%?($movgvoYK;T@sh~TvhN?SW=9&S zeo4&66Hip0CL~wMos7581Lx)F%J=emx;^~qs*`8=r(<3qdC@#0T!<01lH`EPWeu+I~P6)1TAaXd+Uh;jR@vm#%>Y%-G065tq zLdHkIP3y0SQLkc(@?$fPf>36Y=!q(+*4GA^;?oRZL1Cc`tbSYkx=DTEcyoL z=d%kIv?2WqYXgKgh#UQH%|!UD@Bz57ZK*Xv>U(BEGE@I~Q|YJ3!q36qHRAIEE(|#| z=RED#*SefOtF~DWZKvAG_|~d+mbH3ya1qT%fMyO#s3A9CBLm&0Y_%<<@g}Fm1d0ka z(mQ|5D*s4;8TJ|=d_zZe@Rk6R)K;yH8(B?*9VN(CQ7SFm3Xk;8q}@lbfZ-#6B`1kW zA5%V)>e-OQ$UYiPPyoTc+SJ&?FIU`j73f}d+!G@s@?oM-Uitp*^gDUtKhd3Cy>jA| zu|#n+35=n-HDnA!XRA8G=E`faOc+?x;Ox55Jd<9q&j^BGchIuqQ6LwNB*l>#Y>_`c z;eO@ek3;5SWp5Ciqk*?O*&Ky4IRV zmQ*oCTOzaozJ&xiE;}u3VHC}AhEr|p5M#0JOdtaqj?`v2_M*`BGu8p;tkz?5D)*VU z1|Gk#SzqyByve=uSU+`|IrjnJ3{VCneKBClF5+@Mc@p9}2aSVrB7l=c6OX2?t<5r7 zSYJ;XBmsHT?)tcxmYdq6ej(~X_u>J+i5{_Isq$yI>gPkYMiliX1D(E>ofMJEro>+! z#=x-Y`enadJ6hyjpJ{YLw%BLQ!OQcVCAkOro3)Auf#(=35?f_AcD(bB-StFA3%y$q zNIbR=avT<=N#^5LBL`W&IQW*PyLqC5OdKyhdTHIt8G7Vs1M8;(T+F`bpm^C3W1|w_ zMgUSnn<|N;zc!#?qIB5S+RjdU-N(?7diYAD{m*hp<7GjN<24%X^1(`vhP}09zIq^h zOPVcRlM{*=1~S|7Yb+HU!30}0t4EUo5C|lNvim3HMdI{o-{hYy=un;g)&LE^c4!s& zRiNI%F-byD^H}?~ds~+dBc^w?i@5t}nHm+p(rZMB7k<_G6Po}*ca7%!s+(rfweSAv z@{!~>4(z&k9-3j(yf-by#d1;V;LiOPw3=iZ_cMCXmrx8~f$MCgj|oHO>MW^F4|fqJ z3yqJCJV^`HIbQ2YYn_usJzZE;oJ(_Zk|O-`VrDg0a}$aEt!e>ucKOkvf@y>e+V>3} zkvBe5+)_4(kR=S%V~PC0GD?0#2q_+U!OwTB1KV>_`GLxh3r%A>D4%eLfIj?I;p>Lq zi3c}aA^&ij-@<*OR_&0_o}hm^axS%R{>eRaa-?Zwj`)8oi#RxOqCMg&qn9K44*4w5 zUU~*Ox=!?WaI9HhnwTX&GPN%+gEH08#f5M7;64fvp{RF1f9i-F_Y!%Y{m|tE2IA37 zUM%n%=3b27f2=m`!xRDAr$ABc0R~J*uzr`BlKvgFu=_Gt_}!x+PaW2SD_jvAJ5PN? zv}4{PQ!fWfmsl9ir4F~COkY`zVee}7>X3b`*?oT_9`>388{A}FA!vmFW8$OJQQrZo(U7Hl4fdxw(4t*=<+ppg)@+PWKX1mvr$m&_#(F#-$- zjw_*4q&W(tV+jv%gswuL=bk@K29Ue7tZYXkL-z+}2C4!7g-}JuTT#mnQA#vg|Ee0P z;jPo`8v+iefkt7DtxUnoo8y28yP4mi{QDOA`X7XLRLr>vYR&OvPpj=Hsi~>KZ^yD0 zs_?3YyWsAlyXS40n?>0BrbciN)~W1nI5%;081x%2*pIfX;qtT?cwYX{)t>i-7yTfO zHz`Tp=6M%(@l2*lFp_H+ogGj2<*9lMO#hl8XLuv~ZZSy-c5oMM$dBBLf3NoKFD(B*_O~ zSV?}_AhWmE1H+EX5vOlj`D3*q6-Gz+1=1Sy?-ye;NU+vUnGyx*v=erj>{CCM! zU`wHa`>cfkNQdL}Ik)}0!X7B|s5t@mUQ<7R`Y-m}r1ys4iACl<06u!B_ydReApYN< zBml;kjzOXvvsA7l*crSAMyci9+<0+?w)5bOmPeTgGT58Wf)*t*t4K`smvyee^INCd zQ-O5OaPZ$O%*Qrq*}@*Cy*+q^exp#&ZWC5O$cR)~6OHW)wH-J&jZZDUOJ^X6oq0oB zVc38RoST4}1lZ>#Vbtp%K8Gu3mA)v&@CdLpl&o_f zrlzLy%74S$l&AyCcO=LktCF(U+ZE3Kh^;Z~Po$P-k%ZC2Gko}FdbPaK_;y?Sa#47x zCnyH57wl^UWiCY&Z&p6>jF{jnB;{Gc^llh@E5tgp9Q37n(MRAu2k*EN6ubl)eSJ@S zf^3@r{|w{|wwo@C%N_QB=;93(g%rY>KgwH;_4dD_>+9sbZ1_~!V7Mvq&2R-+3AeYg0J$x!q2wkLuKVj~h z1jkkA_LB-|IKt!)!OA}|*3bcpLCRk@-IeK5QIk|+SU_tanKfWZP0=RpW5uBVs+;0x zGS3Ipl;~X0RwytQs2(K0e8G}B{{4GFXf#M&(x46MB_*r?f(Rn%tXtx?Y~RL{G(`v_ z;$4JzD`K(rs`$gHn&Iv*uVs?ds0jgL)*suI$!jydun?;WcBZ?~{OX{wo$n{nH3*tE^7+R>4*_8t zxLp9_9&Z=M|IJMNJqM=kC;IS+1rbmjB=OtN(x|yDDCqikQ%v98|MNfDaCTewk6ZuoP z08+YIX6W49tEuVf!e(P}Un*cWGzbvZZdfd>I1O+#>)I%F zl+gqN65qi={vU(ZUlj>Bd8*v^UxDKFwV}bRrvk@HtcF~kRTR;I>JC*k!zq};;a1)W zxdAySzw;N`uQz(| z0GG7+%(xM1h$Jv`)G+Z$Qq1-}D^-N%UZ{w)L{a%7EipB6R(@pxZzFyt z)UYWWE!!9{6Q}qABrbL5cJ{Ky6GN;M?ehC~_AWDz=y+nADbhYt3$>#+QT;<^5d*cO zuob5sv#4GsLUU%-Mn}1e(^y!030wMe62C3KV~-YMb_EVtP{IMjM7-@O&%d8@Y`^n> zAHt@b23`+$FWcXe7!+f~&&RFdi4s2mTUe=S$r4%XCCun@Ks;g8{3uQ_nZxJWbt}x$Fi+0{-Uh$XvQBn5Vm-DO(g7|`A;vz$~+F4oh(`F>WfJn+i)C;CBN+X z{?SV9@o`V3pIt-0*T&t&+ARN4@4$ThN@$ad2?c6D4(+=L_7186L!W1S4RtG&L`k30`PH&ii@hD`7G^8*-PVfLZktaiwEBk<;^atfSwLMyin}!uhx?s4vQj>EWvEsGDrsK%@TAuS`NWG z&@cv4*z7v6j%w-ZG9(WH1XCLPOM)qA$Sy6ibkv*+yblB4b<q8hhDIDOu_8X1 zj>|xrf7z!dO7!}6_}@A1Ty(_0pRezt#x&X3o@mUgCk32|yq}*aFvFqVtYW zLB5-XO2TLCACG`={`dV`>iBar-UiwLe%hF0w#LNr1L-g?B8+nf+aS7aza?Rm@kJMASCO; ziT$_4f=nt+P|03Vf*h`pV7N*STY5KYE_VZG5+d=pnEtW(H9i3?qOKvSh|STPb(Ca` z7m$_HlCyOgPKSv2^cqWnpl?_jr*~^E#heNn77kpZS=WV2<|O@poecx-mqO#WPlRK* zaV+3nqT8ud`|+sbk)gd>UMy1fcXiz?2%@WWBa+t^AN5=h0r|SN6*<_xzt>& z-gJJh9$buHlD}cUNEjeoB8v8@;X-PzE%KB@GiJ|0kt!fRQ{>fT)>Qj{X}Iw>rv0)W zOL0hOc>QhZ28i(^VXkZu5v1(leX8{LZW~I<)cm*sjVDS)HF{ZhpNvgb2NMO}jzUE) ze(HPrUO8v+d2!J+{&~^MO}=nBWA^fBH6}yUPe^Hl>u259<(_ByRVQoliR`4ui{Usk zq;cI3Y1HgM!FH)BVEin`Q0GR!>f`+au`( zFu&!~CT}bQ{wL7hKg}V9g8FDXQ-vVGROSZKu~ycT)%wAh9?8zR9>LCVC^Koy(ajzB z0>h0YC53h^wQ`6J1mHH17R!|fO(>xY(TvA&`(TrE<8n8a zNOk7W-@kuj`cTwV3AM%CGID+2aPFewEJ(IGJQ+LO-Uhvdl#h=vpk~SitIY;*eNTp% zW?H>!VaPUb-x3ojmCUsnvG>2Djsbk;OV;AID8RS@M)bPt?e-R$h=A@3sP?tA*d7P} zJ4&ARg-HKzcU3@@k!?@&*On4W?KggWkCJ1FH%i1Zqy!N~x5}}jlf|@lV~p}v4V;`q zOfA{om&pZ&h22lxZ3*a zzwj<%35;Nols)C<%Ia4$TMH%y_q$zj205+$LSb%GG&u5^WkLX2qm1eX-ipV&xW0W3N)=4un*yWkp^qAfF|ozoXzrJ*+T}F9c}Gc+ne+ zNbX&)Qv?lW?le~JbPQI!I8BH5wRLNY3DUK$uG#+izNgRrE8^#mF58T5&GuiV3|nBA zRW9v2c^k03q`_0}2~>-uOB+CHur_tkr}TGO^n$)H#_QqGii;7tdV2j}Y5Zjm26hm@%ohz{(*Bxd>wvI*u+UWc=@SwJ zScQ><-S;{HGFOLhCc?KS0J;OLI1LzWJXF`#u9Lqxk&Re792jECjRgah%V1$AIVk9x z-##3VOXHPIPO6C{g6?Pjf^sKS1_WbEa9alsgzma@$p@v&EWjnjWRj0h)tL{H}Qw>Y|$0Fr2(^O z4JH33!9nl(=Y7WU{3(1u8~CL|*qV?(I+LRTJma9685*N1fbfOQdAsWFLcVn5EgIyl zG`(xli$PLM=G2i=tca&Itl|7TbjHkdX-Xyl@F1pzHB5h&wiAf$a&x;Jn5(lYEl*WirD8!8j7<1TQDXRV7 zchn((OZNm}OGgbIcPe#?=agXFG3h!sG!_J8QJikU2k0ZHzL$Ur1{1IowsEg!gab?} zgEI#-IRo#VkBuO?5CZAA>|+N~B8SI;0XX@r#_d!f`=}dS0ulQ5O%@F|^n_XHQn~Pw z(7?=03T$#NWI(gyqvw73f}5y-48A~@3;NIDhx@FK+>nNdwzwX5s&I_=7*!O{Hh$#{ znd8R~5X27vb~!5b z*~iGh4LGlbg92ezgI5k2amrv5C1eh7+Wv)~zkxC5>-gxPVj3ySa)?rn)|N z;-rMdWF65rZ5%C=<+&LgLM+e=YGRi9PR;U)sh9_PC>b3&}2pfRQJiK_?6;*KtHfgW3QgB91l;Y4}eHBEj<|Hmjryt)2(i-_@~!7 z4{WJQfNNj@iWc_p_X1^-b{zxg8X}g(vc@JVhMdrU@JXQ;r{gF|=ko>x6;1KOiT^Fc zw>J6k-dF@)UeE255d_G5p+;-1zvy4?g;?p4HXOEh@zf-w#~IXC1&dndG$lumJGj3- z3}IwVva@EqqnQF>q?>8JVXbtcaN?zA2$N1l=akdhb!()DHr=u(?5dtAM`Gr1fP31Y zutsvT;|Q_-Yu#Dn&z(OOfY$?ak^a|{xvP00xXydRxo|U(Z2os+ap>R3Fp$E{0TQJC zx~_fKD3@kN-urP9M9EY+u5^zH;U5bCNZ@q(jeqTv;d|+ZC4XVUsL*EroAZ6Bs5j3$ z!OaZ#6hLN3z&?o>6eyHW^$)GhX*)?F6_ZeM&?YxIDoYC+8Ih#7WK@}M zQ1deDGF7IY(KLH5Wi`@P*AnSy7oru3yAU2ekMFda#p)dhxMw=LaPN9 z+jdRGS^+{I8(Ek&E7$Yz9P3G*6)?BMT3ggOI34naZ^9tR9${$h7~lmKERk0}go>pB z!y<{REOoMQhA8NtCIj8SM0XrJslwp@CHwxVl}lSw8$7DW@ZWD|AoX<(h1JEVG!2yd zQOLIQau01)sMoB_#4%7U{TKyZ$vVHvkRe`%CAAyaHi1{_xI?fmzy=^0u!RZN zY~Y=?%`Ko{RzVU05`@aBmw;qi9B}b}$G+m>;y9Wms@f>v_R4Mjtyz{*!!cWJh6Z$a zu)PCZN1~4kRf&mK(!zhCacx?jf0f1N*VDHsOtvLLXt}Ua>6J#+a5ucG@ zM_Be%nV;A1?759;C)2Ftu~r;5%fSj{YektNCMJRGx%Hw)<9?Y&mLx}-=Tq!tJc0Jr z5?^vhiydK^kAlV&{S=EPFOv4sW|6<@`1*O-VLxFzcHj9U5Mi5qn7u$0%s4Ojr3S<>KTqnixiLIADs)2i?KTqV=Fq^ ziW_KXjW}5A*ti}%yJyY2z`~$D_M`%yfeg|(L`bFzk;(=a$Q3n&NOW9#hc-A2OvO=Z zKsgIw^Fg6;fSEF2D`EZJ=tmUAWF9y0ELXv?h!y8a>2WL<`M?y}=O;ffla{6MX3s!q z(b*VNeh61h;~hy`JjibT=c#^UWmLhf_dj&TwZbT~2LT$BQGlp&PiJ5zg>Q|YupAC~ zFs0?#!e>5J@oOtk$PCUpk-!mA*m8#Q`wI9wo(w^`U74|aB+4MR`pDMG9ej}uy4iyu}0EnW()vyfe?YH z%rAWY=e4;eJ>fVRyf!*pbMA?pWX8V7_Hd0tLSc`C-nNUyn0T>k^!Ww{c@-6$9G?Th zP^tXr-9`T!yIbHW>;>Z-$0g!-7=Jy+EK}{mP#!D%=)M9%VsP>bCYV9oXX<#u$VLKu zizLwipq|@JV2A_tu%=|#vKFY6k$t9Mo^TtqMO^Q-W=UNO-p3FFE=#lbL|AdbxjHB} zGR^(z?H^$WHPHHJk2)@2K*kswiS@E7{E8q9QEp5vj|i0onnqCwN{)}=MV?*L@wvz) z@JsKb3cUBCol$R|gb(^T3$?NDyIzXQ)F=(QZSaXNxXWYmJ0GsoIK?nMd3Vfta`Ta6 znMY00U<4b3Tv&A$tF4dhF3mKN7<-%M$twl=$e)s8XeZp{Z+uyO?K~-+aeQI|#8mI8 z<5cPyR(L#c;|F@saPvllCOE3hwp4i<>hfnfs_cIWxsgXf7#S1XDE)Lw&-UwE8AG32!>7sjp$s*tPuk^I?p7yHD*_6=@bvoPZ&?ES8|Wy80=> zKOO$s60M3Rg3rgto8nJB5~2|%**_C#kbTrB1k6D-)%HCk?V>5ZT0z@6v1r`9AO0g2v@O@hv?mRVTVyUh~+KtC734U})dRfQ8Dw(+fu!X1}s?X`azmkEWS~Mg4suQwOVIBi) z5qM?(zAyOIC1#I=B?bJk)k` zV1tqMHrNkdF=3b=6&j&_y=@s?Zq!U%pXu-`7QmB8{c3SJY2a5NoKy^S6uM(Oe1!Nx zEd4#gt+(Fu;21ntYNni^VN*gQ28 zLCnR#mi#_}XOK%UG1mIx>0wb|4+_E)F~QF$@$~HuB9F6cV4f{6v=X|p4~_c^h@CH~ zE`^jyY=$s1v5FAS{ZGF&!)-8!#!cgyhD^|} zWu84?>~K6NwhD_k5T0$<{E(YQKCQnuc(~!x6^0o+YLr-@?_eXjKk@41a3ceR zZ^{}B)@Sv9TQQH33%E!_=!*&%4y5DCeUs$)r#{UGX}(^2ABQO+Z~4qSwGoWfYV{-k z*rh`-b&x#GhXTG0APc|m_5avm`pGa<49^YzcarTv#}wF5x1u~2y-Eh&XjRSEu!4O< zMu!{s`&lxZY3edb&T8JOgct7Jl-qhwgRhH-j%yx6;6-^iAE7<92&I0AOj1#dTiwWT z<~;W(g)O_IJ#;3iG@{cJS1~4+CXP-!S95AK3R+{d%tB3lU(t^<61h$ai0?PqFM^U! zvJy6PPwSk7{Mc_&d&?OIpT4DzywBodu{zL-ZGXvH-hClrRP>Bk{FmC@$mOyWjxpui zh$gcO51hiGEpAK>y|FycAy1<9r_Jq$dPc89}|tZA9J z1G8$L7HtpB7at3JE{r9qVRNYwS@S!7nc&kooePh@_(AD@=2tzUEdu7i;HrZr_kjS3dl}+{t*<_Pl3d!Dk?`*PV&#dgt|8{=Q^MB6sT-WJzU7d4@ z@8|uw-}n8xUnAFAtfA^b6Pi?3C?=y_+Hq4s2LE1tpm9d|$wSMEsXUQ*Lm#?%mv*Gf zM{jX$>{KTgWyEzR7qQLBzw@yXg*l5RH)fRowt5Utz3o`XIdbBb4srw?BTS)AuXn!p zd6zQKh^GaY>}$*+BJ>9Qk?G96pLi!6jYR#xdM2E%8jTafdnch3%mER7Iu^ZQ)e9Q0 zWxGGFtmu3=b9NMMhA&1;BPVXV7o1#mIxmiOuKFK66=Bmci1d*0Ry4)k-K0unZupqL zOmoZYqqBcBzU#M7jf>$&Vn=Nqt8~*K4*!7p6E~`eb}XS^3SCh7!Tf%NA@M1FJZ9`x z><5be&N)e8MzM80eiTK-?s~qe&aHxERM(lu*FEbW_%9#rL^5`)ABYAKT;Pi^hTMAK zqaM|#LpFyjn0L2qIfi4A4j=fj#B*;uZ?-IPw^Lt-PM-y}_m3&y_WrsPen;{1K21lI zMr=B6ziXrZjD;xl2GR9 z*-u_$i>_7WU^~0(C7~06eMi18tX+<>xjRgX-`PZXtB%}-gqWX+ByqE*`q4_ERTS=Me7!`nq*i^ovdoE@L@-|FYqejS5pQ$;_kOr& zb-YZo5?)O!Um2F-8C#lSeh@JLG47befAFhKUJuLXjg!@1al_$4CjGKrr{s)2-am(1 z6?t&h>{*cqJ~@A}W>i*=n%mQRI1UnG8@}Ap*v2v6*1K85bFc~bmPffqg2HP(;gdI2 zeu&Mm#$A@%^2BIv--*VLKfCXG#f>e`vr>xK8?S-RlMhXp6YC_~m9_Nm?hD5|;i{8v zvU>Y`%U;jK6QY0X1b*e%ty|jav>h%BKfQF`%g&0>sUhToor5Tt6=P$fFfXK-ktv-E z?Fa0nku}f_rbtRup(OKVIolQsFHGPlx6Y4snJMOj5x-^j65lBWV9R91lm2m2( zw*2AWz!p2QJn)|YVioq@6U_xFW4_6(AM5n6d9)A zE-QOA(37B1_a-*6gf9G4OQy(3T~g$CM~S_wHuIH}HRH-@?YF{~<4+aKbaq{DALRI+ z&0Wg;y^deE=q;2VH?|MB= z5&krYNwFXQ@==MxiBO6pjb}>e)(j_C^7hW7(PMn>=fm8uGzp>m$7M6m{f{y*h)i)I z_5W}vx1SIpj18>O$|Mn9CDl9a)j0{gQ;3i(JQ&;AigB^F>@KncX-iX=ffadcm(%(% z+v>>uQ|2i;8bDxfmY~sn<-axAs0l+LgZIG{)k6cBDRL3%1P{)=IPLe^R<_AG(Ge}H z@?(5Bf0FrPLBmiib)vA60w&Vz(dkR+;Vs&y3kgZq?J@|v&sdwh3mWuZyq|ha78SbsAYL#eNl>?CY+BYL zs#(LDp;ss&xtc!XM|0+6J*~_R16H37 z>zI*{A_x6c><&+sQ}VFDmR#jY>BbQ}owKEP1f?r&W}Q+?en^-Tn31CC%rT2abFCAHCBEv-*=QtO6_Tf8s{8vM~NS zJ#?Q2dMH39YqJfaAp8Y}i#<$cP}YHNcC$$aA|FsI2aPDWrDbvLht8QhC_>ya6{UWQ zoEwZ7g*Q3x_XhKkS@nWR51bNpblSe>1xkoL0sDUydj5Q zAo2>=j^*NU!^*A>7CUAmyNxu}=Rn{BV}{=m1WCqTw#x2!r7hpVfW!;eJ=t-#dQ>L{ z-^U#vZ&P@Yg%hBI(T_@7;XUz0xiXY=K1ay+Wj7Mcp52zBw|^8b0`MabPAncg5ZI}O*K z`k_)1i~5Llptoi0pr^j;fa_uWOuRL@RN&9nH%IFQ6h`Twm?gvyEIvJ5R*FME1@0bH zL~BspCYC+gbCIFZLnj6Kf-mfE2fj$a-w&@1O(g1#9QH}D^jCN&z)uH)mj*Zhg2iXJ zr_1ccY_f*C$2hw?eUjhAvNao;A!E8~D%C0v&zhT6!x9}TUy9?ZmpzSUFpYb!Yd6aL zq62Qr36FbjEt>!jE83ziP8;{kOmL4%=;MrG=c+Har0IO(!bRKth;-iX+wqgt+E6Qp zi(5K6-#$rq!=88Og^<8g5$U_n{`nszv=_yGh2_SfpyKq_pCz8_&?^SJ z=aW2x))W52PLkX9&@A2A`h(9Gz%s;q9{uk2$wLdzd;JS@mMURkunWK>X1`(1Wxj3( zn}ej@8~LgTbWqK>p1|0mR@b@piDA2P@nc^SA**CzHR&f2 za*fjOhQc{Ne!$|-uf1KG7{r)`<~Raaf-pL{J-VuOSpC@)Y z9#?;0f4FCRKVv3UHmfc+ohlsd${H8f4ewrZDa<{}MpIBk8FdqJ`! z8b9Nkqz)VF3DZ(NIy!z66#gKix*!up#4q?3R~3>Wy545novQ(ochmX<{u#7_{zG79 zIsC6CSYWWWa^GqASHBb4e@zb80t46Td0z&f&Sf<&2N^3Wu_FF$W(`zAWEAC(T#exn z^SQ-#wGs1#I_R~_Po31GI6~RIrAj(y7yVyYY|RRX7zl73+^m7X3x}Wstk>bi`4MOX zbn)(GpMN-t670m1K!Z_IQ5kMQ?BG@qis`-STi|YrGx-A0EC6FIOI^`mH2Q%pPcLk= zW=Hz7mshgWc9r>L72ZuNM+-XK+-&dp{Vy41suRmfdAAeOR2G-4b_Jz zx;^vJK$lLIk2B`?He0j#()D`w^b>y*h+94_@q)SM>4{7$Y-E7T)**3E7#V@sbwrh2 zzC^sV@U=w2jsed?@e1d-TR^xY%i1~G3pd?uJD#E?~|iyw`6bZ77>x4qsa?;DI^hI5-;QK z6*`06jT6uPRpol^Zv*YCRHApPL%g27Qbc!9mW;Ar>`&5BIn9;jtGj+=`!%FP79AdTQrK5 zWDFv)yMpc+M22uXtnS|u^D9#UkrtQ|!1gXy)Z^wwsv^Ve_L<**1p>gzv!|lXBxcFp zfH$daM!!llM_~5?SoC<>7ox;^dx1oD{d*K8*;Al-zOcAzfpI1!*lS;Sflf5Crd9+k zkE9hdUzrdyCqgTq<^Sfdjm#;Z`J9<`orszVb!LtPT9(d1%a9{!C zw)$?F6SFu1H@%Hj3e!_T{r-h32-U9-$BeF}LjKYquxNdN(4&9MhShR4ynB-#-;@Yv zNV+BHM=5Js#rWJYZN9_*s@F&Y{S!El@T`zLho9L`{K;=^;HZA?$QxX$G>${=4G{Ge zB0S+y?wnt=|2Yt`Lz8f;`DQ&LdC&7YAJv^iMVTtbtz~sk+rQ&F(?IM{uky3RJB|~# z(3!Wu)q;B-{sC>Srp^E1L%2KsM^Z&4%jY?nqS)QS{$2+8iuR+}zP9yzl`|P5r}$J? zeh^+)^801Ruk_h}=w5aXuO(kBjj34P`<&#=cuO32U2<}Fc*}jJ+>$xz0h9l;4;G+? z`VlsN=&C9TTrseOjqG^$?%hovEexww=ZiN>`?rbPy&Aa{K-pU%n+t zP|{tba%@h7m)INV!&xl|f48JU3>r>ow(VvdnuDEWZQ*Jglz&nBm5~Nz%Zl^D+ zF-L_#&)5`k^kJu@=lxtiV}<7eA~FIG1#1MZu>uxpJfyCmQkN(iniiQP!c| zKDbbxK1LBSJM~;R?&9wnkC`C7u+O^62%DX0T-*h$6mcz|r^Sycp-N(LBG%?VtlnKI ziQ$)X8B^8QqyM$f8Ylm+hxL5A8}HQr)f`;`QMLxA^R5(vn0@>*Zbixbw+EuCv)W;Z zS$NZu_IG!9&=#LdC; z`iAY)lg|?OZo_n8M4i#FL9Fyd?Z3GImxPOp;g3Pr;>!-XUh1TtRIF~s zcWlHjJ{hs!ZoE-_0Ejssr)|{)y8^(C3=%VcWKnMgnOl`^b87oWk0&3*y(9dF-NwcB zozR=km4CfQiq&V@>!A*IRd2}q{S6ZabjD7~?$ukvk}6Dx*As#}Crm#Mt{bd(vXRA~ zAydD6qV$lraR8ry;8)p~?#c3#;lrBZI9)hnMPF);ikX;ld>*7zJ@WC9% zOIL9`OW8%D=zkwM!)>PCojyU(er1}UYkz2UUnnhLNDN^ok;mA?gvV{`9?H5T7Ilw_ zv9V1r&)Cf`Y;-?VWJGsx->-$mO0HHJdcoK;KC)5d$5lSES2KHOfxF8*QOB`kl5B{< zX5!OGdwg~SZq@`Z7tSzRh3QxF3XUR~zb~O9UhXF<{>4q}5`QjG)M#4rsz?JkXKpVu z138v92B-N9-2{pxu4?#SrB`v>`w&4rI$>4uw%>>*(p>o!Z6DhQ?W**r)>E0lBt>s4 zAg4Ek-~GhDjO)jI`l3Wewe$mx-#nw=w6C{o{%ezOkea&vRk6vMg!Y+*vx@~sYOMmL z!N_A9La&W;-8H1|d#7#nXTg|N3*xBsdmLw*9v=SHsBu~>aSS8$rX>mH+;UXd=0m8O z8oRJAwBWrD+qRIl&hIbMN<3;Jt$q`7cwRi6c2Mzbc^7@gvB`G!zOu_W9Tt)|%7>WP z*dmC*`X{o*a!Q&Gmzp$;H@gzM)9_{W=Ta8p!2Q6t8TTZ+H&`*Ao{70tyNM@jZ--EQ z#AzCH;FT>Nr@2#k*yPHwYS@t0?7=!P&w3%>#O=riP1&5+wa~@-RA$T2p?gAhN#0Pj3mkvp?V>Ign#0a@z%W>M&M& zK`*M}KBhkd@4G#Ltdh^s;RMIgR~}!8?4!EA9qD{aYPhO&NZatEx?FY3IpZ7e9BVe_ zd{r`m0M$p51}AU60^7T7b?=?Bp}#n6U;cRz@SA9w1cPbM)!AE4T~=Vw2A1r4{SB8& z-{oU|Y`NfT(*6BMfth5Q2>$VQSjRlyw2I0FvWXtsbMOhjRM*)p`8YOJy@oVIGZ!yI z=R9seRiOPiH%E~BZKw$2YW(WH$Q-Lc-s zMpAqolu6>Xtb`1xo6rJq&oKkOe^07#(%zn(yGWX&?$88o2F4_>8SS?Q&%Jk6tX#Tj zFWAzadR?zqtXFie#^%T@aV+o9eMoRBs83AZUG$3l ziL$pu!2VeselBVPjER#=&phhOQl-EJg9yxUvv7387cc0x)jbH13p>gJGB;8cKSc}{ zM0$E0cKnfgHbJAvrrfpI*XUVa)$&o1QPG2jP1?luXYqR%$^4?)J=kj{ z6E842IWD&BY?sz2h@sUJ%ggaZ%dirlw^gWHU{Z5k6 z_2Ps>Zz&GFY73i7msUPkX8NLnPXQAaR>}l4M+B=QQwONplvR{~Ho=SY#$JvNSAi3n zSqv$u;nOYaJWL9AGRsM06&?3A#3Y93pzYr^!*y;>H>q=RkF?u?Eq;@27aJQ3rWrJm zGSNFZ{WkFh2{T$ux_|j~9lfeIk`y;1m?ef(t=D`P&SnpVm6jIa%RkaCUs|k~T{#$j z9&ogE?@yWNOMF5?Wetta_w7z6fCij^gy|t0+iGz)+iJ949pB8(YTce4Yq{3_)-W65 z@TuS5)DgJ}yoPQsESoX?=6X;NsrS++GnQ(7yI>`^^I-M$cJ1EjQt%^>jQHtj32WOp z#hB=h*wws(`hkXqgAU3!B8cn>4`#~4QiWa3cd}kGjeO&9HZ^4kk_5XYaTda1rapNF zyg2E%PoVDo&s%pMUYsEC{^hy5GZ~f@gmFg;yhEf)kSlUulz!tbqD9_x#N6N*cX>j4 zPci8zq(hdd@^Mn{xCO7Bo!#0<4v|^PJ3`0>{sO*GpfAzGu!<#?)94g0$DC+x&BN3D zqxbXpbXG-IR{;v~P&Z;CI@&_**%iK_sEb}PLOKz{Qqe(^+-dFJF~Ru;S5@1pU3(=} zqznug65s>1<+wwg+o`6an1vV6^5ym@Io6%Wvlidf3s~mumH!x{0#X zC^kmpGV3!2MiN*h<`qkppAMS+-mo-V`kbdhdFt#!X%J3TIL>hN%*>m{=jE$VJdAI;M&aeQ=nen?9ihKugUT_Z$&0YBQN zW6h|FgvM}Cs^HB<_5UB(Q5q71>C4d(+bQOPzZ2E(K7~rNm~yQqJK#F$*`XyUW|hxA z+h5^uYD2&Hf=!g-%G7Y5H*~rkVW1;NeSe|W#l6M^gEzzv0|j#~alue)b&0*|8?yd` z)*b)5i)DToXwo#(4%=0=hwE9tPA)HIZxdZCkr@Rc7kFH7^!KEOiIQb{gb-rx3C<=Up|$9m5*W z)b--?!@66NJD4sO{NoQo?ydV|8P)*C(hfSduhrFwo0}Fagdx23-wkj^S=4e=YvKq) z{OUct9K6n)#BO8%k8GmtUw=wh_g8U!P5m zyTZ|qK+!&7-xWuk>bNiBIFea^sj8EJ^lS!QEhqMgFN!U=yWXuSo$CmXDuxF9Dj)HDUXD-lm{(VBgzq-| zTjtGa&=chue46GcR9PHrbn$qb=l?!Qsrc8S!tda0Pn$8BJz2Exe-RPi;nXkGa@;S{ z9Um?t*Ky%)vGUus>*=h!?}YI}9%R66q2YZ3QKmZx6%k76uM)=yS(l=QpRXo$P@46L zUOg%6?|?H{R8pNN$=S8CXEz!jx7X``H+Ql&fk(TdxO=0mGQ1qmnnkBGMk?gfI|wv( zTOpySK6|5=EExae%oU+|@PV)E(bD1_3WMKV{p^sL=#ug6!}GD+TU4YWFShnMj!K7} z;ZMj%MnWkCVtP$Xe%=1OzO4HH6_UPx3qLKeLuCAlMJ>c9fiT zG4gK^p>#@pR@9K?C&T(EdgXi*!3c8H(>in#A7iHMOYLN)OsHmH?}~A;p?|#q@X)Z& z*%_uq)kFzuL}m%O9Haj?484#v1s~@j5xda_Pgc9nI)uWQ{wVq$IAY8k_<3D5;F$Ts3c5?0lbmqS%*YfG#g%=d6}g#=Vej{_W_DRDf~Ds6mIwoR?G#!P|G z`$L8*M0c-$<%j)|>5Zge9F^7& zhugDr5Mw3=GR@?48AsukBv4OPs6@p-9olHyIet6pYE_Zc(<8s>=!U2L2jF8?hmey8dpND z+?IBBp1XWB&eq(dMH3bq-AhEG+~Urk9)|Q7RM*Un5}Jsy zmsBAtd!(I?5_Wzc$s~yu15swqJRjJ#1-j3?9(<7LgP5t1g1*0MRHU_gehG4Q1km8z zL_obA%g?BPK{tA=#7Br7r40^7^3^FP<4qGN7&jK~WjQBrvhoyU#>Pty4#7Yss(Tw4=^ zOjmt4Sc#DCU^f0rzkMB_7CyU^Ra_ip!za&8N*^g>P%#BR^`x78V5#d9<^Q?*U~;>% zZ?wovt(`|<077V;RdtXgr)4zxb{idoUTmXqwZ3zCWg>)()gJqz^eD$joBRF$`t z@jXla#A<;W-1S6`U*mz9U&txi0is{0P@HdQaY~G*C>)(WY99xhPpp*jtaww#oIt3b zC^o@>j82dgMn^|~O&PY}E!j;Ei}2YlsWGaUTA!}s0_Z5Z>)WMJlq>;}k$LTQU3)0? zVGma=VA&7@X4sp^1O08D&lAFs16~zZ?Lvq1&T?Kup{iyHJ)|PjW;V>GZ>(v*=cw#C3Tw|kdo}|#_K%y0qp|{p_7_ft@SEBn0*fkJiPDjT-Rs2e|e&`z1u?TO9 zvbJ`}Z>tW|l6eOK*$h&aaiEqn$WXj_CH=3%6KoWOq?Rx!Aeb~}T^IY~p^CLB-%}RqY)A3*=-*ZD{t+;DgnloMd{C<&96&}igH7t0xg-D zmAu(ET?j(Heg43-w71vft&~(r+Vy(XDlwEQebFmEec>bGG|@fOF)Ye_RjW-5m{YG) z`Jcwh_JLR?B_x(NZ!zwBcfz?OW z=Nq>L6M#8uDyTbPyQ1sCYi9a4UKN`t?1 zO+Cr{(Lm!5sjU?P#Nxf_Gvr>guE%C~=`rLNCLgO;Q8O7FEJW46k(gm+GCe!m>h_1Y z^qwca23PKm2WwCIHYb*Jy@WCEOV36t0!=%vEu?0k-10tnu9T-Xa=aEUdz@dnfPOP$ zy&Kc*s8M5XQVJAfA747_?oVQo`-aD8!XbY3u%M{Et5$4QMe4c0eWs#1e(eVw`6sni zKSLeVGzxbJhys)mAcR4IrICB3rEe(ZmxxAA5cz^DT(Xm8Z?niZ_D@061-2w_n*E2@ zTdgV{XXpOkk(HgpXegA#f`u80N>ngu-s5bbq%eXsZHFI!#HCnhv{Oy7{+r>U5HI+gIOpU+oN-;3PK2&qqo zr5z8_p4-k25hNFFgD1<|Ce0Iem+y(PZG+14hPYmeJ<7u_4(a2ZOj=oVX^W7PjPO4G2E=(Z6}h6HS@=h;5N8xZN_xJ zt@Ij=9F7goS7W_=`N8?}P;0x!8n48(tYza+SxZY!QRf~FM?V-sOxP~-;A8~l>`S1qy!@8Z$ghcAvU~ZpsPdd~=XFT$q@7RmeW4XK`@q=a?J~F-(MVNqLSryXe z16L^QtJ3}*IIwgwPz>_QeH{Pgoc`Q#nIO3YOMP9 zFmZf}3qz5l4_ZOJ918^_aga^3ZO88F;MesRO7EdB@7T&zP{i_kq>Xr2m{p7Cs9~Jw z3LJiZp&%YquQQ-)mwzkH|JVfac9ebmciuPXI8z@(^b+(`=0bhDdD>jx&H5QeHQbDz zzT>%Ru%RbjDbPXVMx|rKC$wvNf9ssvf8nnUjDYMO>&h^v3(VRed69GZzYVxITfmX4 z#td`B3aHbjOAAPPm5H=STl84@T%BMn8d`# z&L@bFuYThAH8K(z8=G+(I~)ZQ1&J})1`&=h4J_%*Af3-m!#PNfFr+PNG*db)4B}N0 z`9t)j^XmuIk2{al;0C$4aG$KO4jvQWS-{i@=59s*k;jf0< z?`As-DGEhW;e_LbcigY7TeMv$(pa3eEw`F#uUbv5=|G_LJfR+|u*$n6M-7-*J{;oY zipI>cZ(ziKPWOHH+*Tv6a_i_4U48~c=57`xpL(^7te>z%exBZ-7Znt=G};cX7RWW_ zB2iow!JrS;zr(gUIkIWb{(6WG7TQ>lTIQs*s-&maS8h3_QSI=sU-+18d3jmuv-a#W zLw!Wwbyux#82+GV=`k%)yG<>54+oWKHO9?y4e5&=y|+6B4qa?Go|pD);a=vVg6r{i zFKi>aIy)OL=L0IWN~tCuEd5G(7dNV*JzjqimAP@}{^cPLaTp6U(9}tfqm!ab0{rkd zN#x`F?(%=n3rjHd+EvN*V|l;M>?+w_*Ja#nSY&fFVP-!lMO5^9m;o*vFVK}~K<46b z)^oV*|Auq*8Jv1ucYj4eQpu{%>owXOF95wGIdm-mPsTNEI|y`jcMn@QNm89?+&v1O zd02E$)Oh)Af$es>6ih zuCtDIgLVDsN`#l_zaRcbv)&1s#eu6s@H#IEIvT=y}=U0#l3`i6~g_ogRoqx|^kb}WutA@Nwl~mzFXcTVqPF+X*tk-kE zT0Uv%_qUnaN56fjzv{5?p|dd_C#`!S%H5MAwUTn^c5Rq6?T*w}1Kwy$UX^t_Xh^g3 z@=QQ0v$V3Jtgil)4tGB9$E{7i*Yqsy6Q)y{ zJZHQxkuRsRU}@#4LAQz(Ad&ME#%3-0lz$^3!I!J!fw(+&%X3WuZs@`K9Kvo#AWSAZ z*auJ!j2Zd)`5o4W{2&opNn0CZv#)*ZIOBch#Ps@R>cK60{=W~~3B0ZAmLuJT2I$0C zuT%T3q^%QZ)B4T1qvGSiA?-8ZPQk(GeHZfq{&U$aP3pg^Be#x?xJjXvg$OSwJuobQ zNS0?zEHDJ zp=jFe-!)vIH?FTd)&q>|^k~YOA7ZBirN8Ftd-1T<#h_gfyx;Gq?Cs(*LuAL+@ElRC zjZG`~UE^3o9^Lh!d%1bb@vZ3cERr|E4N&x0awO8c-kp2VhOZK$f8lMYJzYt9ofhq& z%DVu%Qilyz%AD(LFQT=Ioo->2yXgUSMLv6C8uH|dk|xT0WQy8@3_t3Xvt!g;z$2(g zD-Wch@Daijo~&cakH-G7=_qJbQ8U4?{_o58foGzTT#wQNEJg?;{z=Ur-bqzHwFO}M zP_fA~@CQlao+b2NcSx8hHb+o6H(g_9F<#2GJhk@ttBUpG&nndi!plm#IbAlJrPbBN zV&I@Q;<1_|)IR#Pj3=mE-zU2tD&lCsR@sGj&HQC0v60&H*G&rV!@~$$b z&UH|F(Lq-o-jVcja&3%NchPFMf<>v5SMuy!TtAz3R-(-tp(2d5jn?Zjr`#G=zYt^# zkqUh+>kh@vyXy$kF01#1P7H8>JMcb)wKl?O)-7DaL%1xgSyG513s^Shoqzgau7FRx zNiSza&e4$Ys#6x z&7A$uezI}rI65-YdwAVKnS_BQ^JCm`kba zVx)-T4`le6F7UOmFajtUJFo6#^!JS2d7PBTSpfces~}V(?CiH1;02<6ky=&wtI?#QwNaoO@c6Lh&&2D(nh|t z7+BX8Q~Z2*bL{{9_U2C(f1lt+saAAH0-tY5U*azBPV!>x<+ z*=y6`%p8qky1+qak%3<{n2G2l>u08c4M`N)GO@O`-Ksq5d})psj6j zS6H&VF06_Tv2Esu!cnY;uo@~!lR@Fcq(T86^l+xv9m;Xd_CF z+lcMhc?d&ZC+yn2SH+4!dM$-qHD5V1DUG}>6?e?sMJHiZi}Svq{i8`#SL@Jx%jsBa zkUPg4e3TGB5aGfd2;nXoEQF8PDZ@Luy1IZs9~Bw-g@;*ms7Qk)8N@2!5#!wz&4`DJ z%pD1A;@3}>9F7bMv!o&@Z~{j{$n6{(+&>193+~OIuByO(C(Sr&7N2MzOf{4=HM?$* zCD_6c3!fp*czF@hO1poYvZRYGR&gKIoL)SZU}@)aagjv2^(Y!*tc*$~fX3H6Z-X7u z#!gJ?nrdup93ju3>AI)fr{j`o`fPds6k0SeKe+G|^%i>%IRDoE*Adr0(a%|6)_Pj3PZsjF2d)Bz#D_9IbWo4>PxMwz~I}bB;jp_?Ds;6ISk(C3}GaxLP$%7 zrJ}AL0Cg44Qpp5NR6kAS{`Dk-^&1DbhQBCX`~=?z7=;jO+{`+?U8`;tqH49I#wppA z`JtYn8GpGYv*B0JFBex*dZ@;IwrPH<;Zm~}L{$&zng*Tux)#;fp5m&i2j|BPyWym5 zNTys)$+jrJ#`bld+~{0V+m73zQK~PEPiuUbxT5u%4Eb3p~Z0n3#a9 z?6`u4t3+sO{2{qmh+-_i=*sm^UK_G&lgzf|K=N{g81gTmZNiXZ!`Jg?BL;pY4O;J~&6YQJsUVj?ze@rlG2Y{e{|h5l;XER}a-7hgp(Vneam(*smZVi!EG{lJ;`Z9l;}v>bsi%zIHIryU6K$D7CWW|bdut*qW{K+ zC>Ds_H8^oyI1D0S~LLOEBzo*2U2OJV#_=2&$uiy=Vp@%mqOf63fKqxfmB@z8- zPEZx3Fh9#8ymV*v{8|6EP%wfqgzOB{nt%K|k$`cLWclNv5QYUZy8*n<-&C0u-{RX8 zmy`e?J3Te-P$9(~4AT&kYN#|VY^Bc5TrD@@a)43^+fd&on_tGePCGLxjIPI-4kJvg ziger|47Qi8THPZo;@DAn@dvl`UBX&->{Kj$n?9TTxQ~efPrb9V(*T(10GaI#KBWW} zigT)`K++@a=8GM#{(W#sD+X&M2+abvS)$2vJ~9R%KdeGy0;~;7_o9M9^IxRp)>pqx zf2Nx_XpIN49s6duZF$0j_Avd|*40k$K1@l?emlErFlS@?9EOdce&FFGi zKN)e+wwyH!@#8EDwXp|6bPj(-r$mRjBqsb^kkgvdz8M406;U6GzenVL@*-Kio-wM6 z?q-=+(K632{k2H;FkbH>RFXzZ!g;q3cUFH|1)6s}|AQR@b7w+Hq#ej2+H|GIMT5=) zmW_$dEPc$Wvb$tI`{Q7a2L{2IC@|XgPd&TxfPMJiTovFDkR=2_)JUX{>zp;qMSfc`B9)1(M*JzdA!IV~T#fw{ z{88cg4HWPD{jo-TJ~q2%mX^kV|Ni2kE6@E*V@_EJZ-?s}CJrWM=B}QeUn|s{z2Ocl zY3|}R(a$rxCGK&QNnzw$=x|k4_*tM4gm;u7X zJc9!98sNgP*@9Kg{)oChkb)YJP!Q(qezyZ5v#B$Z)&)p{+1c69GAlt74{od12d*R+ zznxhA%%r$!m6~&URV5UE|6waMXK?v+WBvNImrobfpm_`!^)1*{{dE?CGHiay{oyhO zyBOXE=#;haR+5vGOT(I<$&uzu*zPu2v!-CdQWX@xH;%AXmq&DzUKYq_wxgP|rhTZ&RV{(y(O>)tdC&@FwJI>&Y zpf#uOnFb{T#xlY2Co2c?xO5NxC`R+wDH+Dbd|M((9p zU|D5(X^b&Vll>{kt#Np*rUQr9>A1L5_78~0igGul(J}O?0Z!7_??(gh3Lw`q%%iN- zNhyWiXVV_XoGfuF>%&?10DLmtnk<7JR;%2i>)LWAw8_+{_3wO7%Hwb^hn+rMO-%%a z;`KvbjjS|Vfy3)u#?-*!l|kN3&h2Ik-o;(#&Ym8axy*%);Qp5Wij&mq-)l;X8+4-* zcNY54@+w)85e`ODuQarhv+l#V;T?T{=TREPI9;5P@9ug$Ayma2@3X{as9-2xuo2K8 z(g}Fy_pZR>p(lFX;rPsz)waf|3r~WAMN&=PtMhi@oaBRadTybBc^kg1Q`m>}hSB$H zx)Y)zms%E^Lx5mnt@?+*REhRazrNVg1&&7I7}Gyxk*jN@^uwhj17xEF$4x0m@$nEBs+CQvEhyE`1i=OpNGKtq|4t3n(W=`2J zw`fvQ5~IPLKOECDYPPHx{33D3f>#@_=8GgvQ>KEE`NUA`GqyU^#vMR@7uD;KJ5{prZ0Xb$iBlRky>ep2&T7FB=tVjSn@vl2)~SKA4U|0CR^~a~P|{#+e#WdfEHXc``icw?P++aYKmbP)F}wauhLD=z z-vjG~&_5(ndi<>5CIrH0KP47PKEhFC1eg_Wue=v7P9ElQ9@Ul!vMi<#W#J9{oLcX~ z_jy95%P6oh1zYK0ROW1@3bu8Us!q1=_1&W|8)Z-k7>Ky*3VWuI&!V8lwYu^Ew=Iz-w++>;EG@WE&(rCztLT77^ zP;(0 zy8q&SUYjxJV5Y)-5RJfWZ_Z@;t;8nsoUt<&XZ-`pZpApGkg)uZUCKpsqi9cz;*^l- zPwFqR;I7G4%PB8_@1Pt>tNg&2L4`XbunK7v(FSJfJ?WbuLFN9-lmJ3Fj5P0|J!#URD{v(&TKo2P{ z=44`G;+|p}q~iy#b>1YN8g}Y|pxL&%8x%g035q;c!0xF#+&%yf0W1ZQk>6H~6ybR2 zejr{ewWc&~{($f$BBeK}0z0H^qQxo~05xbbS{TeVSqQJzPZEUrCTirah90r}h<0y0adeOk+FmpNRk$|J}O*xxE*bl#hLay~+6PV|k4hN%&*lC>!?KQhdaBbDlU~V|2qtL)_Bx5u7w2?7~IC{S5DwAid9s z9hE|#&z({azu)25v`dW~+{kD353YPRqbzFM^w32geEaJy4(h~F7Oewa>|S5Lf?8}P z$&y!}WmVr>sJ!d1J1*R<4ZC>Vn>J23-rhItxc6l0-ibluooUaGE%0T<3u%KTsKeG| z?9FCobKD#F6S=wa=d3hTtjD*icIp-IiPGBep2y&#^Zz|fUqalNs$guWy}-_2sei?r z#4qY1f}rhhajQ|w&~gYvEO%EU>8`cqBOaQs)8=&e=#kOUEyEKN#JOqjXkYaD%kbmb!n2B;uDdIoik!fCm%|0k0N-0o4U%pY_vg6`JNt>0{V% zqodyDvdwGN@yafXFOXxXJI9Wv_e(x{yc)~b zcXjn!_|yT#R_sS5@wl!kbt@`0KAG3WE^z4IH0i&%O^tXi{u%pjssaNZoDQvlS@=;@ z3DQX=4wxcxSnKC7s;8=rPJ6^L)G?~DHh-v^1{$OkzW!0cuM=Su-&>#+Y?=S; zaef5CXDIQ2*g$`XaM$}M^a{`!jAnf)v_Z43-Q~BOET!h+f)+;pWXEfLGVgvDzrDfL zMN9c;F9<6hFtgn_`$3)k3R%HHm5=iC;x+F3Hij6Vd?5=Eqo;>t`N!IlV zz>C@kC*i&6{eGl@mFr8)7;{yz^>MP zSgt2MV{3!E|48XQZ#?+Vs3t>g?N#o!;C(C1A?f!KmP@83P&NVZ{AXE&2Y7mMaktBU z?{=7aG2`*f`8^0MVEF5CYH~-b><2&!I?$$^2iwDnEF#}p0Osu*n{oTqJ`->sS8x?+ z+!o=1HH*iAVfz`TWSOJe}j61^a?nK%a*b3wtGYltbgR&N(fr}LSHqs&V1AN{gm|`*L>Eipf#>rcO7*>SBjSj z2*$k4Cj<8JZvxUf(I_}?NXyFFdJ=Ds=?VG*j|fIx*i7B<>ADzK?d@r#9JfVfay46k zc-uAC`YBW8qCKPq;wejP(=gPF{A=l%BY z>RobkRc`S{Y;R-VruQRnMz$xwBs%Ec!WFj9hc#KMGc%Yb^4`E~@pmPO(S9TEx?`m` zes9L@62dnIf5d|ipsMN(#Lh0Gy)zG2- zKX`(l_~84S`GA%Ttni%~pEKvrd$d zIJ55w7^Rj?%~iE4jX$blbTp6^9`_4h>qsCxj--Meo@~F!Gp9LFAC!G|p^2oz4T`YW z$MVj;HM8m=zsl2_PDC6gUG2Da!wNzmwfLfZH{n>dUk!&Y@D>s@)+D=pZDDt7!3+wZ4a8tO$@@!e8D7SX72d<4|R8_9!`(&t0D2W)JN zxIuvIW~+Jyey)Iaecb`~@ch(ZMZQn)+8rg;^-tt5vqV6X0cg1(dXgXVUNk|Tf3u^; z9gjv4~mGXygJgi3b59w_1}Dipf>yb{z&EI`Hj? zc7Ho<$k5^5Fv3)MKB_1d6}gn8@!N}-t_{3GM!a?7j4pD0VV_^KEg%4C!zWetn)UAd z85tQmJljlqb?d6dxtbdNMTTj$g0z>}lUj0Gr3U*ey;>#_*w{;+jOmlDhDFe_92e5# zrG*&5%MS;7N|YEA5!UWTp~SoV5&@pl5AZ=YV&1X5Qs4gp&1r65%K2chulB<3E?ibX zndx4Bqc(v3?eCoZ)vWD~Gp+h=HZE{Sys{XYe`o5P9$kcK{$DLPH z$9p)(PXLcSd)`?mX?#FvVOW<`;*5LT*H2KeREE7eF~;-a0e*0rIClck2npO?jVi^3 z^I1RKm2ZyMLg#8A9@mY#BNXc}*d#T7K)d6x34tMTZ2F2YG`=3r>}8|)e>{D6Jk|aC zze+~ggzUXH*(0(dl`k)D9!XZn-XVKuuk20s=69X$&-eFF5BH;P=bZO> zjq7@@ixYOhxOpl!WCru_@>YRA47-u-UdVJ-NGLbb`0I(r@5U!N%B?ldtVlz%Zv(ks zv{~M$fjWA?7kh6M9ba&#v`-L3k|(|c^7{J8arSKQt(zEq7t7nTtG|)FYYim=hV!&} zqp0+&B9WdlqmNM(T=sC(QqslfQJL-CO5n1HW6q#yHs!HsnzlQ!U+yKxXoNR(%k@@h zqwZ$w^Z6#;USIY;+1=%yFf#7=F44| z&sK#=W0`D*;t86D$xm{WlfM?c4sV`A8hg|a!~+E7$G}}p9@U9i7Y@^Xe(oHXf&)=D zoI+_YTJFt{G^(xQ5+-WYjzbgwF&8Qpkt3ptNhL1g3+*~F;y*At zKE5}s@a|>RibK`c!a^GtiVU5V6`Er@JatutN~o<-L*}WY&X(=^q|ycXpJ~|qtFg%R z$?Q#JK@bnz0+>X1-i6)=S&vy)T=eJ9=b^1ISm@^qu;G9at_sHTUfI~*ir_NOxO zR^joyyu2Mi*V@28odhEp>VA$y0hEI7iQ=C8V(ux8?WJ;i)2_3CA#s^KI1qY=Qj_kJ zr?G24SX2W!1B1t3Pbx2#bm`b%9u^gwKDPbP z(SU>1AkRXv5?Hf6pIIwvQ@=zA*D-LzPno1aJMsPkps&=vwo>qD?AQWjcgFnOZteXL zJv~ZDXk^m6#SlW)uj0ideaRI03;BSSu)kvA>2KBPN?fKv(jyCZ@S3epQrGEROZDpX z=BU@gzuPNzd^hFIygiIV7rH!0<@)?@euUG`40*$~`*!{L&c(JX>*KxH4~|#yNc=nk1L`e8LPS`(u3Nh)^*H8z z-f29bd*6^zp-2n{M@!y%cUF9)^z@8R1}V!$YG zr9b#SdxY!;FoV4pWH11T!`nODGJ)5`(}vn zTv6U8sZXu+9z4Xvoz+FlH^F#TKpR!m(}&9|t^Tnx(hrUH*QB8p+kaJEAfftU7NTQp z9caa6e0i`r9s>ebifxMvIw+qap*R6T6e_aGW-;|fSSPZp$Z6I;X}doxLu5bR87o*f!=SxM^ZjLC37nj{2^x~?zX(7M0Fc1I zT;;->+%EwilE?~6#=kSheAFr+7Na06vuw3$qB6gsNnp_QdSLQ#f2AWQ}j>SJW-D3 z4(M~BCaTyQZMcff$e@|=a;E{EmTsfqa`)q>`s8V~wfF;l;tMVDh72zIJsy{zXYIC@ zdqk(dDEVfqy>MK8NR@WG2E;Fh!(J*ZFdl z-a>VAFnoi5P!NyD=cK;BC@5|3f>6iPbwK11pAYH}s!HH_L7tC>j0Dxs=*^+sH%U`d zdO%B5(aNcwwc!7#TOvF=-0}WHqRAKVe_DXe_5jRVX(bu&Yvb4-gg$tM(+%w(t7d*0 za6wm;9*r<Gq$>B5_6tY+kQ%V8Ek0ReNurIkgy<|nPoQYQB9X3{-D$o)8Kz!3ot19uIyaDZY1leOjqQr442{JW0J4-IBWz9?;g@QWr< z^hc9CRBs+f*5!ov>}vqR(dp}d>CN5-k7*oG&)H~1=D8vaIGvp^Xqw}5xu?gK-$wN81xDZSWyn* zhDv55b`P|33;R%em8{uOZ#MX8{b)d_Ou%wBxi!-)jOh{z&LsIs2DfH3ZWT2JpsU2r zT!=AHwq~r9H^)fly<%Qxw6K}*{~G-yCjOpJ-spLjs9&&dnbFf;QR3XWoKpi ziELN;Qi!=defF$L-*s9B8m){_4jN(%97E zCn=(dP)1+D%(v~*s2g^`-#T{C$0K4lxM0|(QH5A*7iUAau5Dc_>`x|E)&&^;^ab)o zba3clrGxFAqw>#9M2l}`Mt?l*N(rFHQb`vFIFVK1t$=c~8xmDduFiLapiUuXl0joV7ckhJ9lFD$LDLtUf4GrT)rK{7C#qVt;_9q4Rf# zrBKBEny1NGZleThLl^~k69I8ygONF&NblkGecsi}`B1^@zo;N;WKcu9z5oCd@_GoF z3iI+_GzY{GiwQrW!%LTobOSYe8*ks@P*tg71TQ5Y`0K{192sE*dBtRp{ll>p+MO;= zp8$+Q7_!X0p7iV~nr|FN#&3gfw?kxb3}!`czA|y=%}sk37KSl@cnGQrgPpNx^AyiG zD9Ap0Pq|Wtx*fGxmf@ixGchw8&;9gw+8m4ax;z^wGL#T@T73v-B%FL|JdY=D-<5AM zkw(R4z(MOXf!p&qh60cM1cq1dfiB4X-zU7*yYsd3J2Gg4 z%Qb!k>FDM;=bk+O_PT6qvc9O?rl5R6rod`ruv)#KQnE3F=}yKyvlw+MYImM<@dgQo z;}~-kwTDj!98WtKV-k5+L|26Rggj~s&+7|Wtl9Z>^w>Yf$Ag*_^d*4JfeAx7$7k3w z`?U@!k}nbF%Y`4|YG&U+llvd~59|uq{?QhnMw+RYXa4#ozx;&Z5g*BPuu&XGgb=BK z!$HVBB(fSiYKhuKJYe#Zlanne5dsJIrPw5|U-yyxDBLmnYz&410@&>J4O53%_Sn04 zhQ4flOuSJ?qYf$P<<9|c0NoX&&sX1)?S|kDEw;G2JJ)g6pP}5*HNs-w^WzhbG4$5>4C00fr^E~}aLV{+ zi%%r{+ICYO1eA)HB8r%0(#!>&(M!0wrX0H1pCk!J8*#OR`XUjg%z`%s6p(&MbtEOl z#nCIN-YJEJ99{>RlmiXk*J320#>636xP9I}Z`=ePJOBa5s4C1!M8pTz-9p7Oh3Qfu z?;NZ2$Y9omP~vTfds_J3jDehXleG2rtTk z7leKkgwc@s(c7yGEDhqo_%Wn>&NpN`e;2uCy6{_<8K!Wu^2_oH-m|rws)Im@#Ypcn z{NQG+W}Au~>9NN$HBpe865cp{Ic2Ty}~dVAn*zEkI)Rm%*~f!#4Gg!V&9fk=P*ybV-jT6w@}*#cEK0C?$e+1|K? z0#SlO7oD5e=@+lI^?G%xK1ismfu<6`+7L3rUHJAs$kS=ndyuKCGs9KYS$ACiT(u-g zCUgWpROzM*L;CS;kRd?D+RO#=IUsttJWl@3U@rINq{$J3`|VdGWvV9%-;NQODna1% zapl}B^@VUE>%B|2Kp*iHx15L|5v1#L@9VbDImsv+Bh1uvu?hfCYnNHxBjvXSOf3Zw zMgZD5@IFv>c6K7(`Ij#!wka}^%^SB%j!a-#0J7h=vM@S&`KhBw`DLp;E3w#1KAQ@W zHgN^%a>-B>+#cy+p^oZ%q|7zb5s*pTXM&CqFB-1Kk}Z78bgM>>V>o+gW=5GIaWVEq zgz>ypQSKq&)d+t>voVVJCEslAwHIM`s>-=QeY$i)XRq?%#iiiy(V?M%7i(|p_W7%W zsH3<;ac*flT*FM2m*C}O`Fj}(;9u;}gW{U+lUo3|JcUZm-kuwdU1=IgK{AavW4A9M zHoRt~W~FZq*zV#!*lR^z`xbQ(E>@Q4Ae_AJ)m7m%B%_P_fbP5%v2kF_?4CAux536i z{3n(N8JCGH3^j)cg_4pIGS;B@eim#Y5uM?s{LJ&&K)>{K^wh6)3}65cWNVoILP;1Kst^z#wAS((GsxRcIxt)JOfv z=W^tn(g09fJbXdb!?*BVFyU_}vc~;9hxc#I$W)D!8G7Pc2sQW%{d|qnovCB6Qd>UT zmfN@9%d0#b!Sy(wyqz`l95Kf_@ks#8<%J5n4HTT92_nPF|0E(XdE=?h9n;6d0O)ZM zw{T$qcN7~1ri_yXN;#O2qH@!B?0b4L_ltQb2Le9e-Tl7f7q-1^1F!^q+3=JOz3Q3n zh|#%HoU;odxB{3+ng9qRyiEM_Vvd%2G&~5wk2;5{8)knTfBN)YI5}T%g^VzgToDGB zDvAiF<$TlMOpr#pgW_vFT^+l;3|5PHlE@%4Fo}4bJnEgOz26nexz}}axI zs$L1z+uu{D)ipjV zuZtHEMMXKrO*cPum@1iQ_V3}wm1mD9@qTH}(Pyfqd zZa8+}0lSOF!2>em1SK|1b#-!e%~R%Fy;r#?GMF3JVX8*-$<)l0=RO3X!d!)=+|_x5 ze8xAPD(q=lzOoh0Kq62s_zXUN@oz&s@fbH=eu21GV0)m7V-a&_e*GE*J~KMJXK`3j znAYqZ92&#xs?YN7k_hYQ>fRTyA%o8-dcIi-;(3P_T)EBtT|z>_?UK%YPVdvZ(9((i zZM+3mx?BGyhzCU=hWLM(EfyjRl$V_!dY+Zu7?+P6vnzu3q(0lZ66&RHLUi*wz>tR6-IvBy_L zar2CMTd!1qV+q@Hcx6FN9_grS!F>7d6<=p%AO$2+T?E9qZW?W=cu9fk8@yF_{8!i4 z0k?dvrBxY|h8zBJRLHc3r^V7zrJz%q3{SF?3*+o?12M0tr>DmdB+Z7d)l54sHEXM@ zW0{_B>kMiQigfUSvx6P4{v!&zu2QmsC58?1ObVq%ai>> z^r9P<5@TA)NoZ+#SqwFJG)a{c)>lpc;_#(|y; zE74CFAakIoa}_~GA3zgg9hXJ^(A*4NejNc3^5TAk>lC@oQ2ceKofKBfL4&aDd4t1R!i`0 zJS=t^#Rk+fd(~ySf8aS+n4Hl?QG3a}t

R*67cd3>#-v_-%$ik6Ggn$w-)0g5X`CJF%o{2=sV{J!;B6T@II-;!fj@mp)l1~96S8;%5u7p3ySTthW- zm3$O^j(D25S+Q$<4T=h$bN^N@n_a=}YIo$ke_GG%-AcR`&dOYn3Pa=JV<#Eujv0cuMb&?$#sWfg>GfM9|0Isc3F8&U}`QAEbLa+|N$^zA|B zw8?Pv11vG>zs}r`8BY$6o#wAH#bb^|Df*O;l!Tia@;pfb(yOhdkwH@kqn9>S+i?b@ zwjbzs$m?68`ySK4Ou^b8@UIrg>A@n#@YLliQ_A~?3* zL!-0*t83uM4hG%bRnggmRnZcn;>*hmg;g0xdG$9C0s~3GB32!Q2!im~ai7ghOM6#d z&X3TXXqzX?fKwg`O2ZWxCpLH7a4iPz643o{RIk#+YTwW{0Vj^bulwe3T|-onNG0SM z0sJ^yznas;Wd#HS>V+YPueap`IA0NwR(BEF)jDXRjiT*K6ucTy2FkF2pjDOHxJs z=^5wNkProSZFa%MFzaH;U-08-i7jC2@PUsitw;p8S$vfJ_o6Et&huHpaEg4Q?YUT>y#52B zH9r@2?Y673q3L=Gkcu=sRIEVXCfnMk1gpXuf4-2~f=QNz=J(4|dwX3{If%_g8v3H# zYExm(9^jTA2&E3Rmlp>)n$N*h4eeU6?D^L|7tQXVW1Kmfq)pBsswIaiCN{P#0N2&? zG;*yN`h(Th6r!EMGFD~v=i#>ZpBrpqeP2+mEal58@@&YcJq{0P6Y<`y|Hb*B?;w)3 z01P>c2t!9R^uKSeHq$E$65c2#$qQ%v%3i5PLodXibvGHNjWdBHb$Hk;ES<|NSwWzZ6 zRQLMuj9SJcqyEWzv8mLwE6n~Vdnux57!*z^h0svuAa-Br7K7VwhSl6^E<^uYnz){`S}>OD#S&>m%iqy zo^f|MDvcT_+boOsq!-b3ZWa7M(OoM|!v?gIHd%S-H(v}$4#G<-QGa3r-l*6IAGPktWIn5|t|qQC zxm`ADh~4NsYLM3s1YA|0saG(07UMC%0 zU&Tx7l3oujWMXSiQbR_@aU{Qeo11a5(_+1k!xipkjNO1C;c+@A^ zZNXCqyMa8weel+yrZqQbeCPHnNRYavym{^^go%4%X)B7ZeT?d*h8XN=n;dunfGOY} z0MXeS(Lx?3X$;_GSV|Gd=E%qwKLT<}^XM#BB)~r4ZqrZJ4}0?#*(Egj4MVS_0A))c zrB~4Ch8YCkI5|7RGX+d$xrUuxiyRB1;wNVtcaLOI>Q%)~-MLI{^Fiq#06op7I;Bh~&NCt=4cv8V^&E(JAO zh!bSP!7m!FqA{%zPo;5L&j_OU$KqDww_gmZOK14yxWD&4Cb)%yF}Aduwg19U z68n0Z6kIrPjmn*!Df;KCC4M?_ph|xH!dW+QCq+d@@-}|G_>G2H6)P*&jgh)m7{>nV zXzLl|91Egg>1D|at|j3}O35oyzok}e6g%HBzhCkSZ8z6mA(d%KWXCHIo=E@jaO{h5 zn%Es!jT0M1;7p@j`LmL`;-{YX#-X1Ij-3uu)k_zL_bmf47y6Qut*3qjzc@Qmm-37H=Ee~abWiHxhQ26|ZMA1KM?`RctnJ%uL&xb4 zPlQGGqE)z7bm^DO`GQ{2#-3HT#(BX!2IBb1)?elVsxO%{&vJ&HNMKk{#qNx|bL}n) zne%UCgq+`BitMxnAJJB0)f^inWoKI_h$e!1lCo$tFMq_Q*8XmDAmz_n*iH_EkNJ&e zotN0O=Na(01vk0CcztxS(zg>hIw`BJPLgVC)GJ0)q^qktEJkM~Rn4<_6?@J^hLv|n zWm?-^byacYt~npwJlBr<8B!eJR;*z+MPm7(`wNmz0A3V%onvV3S?f0Ue#SUMw_%OY zda#PxO1!~Q>4^RKW0HHlnOgmW_?h9X)CMQSfj{5nd-?d6N**t|*FOm8Uw6x}x0~A< z#tJ;HVc5c5Ul5gU?Nhu*$EOT+Vo)r({ao^W92FS1{EcS4uWzwwafR3~5aI{xDKNZX z`k*84wpx~no6$RG$F$dL)#I|enNaQfZG^=P1{|4!sNmav$IdaY*EkQ7Z2c+2NT+CYT+eYTKa15MvCEr&^QZzbb#e=A^!StWVy+&P+WtbdP3u8AwUcZb(Y{bPnQl zvB4IAAHS_v43F*?F{YaS+^Tr~z`WOdB0T+3A3BKKp&>``pV08om@bj!WUB&b&ii^= znDB6?h^19TL)1QqgeefVH1@Xo{+cTK@)VBbCKH1@<-8=Zu|ktTz7pi>zXRE zWy|x{J~@v9=G$W}gv`i8}UZERqp08OSK@^sEpST~JVPk*PunE$_2tsxRlA3IC@B7$1KuN}(wP z_?8`@EJar?PA)7PEa*Stk|M!t0oM(fV$hHYguvT32GMFe_2(RchK`twNZXIFd`_j- zyu_pOL)e{l-<)OSFk3SHJW~3+cdC*zq-`RWXxd>_WY*x=FG=UtTUJ*`4(6mizXL1` zG3g{xR6Z?bG4JD^)ZKm~Xtdym}IYl9rf z$;mDA_r$12_G<(e&nkZW_;bjQq{(CVhuwNyHD{!4pieBYE)B+@_Ds&6!>8$=o-XJe z2R}DJMHbV;!`US?M+DGdAG+zh)ag56pR$)j)zlwuT8Jd#aoG%o^)m#60z&SwUa%18 z?x;rZ#}~d6>mb1mWqE7UUVkvkd03kg*Aay>e8k*G`7qejo#v&yYa9m;WZfq1u0+y{ z$kl16I?T}M1%IVVCa75-8yJ;;sS{Adc_|$4WbiY1nsM*XBkVnpfRz5Jz3pUH{XJ!h zRIqTRue}l)QMZ}5q7?M6+ACe?!~R{LZSQAadVls?nUP$6t+H8Ne}_;{_$W>*zL5H4 zy?eO+p;y~*iq~k8`G3ck$@NbH-X{rT*f5>|YL6+KV*}jJHMh`HV%LqRx4^jw+6CZH zL4)2&-Jc#xB85drM8x}Yk2qk8-w)l2k!!CY+7B(4U)7U6hDjvcR*&McH8S;UM83MB!Aq2lgVmR!=7$?D^OSqys64L_v~3G*Y1tJBk{$V zEHOm?J6sUu*B)1V1Hf`1%eJ<*zUj7Xxgan-5>iq`#_=&$ryxaxHIk>K@(D}bcnm^twlarvtisUKai za!Rv8XQhdK9A|Sw%t+t*!$Ab8*i+q>ht%ivA3Z1H*!ezwd}z*yNl#yk6E#}m8_bqxUI@N&fMIow7*gwe-zY^tga6y+r4A(tx>Mc8oCFN_vsJ54gLy&#QJ2)eI4HV8{@&5EiT{MHeXC~u2^iyr^v!Ahdg!$wPAx3a zgsi3d=IsgRHR=6$Au|0y4u#E*Q;w6@JFY!t)z`b~_~ZY>(faOwNdSgXTnZ3$*pMKD z3BV%%#xiqEUb?4keJVNY93rpYem5W4xQZN>1Za@d7 zt4qrNnSBx+H+*n>Jl78k7ZsEvpk0FgA!r4FC9u)2$@^`Ehx1iVdx-Tp$S@)=i9iSe zRSy0`>!KEl$7n9O%Y>xgfb@aWOPe}cUfTI>`&&60T>4i~I!UGD>@*mvyvU51w57b= z2mnI|xWXV-rQODHvp7|k5VT^F>RS*+Mi$^}`1<7Dq{?(}d%Rr9T8EOBat9_)Z$;#X z{n-7$nc7>pg;_5cByw&-8m8&2$>qJ!RtNbPxO{2HXB}3!+@acHWC#AyR4ZSDXN~Xh_t4Z}H!11tJ9Ka%C-AO_-SojAGB`2B5`QC} zh|xV&o48w4-?{oMQ|olboo#hAvdfJ}|A6C`kfHu!v^8-tN*B@ffemvaZKC6K*1_9q61exgvRBViDwtI>7$?lXy zZ8_hNMdrtyUrhWOYIjBww-U&)9nv2Mz^CqTe5$}D*}K#3Hn0%>FiVvjl`C2a3*beQ zApPYSfEwSGy)0`za!|vhwW`Vm#^sPHplu%ro+f$hj_I4f`v zNaB0atn+dJvcRnYx-pIM$LNV{e)fPBmOKaIm4!_Q*#{O3$m~eMO-jcd{BA)E|Bqf} zgNQaEuL(XvK0YG?0w#xNj2bd*VCN8e5ojwfAVvA%z&rL*LU z)KUH0k>dd8?7{{^%t@~TZLr{dOW_?i|2uU<@_zmomL5K}MXqsZP3*}+B@|E|`}_M_ zD%DKefV9=1NHh9RvDOo_4mg296$tDtqX?~G?O%xtuHBlQFKjW?N57v7`oQ>CRqf~K zo`2->yrkg1yg~}O8>_Z>Zw6ed{ZN(7NQM@rY8{cTMq0Rz%YN58K$Y)ia+wDj4=^5@(77@u3HpdcTww11%-AK;aY zG;Be8GjOp|J|bX7iN;E@Pdl2sv$pGP$635H-AZB6V=>g_-?qt}FwBWq>@DBidoJHk zC`~vC+@2^%y(l?&DjA?Lamo;KmW&Oon!y+FazWcDoi2j@^ezDqsJrfqMAOdj6ad{ zL@f_3Eq@N0r%nwSG=5mT&2x<#hdeKSVZZ`TYq!c7$_?^{Kma+pz>=`&h(JIDSR(y@ zW5V$|P7E`eVENB{F0s59k`Atz9C8R zmKL7wyWiu(FpK*?@xMk_jHl>(yHeK-Eh|)Es{3q?N%C|A_NUr^45Pj6KdtZ;&N_&V zwiM3!cM=g-8#5s?yrCeZC&nmoJGA^{tt9mR{gqC|lzo++!XKPn#)eOZe%REWhrJYu zw)$xOB31`v7~?rtBG+XzRq25m8$zhnOF)qTXji7;)U=U#RN!j17^&3TvvWK&G9n8s zMpqoC=A@p}oIluFfbjy{QLXLx{1QYpz>CNJg}f3MtQ){s+Mgd;6L!yD$qEx@UR><2 zRqlv`VKvL9Hu_jLd_G!}at$+0g>m>3;k+nG_@3SM6Lgbuo zE1?_&>sFGz+ATMz|Hv$!3I5*jZYRkLd?Nhl!{$`E`Gmb|wf*#l$#+LC{n_=5sw(Ys zogFdO>3cMSL4TnU8TsUe{m9m+GKgf)Q@=5K%h_imdy_ONqbJ^&_*>>OaK%(Zw0O== zPIfNGm;9cbN|;uir-Bz2|&j`N4q>fZsQ8;7IqX@f*!(h)`YaQ;_2`i z(*DYdDI?%FtmlPL_kZCLk<0N@p7Z}ngw}FXA>l*eZ4e19>-B}<>~;eA71}IWl6N<+ ztJN0fu;k`ipWrnX;!edpCqy3=3iqYLoXHF-7s^bBv1K{w(Va1n8=c@T!+q3 zDTUL3EYUMlYq$7d8>{SvSWUyFrGZT9MAOdoVW6co`m~hBh+a+{Spa4V05VW>2V0Zz z;D-qb4TY!(;DlL4_?;tk%em4FCCX>rScB~n%pL_gjB$ENzPxm6H+|!M@rFh$k*c~i zhGP%Ty~DGVPbA74lkreE^7u3w6iFtMCSoUh%;tG&vjcVllV6%4YIIj(Cuc;bYZJHh zZQ+_we!0Q3Ck?I#qS#f~OIJk28ao+Lhb%W=AHCgG;kj=oY`)FMQRi!AAdDGsgP%0r zE&-+aPgcrb8{BN^Mlj?d5VZ930h{@a1p+>zs3-Iwdr|oFyQa>`{?TUJfeq1H7et+3 z>SIx~KkUz8Nxr(#*j;zBX_r=X@4uRUKJVs#SD)lhqt=(prSE3mQr)QZzQ0d|V*8xp2}N zfepkOnw}1CTS))o%eotK5L2v${R9bh(>-t>9dSwp*l1@(LjC-;^Rxy|qB%K= z8);CdXFYh#cQ4yUfqb8+yUnJe)ViHVnJfV_H0~IqIjyub<|)(1QmlB<3$BG3_sG#e zOxl6z9@6H3!@?zs&opBDGVgzxZ7*Jp)VvoD|4S8R#d&<0;}5Ej6|BF%vIK~0J-E!K z&75j~r%wnUM3Ag?M%l|B6FuAvCZ4f%cP!yv6b?xs!n%%;Hzkpg!311*-r>O?haNSW z;F%`hW*^UXobNhwJpzewPv-4v;G0wEheS8XQv-Pzbo=P#G>xnLW_VPEckeffCo00y z*%ayyL&7(dO(>U1#q1X1|LA7_`JtaO#T2_PM~yjnG_)-vxnMTaI7G%GCFrZTDbl0J$u=WIOG&rI>Si@re^ zWCSAezeqhIE>EkRn2`W@8J}u*0iY7lEl~<{r}I~Y^%aQN6p6Lj4jYJgecB)M=q8t; z$hO$h(#2Mh_w7G-A_H|nCsd6|`Y}0Dk8xU95&KV^6|IR+cWO#ax@*^}BYdtp{M;l? zkM`Yzr}pEKK@Z$Cqk=e0c2JnRJc%xd|wEW4+KXdP{Ka zevj+lU$t88y*)L7wV^#Gv^aO{Iyx0k_E#nLjn;h0&Qc#0Pi}R7$WKdq=${Gg#|+G5 zoVS-5Q*;Fs^O+Q>ssA(T4rg~xp&iGH*9)f}ta&PpZNZcd4V@mqEYf>zGlMXqbHFZX zk%}<9IL-aW*3d+;mb-|X6DfDq%-Jc!b#jZ(EfJTA$qA^=H4DlvY$)D^grF!WzJ4Qm zclX?}Pj>{8I_CnHmh!dhlj5<3`~os)+D-pfP6JB-_c*LD;(%z{sgUf%`iL9!QJtmF zy+?w$GDBTcTN|(ug*$pj5s8Z#V|J(x>V#X=exki2aspr>IIqtKy0lo(hieL7S=nS%d zvqDC=P<9vE9B1CHJk!vKi=pJUTT?wVbiRk=I%AItC)|1^sNi2SP7|wELDClZ9si*V z-)XX1mpisxo3uX4vJ0is5i>tc>qGWgi9PCSsRE<_+DQc@1eT&qau0gwm<_K zts-$ExFSO{2bds(3!RAO50pUgknfO3w3;NX3#*4ai|@zUQA^2+9UA%A(RIUEH6%!a zRGlVEbo!*QmXT1Ti2ZfS4-gRi-em8Y>W45P9f&+j%EO1kiCN!l4JlG2QvE&8xXQBq zU9Zj!NfZ=bF)^o?m8ow%T2^THn(kG+8u7n_i=HNsugz$4IE8W=firR@j_j5bfTqX8 z(cv=Cirz4rI`o+4eX=nzr~|(CnUV)p(*Fz$!uZez;xKu!=nM-Td?mi!0^8(oBSuY! z$|+~Z&oBNoNFW*6of`eB2+z6xel_K=!R{e)^m^XZpX+`F>_U@-6f4@%{v`(>w$)K% z#IeK}AGNz{yPI2&OR*#_&X|74O~e?P_UK)mW~4l<>K-jbuAcTWCZ0->e_HVZ6_fBT zqi(@(3RT6GRFUHQ{DTKB9PK($g&6vcA<{H-U+9T1_Kfa$>$R5%#OHDc*L`y0$R4t& zozebLUOqT+hn^m@a=P@p*5>-#^vPfd!(&iN0)M+xK=SZV51kcai;T;)F4#MBuAkDn z1ywu2v4A@)M!U0ijj|ZZ3F~dl(Lh*=|2u<>)9so`CJvX~18;B6PgDSK8(}PgRBEV>-BEw=Wskm0xEIwTR{PrOAdhur{$4|?$Z=x8~+bs_C z@YflJ$e3$1pa%n)2$ad+C9HE!c3Kg*71$=A1)J>qCzge<)5P0S$beXw`O+e%cl#=1 ztluY=5?s%a5f5fc-7p?fHDh0?*gXiZ71`Av_My5_j|BdB5uNR{f;y!w75Oo@^^Wd7 zJM*sOhvf?<{b`aIBz&)O{?0xTPQFZxn`}zg%-x{5kyb+MM@3}CRXjH^U{p5v;|1#4 z7X}`3a)Nt=FY^X`9K|Tia%f{uVOI%dm7p>5TvsDyg_66C_=m|d0i>%tg zu~@E0ba}SQ|I%R_^4>gHZ+?G$jb?mxR>)&rzv|!zq4Dw zd{DSTJ$ejj#bbpmBbQ0DsO}T<05cq9HsdaLNjC&cT08&bpsbA1K1Pk6DPD3Cj(xLu zd_K$z-_h4znoGHDZ0aT6L=00NvP&3@Rb3t@*3^c(21?A`Hw5=*hsR}vV|%F=Tv5eS zu|tPDgXWr>xK3RAsvoDMOsyq;z02rU5k6&$WR;U|HvYMb$(E__tt@;g!{Lj&Z-9~^ z^Y{y6;0^rR9Bm>V(#*y@c&ka(IIn3yjUTzMpQ_@yeCP&|&G2r4t_CF<^!hxBYJCrI zy=0^Z{P7ZB6m!P7b4xTJWW?@~3q_lkry1$S&vqh%`v?t}3vUYvJa7M>s`yF5YAZ0C zZ$La>ITt{Bv|a-Ug&rtnQ(e#)o_J7G#a4r+6-qG>Vjo#b2-`CwYeCOfMZo2^-^aO9 zy>T;Zh-uI;-`dYF&hqlr0Y_(7QRBv?nAM2&qHDuB5i}b)Sy|vN3+-F!%B4~MWfG=a zDjP1BZwGik#EC|G42DyuqVF;$6C>$2Y-Eh7c6TzfGV^wRt*!e|FgqJUyG8Z43+d{y z7nyRPu(J3Ka;!jRR@ScKSlpX4b9Re!#my!JE;2iL8x>ET{elE`nsxO3EB4GL#_VVT!fPq7C)RfzuYK$ z4&zZNp%U*{`wQwJ1*AdtAHUyv4t0KMWZ;;!6M7_zIY(;i;p<16jvS}O7C`@c?rdVC zDrIB5(t>uOJfgXHP!g^Z?vnRWPUsyIgSQEAYfU-!+Nf~uvQziS^n+x3%x$|MweI?g zV>II6UkA8n-MS$?X?gP$DP8#vD1p8)8 zf$tab4O4kLGsC|REU;~Vwh*C69Vo^+T3A>pKd|x5_HkQ(Z0^QO`svdrkO=);a$x3B zk?#SM638ilsSSw=m4z69D?->qM@L5#pL6ot>Tm+2vN|E}IvtK#*)ThY35yM_(q%in z!eMAZ;o$+U*Lk)&4XP0CKnfT~``H%dsXjH0k)QkfZ z=+FXas>!NOIAnpYl6j=kq!!ir4;RJMdD-Y@vPZz#Ql=N3b;cFm& z9ji~4w_@$XAjv|rU9&?{6Ntcp7(8F_a#Zsz$`SpMw(BtE>8^6ZLTaeG5&$N6M&#G}zz?Xcdek{XL3&FUm@& zq48mD^<9d&h8J;pK9P1jJdtrZ(7E!i@ex*hX3o4z#tuqQl0@6R$ zJ(qPHTL?QG?{gU;`J!N+wQL~h*JSGZXkQ@65Ia>P;f$xipL3`R8u9-MhE2`{{^!s^ z(SlkZL_Uzg2xqd6jt;@;sF4K~0j9lSo2M4LMs-ciV>-NpjZqbUPiK5v1DD` zen0iR5)(lux_>YB@7M@}1jz*y&nhqRqD z4RtbNh*l6Tt>8ibBW9>=TGnyD?db)wX|AXn7IrK33KV=At%!n9(vnD!czyu0OY&zJp?6I#o^%@%b1F#zI)tC>b6oJ<(-+mr z&enS(zOEDs5q9bgnI}>GFLCjJy*{$q%&%ToV5k>(Hm;3HDV|haEo|voMj#R*^roo^ z3FB<%R14F$0$U=f7+bWlgOvYkZ?pycDTMFN28vwd8`OJd=V~mi6PcqW>j~=lqAv9C zc;Q3K5E&ph)~+nu_Y99dh1j;BxBK!=E_+3gGeJJYb3Y8Kv^5p4n~jnn9eeg{faCR) z6ZGD(_nr?tZ5j+7f9mG$n~Yc^y1Ekf(-T`RAt51xyHLoKbZzrKI3 z)+x{jzxd<9#$zZBxwfKApo7;6m95vd6Dq7mS0hpe3jAN40hA z8BzG(d+AGgY$clot#M9eo4u||q@4JM(tK<;y96CyfBJ8!r_w*+ZuSfI1k=>4f=$46h3O9402FDC8yoey-AU{@@9w@=`~84BL0kG!Wmy9ab!U zfrUlwZ3DBm4=Ug9_%M$=9ZXI~)wtWlx%i`&ad_k=wVE^aBSuoQdTPbZmxbL=E3zUS z%!Q6;Tsff|wDitZQ$QDj8X5u=A_~lTPG&dEuku`rRvl{l;keog9I!v>@b0&87*5WtZm%qY{d$Z$t)(R?4lz4($*ZiD5CFUgma_o~(0kbeb zn{Zoz%omC#M2eMxL7^W?af+L0;^M^e%jy~LR9^GGmn}iKuyIEU^}9fVDP(erd*Qh` zTQ$GO`bP9Zuni?O!?Kr*;ekM@<+dJ1Q9M2jt`Dhl?4XOe_&cbmj_T93q`E>g|5Wg@MX4kwMzUH2 ziQ)RVA?fdq_t4X4>D39+V;@(1F9^9M9jF0-k|DasZLvqE(53KLNhLQwDAE@iCrDVB z%~2ISzS!4RET!;arHJ%i`; zed{+BzySy$51Az;s?P8J$-4qAoDE-7KPq{0^s#^VR-wdpP3kiEV>dZh2^|ev*eL%i za^|~2R9^D}Facg>#C8fN$re48P=Ot8Q?mt5eqzwLE`arLreFsKW(WNGB@6#V2Bhdm zriV3tZ<1Hy;?z-q(}3`M{Yg(XXcDVai+2h=CV)78$MBZ!=JNG~+_ zbd9&LQChBW>^#-h(i`0J+Wy|fXUZvzDt-xw^~3esOEef}n?wo`bP^;34VL5oqv*I34^eI z;)j;($LURU$~}p8OglAHu{^JPyIp^^G&Bq9jMCh5k{sv?tDzk@cpV9IwK*FzLv(cA z^|rxH#>MJ}lR%)jLA+6|7m2{6mT0o96+?P;`IqLelRGOW{Hw#F{R~uiC(!Z2aU`Du9Yk_m-qV`xj?}N8Ycr#WN+GA2n)@&E?tXPz~y(ccCm2dCJ<|w@DX!K() z_^!M{Pl|kY+c%Y$YG~E2`=~5`MP+sVm6x;BwUeEkrnW&~IjGQb6w|^`0{ojMuiJ!5 z7ka&OdgE9Ir(LLv6;ivFSXgQ~-rg44UZq&DiIC1cb5e{CB$+Y(`R-GLJF~BJHbo*0 zDJ1K4CCZtZH4;7#vz#dJ1HCL{npCbWCjoL};IVL56c4ZR!B-(m?u`8#bQcB(vo=WtlzFaL@AIiHyI>q&C{41Fs4EMjwB zIsjS<5^x71CEe^{fOFA)yR1JI{lm>f`J?KZwe6~K3DkiX=FO!t;w)H^u-(P9SG@rI z77;ZVzHSy$%2Chm@^q?~Urh7;abmiOWV>7RC6Vs0m)XiMc@p^FWBa?+C3_wA(NtJA zMXf!$H{$mQE0az!v7mJlF!jPwNr*`VtO<5hJZ#p+&l-#GIEV_IH3NxX@lBQ&^i zcOI}1hi=>H?)*iU-^NQcEFS5MpcDh&gjyRn0;hx3)KA0z<9kZu`QKvoS1AbG#A9gp zeIb>6!l*Whl0hppIU+tZhzHh3Wp6V6$?mkNLFRe*3X<*Wrtmq-Eyfz5NJY%i@yH7@ z-&|KnqdFD^u{c3a?h5e^h?Wkq@j(?EAMAeEA8mM49~+rha@Br)$cOrax#5X0uz#%T-oYZP|@w zl6idhj@RYFW{FkhM^(etCseGMsQ>!=8n=P+&A$cXE6851ZGYs6U^6Qt46rPG?fLdm0haVsnTr z8{AH}p>jLB!g>bW!r9;hgM=QNvE;mMfvU9IR#y%Y9-nQ0^1R=le}%Z z>y_Lwdvf-}Pm~v?VI2?=zI~himz0r#0a}(2CMJZ@*z}1jlR;9PG>xgbxgnhLlS18VK(%5(co!lMK);rM(F|08awURW3A{rj zy6UCnksMJ{9A--)%%^yKkJl(l;exD`yW8~{LXhyNKgC$^j=TpM&)4P6eV$6ULMl`cs?Ny$X@_b8~v;IE`~>!Jgn^SatUrg{`RvVKQO z(a)%YrD`;r;7!SoSl2WkF~B7-B;pP^jbn*%sSDy6wr4Q1?3lzQAb_3*9`j=hm_1UL zjcLc*PmMy(`MNN8hfmlH)y+3=U0a zbdrFRnVTGk4opdbL0~1{H1BV$g6`ABoGJM3!&&{0NSvHRcy!aSC3Ry2z93^jy3xQ?tJ0c zPa@~*vjUzIoz$61_S^~a>Tm}vNW6pugsRi1;Mi}*B^m*ArM+O+hA3_IDFKjZ@`IQj z5C?nj-dg@ga%jjDm>(WJCKND>!B%uAk?f89H{#cA+_bRwwEbDYfDjMqiJ_I3Q+MwV zA(OTv7WE!`>21TaNR!`Dc`Cfe!`f$fyLOf=w5;*iYDexvU?J?GSnV#2bfi_2E0qV^ zI=61WCbfYG)LBT8*djOiWAti;A8BlZmCJG3jvot4+=2y=q!wgPUC%SG`HMj-L==6V zBXE3nt;J~JXT5~FlMy9ry<%8y&h(sZ04&|ZcbLd5Ucc$u*>c?&=1=<-UfejjUM_L* zg@i*U_v)U#pghDasQQj+zMns6CV1IpYHhs&=EQfxOk!nIO&CI5 zkRv1qIdYH%u-L`fo0XMCBm0e6vr!B~pc!s+fQXW98t*6Dwi1DZbRWhvNYg~f9w7pc z2jEmNVTb3Yd3`}J+_k%niX?^*aYTM|dJjYJ6wx5_{W~MDL*Sk;O9BJE?akH6!04zn zOp-G<*C%J=BlVvrwwAXlW|j#WPEp{WH%WB`MNbR(nh-v8$ji7j3n64Hf9{blhCZME zZBPOQHf@{mwFA6g^}U~~jY!{>)YjbKXZfkyK754Y~{K<=z6%08z6UMYc& z%`Jq1Y>4pYsMve&_ZBP)+EA;Tef!exqz;4hS;AxlA zP!PfTu!9A2Ujbt!ZdR+L8~~b_*jNT8+PV!1WHd_mqnE~%6n=-@C%<>r*9{;gt&4w) ziwqL4r)xGjhHrXrb_?Dd}&BfSP#hCIE4A8WO`;FN+Zn+h9YlYA51L9<3Mpz#AU4Zn@OJ-tVLI0`cehF8aYczAIh-c_a8mlENV zH+n%S>^C`_znT3&ubR_HPn-w4k0!c9slt}}h1VgqM)|`JU@`{B5ds%KJzDM_+#3B8 zHLkT?b)q-@MIfo7vlDNQRrj%-SG7P?#4*BpD;4l843&~E^5Le@^Xy=hQbk~+LNx2N z90w;|njV>X0)QOmx<-rSb+Dmt-*tJ$NFcGyF{3BFoRgI$?y0AtAq@;S3{2l~q>8`y z?l?qVNlS$&B(L0~-I(Gl6~an$2qx3b>X&h@I!1yE=h0(s8(CN0IIN>`*%-Es9FVcMxA$M^*t>0L zwy61(Fzea)U(c2k_P3kJL23k8YW^MTkwb6015z=t?3WMD{+X5WCnj~uLLB}Xe45dc zpBN>0u)Kp8u+3?Y!Zq0Dr@>1|2kC0){_Mn|grTkI?5dC@|8DTxD*ze60(GxXw$fFZ zR3)Q9%%XGS2tH2K-#AyP!Zj+g#xyvP_;qEyZp*(EA*xP+xjK7{J;HS4%6$DIQW^r- zVA8hh4lZsfd7|`nHvZE>hY5-hKknY@P1r&WDYmxP_|;jqC{_sW6Qx~qQM0bp{VtVV z!vzys<4M~#V94|Ng6e3l$A)_3Tnh35+PLm#za_gC% z!8{c}@zx^J8lZX|pG8YNo>doN$Oc0X|JC6D;`l)ry<=atm>1W*?3Ju!FDuDdaQ010%PN_tg=UdBLvm8vb&+rD$@R*d$4?zCTxR4(R226VZRiH7Mk6DBbnC zEFmFhk6kyG3FYVWnsMMux%3e6L5utc?Y@bLh$OgVr{co8xL29O8AIQ}6WR&>1Hab- zyGSDrJ7I6n9k$1Q-5)?>`*)LV?2-c%*%Q8Oa<)408%3da2O&h4Ii*p~HO}z{eS4zH-vc7X z9jV(rO6tMh;RtJT{&R20}O*4hi_t>=lzyemu^i)N4JFG&vY{j z2$K72|7AS*R>zD<;}!LB_n`?+Ek?d%VTO$(B~gXZ*WvHkN-iE*+AyOQ7KTC%Ap~mz z^)W_=6M4)UwXo2kj5eY|sy2VkohaAeLN~wZA()0+3mtHXCa~WhZaHiW7m8)2*@U7x ze|AyuZJI;hP~b6u--qH!9rvj+54&M{3nj}pyFPy=ubQWltM=rk-8NaaQ|+GvT8PM} zhEB6H5?S4yybaCCPf*#t{j>7!{J9o$oVD8`gVI;wKgD-vRFTfpC((qSDKGr0?_I!7 z%XfHjX`_Tpjq(8Za$Jc|&vlsLbZz%1HfQsovx*8%3ZEmyweCTMYkiYD{4BYtZj8XA zWo2ixTZ}$++L>l)3HkHs9_QOeWErcjWZr1R1Osi*5s{H1P+9`XaR5$18Ym1p&H0;+@10IK+g|StLY73(kbB-YtAKy)Hxm2_VRJLDl*~#@%09_Ln*#^DQWu zYZ#*K>7L*LH~MGJ=Beko1GHd6irRppPzoGA{r~=b=rdh}!YJmc|M z^!?LHsO@s&L#ddO>`XK%&6`@IEQc^ZC3CK3QOdgwmmHt;y%N>&Ss?$uJ%Juxc>8aO zn%X9jO7uMMt{7hHy$ZbYs&R-yeJ*Kc4b7z#uf7Q9j`W>++5N35DpF8*5^RZzeXuc~ zRgdm-s+eM?Nc&Hv;!gYReRw0q#O^@p6;wF17(lcw_^F}VM2>fhYuWRfcPgHZp4<2# z%5TI-2N8F!(uKxn7dt<5r>=GfQ=GbJ?ssi`A269Hh&& zo)>49vS{L&msj2vo8;wbld4sw#-vQNpAECj&BVhf^gsQf0Ik15uX&kP*RoNdI|XJ0 z&hq@xAS<>=T(Ha6!BvKmt3i&v!S~K0;zIZjIqGXkpqp4wTVXL*Vd+JR0t6g`^vh1( zY3rPet?rOYC8uCzEtdekRqxqrnp`qXU2X3tjI$PPXBs&o+vgyD?(G0P@IyQ5DgHS!7RhJrc>kgro zx)h{ATUuI{N^7CsVvG&Cqk{fbRATOhUw@T~qXJ&AKl5_`R(!vstNQnx*CoGZl##9{ z7kZg@%9EvTj-S*xZ6PAofC<$qT*g4Z=bw~BbQtda19(y^Ykl)Ztgi!W(z3FU^)36c zZ{ukG;B4_goIh8Pm^-Gjx6M(DWlmfpZsOkUTWcIxBV-Z9Xi^E7!YU}8N>6Bt%K(?4 zN`#sSvoZ)fWV!f!iE(}(TiiRCtYL;t_bphM{x6rn6>wAuzW!#f>}tK{I=oQHSNTKx z2S@r!d)pcv&Z?}hrM(uz1`iWg7T1EQ~}k`G{JfddF5 zG;OHi`%cY{ASBoe0lgeCejcOhjB z;_Se#x8roG6W!4a$!!1D93X%JD*hHXz;=RI-)7biS_B~#tNTXzL2_K&-QRtgQcxrs zgPh}I9X@!CB%+X8&4zr&LX|B};L~j!y;yX57D$uAjTeiDd(3Kd_4(-AkQwyG!m=Zo zJ7BvzE5b2Rd^P1f)lzqJAjI#u*J4*X@t?0VpnA%8V`Iq+eXJ~4vDzuN+42c)Bf-($ z@oq(8sn-LuLF5GyF0W9UZHd7LBuu7i`9r3mTB36_l;0Uu90SUEQx7j$c?5}9PUqj) z7Tw}M;9s>Gkm1lxwg=3J273-pzh7l#>3yb^d?Y!!BeLhMp{88K$vv_>E6KUMR}OcA z^)=;g7^{w z3LUecBM$vbNEW%krb9&+eLqxkfHF=_81ql(w07&w@s0j!GIIi0tT!7rSO-7!7 zNrh#&JebW`Mgjfg>a3UlqKngmeI9LBY^@`Ev(}J4eMKz6IFS!mxuU#0LpcwcEMr8W zo+IPGkfx7%#ceAGGX7W;Cz`lFbFqhg(2{2v?+xcg9yEK_aJBU?jHK#IU*^dCk=xQwb<{p}Jx5hL z{heAIF*iOa{?mW-RoL>^Z(*sfn+S&%(N>P{7aF%!al#h|4TYS?05(q5R>Ke_a&A$8`wY4@jbso=m_%pMNWyNv6vo7R_Pe8YX3G*1&pDmi(2=U0)~FUTtxjBAzDr@S3b{m( zKIZ9s8>wS#Kh!UESUKF zd-?uYLhl>Stn6H9pDxiVL}>oN?AJbX1A0|S*=(y$NNPv-e|O>sUx^V%`oJ1|Q(2G< z0mv%@jaH#rYZz%Kz$lg9_NaoY32xbFb-(}hS$hrcSa@X-LH`g&sjQ~f3b~W8er#aI z#;rfa?sc3if@257t_)_3h&>0zFXF~F9aZ{)SI=p7m7kZ{lM=iC&WqW6#2^B(me39( z^^qpM-u=Yt8a{u>1$~zWn#Zg75LaQzP^h9-@qKfM`!p&;z*q72qp@Kr6va z$DnefUBNMT|+<-&N0KvH=1O5H8B)s=Sc-sOAkIe`05kse5!&$d= zzPf4!GtzJaQ6 z<$&RA`bH{XaN+ZTE2(>Qq~On+G6UWf5+8^|FxWQ&QciYAmS~;q zFa7&8q^G9;C}gg!pdub7IR`${mfzE3KhL@&sV$NPb*sr?;(@wgBNLOKd;%%v#Wi6= z5)$7mxev7~=H(ToAcD_Cq$ikH=k(NX^QOtmfsu3!!(;%{B0^=@p!&4XG^Sq|N##W# zv>ElSg&#@L@C@%o5K|v|v((4Vx47TW`2M6(mm=pkiU`@myYT(Q>@erPalDoE+%iZ1 z#!GmA8e3uv(heYUig z%h!P$oyBc$Z6Zv14MFg!;VC#iX*FD^+xab8A>(=>oR)!&<2nV=Q(Gp+z)ceD4sa`? z^94X}B5R{EEm*ae=S2uO9bcBNERSy#Eqz;l0+2`Ne)S)x~uLVfOpudsu zR&c*=fOfZ?&-MIv9n^>CDs27IVxh$91n~}^6T6MgtP5%50_H;9OJ-teCIrYZJ_;il zzI3&hl?`Sld7dZ-kCM!uaAhZ4lbb1+x1$0ol=Fvx@?LuY8!8w#k*bQgh(noe^oIHy zyXkNaHrA0q;gp2S314KSD;C`sdX9!(4;OTWRd-SUZ{(rN-<@n3)8?A|Wj{{LNgtaa z#))I`+o1|=r<7uquCv{f_Pb;u)`W?5F5D~0?h5zpw6c}=Ua$0kDV{kr^w4z?OE8TW zr%W&WyFfoPCaTTqKT3SFvM%`Fq=SONf)2ak*C8`VvgyY<&0dowvv7?N=Kp=PG@_!W z)B2;=pS|KjhudQE_v5hVyAqzO1goy|RrD?yGdRf&OCF^JMgt_4IRNB-5)r)1cZ`?3ArvqEY9AggayZbTN&=dh&H!75?~B7rzCdK}hQ36jKrB28 z^DUmq=i4ZxkuP6=6jft5by6A*^hv|P{kY}d!uCu};p1&sfjpcq3$9h`Z01B2c$aX& zUI1-2R7_04C)4hV*!nl z_<+3^|D6d8DGS`<>8F6PxPtBt-mA@tig2KKZT~XlA|dt|J@>6=FupLr^iZgF5bk~X zX@1@SgfjPqfh$Gi;cDL}!1jIs)r?5AQ{b6HMpQ|KTmifpNHvc;8^OyxY6QFp;1eCak$1+GX)Tt!UET?u?}qq z6sFOiCKxakN2P#a`3@8(LZgerOl71r#qS%PZOW~+#b36N&@P#Y2qQ)(<8N=rqCS-s zyVF;Qv8S}nznR3{G3kmm1f2^ViD}U^iH0&9uQ6lbc&MPl`nT4;Js2qLDR6##c`=CY z_c}n-LgaAm=-hfJo^ldD5Ci+0(px2>Z{G{38YuK7?E^PGQxyD9Ua__02iuyGgj`>l z;#=xBTbo>}N$!Esq*l+`KY@u|fF(fj!_@^_i;)}p2MF;8tgUa&;nH(@hL>v(Gg8C% zSNMR&Sa}qhNzWn_$va%rFmOXQC^*;L>hyx>q{2udvA8nA)3dWtibt4oCm=p3TM7Ed zj1J>1{X_FJ)#-cFMVNXaZA!OG;NH$#g%jS|pNFJQQ!dnZmb>qKT~GIi6~XZ4`U+{2 ztRe|bumMSNR7_!qWNZo%&&_R2gflEJ?3@|qm{w@G8}SEza^60+zvF(Lq7J!P_{_nL z??k=^o3jqrucm{b99mMHR~0aQpaY!}KNxsCFab;^#I+t<%J_?Fy77UN7&#T~O-)yv zgL243i~lonjeDEu6tl|(cR1&V`R4?*35ZK|W(5(Z+pFp&}lJkd`i zw(mqx$$x)Cw+;C$t(Fzje|h!2WVpyyh8jhGSz1CH#QwoS;#Hf_?H@ak%y{B`?O$cT z{BLyhNuXzmch3X*iYfcYoZP){_99y3^n?=It5Lgru$rW7_N$`76rxsr~ zs1tEGNc$^qdi&e(K*zRV`LrdsTj5&EW1Q))M)LPRikIpeFSbX*MJ;P9kNO#Qa?pz5 z`l@(6zi%s6JOY0f#Hn*}b7zcfz{mHWxB!)fg#|tdhSi{H=Gd2hV;0L@r-{C(GW4+l zN09!!fS{A0cLEXA3nNU&N{|NUyxt=}QH~5*@rvx$ctCe3?q>^Y!yzU_PolqgWjT54 zK}V7Be}~$o%jsAEkq=TTuRR?cwSY_^a_box=gW^b&#fB|kMj&g01Ff^3M zK$ysD#@H?`f}+pxUtzVW$NTejWTOhY;Z8gCuN$F8Mh1Q;h&uxj*xwUG3b-)EZxkqh zP*cMPK=2_6PlSr1fNFg%#MHrL^b>k%wjo>;2CH~|FJ2g-;1GqEUh~JBTZnW`*iR1+ z9gKUD84jS9?7{*OI7_FP$}E!%y?Y(#kLvV#K>~^htOczSj@}KYp6@(n0pzW{I=k%0_^LD^Nt>9u{fI)4Y#rlPTV^Q1>9KZ z1`fdSkKQr_Qt+rfn8k}vh$gp{H;*}9A0H&z96l)?-HKT|swEHSthypZmPzHKWvge) zX>LI-OZcMD9Y;`vzbBPHgw6cOpfnM+K841(#i5P@?VasjEZy<;nC$hs2X{klqE&uP ziTlYmy1?T(n@TbDPow(Mtt5B^Ctvf{Wc0jTpDGHvzQ$KHf%_@2OEG%;Qv$1N7@5~9 zrB&6D8d7<(w;+V=M+i~p6iXm0Fpe>V=|*(VkNSP33S)ToQdTZhT`qsNI%Nc_-#@|r z4LV$YEO+jeTJ}+$pX`Jy=<+R zqUWP}S2kuV!HG~R)d>5}yk;|6wj?@Hs3eTHa7u1l(_pVrXl2Fy2{xz92o}Hj$b&Ie z;|T8!9JYC<2J~n72fQw`6rcPb=Jb9MOwQ&F-t%v>r|}RMtZ5lXlrT|Ch6ooU>Yu-T z`xar~-)EY2lPZAQlln+l&}L&>+x6Ru7~oSvwsR{48SLhZ&#vp`!(84xo#^v+^!Ozb&`W-Se02~Ji;NTm)e&<{V{o9rY3Qt&;e2?9q{c>P%H|cHt<;e8ipWJwExjR9v2*QjzHF9CafwwWr zQ<(5+p1cuJDPe^b$q~lTLiIE)DNh^qGXqF|?eFi8+9Y95{I_wmYCSk`exlas%dQjW zppP0KajMxjLPbIhqlx5bph;2ZQq&Z$SA)J}ci>Up$VT>t*kuJKRr3-4$&Y|59QY4% z&O|wgE7bG8a$GBTdG!z$+}_01UCdr#n3aHpnzH5ZyPT;GO>5%D^LVBlTq|K){h|NG z{sPs}Bop90aQxiQGl8b9>1p;Jt3-O3H)C_i55JM$_ke#Q>gxG#8d@eVK@?R;&Bi zr>CB{SA_a_p0H5@ng~NTZ`t?R{1S^X4%inVo>lL;NWt2X+e;=!rH!N4VGw!y>0V!= zoVbDjUYS-($kEyC9Uncm5~Tq7mKNY6fk+Kmgd`TyfZwgb#F`uy_mMEv1OsGD=EsxG z6WwiCpVbrF&GfXqdHMrZS#%N}B$|*jll+5lSF&$bhmKcU75kYx14lg7{z zud7_6cZH()bsxTbp@s!LMn38J9i^Nhj%V+tP_fk_c70CqJSobal~w-L`PM5t&DPe& z8u*PwSV8TA{6s|{UCYW))fS5}^lofld-s;gst=7K4K{Kbdd92wHdC`vu19TXG>sBe zh_zvCbLMrwzu5Rom=g;rolChvKqtJ|Kl$y}RLNZZEV-0S5{P=P9*M1IY ztD}-s$p|E5e@G~OBgXf~PQawe+^h|IQDS z6Dzml^_CzEA)pHfK;1wU`L(n(>htHjmtGCH+FZns0P4vfaw|BkpQ1!=um8M~>a9mM z(8}2}n_bJ#pciOTtB@-z$ww3lw*}Dxoz7Fxm79=LO_vW!RN|N8 zi`4>9%<}wrF~GeEe6;cL{w)S;N(p+eU(-zCfq&-LFD?kSg6k=%o36zJYYBu;YyH!= zupi!icc|v(cJAzipA%&BQMjLF{^SBOihwBn0Y>OJW=&B~&pMqQ7K~SnM3~b$w_?2nWm!F2z`^;9+$^K5rVx4#2n+Ld%ALu{ObU%3jHrW(rPCK`TU`bKC`}Z41(*n zo)E;G@uU3s#gzqotM&UA#y=BTb*nvAJmF-YVdP%V-&GaB(<+QRJUm378CY|;Dd*D3 z?E9CelIvZ=Qm1!QChGq(`@CW?IH2*=nRbdX_Pdzox%!r&fj^r4rRN$axGI ziOmkyG?6r~te-S|oH(Cs4en;U{SVuWQpD#kC*yrV+(qb-AkFEdlwoGmhugZ&`2pWCZ8IPbB!Al_J z=vcPd55Xi3Tf?f@f3Lqae4-W+$Jb=WUu(zon+4+;tN{$=fkzZ!^5S8E=E;0}MFVR* z$|_A?QUx?YdsSO+bRRPB8)m{`Qfu^mnce766BzoK+rW9WuRf1fJitUt`;~rVYx3s9 z#=svTNQiL)q$Ogx18+f`F|nm=0hl~sL|EZ%c^Z@QXoS)j>;|vBU_+&mbBAQtUBm#VO5vG`lgF|dvPYiunCfiAj5)(B<|!( z!ZHD=l3N`agf>ZL{@FQ!nAk*@{f+`t0*=XE0jYz3#&!!}(khR=ymeN)JCC+GRTB>= z83@8)-iDh80_0$dCWB5xIl3?s-rK@nUV;PESPqiZp5)%ikF6^|a?W@}Kb|n`1+E9? zHc&AjX|@;knIc*?dc{0<^E`okz*eV+wQyf2_+oa0D%V$dqQBn|Jna#nj|FLN@VoID&O6gU z@BHoTgaA7p$@U7xsRrAzcl?h1G6iY;i7PLhC3W@La+Cdn#e`!smzGLEdAB-V z#$+QGqhvm``kGI4#IMrfBAY9DM0iKF?iL>pFERsj&R<9q1Ri=i?NGsqyE%$xc7;H% z-ACHjw887wb$0C4!tsE;ykh<69!j)AqBt{tG;$rqGRmJx*mOoVVpp09IPAN7%x#Et zHXU}vpGmd+nLvN39t{!|aOMDWUt+r;3Ae@SaN%RH#``xxz}#=R=>`XBrkH(3@u{LJ zTSdDtF-3C{zNQ^7#Xodm9UFP&b#)Yz=0fFElLEIG+`tYjTwGi>PQ^bvy1TPMrwk&+ z4C6l%Rt~Yy1$s@F?@UD*GT#Prk(%Sd?6lqdLwxL1Re%p zOGjjG_RhCgyY+JHp-%-4)pjCnXVLpS3NQSm&Y_G)r z_Ppj@>52$UR~TM_+}tOk*rx4EO#e?1R*DK~Fv>bQa^~jwxHt2Al_5#zij-jpJc2tZ zJGj+?J328D5ju&$+!w-y;$9hK$hHC$+Y|R6t$Os_TItqqG0rGr@JH(CI3-t>W+uI9 zvR>FI&qpN^BG1yhxAX;}Tf6X8HY*nX;~kbJj{sb6wxksm>47EzAaTyA24)7kD8eY; z^)Zu_*knO#`cEk7^f~(|@8kK#*f{1;-X_P!w)l?UXMTJCxpRG@pCTJgG7xB zSIb;Edo>CXbj;(&@J^DF+_F!UO<&;Jx2nb3VJiN|W#AhkTRLU|%fJ8tmFT2=&47^x zwiQQiN0=TGiX`%-UlUX$?E#dUW33N$lQetZl=Ei8f6Oo7J-l(@k^RgvcgU$=B5x2% zb1IRBLXq--YFr{BMf9)|oA9t-_7eK+HK_jd*glgJwB)Gf<&(4`4NOn^2$a)W4CckE zT@}1kNi^7g2MktW2c!4H_x?3u>s}x77>Pa011lgyv!81}oA!KJ(Y! zA@yk6i!C@{;jnveW|jfKZ3vkF@z1d?(Axn9;>_c5`XhPtIpM=g;}KRWdHIm(ns`Ne z`S}Au&!#oJ5u5D1Ja$I=(`Ia` z!={7GItdnGJO^FCV5>pPnS%`Kz0Wr1sJUWhdoE_bzF@u(uc{3g!`{K$cv1F3GJx1% zDj@e(}j z{aAEvPtQ*_+Kz$6h>oPL`fDtPgWA3@48l!z8f1LR$@`QGS+6oj8>~nb{4<;OJV|{= z&AEtOWeal-JK1ivcl0P6+x`lEVL%%6j5VVnL^5+TYHg;Wf!}%l3})ws;j>fSuWI?( z6QTjGq7D!l0Xd&>aB;(z_M%xHsw?E^qBpN#XT6+0UK>FdxeP4!-n6_+!-|GE!R_GIzF|6PMlu+eR<7{m-CNNHEEESRP z&z4VH{Cj|brif3_n#-#q=AcPnUM@~{R*Fw<@Zviqn6VaS|9nE4^yp;StXje+b2)vh zkj5>qfQqI(21IZF+G&P~;^4Dqi;K(H)>d>R==3#qrr zJBhdzpq>qu3Xa*#TQS@gh6~WEyXLTeiN-d2a$#Fh?K;}uqm(7)p|d{v!Q6<-C#~_@1=Ki(!*?os?MI27YCqi1C$;NmLkO?(J3h`hUwyoWj3~hf=a=A z9GRCS?6$?qd8Y2=k7~vh_O4o>cCV;74;s%hfOqfcp`)jliYrGm39WR74GrWvU4h~n zHCCkg2hm|!xz)}l!d68gYx{0>`}Lr^1>wiqDJIG+j1k~)fsGS>2Do-U+)DbGrM+5M z@!9_B=sD&?ClJ&91MS?HMUI!2K#5C;k2k(_$;)QzZ2ZbxCx6sZZPaLky5J2;Uv$bv zB;}Yf$30f0py?-#J15|5F|GW5tMFAP@28%*zHzC<*;HY;#hKKK-bnS5J{*1i;ctCx z$i>CXtsk0&zsjBG;VXU2B^FXirq@ZBBoJ@Zx1g~707#1h) zlhahp@V1Vg9^>{1%BW^5Q`3k&p+;Lux?u^DsDx(xG>FrM2p7bJm@P|C?YJSyLt+dH zPXtp3kQy(GzNRL_3*DZA;+5e1BC6^B#vJ?JCFoh$wn%$OApQj)>&5-0g6cD4yYUzL z;tulbS(P@A5vpeSFU<%O-Qj?uW|bYSKL&Z6t%_*Y+HhGujg34BwK+;Ud3alij-`mn z3#ZyVs$d?BJX^uM8AaNUh9!jGH9}CjyLI|9HIA7ep6c>#Lr9fO=smaL9e?2u$_;5z zWCHMj&i(#)2XZDOPECAd5~HK8uq_Nn)^ZOnTL|vRh^#lIlb3D}IC5cF8h^K9JXr3| zgnclC_*oE4Su*`3QJ%K}k3-ND=%^n;AJ^DSSfc1S>puEv9J&-KMMnGlc|4#DZWa@t zB>^#R^5?BER~H3Cro*O2$QF9gh@N{Wj5_E`Q&fDikmY-Fv9x$CL+;tk$!Wr|9n6LV zI~0u4GW#PI-1Naoj(mW)%Cuaad<-a__*rb%BabEjA$ zQc~mr%Ma&%X8X#0QWf}Bm@y|^S1}p$V-D856i{ zsjlqoK=tfWr*|Cs@_`w(Q#gfy04a!YK%oFqK#)?beZg9Ep^A*C;|BEUnYo}r_ZR-< z)Yl)McX!_VgJH8uf|yF&U!J@PcYWEec=RM=nF+{E-6V%gViiv5LD; zgA38mohcH(u_KB?pLt$nSnsq*ht^{+jZ(Gtm~t6#5hL6VxDQHxg8VX-me#aPOY@p# zTM;WT*Go23FMlPbLC#>npZvBGB>ud2?#?=vYj>%QxhBRE<7OeteFP@lI~bt*|6a@Q zng&^$45zC{ZjEz49KOM?pyro`<@a{nC=eUxY5ad1@aK7PQITQMhHA>O?zc|~5vMj_ zWe7yeUA1!E*CmC~=DK2`?F+N&b$ae>{9QlhOUH#%AKSg7j*2Hs{SUl&JdzA9tPjW# zdS(-)Z6=fl_2f?sU=E$ZnfAJ{EUKJ;0GL9ERw12`P#T;B{{{!e?d>^j3dlv|EZ`@E zCEbosfZiV-Q4k3l+3vxl?s|1J(q~r2q4o}RhmcAGXff?uwB3x3=9%kjXTcX6%%AJ_ z?ryY(ishiI#MFyGaSP%{H&dw60TcNxVtu#PXJzg!=v>f zyYo>~E+-1+xlxCPQ;WT78+i{^hKhhFtg%Czu0K)hiwP5xU85;4ZjIh^*y@)sUVxTj zA~EWhd8&+f#F>#BkM3UUsWdG-dZaU<_s!zxSbJ};2{=3;)BeYN69%tiFWGTVsyt*3 zfcfCAH-CcA`)l#(Fn-q8y3&9u0k{ji{!2;5L^-(Q?*Y_74X{p7&~&o9Rg_Ywcn0!q zGpfiZCo|SSXew$nT#J8xcor~^$Fy2&^LAfL$C>o`w9TE5OP$~R{LeU7uV7Ius6G7dUI@!HBAiNx|)NZ*R|LAZ)aPm5@qAO z1gaEV=Cgl2}hgS`c z+HlBVhXnmiyC_N67M-T7HQ@2A?Km$OA zhq%i1>fB&|{|Ep%PAixz0LB8L0nIDt!_`-yH-YE*Ap_fr=_@Q4CXQKwu!FNE`3Z)9 z6MPi1eY1a=ir%PMvLy8g#E;n9{rDv%7B~WmrK6SM%yU`0w1q(B=7+Tbsex?^piU$T zhiMHi8+db|kVGX{0YTdUGeopOO{It2OjBXwn#K1N#tMkFmBhV2^3v>2)oK*xD?zrm&UKigBMu{Ek;`9<4N$iI9IZdQZyDB69`@bup{^*Yky={LOX-uM=OWm|l zmCMdFqUavD?J9k?(;O^ri8HE&=Y&`G(vvA)kEYeo@1YMIL;JstjOK&U@{` zUx767AsXp)YNs4KoSx@s@U2{;a_{+3CIe%21nG;{lb8LnIv#xzIzz*)5$gJ}Bbwr( zfufclpm&-GCu?Mbc8m$tj?#?(yqy|sR-dgW19&;3*<@vT9rum&1Z*%qfBSfK?^s3W zb=PshR!Dhx9L@pII>W_M*(01DqffcLPARFSLf#yHepK*SD7B{aCxXd_F$++py>CGN zsH*xBKL%>^^}Ba+{H|1;{wyn8-R}$Dpcux50?HXJNnF#q)re*H!v_z^;e`Y0P=0ag z!e6E{6~|}cRx>?#Ta5{o(*~r0UjBFP9S;<0JCBd2E@y@hKee4t15p@EFv}zfV)dLv zLeEs6$7Tj*!uJNFBs3C(pf*<_1w6N~5rPJ$8UtQ`_M~oyGCH))%qkfUH>gCfZ4aKD z+OlHZ(`!_bN;3c*1GGvF{QD;iEkbY(ULLP9VGXJ22}TK1ymUI&255@mU*L7vHk)&s zeTn~{l)EaG#Sw8#+N%|{`gQ_qp0$F9j;=xiyR&z=jJfyQCT`kOgHMolzwfBRRRY2t zM1#FF4b=r9h{wK_X^g7tborp5DUtH*vh_0k91H0%n!jK6}vuw-{7`)dN@)}BSb zDOZ0VRjMc4R#5B*AK1G{S2L5pdyQ~?0_cht!+)jE9k!#+pj{Zz+Q5DJ8Y^&yCc`7? z1flImNKfv4Lnq~rfFMC}Lw19{Z_LbL;+f(T^o-PzPw--6La;Noy$%)e_w;)2p zXQqHz5R5Ad3h406fS^AjHB~`NiZ}?=?g*x zUuIErYQP;%BEyUi*@Y_F+OlF|pJ@I)y8DU75=D~^^{UXsBAasjgLzRf+~b2khZeus zuNiGMr|51Qp)fs>kMY{Fh20xYjG|v$laOsRE>A3W z$|i+iqC-oU$Z1G8S7dP!blG*rC1A^`a-|DIuGC@MU5am@j{Km(EV9zm`<6Q?(RP=@ z?9;8#4&RsgOItp-iS~wuhd=kOM6*jaN&s-Z#D}eLr(_B~1cV=|cV(e9$!b3G?4auU z^JAnZ+V}l01iG^m<4d`I;YR-vf1mN1j~ti;^jw?|O(#?S&zOS$Eq08K6txH%e%8Tp zEGye586`!h>WoV_Pg7QmiBryDyc4nUQYTvdcCpPr&xi*68$5`BfEk^b(x_0*8UbaYliPGiP{V5lI%m*g&+m7#u0(#3db-gy8p7RL z78+fmn874gAaP5?BX}#og{h2@_hW+(UPx$2HoQgZs>P+nuH@tNzhKU|i%!xGiysIc zVCk5H5LCB1fW_bmYp->!t6GW^;J>s{jAM2cJEn&f6uxv=3nyK~`e}cz#!6VMR@`dK zN3TyfN4byPjLj~$p4Iu4c3iY$9vd;A7VFi~bXapI0on+=7aT2MwJYrvFCKyQ*99#2 zu4hZ}@Amj3aH*l~5m@Kwe8rvVn4NLjnV;2PKMYJ<A%e`)>N>bnX8Hr8k7KK#D}B@bjcu$&MM>i7f&zeFC?W#f;{ z*j*lWHM|kT5lWHXZq$)+0)Fmu!x8j?78+RabbU}!%r-lB7%tS7l92GDDObr%7Pn9} zb8ZUbbbd23s>y3cTktu*s6NP-;iF{XALAdMTehfkx1v-Qi&(S+ymxPvo8q2;JJhfZ zeH=8n&|3|dsiNSS@AFHqoX4SvA)&UG-^^^;ZdQ0-|D9W%$OGI+b?Q+QT26%2Tz~q2 zw!RW$pnyg*(M>L+KszGsHe>9AP_1r%vu6kE>y>q~1YBg{G}NkfR*PJ;rNakTkvL@4F@fIpC(u1iZ@in7#tdaS|e62(EQ z>{tfsPjI7df3B3Is%9##vqqXthuDVU$5yl8b~Qb8dqem?G<|hk7247^Vvy1;AdPfN zx3ma~NJ+OK-HoVpH&QAk0vi#K1`&{M>28pcZun-O`+oP&^SkE&d#^QX=9wpwEi$ob z-eU(0e;EFFBjPDVbT%tnHe1`f(9p(=rh&oimLzs#`<97Vf8ZPXgVPPe8z&xP+`o#8 z;X28DiXjS9m*c5#P{Ab6&-jrkMMI;{%f;oDI>A#BAuMtyzT@4ecxm}>xeJ9%$Irvp zZY+c*tb1~}tPj2)?`BG%`h1#cF;b+{3|~AFw}1sKV8B3p2B}rcyo1A1$otyu3CKN- zz~Z_{XMBvgK67ac;3&}^9O;zHwsDp86O&&@9zXK!>w#s4!soO7u7mIu#^_!l5WE-TkUUcO=@NPk1%6d3|C?$7?}-`)rO=IF#MU|48SD zEL}_96H}1zIDL3|pn;D6NQej6P7D~8{!tgqmi}%6Wj}fs-oN4cNzCoC{}d;~C1k@1 zaq~o3>-Vmi{pWK2btjbaaFQDx=^o*&zra|qs-hvY9id--=A$v|&DHyu3lbK1omW=t zP8Mi1z5?0E63>hI9VYSci{b89DQ}yX=JYnIQTVkU#%IQIhT1q%!rJe5TZk#~&S^#y zl3zM--8bXerln7J0_CxGaT6%;(5ta&5x9MW z{j=XK@(%_G_Rn!JXn?30#%LC|I%wU28w@(vj*9UwhyuVX45LaNo?%Z3#N4<o-t^$C3bj!b!#D)76(3J}08fS#_ZOwr(^?sXiFmR;8ES9$+4 z0xO5p4mH1D|F{~AUbD8=UHAkx(JYd1nr%u>X2<`&T)ba&PdHBE^b{H%&_GPKRTW2S zvoo!h3#rauycz1~{lN!~4E(O8De>Tj*tZH>L_VJ_2a-tL7U5mzqX%Y`4?rtkU0to` zv)h{P)X9R>je?dT36NN%>jO7gLa9DdwTnWk_l>exlW|AunV-1nw8+96lnIVi-s3HW zkas(){LQb#E|2pI8p|?qXRZTaueHCewDa9Uz=$B%+#R6=J4a(Z+QM_pB zxIE9XA!Zx2;J5!S=)lY1ak|V?cd(dm-3V_Cyi!=exAGIcvgWbdPu~U0z&FQ$`2?}d@|SS{_bLRcFsFA`3M^GQWS18 zMJALoi$n9J_UpyZapCPR6WX5Ji^&}^jwh&N{!A$~J+W98d?!PzWPsTO)XmPo>4V`O z(9*y@$IVeWvV57UfY;Thmtu)C>l)Lo-{PY&VMIWhm0=vLNFXS89M(Kd%L1 zs)zc}N`dKHEN2A3r&RPZX2hJlJZf?|M4JRmL#^buy`wKXb~s;tiDAP$!VRXA*lKeq z@1E|pd+)NlXVtOA#j<@GtE-?+X=E83^M4QHM{gPA`euy|NCMCM2Rvysm%{31E7ZhVhYRz zPFHEoj=hWRrAypyL)t$oUT53SHmIZtY$^1~;YFfSMBW*WAkSHFypy92SXn25UO-1z z5|8INug5>>H6euP4!hZvPXKK~0`>|W=faO?mGeU5(k!`KEgZQ%WqbEf00N^#(ko%Y zjffynbhklQH!K_m!;7D=!9_0q^YVg#_6Ev_pxK@LuYa}J^}Tpez+80{imw2~owE8H zqN{-RRXqSw2jMcnfVUVWnd$g5Z_QLG zg~z8zv#<`qSU|8+IMHUj-Cr&C15Ciq$e;nc@R}|;oi)8q9xl}6vzn)Y%lFT#zQtsV zZFO>D0%gKm+}c{vOYDzZm8q=panVb=c|lInj`vunp6tJWY)vjVkS?usYI8oz<9tW$ z_~iW;+NlRJWJIXZLRla#`m0p9p8L18^+UK$iM|@Sx#SqyP$G~f02BiAMY4z1L@0t& z{nW=J+wC91XLpj@>`S%#xpdzlvV*M`i*#CMJcHvNa~d~TH%!^Vawya+F#7KOt_2sP z%BUol5E~|wekgyQo}K^%MTu?;*-d|cuOZfZx84ir5beFaD{AxHfIv!}U#PntWRV?s zNpPon@DW)z<`--7>*#1CCiB^CYX28whFLZ~m8mmME0(9uqO#(aoFX~jmUf^VtAc;ekiRV7qf{cMmak^guQv|8fI)qVy9%-k*m{zs-_gmr+g?>*#UBQRWs=~T+-Fhg z7Hy1Jn4C>ZwUPDKq|~UO9HZRl;NB0~6lC#w@2+k3zf z&mGnTIasv5jFka2!x1Y?&KKnc z7?1rVmhTA;+KlsJjuz9qO}yGm8GIJUN~=_hvMf+rAY1`gTj1mM)4ol2%QA<*GTRq& z#I3}JH@N|TWf3#0)#LX)BFDnQdS+=hw>j2;x4I&+haL_u^Rip^L$Vygxm6~@T@T7f z6J%&_rBOV^huZYe5>CkM&kGi#M26$X;qvzTB z-psoHpwcZ}T`R8@^4}j+gg6`Z{8Vz)dGz_HM0V%A|6bv7lTBoS##TkdNuJ#x0*GGP z=8Vf}0zB4BisQkw@9u!I^XuD$>z{TCwx$32V`zOYI+!EwNu(3AP3q)9KRpN=INsC* zXOTo@FdG2vgL*$99%M@BweG8+m&xQ1_ujoxImtnf0H(=Qw1ZNWsht7U9&2(@?K@Ao z{g2^ijYC~?pL`_>hpk!WLiS1e)M={#+ynbRq7SXRm^TplpO~*!wRK*2yDS(Xu(euB zAE6Dz-%wbokRa%T&}KaTgxxbgN{pz_nK+Dp9|Ml5Ac~{i?E%Kv+KzqV=ZCd@e}<{n zwuv9C2~?e~q`?#U3nIaNPMxYn^kW7C%Yi}}7ehQNw;4`zVNyEgzM%asUMi->^rPrG+CnDPNF*i#=#|Q4_~OO;4zte?CPMs>O}otEE=Y?y zr5GP8a4cs`xPP0mUY0z)HU`Qkay1X?1@az-_9xOaVK#J{N~6QWJdlN`(_N@uki!S{ zKUPiBmbn6Y2c~!>f~r}xvT^onF|#dQlwOHd%F~H7`#R|tFNl$$pO=0RGRpAoZPP~v zUO65?ny#K!OxLuYprQ2ysync<50PIt<&wo7I0plw_32tc-?M|Jt({;f5wv1l`1mgxuU+a&Ydij98YT+u5&zl3**2N}NB9I<)m>OwCTIILh5dA!JsWQilI4lFJjHDIv`w?WSbr3|Us{{7;{5 z7`Ayp@T7O1WQ6G-t0{vRcJiZt3p62DU9|Y!!L5tMpNLvpSb3 z79U0k+1*n6BhhsFbzcc_O4b9B59L_J=ibwU#{3kyi*%P`t(SKE6yUA{fP-hm`heB? zJS0`%E@ZtEne z28FA5;g>RK7J^X|{Qsof+yvk+1TyJI>9_w*eUR+2Sb7DgzXkc*!@?odC@5)7zuV{~ z?;u$bewSylX=z>RZR#i_Tsqx3gv_O{7MQ$z|AYfEl2t_U8PL~Q6HO)$Y{gvvK1cD{ zT_#2GIhhXzTK@cLb}(_gW=t7PaAcQ&`cQ2U9D7g~FI#UO*u<%F=atOZ+1dSu=x-O1 z8&)>nkZsfo`^nRz$zri%JwCTujN~rHlGSMGqLjYcUHKmnDsWx9ZL%Cj47f38Cik1l z>q~o}HG)_-y~g5hhex{B-kuxVO_D_fs0`_4T<#)+UtvZ0OiPQoLnpSiWM~~$q`bdb z2||tdDFF2~v#@}>{|LY+VCzR@kf(F+-tsfN@?OEtXtvDqm(Ls668>2U$_E%o|mRdLR(WXlrfsF#ln8D!1 zq6|Q0P{H|BpF9T7m5>#=<2BiJRlHr3HyW77Y$Zmo?3nhpYxO@jvFlssmjA&#uo(Zo ztnnoESIqg2f^8YHr&Z4f!6lX{4Z-LzmTsHgHOW(C4 zp7B}qH~RY{X}qteS*MMDxiT%ZzPl-n{*BJ=Nl2;5R7)R(U$~8gc!T&I9Q*@;E92zs zoGS%r5XO5M=!W((I~EZ|wcG~}@rt~Ig1S{AxatBpMDJzj*3SmYLy9WBS15F<;5(Oq zABY0RC9rtYr(eG$5AX@PjLDXl9-TYajG%tC^eGV0mboG)QtHRwo%X1H;@FDlzNq11 zW)$KBeOMV{Rm$ zvwnNkyq2KDUOcmNYd4#AwUc>mAszK{id@^=^Hc8R)ZK=^xw|#Lr%lpsrKYN)V}@*y zW4;H*scf!#tl|YO$>TT;Ojfqay*~e|a30g&F&VZoqb~NLzS4n5nD6HhwPd1p={{Ge3Ro%i2>Q)^vlwI~4X$zBgg2hgSiX zVX=xxG^iGMoK6&@Gp(z z!;6HTmjZld|L_D767X4Q22(R{6N*CfDd$_dYfn&yrvnl;^L0eR# z_PHiNg2;;*GffvViTk8!H^Yu)vExH5mEBD+n03Xd^9u@~4k4fR?HLjHbI2O3gub@D zfL%9?4u?2s{&lzJ*_z z4tHP2-vlD$q6zp&*tG+C zEEdO1qg%~*skWQP?ZFWfR;*p6ZPbrJ3@34knBB45U1$ZrSr8+7IN&^Oxo_N=DH+wTg61f^L2zq)mT7cW$-Ob>1b*eY`r=?9! zt~QYmN&ri5&T%SGh;K&9KZ2L=^6W5P){-@mj-LJ|EPMO7h%k9PhFQ;gKgeCY#qCc@ za@v0)$m1|4g|vDJ!X@MM);uCD(7l}(y+yAuuXl0}ukaVEEF_%qQE$#P7 zGH>oG20sQV&+2{$&aHtB)GhNvAQi%r4z`x#%ocq9N}|u~xyrh%9tKDTHMfXUcYZHh z-Y`jT)uN0231ig)l0ng>P|MfkE>~Z2*GoZg4 z|3vY*CkWPUDMOW9d9;rdx5jRS-qK1_(Z;^B&WpFd(<6(j!Af$p6>hPi=_lyHT@pdw z{HN{yDk!$$&3b)x;S86tbL^q?Rk$P3uVPS*{fm0TphPG8P0u10-$w=oFN@IeIp_zH z0`oH;$L4k{Kt22B_t%Txs{ir{vuS2hhC4NIrHD}`E&B4dH%f#pCIvQ=^+)`uj`nrK zP0#lp-wTx`$lweFMHDKeA|!CKffu5;-7VRr(V4IUWGxqbz%V~AtyR)5LDBM?z8>4h zpH|QHbAMH>tSZ$5oaFF%Bg_Zu&e~1$Z}upkA;;nmu);jwX;hm#92GtqGi9Naq~0R8 z{Abi=xl^}@vtVlr=qx#H!i=}Na7A1};&VU*p~!^}n`)X4=#rH=s(9nqHPK)#!1w_| z6X5HE@oc8&zP5HZAyF%Yw);NKzHZ2YuPx@6TlBMKJeAR;$!dpsN1Q2Y50 zf9=As>e*-Uz}M2MQ4CE_nBpUz6BeGyQ9c7KkVnF#H&pcwv{eIEQ(W_Z6`{?VE3W)? za``N-gNPzh_h?yfsQ+gR<71Q*&sO3KQNd(l;HKXeyC2SDd+wHwg9ahaBJBw7)Uj$) zG-hCJCx?^n=NhQ>{+svVb7sOF9dR-VPFsRPn+u}=IKhfhGgC+Jf9`8Dr}8%}gzwbZ z`803o-u8qOX_tRldh~`wo}sZMi$~5Z7o9b`xD$Ii=1_u_$pqU_d%xLS6TQAPv^gMb z*|Tp*-Q0W)Urp3kRxjJ>F!x?c7ZR-cJ9j5+f`h&mVWS*ZIRb5{;pA8Ea`H=&8S&({ z`~EVRIm9WAHyPnAE3uFH;+|h2x(jF&frd7 zz25OeWV${q6X;#Y4vb!tY?Opoc-HXT+rmDr2aBuW=L;=^){+ms4CT(uq~O8`H+&_U zUjAd2$l=HIA+4kmhiDh)ag5~MJvOc`R3m%^$lrvb0$Uq!lF>`uJoGx{A5v0!c`qya ziK8ppE~loAP2cPxdKg}8ZcX5yXj!_rcA^}CO#+^VG$sGrmuK~XJ$aT#o3?;ll25vP zgqsV9VXx%153CfB3}!XE@n1`9C9=t}Zy1?_7cdCH>WD~uC|H_x*;#|OKk&8Xno(w_U*))3-pfCyTtElTU zn4yOl#5xi$!sYzEc!(D%f1|3d0HbjnyNTxT?%f0oX`SM{j;%ZuJ=2O0aX$oHbadjd zN7r5Aijdxr(W6)$IqaEWnbX0Wr!YM5C`OTC$ped)jh_AyiE8*USW;|m;31en=BcTv znQV}jd8SaS#GfcB?T(k^A-9 z(}~V59vAdSGI}?wB=P3L2~`7R0~6V_2!xNcw|ybIpdp<$IRr1hQ-9J(}zlBFo?NZ}+nNZck%m zgf3^w@L%H*4SLQxJn;7M(rtT#_c8jNjE9_x)_-g^%o^%xNc;dbM8i4clvN&vynhX^^Ty5+%DqT?$gd0Iuu@UgD65vHA;(D@Uuu zpbiZ2VHoFZI5D|`=nSM){Ar(mZ|x3JUb<4VfjA#962Y%A_n)hXw`RtOTZ9%e<_?}M#5FxaSJQ3ei7 ziAXmm3Ewl6Zy@GnH;bz^1+0nxs0VGqXmz~viU zKZ^_-!E{&+-n?v5PP3_d_TN1IYFr6h6M_75xjc#F%+Qn322r1+b_aKb3-|hcp?y6C zirSy%ljX(I<5Fi*6(lhy}v`{&5kQJwvDkSY5dF2vT28d^P8SjPZY(O!Ax=+ zwZBS|X0QyX-)@1agZr#^G-ML0*xId}{F1p+H|#6_AwYsdCbip{cp)yBoaKs6h-#u5 zPTURS?%egQaUNH+RGrj4SE=9J7{7RZTYo&5?d`d|%bekY!^mhEbKS!fL8{lEn_CN@ z8t_!06eG=0kk9zxL9iUbMNm@+{8D^B!V1FJ1t@;e)apK>F1Nq zp69dn&Kt#*s9Vl$fH^n_!76zPEWD7i`K`VxVdrm&iA@)$Xy$dp)(^o`B!8#_?Y`My zejgpIXka_)XkXVvO33V#Hm$1U%%@$P!2ht6Ml$QWMp&Fw0B>1pAtlaNUx_PfOvn0h zb|nKIL&*JZt*BTsvm6>LodsSc2shtI&54>aijc@22dL&xa+q{)975N&RMFery~$gt ztOlV$ka7rgc7Td_w?j3;5|a%&;R>@i{*!Te^?s`L;X{-QamlRrzUO<=ru3_B=vXM( z(V{p|PCy9=DDj#MEp+^SH;<8?3iCO@q96|ar;#O5cXYNP#_Ppj5P{uqmBQ;IG@Rw% z3l4rz374w|+IBa;THa{akExv$&zwo6of1HmA$vff`-l2*?&H#tx+L(F-~(rDAY_8F z9xfSFHE6GpTvmRH>WyAeFj7o!^c6MdBwcZzZJl?B0Vfl1DtH#~8Ozk@6-$%(%p4|06c^g?%Lli0-mv#A?5p1QCG8M9)jh_z;4$^t+w+M%>CN1;>QRb%ugKXbs zL31uMevjlWeEf1jp%13&B7JXqFKNYnsa zu%E&H2}vCtt)zzC@oEws;2Yw(7%7+{@1bq#h4(Aaa zORy!X+=b|%e97SnAeJcx;!L@s7Ec`BU!)7`fH5Zx!d^ly>d_yaEz9BP%X#dk&M zasqbnyn()WxG}=FR~AbtdF7E*$<8dw>@E2Dd5cPJi31588tnSb=6=2biGhNBsnHK@ z9EwxeAd(3?F@WdT&&6GMcaRPC|4a^$&OvYik487e4lDDkJX%{-CnCF%f3AD4xlnH0OP#7yIcJCd#cw1)=j7n!IjnHUlS{$dc~UB&jSZeH}Y22gxq2EUL5Drz7ODo?+pUtyiU9)5Edhab89CGEgjh~aDI;TJ^Iyjq z6@MZE-K9jtT2jLMV9o}ECcWFZPrboTFPrd{mDSH>r^Bl4h?{acsbPca^nGHBCjB41 zVB1n>*}%!V@O`}O#)-v>O45_`klfFKkV*_bGh^Qz>EpE!OJ$&$?pSZpHso4NgZFOU zfh>QBMJ^I_8AzlXi~>8z1h8jUdXVM7$8E~-%iTMw1{IhA=S(VdWdqrzWZ2&?y#F|6 zBUjVS#;6?uL|lXKS?95pqSFXX-iBmifpq+3WfVkY@H#Cif+?Vitt|)03!(jDaRXl}G@CpKWnp=xDK|f01KGhVn-!#;qw79eDHS|3#{hNsd6(=0px@2 z4;U*bf#Kd_TeKyFTB&!FiMp{vgkQYpA;jV=Ax&57>L}rAz=8$X7R-z?o880Ai&5()#j3=lK-Q}-_%$^}= zUWvpfZdG5CfIA9%>aHQ6V4#}G34ygHJm`=#*@1%00Rj+maB6Bs;osHy&VK(RT&3hz zn9;}TJo%7iAzLAuDOCk>%HYnz$BQh!|9)W|druKlqg$X1cVk=I&eNfGZRK*h~S=pYEV~g<`p<*|Aj)VaQ0;AYI%bzX!w&U|IwVH>H<0Y%WWu z_fD9ipUlRZh*^$^ zN%a$27RTRx&Bk4vzHt+sl=P9OFrtVZ9$ouXm45tVmp4sP%K49=n#e z5H9<)V3?hf*Q_#xc8pOoByn@W6`T|RZr?es6!i#fnhwj}Kzud*X2-p#5NSDiWXtQe zX0_f2zCRQBKCfO09M8^zf3((35V*rMe*swr<1mq&StUqUQ~;~)g@}P4uWyZuu6e&i z2}E3~3Qmk2twG9Xp|69|-3<8@ zZndv$Y~n`&IRZ;fSZz2--1tr}OEf-85t;7U^N_)9bFNo(n`XRU3R;YHpF{}0n5<_D z+{z2OgK~9wG?@-|&!)BS6qy?avrLh2jAV{N-vPq{J5`20`MN)e?+w)HOG;6Nwau8)v+{DyZYRoq(uJPKfE z1EPmsh>h%p$C9O^=vlV>R+9gYiwFQDyfc77Z_Dc)LdOeo4k#ONDS*uby-YNybHPRk z$_`F)SH-Bwo$`_iqNQ9KnOoA&oyC@ORvMV8&^Pgm2AFQLKUkqyziC^+Z#xr&FqKCJFH4~kv zsCT7yUh|u$4_YRQZCG{;dtY@7dAyo>Tz+JeE1>;&WhgZ+fjw0qvbON6q8vPPFIid1 z{4aLDcMFOVG(n&|aVH1|wAt^_gmyGxq3u80RiN}njeYZqUq`L@fyEB_Vd?VY`K+BHeiFG$L~D6dE6Ii;JgK^7 z_}-9*I39>PQeI(f^_n43+3}Ua5@A3MJ*r{^JxvD5!b4iw0u5HgALO14eAWp{$so7L z%^02e%?bO@AGV2mV_=0X$D0cNmygjD7I!Ed8K@Xuk!qch9_9B;GkI$bQu!&cF6`d2 zZ=`D7(c0ZCllZ$4|J^}6Rb>I9H%)seRL4u-<_BSaYG}yp>^$1|3VV~r@DOKSkS?yS zKG)I;p4|cYv9dAE-^0Dbamz(Afr!u0hA)ZkfXx;cu*G#iNs=aL51DUH?(*{Ilo;;; zP=lj#K((t0-K1M~h_~*Ae#w9p{0ZOh$%UAFd;C+yU*885i-12vy=4LeabTtbUlx|2 zKvzB908P8|17OP0BAvzfDL};~X334GnydI{1ghS0nX+sLBLT+tYwLxa;jO@dL_W*C z^~YR1AN~D>nSRMJ^*+&i3EQa6`-4hznaUp9cjrgrHSg~1kZrPPzOwHaIOuad-q<(A zlaaSxZotr)HkZ4|JTt(NjS-FeedI9rwD*1Hgl(LJr1zlXe=ePY`fzjPVJWF5wtEW& zmQSyzsz9ml3BE3z=j=tA8`N0*hhX{S7P4t$wG)hYI}d!LAju9METkbXVE+)l76T7K zEZ67fIC#L>WJU&&L%W#pxeM-#o3jympjr$dcX2=fhW{;j!@317SDUX@#l#LV74RjI z;~~VnnZr)Y`$7d^a{tpVL!{fV3_Q=^N_hb@Gb2g(Zrbd{ij=Bh6E4lLbW38vM8Rf( zBQb;&(AoD;u&-vR3B>r4MehXDXj+g4hdZK8e=Pszp!)y00PkNv7f_4#pEkB{Q?K5RvaiPR&V0`dejS0dCvj0Qg8}Wg>(lLlt&_KJ30;{7-Td$U zm>qw*KB489)?)#)C%E|@F#)w>YFl{iklSHSh7#wl|Hb08&*dSnfZdo>39iJ?^Rtb$ z>}MJoQ#XPMKRrz->m9tw8rQL%Ye7WH?6KcNLu$A=*Kn?zi;lPTU`2o;^1GF&IDvBh zkT0{k0$$JhLj0Q64Kv{?PzR<(DbfW1FWV{NA;sOMxw3=xvXAtfUs4p8998lr&AN3M z2%1hwnfI?mqgkBuxF3s$qk7*kevty}`gKlxL@fQ?0*x>j;pL;F;?pL>Ne!%)Cv3_* zuP-5`Yio2IRL+n{`ftYDN5GoMzV4K%^?5!}l+6_q9VpP_BuT=Nln&6Y!wG?H6bNs@ zEUx93F%yUO&qstz4p&)Mvdcf;6zMjkBl%#@^H81|7(@X|QGb1U@5MDDInnTcdFS>1cwXm>oywo%}BJ-Y@$F~c28L$+A7$48; z>1E3Ej&;dc99qW+lbNtBc{+S>e(jg&yG~D4BLCMuRjmi^*zD~+iGd-o`a%tHhrO`w%wQIS51)@cUtH)e70=3J{USrYL#3M5x4GtXCZe;x5vx zzT@n3!L%MwCjA4C@cxMj%<|PvNqAL|I7~pYfmbNRHNo%Iaj==6yrf zHaZ#_?*Nw2<`|Z?Y+y*iZqx6(*TeAeaHaRnV4=PcJ^4dv z&j5h?)wcn77(m#94_W=&YlzbPfRp^kwsKarnbeT`Vo0sJbH{RQsyZF=l~uANGQehJ zd&_~m;jEJl<$?(ktv{mFPIK-I_423yTNwIMaP$jI6e5{7AZp{Flr*7+PG)^B@Tf8V zrLHcr_qgwW!2|vg^myoVPSxB~wnk@KL(7(F_BKi4)KFN#jbwBKqL0Bk1)}B4^>O5c-&|Ib@kNXInNIhiO?+Er74j%Z&$65 z^V0ppnIT^qn%)fuQB^OB!S^}aG%j0MHD{;wf_Qz@=26HjLg_x)N@KTM>kpk*RA4~~ z!8Wi<EnPEh(+)8 zNnVR_HJs3a<^UFUoRBaKu1fO`Cuqm^W#d(UzZQC2?6##sB;@7!G4NJE!;;_5i3`D` zC4Pr&koE!x42Dv5ZSD4(xMKat3l(i@Go+b0B;MvdaxB#4FfuQZe*ZmeHpICh0EpQ- z>myHpd(EJ0`qA(!fTn>&x7n}VUr0J6U~4ka|LNnfQ>|urbwwiR8-Od3V+O2uwtu&2 zSrqN?Nt2ax%~}#@*jq8Z=Lb9c41b0ZcclvLV!=I0H*-RdRlJ21JPd3Hp6=7eaywt_ zF5<{#v`NsDVJq*x$W`yyP6A*Zera2OJNg7{Yc{R3#iAWq?=^)5a$@du7ezOD>B?< zW-Ez&(Ek6i80j|ndoMKa&Z!8L1x6$2eM#o2aIXhHUXFq9#o19zrGpYv$Bg? zJU$2a3XphLw7sj=6Fc6nWnY_4d*$kyU~c}&Nd%50G?qxwVHQ#kr_2-&a28OEVdbx0 z#SWVVNJ*$bL>-!&Uu*)$qJHsY1fh?lD1>uRTC~web31NmY8rU46lh~d%F{;|I9FE! z?Zk*1@B(R@HoiyQEE%emFWrOic;A`Q>yN?FQD?vpL@)2#d6Fgo6e_E$S9}(UsfK#T zSh^*4j20pIjm)YHNqf z;Hx4z*=Vrw=cky?E;~?^RqMRa>fis?NOkx8?OXD!y+=IC!F!aosNP`_XFM)fDk9R? zzJ>duq6A055gL)x*R$eJU6@jFa}q>-A6{L3WXl}NsFf6HOj0e{+4_5l&|NS2xG^v; zKJYw)PkcA!_;y&A9Fn?vQzP*un>yeb9(2-l$c17hA=$3bu6EJls?dw!VemLu6ul<| zf#CmfTPyZ0|NcFy>M`O*no5JI81K2CA^2JW4Gf+vn4~2V870rwvS&TPY*}4Hqop7} zvu1P>Oo8P83$kd`dH{C3P_b2*hTKK)VHSq(Sc8?ZR`7_}M9$jH?T8wKNID2oe89<_ zmMc*rj@y1l3{ihHQGZsXJ1mh@;%P|FOdlMlam?yBLkO~#f9IF5nF59n^cHn#$DEP# z^8C&Z!D|%WHrCKqxE;;&b6gVl{X08oQ&k|hRxwu{j)qbUrpdh+wy&)_5Ga}I$fc;X z>$OUG34a$|tPx~CAXC=|Lvz&&phg3&in_P!m?|N$qGV8FIicB?VO9<_>%iStH?n^9 z>Jzwq!>jpki*a^A?L;Zoq$lB_ikLASaGb*k*6UH%9VO}L6opn~(=%b~Y{U&Dc29xC z&sE>!h9$3s`Lv2+dLP1}(-&PR1ArWkv97MJ*|T!kTfY{_)+~guCisQdH&3>n2<{?{ zTcC!l@tC6Dek+b3(yOXz*$2G)8?Xv=Uq-K8}KS4i8Dn-2{Lc+_&}Bq1lO{0mH*H&z22Mn z_Doj@Nb#;s>^R%3FUQb zvXXG)n|Wt3Tjgw|AA+$sWox}b9myW#OTIj^ltgpZ^S3fwU*nV+{!~RG$saA+W=j?FE!&6`=eJ3q`1E4G>%Ib| zv-?`W`npg;pAeGbCq#B~k{#W@K5=@#STz`tJqih6NSkp?zcnd$4Uj_cxw--;9JEp0 z)P~S{5s{E=AM?Dbn7E9JWPR{pZ1HFitNQqkcbPwa^>^kFtLU3=RP)cJ2}aF$2TBYZ zZ%zaU`YP}y=BT`o?@aoOFLMW}AZuta5aEM{x?MZvP2-3f4RuUZ1SoFKZ2)JloZR{{ zq^SrBMcC~@LI$Fnw6N(mi*VakkZhp$*-_$v;DR_*v&l|>XLoe_vfD7Dh zu`e-O8;r`xI4x)myjM_J0f+=&G(-TYY>w;5iO2%W zboDRFx$5e5C`&0}R`hTTKtxGeKxE2Q6B1a&4(l*vh{`WT*2K778Gz{l+!jUQA>rK8W;bXli2n>JZS|QeV)3=uzGohgKL2kn8hpb0i>O(7b zi-0{^ZchnQWv%tJ-7iUWHWW$)t{W_Y;WNm%2cW86{{Y6Pbq8s{3V>Bm#{~ZfijHSr z69SzF0O#8LcZ4F$Y56xZcC5D z7gG-rNi1B_rW8(fs!f|1iA)pKi%Gp z4SrXilq6V3RH7gtiZky;zE=%JwF~CQT?sFe9knL)FIdi)lQ<-zU)pnk4H`R>$`{L} z_UE1pp^cs1$}J5T#?KDIP}CWafuo<{R|S7#fV6>%1&3+M?$~bO6Eq0`irJ+>LR-f% zXi%ZF*=Vp5P_>T2!?rJZ60p#C8ENl-`dC1e68R{BK{^P@OmW-ESRhXVocvG=@EYE& z#TuaCv|CDfk-ksSl93H>TZFaL`cq)O4q_zD)B+XT@nS@JDHMG_uh;b7uckrc1i$o0 z;r}JdNu~+mM~-%ZO#-0bz@lNXK(EZ6-I*<}suS%iMZA+yWDz3xSY&nSm=iyA?mWB0 zRy{+EFB{DI`%9U__xw|r2lS^R;TmX@v~dkRYOCA6JXL|)!7ljt4I4qv9sW5~>3czy zd)lw>=yFk_3+D&z9q$YBD@w`LbU&PEiK7SLjsoo(Tr<6jBCw8z6j60$ygAT?*eT!* z#45@jQRS4hb0P|im0q!sQu&Krdu(thsbDoRh<{bYiv@sTZ!dCbg>x=DTEgt&#M{hL zbyddnwq%qMH+nhY%;#`$GzCli_RB22Fao*q{=oWfP7HHt3oLXKts)E3o&1s{HB!l2 zu@_RV4>4*pBxigD{Tp^9$nP=!7AFX8w+$cMn8Iml29{%rEKk;8SN3~)h$JP4vFSex z@ta_;2;YdK=I8VV(N7F70w+FMC_7;G_`l9uA7R2gAKCrad~LKnMKR+)`#Vw)0Vezq zc9)ZKL(x6bLFy0^ut12hlLfLtxew8~kBZ2yED1pEh}o+o*Nu@5M-@_Zl=WL+B0D%7 hM%Q-l$M;D}g zk>!wtZVZ((#Q)*V@9^5=etfZ4V6dIMnba zBe<*t=(nKofRPya+hmE=XqN}q^O_FarTJAK=xuwcR4m(PjO;17GBSwHS@AYQ^{#29 zv-4Mf?kH8Qb$TFtTR-8c9UTcJgcNK?ii<}lIEwNMJ#9-1pbJC#b}Kdy>^54%6G+M3 z%ahrx^|*0iCCv_CPvu|y(~Pv}NM|DY99h9Y8f-b*a-fz@-vO@zm?u$G(-qSAD@>=I+&0igYR^G6^a zf+_?y3}ZfB7QEYCP}5-Dea%1=Hoq^&!k!)t zQ#BY-Zg9Pe0P_>9Z{QqP?|qzfYz!_`0Az)H1;G#yO>t1cRue)(wpT<9e3xI$c%D-U zlY)aCR4e%6F8n0>?!2vwQQp<%9p^Opd&s^y8V$7jZ|grMh5UzEf&Ro!LW=sxiz^Ha zOg>xHw8w16;325z%ke(vt-V$v9T+tI+M-9Sns{LOs0K?GT?`oTcDQb#ETAX>st>&V zK#h)%KqyDo?0JYerO7-cj6!M`D20wRha}Iw8a(C- zsd{cfHAOscjy35mTw`)S!!&8I@fMDye~{29LS**-qq7q?iP6hcdrTY-zc2e{{*GT( zjmCdvu0Fu;3#oVI%MDjqSM(=2EVucOJmnp@0GvP=ia#f)%gp1kEwELYwKBri7U~N7 zAvGmN0*`tFm;dwp zm_5JtJnHVCj(K+%|Ms(IL^p`JU3Z>oRgBtfe4VkD^Vi)e_Nsu0j<90Q;$hul*WuP; zqGqRglBYq&W_ax)!rmpb_dCv;1>0z77;cG`w7o@}UrOIOiLh_qIP_~YV2c0hHL~u~ zDPmdZI?M>=oyVj_@ptq!mTB9BMq4o6l(3KJ;5xrVmfAAMiBH4!*8>M_400%m`27=e zc2f8qaj)o-Bw*aF-(xQyks5CrgbTmTCWXy<@N0a8*>P^9&Y*uOZeso8ee z>E5)R>;szzp0m(_l(e2IaU}H}j=6?b<0FXEF5~-%ng^uX)6?k;%e~A42y~Oi?V`B3g z`@>F6xR!xmDqo*Scq*iPGp}Z}F{TNy@ET5*(tmyjvj^%I&35>#2QdjJN?O%fYxiY( z;l1--c0ezuqJsMfys|O2@JFJ@aO+?;;%rzV;N14yYA<*`d4XxMgjlys?W6I zpI|#)JP)g{|1J_t*`P)ia`{1jygoncuI?{fw_*Y>g>CbfEsNVyM;GQ=gSfXo36HI~ zEAVL7*8iwrMyvVjXJ3vz`SNY4d+uYkTBaYCp2?4JgqOZm(lT2t#XQ3Cl~F|U-kVqM zyl%F=_`F6c`}P^OBWfnY};amV^F%!i31EN%jq1SoxDs6~ zJQ`oc07d>(BlnJ-w3Zian#NyiE;YFLD5g}6Jx~&O^z0cv{H#f0L9>WPj(_@ET4)s& z3^P82@dnZPg;-EW!MEJx$9Q{p<`a>OJXoW-h&%zsByf!#gdj}wNZ6JeL{+*-j*dxC#PCjrIVe4S|_O53hp@KXHhG~6E*>F^0s zEnwt;ZS9xWA5uvT6uXACoB`!?7}a-ibK_kNx~E-ga(hGKECkd#1_qfm?)c1RlHqbm z=pQGh!Z)`uPb-U73Jz*D|MBzga4=aq`=h#Bwc-O?v5R4~DS-|bN2S(tmY z#D|j_*EJQU?Z0btE18_cr5!NpK+6MgAxyvEq=D0k$a?c@MwwxWTZrdrHQHrp6Z^KU zedBf%o*V5S_oRazdq=rR;nKn!H@6Wf!?lw0b(<@<(P}rdEx%Fctyi@3wdgl*mL^wL zFqer2938Ei;LNscYioH=)Nlt=I<*_S)Bo=TVybU(wm8$^flYlXh`j&(OT*ot|AWio z{XHVeC74dC;$8W)oz_xC%rJP2;=hG$V{C~6mtk*Jsp;u+nxCQylufs(ar-QIJ4u*H z!V8rBX+OUI#-FN!^3@b9dBCznfwusl0yuR@)g=Uo{rdIG;FdMcG=sM-M|WB>Ol+`? zh=SGvhQ?hFc)7pYNWTsSY_d}x|C2JhDSm3Xo7i6Ek3H%i1U(a-9%B^Bcl(EjFFr0Q^W8R^z95K_%gI_j~WM zeTT@J!Qe-n3&k!c==7L(pEbAN770j z(_Rw$8_P^%z`fxWkp~NcPo#z|pGJqO{KSzgG^iW3(+KqArw?+Dlvxu$mzO611y>?< z5As+8@{D4SQXgzHV7gJ(y4%wN|(|hB_Ie2(kUt3 zB?5wUhX_ccfOL0vgMf5NH%Nojx6a(>_x&-?%-k`q=j^@qTJL%T6zb;@;@~w6E?c+P z=M+jh0RVO`>m+Jzy5nwCOd35={|x*c;y>>oC(QIrcfC{4FA8+4Rm^AsOI{y|2$-9SGY5o8n^tgn#KE~_OAC; zwbN-?;f*sMT3N~@ftYv2rblWGty63j@2~Wux#ayJ)m?eriLuM={L>^vVf;m6r~d-} zj`Wry9Re=A7Y8Tv!S6hAN^4;cn<{*Ar{=;>8XD>rdj zl%EW(e(SoFM)Ssn(8vky+)hs_Wp}c>aP`ZKk2o3!#88$zKEVgjm9lv`^ zOXE5QJ@5P(-rTO)i3VamDL>3hQekZn#Wg&f9$>GY3q$*DQCSl|2RkTb<$f#S4p!(0 zPiqDi7T`iMnLl%#H7*^RQ1fa|T}$)VUtZI+tqm=!blyYe^K&4N^V)pZ`rh>q@(}=l z+S+m{9G`h~Jd-{*Tz@+{9E=7MsPN@qaV=KWLMxwWFhuO>Wka!9AyUP?>+5p!_te#C zxRm^+dA|;7W5NLRBd#Niq8G$*3`|U| z*Sobp@GHuaH6i{H!I(gdHF>C{u<`TFjOA*Tz!S+PRqoe5JU` z5Q54#Av8fOIy-*dTfs6(c1z>rq%yJtg~7+z`Ie#ZZ2c_q)DqTj_v0*gWzWUhysX*4 z1|P4TE9R-BB*E#{imo#us&6}%BC)3xTRWIj z$pxi2tQ$aobDO!cq5{aX=%}}Pf}Y%$&wuFle_Vi2#u9niK4Kyw22BRb(Q@1ljazTf z|FmYwEwqLUx2!u1Pfi9-@1Qjqmol`dGZtmk+<&c&q}kos7?q;yKkGqO6sf8c-_m^N z<^hN`fx#cl){qK>T^QSb+SvHF4&@sBx%gzrIcZ?86gFwG815-|u>O4qHa}oW29Pc$ zoQ|9aG{nJ>C8s=5i++pR*wmg~;y11#CmBFTFkS&^2rk+W8&K!z7sH|t3EjWdEHvP( z98NfESZDPgYfqFvpRP_#jFkv_>0d4S4agIRl8Mtt1A>t=_>#mgZ`yXLg9CKAkWU7b zC#`Z@8XPQ&DRb?AS03Ph;#8|WNik_rp_A_C6RyepRR?N>PjFn?f133#u{<_C43F&( z`^~FQrl`Pi6iBD$gr>S`Y5}8WbdUt9R`Uh0HG21d3`{rzA#d%u8f$Mn3Pg_IR`eyw zwrv>|ATkkX!L%;$`FQp0L`Qhm)sU1-`;wsDPWk2Hzpeepmx)KsGG~gy^vuc6eXDOl zXVSW$HwmWLeRZyvS5dNO|F%o3_gXNsv$HpL^FC~`U_DO$xw_Xaa)Wp*Z4O9u|7r&N z#=7a8o_~xZ$L>2nueh`-;5{-D!any^mqb5v{utyEoo^ z%MqW6`8a5x-Ie+|GWtfg^7K_~7Q*@f2E)6a(8vjm{+m_)EoLaY`bq7%jEA?&R_xcW zpt6OP4Um$caqOn-CE7o9<|SuDul(@?6#}7HC~;JE9f?#ok7t}Nb`n1h%P_`1M_&cZ z9>&z7BHY;C48|h5rPNx3C2UZLv_w#OzPmhY|NZ+ixuSwm(n^-w8^(02N=OO=nZU%( z$)04UpAUXzW#y7nt$Nw}XM2qz-YlB;c;L`=6Jya93vf$XEl{*#js)_4EFdy$ce zu{#m>&GRme{3^T~H}cpy$-_S5L`V6)wQr4h+j;rJvAYjIRWB}%Qd}oEHs?T)^w6WL z_1?YN#c>dkI2;(RF0VyzP?eNds8Ck{i@D+QKo&tXAJk@5$jJ(#s9@UZmh5W$$VhFJp3wQ!sciwZfk4kO2dEf&-a7C zmvCJ@Sy@)Pr6?D+AOL&(x5PFGA&YW@+w3t`g`dV^iquCqKW^-m3?v@=o*yKg7V6Nat1_UQ)}xR zKX&?GQ{QCn#G?}oPg3ccTV|JOYiqbY-8o%$P1{)>3PM;Wg4ZNJKR>MB%BF@mYw-(D#@S_|#*^D_ z)Lit4miWJstkp^k-i`{X$%xHGp?i3o!skZ>LG&d1o5QLALo(_K5Z)ac9nGkrYP zIGEv$c+Pr;QhHStDUhdOXXIQ~&QaRQZ}v`^=*G01QTGPOW?;Wik_spt>EYpd>%$xA zE6*FAJy2d6m@}Q;qqu89#{!9#o<|o$86$mgpuUp3JZfZQe%l#=9SYM`sm(hIB!f=j zPxE`KM90*5h!q(lBO%^Hbkrvd3~wlIT~Pmr2ZV=(VMBl7(fBZB5JF11KxDMKx?4>o zDqErmW?tXyS;!LPvy}bNj_CdA6vR=pP%&CI*pZqiMVZ;ux&+u1CTY9feE-C3ekiWz zKg-Vg>2_ghJa3N^Y;Fcz!$il`cn1fE=e&77gvDG02Ws0PU;_qJag#=#xj!eH}7e<@o`u0`7$PdizJ=k?L6I6_>X!o_6s zLGb0kVr^7;bxs@kKZ4053;}V{ohQYK^_Asqj=EwmPM&S=3b98dA-RWcB;zXmlSPeK zJDU5awTtPNtF4NCL0{s#+KhW99Ou&xH(}wzH!&_!9J>}{>ZLvlPz(>(2G{<4#>p%x zvHMh*!$Vy3=^$psVxkP09t>Xqo&~b~|MaNJUTj38`WN`v{%*>`K$il}JG2onpuy2R z`gpTlI`RWEJS~3Ch#0z+3zdVm}lS3^Hcm7 z=@VQfC1%kHx$+@^Qy8Qc)~@g1q|=$^&nj8yKd$Q;`tbU%Am~eTzQKwTwmD!>*Fzam z5Dp)ohsX7&LH~%xD+ULEr-tU{9m16k+N6}I+@tS%V+hdyt2x5 zxYeIFRU-D~vPKNMQh^FiHgbMhF(^~=%tU-F;-h?lq_i#`w;!8!54cgS#?|hvUM0JI z<8ZH`ZZB`16BFw#?=G(saOZEV+2IyGU%&~RwLy8@m)PySfQf#mrOv)hz=kmK!&Elx z-sxU9jcMTox2Lamo0S9M7UML4VOWM*o9UM&3#}(e$qUaT3Lb4diQph^MtyDW2oYC; zAjL%WyuTbZ$hr`6HTXyBGN6E~7X5~$uW&q%%C?;-(RDRG#PvW%16wcxlJWLORdury z9~6$~+SyE5nYSjKDAxb{M(vKbP}@Q{qw`6paE(XYujnYh5=l)>XF&3U&}uTcZ~Bvq zK}~Pxeh|i@2|??K9ZLGiUyV7rIvMu+5-C}aU-4vn9*?Rz4>l`!2Hos=uKDUkxQd)( z+}Umv36!`6fh)*&$N?dt^mJb(6XxCJRT)efv=uo+MuH3=8VGU%A?R^mq)>W!-0(mo zcdMktUD)gi(+raDoUVi~t92FY<>FF%#(w$2{_)HPn&_mYq?d{K9H_5PG)nyFNa!M^ ze;$|Srx0BEYSUd;s#?Zs*C)9Pvy@d(2zYPX@8%`-Hw3tgc6Gno6ZM=TwA?zj#^l_^ zxyWunC0ZA;eWy8C?lm=db&NGj+&nct7}0>5ZRzN6>W+UbD7x9I*#vb(m~&p`Uw!!hJ6hLzOm99 zyX3%s`ZF%F+mLjY{o5M?sb-0)8|TvzO6$jjcOzeB01%Qh%!`YTq-m)N5~mzB;+9e4 zQrqD1-W!SUFA3u(f44=+L?gz>g_T%WLBd5Tq0!&Xdbj{8kD4jR{D#Mab9Fg7kXgG2 zgy8Gj+iykdrXJ0!C-9WMKeK`B(zgiSxbP`kF)+WKya%zK%-Z}(-O;fJLsC-6zh*u@ z8y)p*+B-$`Ad?n3t*N=W!GOOe%9|8^+DcDP*U`DT@&a&oX)w7y=GPvZbf+Y!$bdlx zH4L^RxadFSuq@>z*-76fUqffB?qI}8cGs;#Q~F(gL|XY}1kA8n~Bjkfke^!W}x$I=!?Occ;fwGRsSc0oXn;b2_~baa>FQ|08PAD$rvcZ4pfuB?z2atzm$ z#NY+LD7su8F!_hOf*|eNL`WZs#NY)%FS5QJ!|!?Dga}rEmOWd?Qvv6Ek+8zH_ymZ|LD< z^lw1V8qdLwf_7eHyP&-KJGc0isF_hP9SRj^S8?g!(7eyqZbM-M`k3_v+3>hVx5r?m zy3Niy|6~#=^I&HV-4sIyGs#VCb&os zgwIC{8%9hXPL~*|Dx`>Ge?~*}6fm0txf|hc3f&{}PY{P+9uDr&-;}W9#+=Wpi1mXA z_s`+Ei~a&ZkD~O)dAdaP?bsh?THZ~*PvKPo)(QN)b9Ix)ruE6-Cs0&Wmv~b)IZ>GD z_pCS8fP%w2d_XwCTqVC{Vk8g``Y2Y`js+XsK#3<{9oB?`^TQo7>RtDQzS2jp&ss?q zU`_%noQ&fm@4e8_Sp(v`w(f86YA72&6z72wE!gE`vhmHE;)t;^^|vYmbd(B=i)tXL zD4m3B&Pb95;<%O;F}++H8svV(*+zjks#)JFh>4lkuOT!LtEPs3xxH_DviA5R=sPk2 zW&&#bs3XCDn?g9F&r#d|Ct=CX$V za*s*Udfx2uPx7->z5*`Y5&8hS z=6h0ec9=^ZXW}O)#G$03|0O9Xf&8#p?@v4)&Dj!7IFcRs3^ zh@&Qb&tc$v6IGpG5VWJbWTgAK;=XgLx5piVhAp<`T52DxrzcKB4E_}UeR~7D^Lw>I zfhX7H6zErcthE>CX>=u$dJ{vtwL9+~u~g}GN}o5E=-lab#PSo$tM}Wv(xuhRBis(X zIVF`F>}_^nf$_Zc^bTJ_Hegw=z#{{;bMOV;7CMo6`0+3DorfRUzrP4oT=XNpQjdR# z?Qd#f0p9V*;ho>NfBd*Lzjm0tX>U1E`gT#)x27U}(yCGkJUrX=-%TA3qWt|lrEy)a zhrDXL1kJb{-!^+sl+25_%8}zUa=hd!Z3b>`0{>g=a5!zN!75M|5ZUN75}luM<1%56-_V-;DFau@YhkOXn$iwF7z<*FsqJ8H~d zcgWoJ@?3Y8^M>~W9iekMQNhDak0>VybrDi zu%?5tGp)Qlrl5co42|%ap!K_3_jQ+;YR9OKjsQXg0gNB`O1ZC|@CqzpzWkvj+SVu* z8w*1<0zJ0mwfX0$75hoZq=GqKC10ccAm#c?cDN8)Q+gzgoAQErw_P{)MZ^dmY=VNy&%sOU`-QRvURG#}8e^t=M9zg_sKTeWYI(m(_v$JDy*W%Xt zGX4Wpc^BrTf3dyBvo}=-zi5Ce3*o#*5ztL4u zoO<1}6R9y}K8-hIWKDf|fjK{ZG4O7_rNBY-NR`M&cd$;Vc>Z7Rg_-lbtgiB|yK=qB zp!tb?U11*K&S01qKIh3(hLl$4)`1CD)5a9c=s8Ejn}=+b)(Gs?OX5H5br!YT1jYnG zU<(7951GaAp%?+(xThuS=TB+%d!m)Iznpy$ik5Je*YBsErX~oQTUurSS_>m9fLr)X zZHh7nY(BrhTO#P!INIt<_JX%PI3QU0KGgN?nK=^gzn|Z$+)$5%v8!Iq@bVx zMX^x=&1kParjoXHKhOvjc*$2Gr{hO{{;SCcqLntlH2NYGKF0k5-J;kILy#!7eZsq0 zU$4xK)vJj_EgxGkdq2qKS-e~iTDKni(OoWp5&;MS&(Ll|PDa#O7#ZCd;XAjrEymAw zx(yQG!IfB^*Xr?7%;cH5)$xyoC_Sz>bJd)lcfC#`f6gBRR*;~Wf*}XC<~1LDD7!@? z$FDp*3wJT&ai|>IUq}llNIOi6!bL``XMs3k$eCSD82p4qG`D;`viwPf9KcUT#pph% zW5z}SPpEu6|F=v#1%Nk0)7l8;=-HTkp)tKFY@BZ9Uz8}X3%gG<9<(^t$~uZ!ytLMb zZ5m`9D!qBr3?adMn?JvUDv{i=gG|eDB}S{rj_x1j{-a3gUrw?QkR&Tfj!V*`ih-WS zsL*P`eLAJdiBm#vL~e+~D)IrmzHTTVVqZjrdz|A9i12|iGeV{clGd7<8iZyBZ0lBv zTB{TaJN3#B%xfgW5ZHP1u;Q?;yQH?MX<=9tSOpNVutapHa>cvse?mcQE+BRX#KSr6 z+cvyE3kp=c#;MJq+W;Pd*K;ILVVj%hew&Aj)vo`h#SqYMr#GBZoR6suuQX0&=guzh z{+{kS+D;mYAePIelfP$7S<=d?i61srZ^Xo5PQB#`MHkTz)0^R{z5;%!4 zNxinuDc2k+aL?z>>hJueA;0sg>$=^+twLE~k*6@=_V$(*Q=OQxHS&^IA35XO;AGoX ze~F`7P65<7FE0c-D@K4Owom8RMk&43G~ckDNMiech9?1J8$A>eJ=|(=Ki2?}0T>X#6F6^K zuufc%>@n4wm2&@VF_?RI;(+6H#*OXq&9;e}b%SfIiW0PN$BygmBp5>1yt!s(gdDqv z=RlAPVn06r2yY8KRDlv=$_M88tWav!f$O-oCiw zJ4_e)icv|51tTH82q~#MupWNd$CqSPTO}5JJG!-5o#sW+QAEb&MTDpQ<(T<#(P0*Y|DcfX9tnPDy00ecOA&{MK9{;NUYhf553r zI3x@8Xs^gg%Qe;LI`g{1@5Q8&_lOh=E&_-ez?0~2`Uns{nktR&f!#Z#FMV%s|G4Ua z-(}c!L=HyG_8{E7FfE@(pSUaM{K4u%mYrumryB8px(;tAl zuVhjFNrysjIE{Kdedj~XK~Id}L6?L|eob6mUG3X(jE`JrU>M0{tK!CN=^UHKX1VTM zK^I@KB!2Rl+hNA4lFRJ(6K<=SpFWg)Ru$~jodiR2W98&L)0<}2Z3R;*$I4!q^JRV$ zZ*I28(H`5`e{DVatIZsEVys!y;4^1AX}`mAA*G4OHbF7TF!gK*_!t`7>w^_u$qC!X z$@RKrTQ7g5(7IQ==ZqWM9MI|2t8o$y3z+Ay$hDy#e-|T;J1LjN;E zNyNn&j|Bv1qu#H!klMFb76+}#gy+rG`C-aU-#dSbv8*__V?PTEJHZg;;AG(4Uuyio zCw8OoXMs&C)F>DMfrSN-9Q;Gwzs=kxobx}Qjq=nu?moE~Te{oLV5mkNnfm?vXHesN zeHvdvXwF+R<Nj@2q-Hg zY_xN5^)|3&fp6m@mXjcs_YF2WkU!>l3q4*PiaIir3j5;qh5A!{)K~regd{}Sn~v~4 z+VAt0R$8PLlo1Y_4*W*_+&gcaL`Fc*xcgJ@m?M{C;}!JJj(ec7R@NpJYcpf&qTAML zdr&zIMw3b>inqv4!+{t9o=Zw9Dr3E@rcygCfNQt<7pCTJ*#ih<+SshKjRv)OOMVC2y~K??*B^;8pvif}k13 zdUzCp2Ak8OH5L^>rH}H1&ZRt_h*JS5{%PX=jF>chmFTol;r}0$-o^CiGd?zxGcqEF zwe|!Ple(&=ED)98gRjrod1u~LircMG3zX}0bQivqz9dLrr$g!%l3oj&-&+Gf*l;et z@?Zc@Dz#EWJ>}(opV8ponfVkN7mEnYdJ=p$&JL3Y*j@YGlXG9A z5a!*W)%kF4#Co%#z~R?Qe!l04^7;Z1ka#O8$v&+>LN5hp7 zMS0ecs;VUS#jpcRR)sxg0m~W*k*f6aURUzY6A#}Wt}^v-7Z)rc4n7T zTi@wT(mgyY`#&x~$w-l!l@j+GF{I$*;E07!Ill)CIiZ7-tavF|F>00pI{`dZ9gI(D zRdE?BD|N=@2k(`MzySoJthW6hqBVW^<0Y4yyA)+!0Fg|Pdi?^9DnRdIN>oz)yg|8A z+WpkT9GefnqYJdaSkLq>y{ISx80NsjkgUSoFC5=e=BsJHc5lY7@gE);yZ^0hRp9oUhB* zMuTEf<5Km&N7T$v=U~$X6D}-sB~Q%qohxE+Qtvf^iI16kfbv^N?z~GC>!=7XqlZTW zzZ5g^7WRD{U$wW|{exE?Ur{mMm=8` zF89ywMJ5&;rB(%P|xA_jtb zZ7e^tT(3d5FL|*nbYQKXFy%-ys60smP!ZVHz}C~Zb7_O?)yQi!IwL8Lw??S zx$D6bJugn!8rYYrn%oA5Mr_Qb20&oD?6$tiO_<+#A7aXLDiAM@gg zXj|7SSe_el9Eq(euJtrNF&ZipDB{6*d2!2WjM&WW!hpSh^7-8~xBJ!Z(Etj{^#Nn` za_{Dv4P@uVB^dF~%!v`#xR7xJ40*%agGmVP`tt6#5%Aqy9x{NBS#&ozNbG?V%V3Fd z|9t=|;1L#tAIb_Y9(CXz1;`pmlmvC)vO<3bBrt};`jh*BaKqg8(Z2vp9QF){(j~Dd z_`jGWyJn7`Qo1hVK?cqXSe83FIs%7YUSQ`b!k#rzehr(#69AzZr)f)oCI5bZcohIY zzi|8%l=3dS)oXDgp29#x0BaK4jf_~%?8oblpeTpKjrb*CC5ljiL(Q=t;PW>xtS5%1 zyB>sMuxTh1Y&PkOYgSg(mQ0^%d4d`MTfhr4n8Noa5*L=^w47lU( z0xG`%42wuXMfZHgf+nKxnigLSIT^mU)avQ&?@JMh;j_0gTxf|7d@({u)b6G%Dx2(u z+X3qcSlXZx02Pa!6gZqr-gw}#6*4@mh~P~;JDq9$6|K+&oOo}EiBlF*LG#EbwN3EpYoWdpV173|dE!vj7# zD5Z=`!KRL|`^k?&)C));Fp8%A$_Fl9jGiz!0xJyxtSBb#ua!rX6LP7_BPhBUn>#XD!=MFNEPwHPa(h{R`6!0v%{2nS|(qYPisM^HXPvCRz?2k-8WAT0@2DkqS50Au$DU@0(l(0%IG zh;*boOp&I2%j0$8t{Bg{1qBlPbSJB9zvJ`4N!)O_Upbx6$=7zPPmkTEytO%JH21uI zb|8yH>(jnB=DJ$(t;*@yVBE1)8gy4?iIQcNrm;(Gyds|&5?K~9ocyb=4)>&q8bg#| zaQDbfBI|3i;LbJR#PM+3v*vT@Zl=BFX`biuG-(SVOSIpuuG7_&9qEg|Tv+h$?)%o> zr(Vjt29&1NBCyYUhXP!0;Ac6mIa^G%)wv!bMmpGFvtzB*9UjE-?A?I*->t=cEaOu7 z+1wB}1O(`+MPt`pD$aC7{_&Tn;QHy|KHnOs?l#ur+9!%l>*k&`UhQ06&fi=G!_pVX zja6F%wY*EMTxV-rH()$EsMM0xyOLg4mk5q=urnijR;pTns%PlR=jp`n%1^pHlU(3y z!`t_jMU#}U=IoBCW+HOY%$Sw@0hSPfa-TiMT+`8^2Vex zci`d1S%f@39zmIt>%q)$!Mo@E#d$LMj`5I-0w)u}#JxIF0@ebwJUb69dHlGu#A|}z zl7zfCx@h<_-Bm(CSA{x1Ru6mcX|aJEgT3|>bgS%tdu*6V4ci}_?o=o@*X6rygfs5U zy7y@pqx{y9mH#=%U8bTlDRSpRL#agM-#Yi%G(1IrS7#Z-7NFa&tb2 zFo5uX=)nthr*6OF0V2v&@a)fLz(6TKtWzbs?eZb&5cJA$ufTC7nTSaR%vKO#OrW9@ zFw%4!dBtN334VVc-t0e|KhpsW7YNKtaRy-vY@X+sFpV%3RC#ABWpTc1@uA?qhFPWR zbk5Bcsti=!`iAl0;TCY|4Tj`)FknOdvl6Sj>UD?mk2CD2;PxTPso?Q%C1#DX0IphQL~GO%A78*E;AF&CE@%q>tK3*uGa@6nBhqk(XZ1I!RSH5i$U|& zP+z^L3H`vl0>&^H8n*$4q45S!7Obalcszyeb8`bPFXlJ-x#F=-K~Z}Vt2>a+VW0-X zj&=PpanUHF3{x8@DY1F~AiW471@XC(@)T4kgvJ+muoJ}wh@0Ls81dXG`yVl$1iE=b zem2G)PlHU2bD8pjel<-J z4yP3-4`>5(k_+N8GwGpvDeHJ8s&4z2&5DYpqL_uWp-Iaw-!)}PLWMn%Wo39@D@_`1 zDYq5spV?s6#YFpockr0?CGdoU2?Z>%z7R#JXpK0%@A4RGpsx_u5O{Q6ht6zA?wS%{ zJdBs#uO9J?%I9C+Wa)2mi4Z*a&Q6I5ZEiNQP=pqKFR(YVvC?x{-XDL;ZRe`aHr z(XByEQ`xdK&*z1CQ;7rNUUzsmeh_45tIO%kkvr}|OkL?@-gd(B{VR{g%{uRVs`V0L zAot%Wsl1S3Z0}-gq>beLq9ku>wA5ksX2y`;tCv-_6mnd!wy=JO6uvw9HgtBAlF~EI z2qJSKZCVli>&t8;ayJVWV8+v-p-6e|-&VLE+Gp`z55Sdw$@{|_4o|tcK_vnM!Rx{A zAemfns)f2zHfUzD=ta=oH~X!db9@b@o>Gop_;Q`btRr-56ocw8lHvy|ZnLOP^q`Dh zZ629x0j$-)yjH|$l3py%fzPy5L}DW5S@x{K6s}GFpNc|#)$S4tPCTc)Y2a0&q8N=9 zKQ3m&bQ2J>!TAzVTss);Ugt$G?_9>UJY68$7Hh$wue$qAp>VC91zp1}>A=w`rXt{e zt@vVm@!9`3|Hw|l#JdL@r7e^mHuS0}rt{Smzo++*_+@h3+UK#M_;51>JZegQV2 z;P#;9FeF(&2Md3M@dCsDJUbbbG7&3cI%BZfj)$EYTw6GxT6W!Zg7AaDILa?73LoN; z&Np)l|L1Ul;5$O0ff;^wVT=k?ZWO--;EH-@7H0B*K9SgQ8Lb4gK1wcX85+}qr2fr+AAgAdAq^Vzli`h%$Y zM?POCW}q?-|HyWFYd>8xU1iy48RX)?p9IniAWeL8wiNcm{h9XqCke-6)Kmw;CY50g zbSFz4Z*(&1r=VHhJ#cxHg!VmhKAfT#!AF6~?g6(2LgfO?4F(QL%$a42Y+m`TSAnV^o5lq>ZSm^kplV# zR7L0vz!L@`XIpm$0}pWA0~oBxsF!#&p4z8wo2+;`iW&X9G9uCId8(>Q)%ezqEa9Y!nDarprYHds(M z!vyWVl_be#)Ch>u-aw!X0~7z`XL!3dtEtkC|BGpxSR zUlb}h{2(^07I(gbRH&}gs$arxexnXw$o0Q*c3)r7FrgFS)xK)vs?fzn|LS?O9ghm1 z)(}$RM7i*)Orkqrh!0cRW59wz+R?I5^Z_l5lIvT{R!yw{J!^7Tz!1$Zo~Jf_Ju!W8 z!b#Ju?Vj^A9HZ zdQPa5%2xt*?(V)@CyuWK1gvUbM(wh4+OcnE?7VX`h++A2ay+%W*)o)D;QX!#cXe{` zlRJ@sK!;l^e0X!#8T2&n zsi|UN(+)uBE6yqMS+y)09|9hH+T1h)a1rJaK;jHaC(q#S!^E%G1(}%uSOP<3`%7H0 z5LArn@n>+c!Qj%Vw^%$47n0SvK?7C&;Z;}LQkZ~zy)kzJ-_bAe3qlF2>J{SM+C5=; zkt+vizu<JTj3i>DcJ1C(SXWx71VbsF}7R}~ziM)7AFK9wzdF(W{Ou@v^ z3w*b5kyz{gQUlkZM-R6|k+IPil|WIB>1n`9xJnZ)kZ=Qhe{(1F&x*aEZ?yy;MV%6# z+gV9|gKGu=I0J|R^`%fxhl;xVmftc-*ZE3KnP?TD@{#{wORb58b}8ic3v@LcoqFs~ zIF+QG@ubRTABxeN*K+!xe>M3up%X}ISUC;132cD?i61BeeT}vCUJM&FT5o?Aalh8! ze=5NndDp#K9$x#L3rKM(83RW_(3F9>TjrP)OL?Nm;zxdiq{OmqT7*}9;sdMHs;W3> zz9Z#n&;GXJAiLZ+H!j@?4P8I_u&Sy$GC4ED^q86yi;+q^z;VMHdgb~96`x06iyh`y zjCVN93F|X@CJy@M-f^ANIiHbxOo}y}p*fa+6&ms_L=JQ7w_6HEfM(jZMHG_-A zxwBJ=e0KlrkU-(}>(>awm-KY+k`jdFm~koDR_)&KK^s9^%7>sZ*TcB!shqr@5+Oth z?CL3Ew-?GJP;b^OM>Uv?-nO@aHJk^7Uid!Pxq_uih7wo^0=MN>Sp zoZAHHhUfT(_ad=0J8-m>mzMo)TI320=!v5Vmu8{<}V~KG8=vcs>3%#M8neP}dbm}=ku?0o&09}+CKs;*9s ztF&mUc552#7kpFf`hvR2KmMiqHJZ`EP#c|IZK4e>kjGp~ZGo+szH?I(7xxIp<{3`6Ft-xAwA9zGKAFn#jrWS+Mj&{oJfGdrzN-&S&8&4Y#sZi}V$} zTt)`-^_qyQ^%!%QZdJrI1@_7vw&hecOc}{yZkx#k8(@xr0c3sN2cJh@%!AwYFBu~B zjKxttp3{NXzxCB32{hr`PPNpi<+O%Q+;@I4H9lwjEBTSYJQjq;T{;_DkzqfiX(4(` zIY|vZB2d!*EFdk;j@*Y9qGwD-x@Y^PTk)OYyQ-XX*O-@t#Dt90F5Sa)f;%7XYxZ>f z%JS2iy575B$(nA7|5B?2;?@}Atl&;Ep2X^?K&>d9>gseMGeMdTU&32-;8j*&Uz{k=mzVYt9UE*z;CUoh zRPFo{tD`>@$8lLwMhG-tbQdzuVwRBtRZHiH3Ju+{{D~w{>o>34DAf(3SZF%Glot|h zm$XZs)7*-3$`6Wr1e+k`80ZsGZ<+1XA1%rv=u~+|`I{C|<^#KD5&OjNWD7*wm|epI zETUp*E@bn%f4G^S{T0DQ-wvM_`TFl41|bQFb7AxF3S7-yV$Od}7>`L^w(=uMv1U(g z2Kes$n!6S@AD>g8x0fjlL(hMnb8q%5D;XZQp{00bfafdz{?F0$?`-&o;`>9Kt0$^# zX)G;qevNSlmz4NU?A%P6oPH+Py-37=zosy)tqi``fC_*wX3m97a=6A8Yd&s{`-y1^ z(LsH)K1X@(&ia%tZE3D;`&@eA;E{6mw5p@!E=d`=)9vcx(o+KkRTG@$>W2OvV+D=b zBgu8+V75sLT9ju_0uO#P6n-xp@Y`BI)T(cBnl??f|BT-4`4Qleyp$x;dg-5aUfJAFj?vVjTP!Dh&q4#_~8Rw zbl8pq%LKGhAWDjtdvX37#|f+^-zY1$gJiD@QZMa+C=cx^aO{Qu{D_uMPtE#pJpK1* zM8O_$_+X6*J_vEb?)>n~R+P+jFVq5Q1E#aC-d=-YNHA7a&3$%yPLcwg3sF&5WI$}o z&6^E5ZPt>U_a{xtt7dr?>}DZVP?1>l7R$n8*od)-foGMSrY!zlSLedP&c1&i<`SL- zw_}pnjVC!D^lDn))|+baWsZLu7&r8jv3jLSKbzJt<>Wr?TeayVDqKZ159k2V0CjT+DTgUdhlV}QAhpwZfB@)m{EZd96;kCY7`Q!KZ_Fv^Gh+RnYKX7RGuY`!k}KF zqV~ouVU3l&JwQT82#+6vn@+UFRJAR_hVrLz>*hg1cgIj8zlM7Qo2Xa~Gc&Pl%B+qC z%o!kB$QPO=ghUD8g*?Lj)011U7_Fp0w{R%R*lwNd>Id!vwD@l*=ooJdx^NXeL^_hg zlC}@&@iE|v!fzPpIYl0~ZRQd$j`yT&FEWvkuK-^Kg~y+ z=-!_OZBK*i6EXpI)89KNmNneQ{mGIES+4?psTXsR>}n~%&;_stYGd#rzaP2?ye!;D zw-Rvo!Ok1Fb70Q_brx7G@CgIJ3!g6R^MN3lr&Iq8fUg%?-02r}HI!*=BekuMk_KL9 zZEZ}XPJioJDAIqr*=1O97h{T*ldN$2B5KdHo!T<~?=t@!64mG%;zg z&3fc`X|cajo9AWWR+4m{rr0rz;HgGg>?Dnj>sd(7n08cAtRoG(D4_1KEp&v*fN7=2;MGOE3oUgp?h3y>F)g% zTK@YAR&}9YugJTVJQSgs3q7R4(sleB=aP*n@z2U&9>-X=2u<#1u5j_C{A3R$MQyQJ2CVy|K zXsGbM7QYQshw&F!O3G&`-PXelyoj}ln-p3&Mu^%MARRS8(~1h{2o6AkiRFH_KQ4}= zoHnhPUvQi_-at<*tFgtT-a8yhmMj5Zjh07Cv5I;eKY>a z>i_Nez4L;Piv)|zzuC6S3v}F{^<18_GBSyXXVv-|gt_VlA~NM2lP7na=p>}agA5nn zciVrG<%(6z%KcpI5dEvQu{ybRp{Qpy;`v`S=1lL-St}lRVqrxNE`@h#0HIJMx+yW1 zP`j9g*LGt>fhu~z`~22bwH&dRoa@DZJ0v=5eAG=@V#Jo19isZ z79RE4J`;!JbU*S>*TKQTP6$RtM}7PFYe?X>!uO$x-XOUER|q%${)*Zm_7lR)W7DR1p9=Kvl!$e~)3%!OM5hrTmop+E;Fs2MFcaCfdS5-Kg5y zRtE>0?4$!*qoP#yj}5@^6y*N~N9#k3<5H_{?Ov44nohR(sr>wR>L^fyGe)4UHO<4C(WrJEAF^jDDcikt61Np)U)A)mk8F1l3f|X8-vAQ;PS#IA7#+K7 zKLfWAP!HH|RcRGi;h{I4wXA1#AlLz}!7(MUG8ntY?o46G6omG5eeKV?hlV0tw=bTTQciiOn~YOB6w-`y z@5SO2>I+w?1t|kfN%8oF>y8K3dJy2CW}uCNbbIAv$P1LOEGWdx@B6*?(EV0=H5=86 zkkl%$&d(1=t6+m^Mha%@Fvi1*PPx$sJVZgB3f_|7CWQL*WL8f-%SEu@TG|cfDDByg1u5eMDf_0X@OnY1@){Hyl-;1wGyUxIDlalcVet*oi=f*c&nY<gusw^|m!P2C;UjRuM1_mY@V&vBx+A1o3B*~u0 z<63U_>~y;q#tA$^-5>5MQTNP8drHxgH5X)RlPU|}RVgKUY%M^BNZ5c~j3aP#bLp3- zPBlC_s?#0>SdmS-wZDH#4Q5SIZi(SSZce#t5IFd3bCVL(ZC;ZW9pX4wXh`hlV-|o7 z-#=VS`3wsNx?8;+v)iFu@QupFbKYiBEog%{Nw>H-QBl>exCYf+490}!f&6s0;YKei!WyJJ@kRN=go1Y5?fPrQ4r0anx>6oC z4c%ZpdU;F{F_ zK#I;Vik@Z&McRX42{NeNNN-yWgEPugz_7pzf?Zr)`M{P6m@KbVR5GQ1kLy14X7eb1 zHU{}VC}7(G7ZJvHxL!z>13?@H5&79(rVC<;2iXb>QfavCj*Lb6w})Z6$Qw7=C(=stso<|8ecAG!T!7Xk$fkUH2Ow=YSmLz! zqVNWkU&QzKUqmO;BC{q4x&gZE^$z)d<7~j@L)9fD>_;(j3kn7|KDDQFp_+cP-j#D7 zFo8q;(Bq5>e1wav=Y=8e?=B>D1f-Cu)-!U(Ghd%n@}BHq>d!YMY7hj;Z&$NBi<KLzP6`DNFMMI-ld9pNfgmn66;II zV|YW1^zv7PSOD{Q+aXZ#S*@*JT)FMNYx}$4LQ8n-z&A9(Nc;%a%-|t3Cp4Gh{h)M> zfwAjsk)!0XzXQhm1c~0W<#`9iZc1Fmy2zD4-pa%g2YziEw$xckvEjsmbm?UsBs7az z{yQXEHfb7eVM5W}us*0xl|nc8vPZJ_ibRS&+6(*`0SyGZ@?wk0n`}NvPnC&#=0@yM z{!caTWY0A2^g!_PvQWey($QodC;7OSo-PbR8J7%=QlO8sH4~ zoYT#}8Hm-A8sKTC!v@EcR=-&4kAnxE*Yo>qjWctplt{*d$)8c~?6ye> zm)!k~c2Cj#1xMhXxF97WJwx3j$rs8PEZ`kICrf>{TH;d8WjlO63J=tNyuOyOHY__i zipAdeMY`TtN7x&+yQRDBxcJ;Z%nKu5U`Kk-nxpu+G0iE@hsA=efHJg~o+3;!loT1S z$FeGAws$)mb%kr?e>qds2#9qKr7~GbQ1I7ye<$W@I4LhY?%;iimU4ZRb>W82kM=~G z@Nu*ZOucWxBmCYE*r;k*-mBP{h;VD^*`=AKYglqvf7XI>HKgN z`8^%KCHDg`U&Ia7K}o$8tLt(5MaUTeq}E0weDGr0EbL-?M_)E*dkT?1;QkYJI^QXE zb7?Z;Iq&}ecsk3dD%WspFIqxSKpG?#B@NQusUjj>(uy<)NSAaiT3SFw2`TArX%rCz z>6TVP>bu$JJ7)~HKNx$D!Cvcqp7)M9ubFl_rv5|BSIj6w2oC3mMg7;sjg3ZvwOmT| z2AnDAI9Sv-7Q3mR@KQO?q_#vu?%dUc)m$`PgOL;u^!#`D^{xB+rw;f1WW?LwRp^kEJexOVX`Gi1ylPWw1IPoe&J2&kKgRFP^<-iqsoSrThvqzJ^mL0_z0&_#T*&HDPK+12e5X} zT!)`5_#VyAetlat^sPG@CKtX zWkm~Ol{>M|tgb&)86B} zG-WqFwbVg2Y0sM3!jWasT|6_F`|MS!fx$~H$iH>mZF5adV%MGOqDB6GdwdPkK~b^G z@g`x|__R8M{GoHMW|9grNj%gaCs@{b03%Jp>$;G`^O!OWoD|07dbCB>Xl2re$U)Uc zb6+gNFbtD2@>nZEqbIfK(ie+y&TSvb>8trdF>nZhtWxChu(X_%jY6Hj`FPtYcIgz^ zZ@Jf0n6|O!Ls_KV;2n*wps2{K1C*<;lN$zNZfhqUFSDFVE`<}@&dhGqUi$fLB<3i9 zekV|*M|5dQWj@MOykjA%i}R=1VX@iNYj0DHv8an{V%WY z2WFS+*BT)V31N0Jdl}o{|L;+9p?$gDE<6%#gTnqKJB_YP*25-IZelS|xWLF0oDFJ5 z`kZ9T2EEpmp17@JH<_HKc>E(?2BRG{{=0)9P4bzqBYj}$i0{|^3wChERLYVVW_2lS*zeBI8Lv>Q$_Z_nl|7!G+c?8z1+x?SJCI}?OF7+_{yRo zd7vR^B7|qdj(qpEh<_sR#gm|OwYB&nFxC{lzSv)FsiJEnqiA_1;WN8eRCljX%eJlo zizOJ>swVlCM2})l?KOxz0H^G=BrNUkegKXtHEy_ia{z)06fRc*cnv&1V_N(+%0!wL z+_W#>Q{|1&zJG7a93Xv=KJoD3p1ek8E#c1^$DRcqUtA(nCp3iF`0<{tgX@k8nzDMa zi)3MIp1YN87Qfp<@89^sR7)1A#fXVF@ooH%v|7#1(6;X7^Eh(US(oeKWl~C{1mTuF z;Vc+3r?7v#Q=IQkH;4{b|rnln3Ir&{@RGNDtnv=Y6153SRQ(maX+Q;Qr z!4J8FkRG*)#&d(#hMl1{^5$Jd@S!oK32n_{?O>m--Js#g_;t_>0S+;Vdqc$LCq86k z>SXTjw`J*f5&V>FXbPLVW)TuVpnCfC9m7iaykv*Bi05u@B&)ufT6YrW(XHmMTG0t| z*j<=X0!O&)8oheUqE=RZw{q%?n$0vCA^Z(b??L94-0q^K8KY#9b<(p7~q;>POxnf zw%hG@;T%A*mcKmBmEE$uGu78|nL0SE=+j5K~LydjZA0?ruju16%< z?PrJF~YfEzzzn?N> zWZQ)@4T+WwFM9G2&u4lNFOQGc@-qm{_7!J?>{*_@2#IipE zckhNIQ>{+LsAx{%{`ozlP|J!>e@G%u6c`_B;>8lC+TJx7u?ss& zDvgY7Js#_(m`LV}`1~UUo#W^l`?Ql(bu1@)n$v8?>`1^zGVV^@SuY$!(lIM7#r=1c z^rh_9nrn0A6`552+=x)CA8Kd@86J-3`~SwqN)z!g1W620bUn|0&kWLFyY+;}28J#c z5*RD5t@%o1t2sFB?5He>=pa2E>nL6>Z-m)c@a07d*yz)eD z6s4HkA7TJ1Fy7VAp9NRu*wo@)E`+Z^?S_Gn*!_sJ`|Z*j55WroQs2IPoAVIx4}1Ig zo~L7{_f-|><2R})aTw!>KW%Vy7A?W)z;@{^#3O-_B@6~vwPyC^{ zm;hW<5%|a~tLwg~KJe=#{6z+&KOK(Vf;R)JQf%k>urv`uPu!Koy3`myaTv!!DC+0b z_5(C<@sU{`9Z(kJ%N)w_&N#GJ+GTeo2|h9tn406S=j9e4WXO( zq&Wf9@zvaFeQ7-&M-IoItBcqWC*K+_VO+#BY)1g=`F~ zNu@W|h3F}iQP-@EPJN^l%@3ME#vdWcY1%p91F?0gZ@Kz9PHl~85qP~Ws_p6tiq>8I zoF{NlArJBfOzx#}%37P+%6Ijx^{=gMv$AH^?g3A11iMGw{Ib)-zS)I`k(l5zOrH=A^TjyW03-spm4XW zUcTz){NI=6GMv`0zOE~HdDU&C!zgfEivH;Oy3c%d?d@l(J}38GpKDdcZ*%;LvKuT{ z50v@o9b%F9qi;2_o%o4R1}t)%4hPbYk4PRM5GmeGidb)bq=?{sO2Zv}%RYa{96iPD zc@m!3v+fxZl~oy=7zc5x4jCk`dcw$Po&|k=zQ;3q8xa!P7())Jl={|>?%_{+JckCm zCPsMc&Zh&7>{`+c7xiXzFTEbo?9-z5CUWkxdYMWV$%GNoiv7c`PlM;1hXMNjSG}O# zu`&&l%L`K40x4dL?^4b2n4l>-BC}$H6!`S!&?VPyRO&vNA^*;h67^(v7@O%?+`^bT z_rvS4G4__X5y?*pWX2~`kIWXI;oU|OT20dGue@S@q4OXuK$(MMuln<5f^EvZPw83r zf|3eR1>sD%N|O|+7NBo{{s+7sSj(QjUwF%ka>PEceu%N9KjelPFJUEG5+%KdJ6-F} zL2&&#B0#^aC3cv{Af!4@I#$&t^Wli2{Gozbiu8`6R(6j~rM^a%&@C7waj6@aHGhrf zO5u8@QA_9feA=Q{(KW5Y8t=vSbcBEQ$peW$yYj7=W|S#csB=I)!;N~Siq3Qtao%I) z?v^~=Zgc5yNqeI7_vpjkj^JhYP@OoR-?-qrFNiNhJy}RJ+9xk6#Qf?!mVAefLP_?MZQY)Mm5?yX~iG(pkR5KFp8f zc<;XI(_8XxQ?3eSl(ar%%#y_p&MWDBbb9c5(7M)$`&QJwdq=IS7$%-i!~$9tNpfl_ z0FDd6W$+=Vd92+)m`y)@H(yd>IKS%&Ee5o&_>huSPjAW2RVqAzYBJKhh(Tw`66Y+j zxl1+gQU?PvPysydaNWL_Dcv3R!rn@se@N6q36DgpHy)j2r|n!5&%%Y1rsnylAxVgp zUYy3l{{;CZ-|3X(Mi#5}p7lfM-G>iqTSVZ7!sXM7UYPE!<7WO-kSS+Vz<4>6wMn;= z{^J~toij^CgznnT1?FlQ&uVGI(TKG$NmuW#1>c25pcaWIGsE<#-afTq7oHp*IkB;Q zfL~R-x0%h+Mv=@&j-5;KQC*vH6UiqVxCQB?dyzf3NGu$<`exL=}um1b0>G z(KQRxRi^AVhx;|$Q5RY&@%lTc&LsC0M~{ZR{T%~!-6pTCYNy}7Vt_drE{U2z9<5!Y zpWks3Azkl1-E~ZVJUk`@baJqvL3aj9OROgHw7ucg5$hxj%~Cvl!ic}W9XWWyV4{%e zG26BA^?|Z{#;3N`Wc{De945ykFgshm5?6H}vOn?YPmuS{Nz%R(T4|jb+De4M+YueP z^O)ZD8akr6@wi{_mDRHnSTND>v_w~~3_u934+8On?8mEr+LHXX%qKS4l8+MVz2wEc z;J3s3!qGQoI>vyJ8(_qY#zTA4Wy?yG*)L~egt!ZqJyt~!%vX(FQ&ZJyWEjQsAmi0X zA&1UQYGLy)OMO=(?e-gs5b?&8paMn&;NRV5(N@uYMaq9XJ+@50XkgtT&<~;BkU0ts zdHc>0XqFi>2Cs&UM|a?7TQ5HTwO(mzY~j>Jdg~xceD8SD;XcP1Da+V__ z{1HDIJh+F%9T|T4xDq1h$)Xq%`{3^)cYRTF%x!g+@;7g>U+g(NT1#XuToRXg5*n1m zsmRjbSFWAQ14|4_Zf& z(UnKk8T+ntof&c4a^n8Je5M9Z7HqefRMoetai;v-+!YLd*RvWBK6evyRL5;#Z*yz_~}s0y$TwWW#oRuj;g)I_dA06gAt5yPLz*RGue zp4Kla$(lxO74H7SubnZ~wMemiaVNRmUpZffJFKq3!{S?S!Umli&Gh)U5Ye*cNOy9R za8q4v2r^)Rap+;OzFw2{b!*3|kYpw$wtW-p{lrhn%&sby&ra2CR|C+=uwpiLbZUm| z-nyF%zjh{jW@k6wG8hL2DKrE@e<}t(Su26r+QIN5QP~+9^bnjH4fjAH7hG*@7H{Q( ze9D9C9?MP__mQt3C5_5`N5PaO(8#jGM0*pV9sSS~JPW)ThW$5u*SBi;>=u=L&f4+! z68Bvsj?NBxhtdKw+X5cDyFWXpXfa^8XT5xIQeYTnu{dEQt(q-RS`Z~~cqgiGIPKmr z%RGR>+srX=N8I!s>c>kF_Q&Llz;8+2Xv^>HYG53k?PGP{WPYRiDE%Cg`vNG6gdB3rC zkH9kMR4-q;_n8B|FJbS&A$(e(W*o0T~5(EMxw1c0e z=W*h?62C(_T9sjI5>L=tW;TG6|3R9&V07iBi-Go&fS*Ta)z}+DS+2& zFSLbi(1jVv0Uvwo7K6aBmnkY{AjsiaJ>BL+PG|&)uEp24!XPZd*FGV)Zdio^`TTTt zZ|CXP-NKWDy`ERtXMSs%z+3C}MrExD3N(ofQ#;RMjNvB z6NrAGdIpua-)S!sBETJ-UN+gjWF)K_t@|JD4EUc|6$AgumdRB|In+SEBefO!0p=r$RHfsSkv_ysG8Hb*%@$r)Fh+rHdSDD>^E(4^-D&2N7 zH^AjtJb>58H2Cgw zt{#BEC=XB_5ejeUb*hd~dp$?N=y9AxD|?dUpAr`-2tIQl2Tl05Eo$)hk5Lyp|>Tjm3*#y_O`KudIIk(QU zvS!K6if{MZtgrbMN|a3%;K2pCHsX9HOAbS|HD=JfEV+n6zr|J_Xeo3VAMjS4F7=%Lll zAaY+`S3xCH&cF&17CD3Vl=B9?T1uQ&7BCWu>-qUIhQfKTYtwnZPw@E9JCD3lhjL=u zH6h4|L%X=}sD;HQ=tPd;2z-4YSuF$PwVsPr|J{?1W!NJIhroV>?FGb*v!N$4CJq#{ ziVp4VHxE#;GN^?Gy^s=BM$Xi|aFIOPnT>mw<44t>%F~mB#(6P&+4W}YXF`SqrD2T& z7u#QCf3j*`Ck@1RJPYD*hgcX)aj z%i6%9zwDXG8OLm)y7^}m?^scNihY@Gi&bo)7<4=8_nEmg`6*S;zVDXC4YtP& z`8*>e!e1ipN-GC5owq!A5Hboqmhwm!IEr85BJH5AU?i(9bXDOrDA55f2CUYB>pYD{ zpFYeqrd0c2`PKh%0TM%!DMyjx%nw;lhR`53BGcoS9BA-hE1`(}#YKBeRAvFS2%C0$#v72< z{;1q@FLkdnM>3?$&%KCBnEGX6Rpy`L#WeWm_(;w(%!-m# zs)myf64S1DshT1LdYoxZUINyRzoG}D$UCI$sSE%HlBBC`Hdgf%5ipq{RNbR(#q6i| z2m^$2X1sb%#!+2CvccF;krWMhPZ9;EZ&!RvLw4h)uMZyuOqg-1IfoDPbg>ONvXMe! zTIW@XT=VmK%Pdh?Mo@(`X7~K)WfNerpc7D3WLmd;a`pw>E@ij)kOiMQJyaqU#{?N>Z*7S)V~L)GnHPLE zjhUuirl_(T+ELAu7n1|IF!W=4fEM_`@{8v7aPl^ZzTdsWgoJYT)r8o$=5oeGa;W>y z*S?q{#qY2`Cdf*#roD-ra&;q?QPv%KIK8&_=rzUr%`p!G-HEY*uHJxdN8xo&_BF{V*T98UqHj6ma2JaR z{m)~46I(gF->I?WpMMkQPjl(BLaE_%{3Nr+h6s{+4)0}0=Lia!cjd~$E=5M{ zy1bX@02w}~z5mq}cv5is?rL-Cx$-)mccs!f)@qWSa=7asqmyJIb@0SD;sySOY)o&! z5ugXk$Xfe}oiib77C(FxGGFQys}>@iW{U(#!2r03pEvHSJLOqcCE{qhP^0tv3 zSHY(@x0s;>f;gO{8-~R_anYjdM)`WZz6OTB)TpEOUl*EKt8p0ZZf>JAx~`RNXZuSe zpw(;U%PaS=tt_C6k*mkKX*kNM8yva6^*61vYTc;Bzdx99vjUR z^FaA1Pn_!XcF)TPVg`S{doFwXHJ-QJgEqe~4tCSO{4af<&(v2duR1`hZ+bd45&Pnr zm|GI2Wzo$^Jp(bewCW7C!nqd>wr&*@K(xpbS-ws-~(JQcavM?$tK=4d?{sc5(( z2~7T>&kr|Yd;Ll8H`W15R{+c>hr7*HgoFWu&7=kI$2r zfDp&*E_xp_np;=4h;y%Rhtdqmzh{X8U^7eb!&IP1ING<#x=a zAlctP$}wPM231cEK`5-Xo#9S&$+&)SxYco|#q{Pm3@*Zz@K>D2SnVl|u4$hY^7jM4DyTY%3 z3zrC??kZ|j=_P=eixK{%$=nJ^tT9uS{C^YUo{Q3stu50;7H^Gd=KR`QR6hvZ2W1DH z?bEi#SJ;hWUi>Ds;$&Yh|MI|Y5MG;C`pkEEXn>tULqyXFs{Q3mkbC3CZ)*|8$T@>U z(;yMHx%8r8oW@p>m_74LlMEhZ#q_Ns28d^c5zRu%5Gh{O7%p=tffo-u&2E-Jx(2}Q zfHoY`zuXRM$RuyY)9o*IE{@;uETc)b&QHz^Y@(+7)oz{@rZB%1W6Y^)xu&j#zoyTg z-rPGd?tCWKJ-s(g^D;O8qk>)e-_7U|X)5PW+Fe~1vIH;w>c?rnxwqN4xi*_++@ihG zBs^j&-Jm9z5_c;$IlT2U$L&R2U=?8#^N?C#CF@SW#ibM!x-{2g4F-PHyK{j1t(`8* zdsLBp-TYPTA~v!JTzVj~GvZEV?5)P6=o10|2UXY9b0N?rv7@AOhT*}2+&!`zRWjZ! z*u%DWwRfQI5)sDdKR)x|Ay3JR$zYpMnht^dj`t~J;&yKgcreTBJ%p-NW zXAw&2$@dsxG|mX^w$=l;WM1l@SE!Gy;lAvfnaYP4@jc~danM!NJbU)Z;rwOszg}ft zo1a3(G<e@ zS(Av4{@bwh)BTI73OR{5Zh*Yzt<1vNcvcMrA||>x4zvLCfj*1wxrxESUNk++YR0cD z3gzrx063YG4c-m2B<`mroKEX+yA@*&3mYe~EKpEzvaK>zu88vZI0VTBXR?a!RNQ_= zDq?9ZvBR)vve_NK>Ynsh`q?*IW=>0f{lDDLycs~7k@;ey=*Pcz(r5@B0;-U!#gsa0 zVqa^0Z)DqKTghUt6@GWCP0BFD-565;c=z@A%}neOnx%n((_y{4o}dHGSQ|Ywd=T#X zgrCBxYdLlC_14e5pJq2wKS#XDlpe}>j?QCz$IWqfX6_(i_ zq7FmC#@Ds(CYUFE7wooss1d*O`a3N{7P$dhsI!JFOwcTL=h{F93ak#zozFgHCv+rZ zeM%k)LfKVAx#rAOOM*DWRrjwi6c%;~M8vI-ThNNdhM4ocvk5trj*Q5hIuDxN5Ve~Iqs2THo1WqNa@zvR zr$)-BbTkhRKERIG0>5b>>1wKq3IVYqOm+WC$0Ma8{@LDz*>q8_1f@Bq|dkcC7m0u#Omh&e+WWiw`T%LQ$Y;s^dmS*}lOekSxUlkPn**RekD_nL2X zp|xD6w_YMag)B>YO2&r0i5niF$VwX->gn$ONM-R|{)|3%j3F=GY8tH_IByVY5=|;13a1vyK+&39GvnC3LNO4#lhW~`mS=`Rw+y&$m~CO}P@q*5 z#OYxoovuM95{MiHIeo&QHFQ2uu09rcnKClf;@|SxFp>hfWo6+MDO@po%{wrDElzV7y*UgEJBh2X0|G+XkI*Sf=f$P4CLPZGHi zCA{tK$?YUo2qYtX0Se1G2D&S*gEyyq7t z49lPGh8yGxF*XlgdYsahi+}g~A^_4u0gLa}KkHx1&Dw%2MAT@{(TJZuw;g!yfto!t z5zB&KEg0q#psCUyL_moNt2b?ZI@AGjOf~-CB|k|TA)%kr1XhH1&o|bn zW0b~|eBhl1vfK{uou)7t-jOB6Cvan=SKnKRKVZN$QDsTowXpWIvbrj@L3&I2P_5#1 zJhL-`^v02l_*2NC!=ENa1$;Ir`M{|qLh}m1OV`WwUq)C|8I(Np(;Iu$(?@(Cd4@(> zOE1Dg$9kF-f5tN3f1t9ouU|)3q^%ZlGt)7pXhER+>augg25lKU1>+gPs}P2sl$?x) zfM!=NPgC}UuKU%1gpDfu5OdEOtQGM>lSbNp-Gr+XE@+tj*lbOOhI;&p;6W2vX1e`w zr~nR)Pji!U1kztrhaFvQ%%B^}fqGoF3l%;kx{Us1v&u<4s!CTv(MyTgMU+B)CN=6; zrbn*k5{et<>1WXviOVT$otkU8KT-y*_neSH$re5B(=6KdUI+IyGQ@7-6Vb@b+!IDa zG^_zIRhl<#X0!^)f zlFsUd#&XlB=?ArrUwlLS*^HhZp|fuQ>jfmOZ$SG2k*^s-_FAO`a(L=zHKfl)>HJE$ zc33ZM70C{@0awlD?iNbQk&^KKh;z-@w(`qgQ^e1QcPy)7<=n{fyI!*Q*1naOHT2Iy zswjt8D(@&gn9Z@cWoR(}R!^tqteELd)aCXjpWTt?me}9!#&vI#oka!un{|%8{usVY zFOS~E`!Nz&H*9ep0_25A>KJkLiQKCXJp65u z9?0EK&`02~Aga$w-So=FTASwQx4A`!I&UZ0CaUW`(E_P?Ps1e9sOUlXM__CDb`I)0% z9UBoOhNrDaV!daTZMN0s=k@MsV)n0zxodHpe1E)C8cHDTLyDN-3XOt8Pwlx?&h1?H zorE2#oJV+4nGc2%+@yP7{V}MCnYI&Ao{|hdN?bsJALH#{M!DaTipKd~9G~?cTS04m zHH~h(Sz*dBAHQ|td66nYx{`*DWtY6h#hla(2A+y zp2P$^aXD?NM*8y2KT=<^wP;M!oVw|C|6#$myjy`M!a1r^@s_L@*R&(Rr_= z+n9s$4HR*oW3z(^vC^NyoMaS~H9)FRo3T|DN7W!(mfVq)I8~|H37AZZL>YtF@TXx0 zSp0d@w7>gh%_Wo77-$Id!DRvTL7Zj}8C*&P?^;jrl}P%EA z1iV-cL6W1fx#(u}4Gl9TgxAM?)>Yyw?{=tRg7<6^@xmlCBJKlu}9ZSR` zTM-w=DURIHB|y%JI%;+1d#a{Jyl^Pg>!4Wl(xORh*Mp7a)pYCuGCr=y*%uru)zzOw zXx{&8x$NlvSlYh&*-;tvT-7Wj*#K<-K?tzQlWo-=7VD|L8-hvX)lUGJ+uH8@kUpNV zAk($`qmRx>a=t0S4(_`mhf+ z_;O&`0bD=+Y|jN;sGhIG^M+5(-D#C-{0d6yD{3D6`?U*^9J{Ho1BKa(>2W*xmFpj( zud%K!>-xJx%<3s-%U_bAIqKT+zdY?|h7i5sh4LOc$Ops#lLUMdkWcjv!5XF8be2UVldAzsuRG>76(~;WREU!)S4gE{tE^R| zE&Hl$!1nt^!s1*xKSqWmxk?p$1>Yo1!j4v&!!l;;D8=Q)%lVpbzVfe0468sAMu<&z zzK%aiU9P%jzkZ7@r+*nTNVF%p)_3D6cN=jk_rStoZh!B+C?Q}jW|i{OW=BR|egzQ& zcnb+(G~aNvt@z8jLiGgfq{z6> zC=Rz8V1=(KN>%VkK80jKudp`nme|m1DO#p!hXKRS1Q!BBntRJGbwD$QN_%vAI$B(U zuK4V04)5{y4~1I;~+*=XOj2N`6e}Xoc?zJ^{|(kLkmvwqWdAe=0`s$WeE# zr&SZ=>ZO-lNnLd{pT|%BBj&fr=}{e(Z8qdzIZ@`YR1M0sn4_xDPIR;SG(g(oc$aGL zasJJlQCP`396Df^Z07Tm&{)kOLi})AFVt)Fmo6q@T@d$}4txyXe*5trmfc4#4tL}T zSC@-wpJhdEp6F`A!kr_+5?+P!dqaFj9FyNN7>j>%F&z=ttyGBCP3xk~iRUZLL+W;0 zztrst93u4fyA|E-E>2n^$*1L<=!UJConOAY_ajaskNo-g5yeRZ|z%EK#zwvx?r<{yqnQ1iHk6k(Fd&1b{ zd3}(Udo`)NV_bE^P*UK^f{2bc>*A*ti%-H?O1=?+WXgpBS|-E4TK6t|#QqU6Gh0vl zoo-QpJsJ;k*f^UBggi8v5IlU)56VjK+YO(RHNUzyPG}~*1 z(g$8FJ%F!N2S@5O6vduEq5JR9!6oi}wA}@s$#P(@f!gcp+(Dix(6Q;(73;UO z`QJuI^U>8g>SN96B=XzE_%=R1Ki3v~ydvCEbgi8=+Y=p!h^}+2Q2i?C2qa*TZ$oAR zVi}cDzFnCy^?DMOPiUHxBk)8x)HLKu5L5FD0C(>E3bikau{*D9|XM_2S3y;`2%Zfurw_X+1Q%y`vERrSS z9#B)GA!gry&>C*1xV3k}RHQ~7-5H%U)5*P{>cVAi3IZ7x3<9b@81BE{N&S7=c(TH!Qn>#~4-ZRN zb*SGxxzJr@SDg=V8>U!@Vk+sY&8`eb`R2iiwkdeStBM{$8+&!EXn%g59}mS(i0R>T z{re1zrw}?m54Tl!bgBtD!sx|%q36c1zs?YTNpAiv0?SObJdKpgJ1JYk){9-g^zAX6 zgtk*A7GCZe#imXyS6ec<>N7_4^t)JTQ7qQEN$*NT(ndc?@#W_>3itWx9O!?Jk1u`5 zH)nd;t_WAHU?OV=%8^U;`}DL?RmislIPLJVnmanZdF8p)3Nq(9{j6D)JVdY_H1AVB zok_|hVyg9NNkU~+y?oy+Q~upoTu3QU%sHizYH^_5&%43RpKfqOoGTN)Fl(fH;x}Sn zFw;^cSE$n)fBsbM-oRQo=f-tnRpp&GA4A^724a=k>0UbyBt*UJqFQ}X?d8em_Wg{U zf&zUsp);pcs$-P6ENfnGThai%mK8XY6a7!=<9oX_?<{UbT|T0TYO4I!`RSs$C3X@2 z-{oI-0=J~3w1nXrp-=GDLctygdo3VDKX!^9wC-pR#eZmG5(~tSt0+)U09_=d@pKcfmd9RGwu*UyAS&0LZ0!5*WP?+Gt*$9P-12T8H;}Vw?_|Ep?{5u!A zqWG)_D8RvYb^U#P_kf2UlOzHYHtUZMH-H!XQtGLg8ezqSSj59g3fMZsm^lB<8}uvf zd9&NIUQSoyAOIug&IYB7FspnK6r2g&-``o;Xyp*Z-*Mg zL3{4hM|Qo71>SOE90mq{pvDat%&@^geE2ZXyXqfUIh-BZa&CWJDOwM=<#H1-mGfBa zNfmR`ag7khjP2d_&Hp?DaBH~J$|H}oq&hhLS9wxc|N?3X4N%9^~pF3scKGoR6yj$v)(O>H3n(7Ei8Ba>p zT}&b=DxOwsNit98)1&3rJQ;zruFBa&Efb2Be`PJkpbs+JajCy5t6&Pz+$CEQ2 ziy1Z3LE7{I@NqVFt9~)$xYPIcR?yl&E`rne*8Ze^ zw)!^1m_AdEVywJa0q}BQCjr?&yP?{6Xo*Gc+?`SdTe|Jdd?9XDPiNH6UT+SGno)|C zP2j^02Aa}k7LHqPNhcB`;jLOqy1iY?#>EF^mlczu|4_YK>Y3N%#uF;uTYY!dEggUC z<~FFs^sajNTcYz{=Dn8%9v{=_$8-2fZt>MG{09EC#b1K1m0i7g75&SZo8PKN#NNF; zxFp4}+5!B-+cGC8=N^iQ7_{ky#cIi@Mo>a@T^pnu@%mr*!00dY8(M4ZbpP>MsAr=tp zfH_b&CJ@zBABPtZ!FtJ=n7M z!y*nSZ^STJfw}aR2kz?w=@_U{^*D7j#Z>UF)8J6csLL6u|Jb8EIqM1`@{3!wQ(c0k zkBXE1Tk+w1dAr@;lb%Iyu?2KNqV!8QsK@wO^&567`zBq(9N?x$Zr-^wlIF!ra1DmJUjo2aLG!m15nV{QJZ8qnabgxMA!Xwg;^0&BhA)?2p(;v6rTL zkCP_8*9)h`+y?Q-p!MVLbO0EfYd;Duhs`KVZND{w9>={&Sn2{BTachVrdrrM{R!pU?zingn2+q|>CvsR z@2JVVZ^@X@5q?@4WYrINU3f-790v4;5;mw{0ptMdH1N(Qs35;hk7ae*6zVY@m%&baL)={AI@))lok_RGfYxNEelbQI(^s5wI0Y@6PF5V3W-Fv;0Sx_|Ky_rMn^q zf5u(=HxCtk+(_eOj(+8t?ty#uowd z-FAg9gA!?cxP9vdxqYh|V*(~s-)lJCaD#wO7A9p^c;De{NeE)O1CR0(oTK$tY0JF5oKb1-hvY*rCA2A74d+D`B`iQIk23$C!oxZJ{m047mY% zb}Xh)9QKsAw#ov$Dd=Gx=uktR0eUM8{m97r4IzT%A6|E~egv)f%0kuGZiWoO_cqCe&Yq_FbP;=M!U^B4 z z=JZ5g(B%M6^F-w2H)y4J?)%>)pY}&{qWy%xA4z)J4%p>#`=3IHEvq&q_eUbB%i|!B z(O`LGXK`d%A(QkivM#zD4mq@qP}+P_j-B>~jD;q3dy7tSvU^qxn_WpUnO+2IKl?EX08a7E7fy54zlewuvz)%Z_{&jw-S`5TkS z5ZGmA$r6io^{!tK$5bh>J4=vAWhKl`xsO_(k(2Oy`st30i+;C`@=$n1$6-r*y-RBI z%dyzchU(#I65d$xf9c4HJzIZ=zpvEuJ~pZR@l)`PY99EW>dbYNx^129fqZs7ByA*- z(anuq>-|>?r5+hYcn1+l{<(3LLvr;#0UI==5q7%{ONOO<)e|q|rgi>I@A599mkX z7=wtLOaaiEVL#qbM%5ai8xjXs{EqpKD>E9Beu(_UjKao>c`}KZ@?%((qbq~@ z&*!ZxgB0g=!}GsXFk67lK<(HFx5sw`qC2MHHXsiu#N4dVCWro}#NM1Fk+W{?|Lw7E z03X(emUy>}k%#hmY;b9So&gBMIGO-r+(u@1)FyQbwpb^6*mLfQUYq0yEF8V2-yA-% z{P)G zc&%be)LlNEbu4`cS?&%fh;YOOu@6wDq>EYc;|f(67eQ}!2*L~gZ1&G!eMm}8?O1mM zgo`iM(6#P_X`%Fbn>Y9 zBlfTPBI@2wE{A^B`D2}enq21mQ~ag`*`MU`n}&CoJ!6^0yjRTMDC>S1{S(UeP1kO8 z{Ji#ufcu2#gzj*whdOl+?YYL-#q@@1@xgI+J?Yx>^^L|XwjB%qJf2mZZOT`DlBWHo z;Rf{?`@L*}@4{na^UC6417lG)1ylkcq2d}e&bVmsP_%K?Opg`XT|uZpm8AzUI>5CD zX5xL(Wl~O)MhXbq08z%(#w}Mi*lA3a6%Dbmv7xE2@1-}HGIWIyT!1i)PFOAT0SNR8 zmRq}oQb!=7$hg{lk7mL?me%7zg$N~|oRw7}F=(BdPq#aoeNO=b^h%QrGiNw#v$TN_ z_SMt^Z}Y#=3xuggSGeItd;?g`mx4W4;v(e8WNKiDom3923t^m5vK%DztLY|_ZY<{O zKmz_zkB#jmEnI@7#f{M$`CQlP_vU!oss&bN7Co^5&izlDeg$95v+BR`qZ&W3#PEru zLpOUcc2Qlwb!FOVk2E^MkU0N`!x1%kM(xv_Bs_tluns6brZ7p;`NNVY4>T z)w!Q7=Un@J$nTyKVSjJ3aWs_2NI33%lpB4;*ZP-zrFecyMJ|0JUXJK!3zBZb=UbKz z(r!nXZLPms%!3yX^qq~6ck-c;sNeSCC$n{AN&(83ul7E_kSYp8)2@iCho$m&wJ#+b zfu_&A(QaLxkdHJ)4FXSr6t$|g%W+7z+w4Mk;)7~k^(55telC&IXPJ~MTW;G{ zhtGSFx)}H<5IBz;exzb!TwEfn)f3-bpDxnc@~n1SfE)v$0RV7>-U*q;S5rh>VqM{#g|`>m&7;S!~iA>iSDsY z-bZ(oqdse7lbTg;_EdO~ri-xH>$6kxfDRWPNKoW_>5{WC@aQ5?Wpqz|FG_-)`+t1BWn2_m_Xdgx(v5(0i!?~L4pKMLAsHYj-gZfZr=aBU+>p*)E~p_z4ltqdg5=(@~jT_n-!Jn6Csst6JAE`L;2K% z33I{0TgA?g=F&;F46m4Obs;A>YTnps9qpk{2#(0)dMcV*uQz3M)ysH zpIN*hl~4Y{i+UF@m@qQflGIY9UvGa*tZyUpDH}BpW)=k2I!|JCaGG&AV8@8yR6QBY z_-($l%@BFTN%{;x&JAQL#ROn+1dz)LLq9>kPx>)nP5Jg&t?i${9B2y7mu1gJyCZ|- z6+dBnK!+Xo7ybH~qc!-YR476dd7|CM+nU?L7HQog2>L5mY6y)~Zvr82V=vNrxJ%0a z_zaHzJdv=4n88tDoE69ula|xxpCg!>_m^6T!TU1IJK%Wf6OYsw{Tba(=hJgjMRel% zlM_KRz29eM@~`pds-+WQls(j94b#>itA2aCEGEW753%1covaXQl0==}C)h~l$_Ux~ zV;^)sI=kxQdgwqd+un8t4l-c9ujMvxm3DSMiSYG<*ePDxmqXS@;<1~WSoUbW^11;2 z+a}N;0_(OXwvC^#9{)jh--*o<4~RMh<1<((f)Ix%4jL%AAax8(4m{gUg<|X76DWc=5}*&Ftl+YULgUq}{Rck80$JqHbQz+bO38W3Rk! zRNy8-vFag|`A=?K=3@;GE3r}R&EMs=pKNUZf9&oKxG*V28oQ2k%Vt#CD@^~sGuKI) zN_KmY@0Fp&Yg{@+L`+5ug%R1D0@d?_lkarMw<=K^-Bial-pxA5qQV-U#50=j433+P zpYOdrIryk&E(gcVKPonaX_EhS17Klb2Q{DufIx1?8owuaxUr;6ddVRaE2y;)`AH3Z zY$8viogE(db-#r!Ck9R*f?ys9yvE#E2Q`5IuL9q+dQ`;b5(PkK)`!{*bP+ z9&r3z*>Q#`y^ETtv z^c6r~)6t7ZJVyn2Cs&Thxb})x#g1_16z@cx(+>Fh~ic;CUO2)a*e&BgYfS6I?__Mjn8@hH! z*~>xv@HA^ti@^8meO^cV&GQ4T{109>F$FUe3C1L+zCw%<#YeGr3!Fl$$x0}Dj}Kgz zE0v>|+nv40>XfU`xHnG*P}Y9x+<%kBCEMi%F@#H`xX+(IxA!HxHyAt1zp5XK$bM@j zo}w^5Ir(IL-bd-p8oSQP$@%N@U}5*@XxkzcIre#Ihqv{6fm1j4lI|4VRY_Z-7+K(9 zZSPeQ8;jlC((E5kG}un2Ch6rRDk>;D=Vlj zx}ZM%r;J@@P={kkbVPiwIe@0)kQw1&)d`p6Kn*8@D}+y*h}(j~%qW~b6BtSfoiky| zo3{xXFiVoUNTYNh`EjH(cHB0JquGyOczogHVM+LmKQT?|u_fAk{5IlvS(uc20eZ!R=KfN)yxgB%p5|t(=&Kbg&&h9%Z#9XUlf7bq4gzu+ zXyp&xUS~TZa#ZM{{mK!)dGALVb2@DJ=ykm8lbth~DVNEvL>cinS;5C=kSO}{OSTRy zEoa&D^(Q?)!BxjJe2`A2ZuWJwrd(>Sti8HkZW{kGJ-b);9hnr%AqFL4 zYixG#EdxlrEdd@`O>fA}MUT549~`n9H}DakKQEA^ac=syAbw4W9>PQvZ3H! zJAhEx(oCGzht0-WK4*i9Pp$UP1HNWXC|A7GcYjwL;j%4-CPAy!PnkqYMQgbmj*NBm zEkc0t!tPvjBFu=hze0+JNC-P2gCt+(r*$2A3VIKlZlme83em$td&l1N-OB46`YaU! z%om;@rbhpy3QyW{+?1e-0Y3s46$!NX<;OoF{Mk^^YX5D-_{GB&3h{xr6b<+r*kK?^ z%@o8`1>HLJVK1NW*W7I)6UTeqIhl`UgnZUs{KzE1B<(LWeCqM7y=3~r(#8fzmrNG; zKn`?T(LgMPupXD>(T9@T{14t%RUdDdBr~GrX6;X8bHQp7SOfwdE?A2^MU?TA%9l?c z#f^8b66s%XIgcUrJHoS-=%c4mlsFQmcK$5e#L}N^FiZuD1kj!3-a+P!V2S>w^7Rxd zx9bs$;#zqgjfgONZ&>tn-!WG<#CSKTKz*_gJ9uEnv9kTD&yu*+;k?1~yNhYe$&LFi z#8~9OI3}p<)#mz6aLz)1SR7s;^gOf`*@QQNqo-VEC?3wR85_Tp`nd_YjJIQlA(z1| z25Odq`ut${XM~}HS@`9TneC1AjIl{OFZi<^n~QrPX6dA^3{*CvDEr@e!1}&KBTtY0 zt^cwJ5u1**g&fM}gP+)Sgev%j1Ah9DwT&sr$`yH-GX;6WXEhGKQF2ti$wwFG$3?|C zTbERiByUL>NYPJ94i?ac(>geg+A_(?+bI|7cMlHSKKz16hm=?Rhs;3HF%hl?J@K4m z*wxU~F-mM2yFPEdzH1FkiZzROagHm$`paO|ipSVoAI#XmTT&XOIp{O+kG@&rhRMe9 z0rnI;STxUf&_NC0`ov*#IBgt^7Rq>47gMlOr8V?Y3P7X>G^{`lav`_S)VsNbI5$I%?VFd~*YG27OQHaraQ zPk!EyB^qn~J?lO#?KyDpNxr7|-_P3GS#@w?^5egwZG#<0VtQqpsRGh3dPt|38(TM} zbKI4FAu>;EIfIU*`j^k#ue`jxzH63(le1iF{QU8V7@M4|85LGJdOgXrBt+x&xWi+%eDxn?+;XWpw78}Q z1jwutk6EW_n&?BJr9w^t^! zW5Ej#fB_!8**0@L{~2ZsYxnLYYuaOoY_)2}zNDD_jzuM9DuN%oo=zy1)`mH|YD9a_ zCO)EL_H_3$_9m6%U7Zt&a$eLbT>U0B0sZSXnyNu>xD z6ZfR^IC-9JE5D64rWY8CTnY7SY#UW`a}t5qS7;LivpUloG; zP3Lr1A!RwaFq<5ZVoi-pouaTRfSmy8X4_wwpI6{cF907JtV6P-X*;}^&nUCK_TGFi zOlw{ZqT0C5bl56C@+1D51rjlBZ?^ca??(Mcu3DPGN{|p887e|-@<&m?rqgg%5O2-U zZ-%}xTD1aAuy|XORuZ)I1Gw7u8H}xbq%si@4M`D7cRCUBzLHXzf~&Bf%KF6bMiYi| zq_;d;;e~b_Rcxj+w-RzgJEj?xmorJnMexLXnsK4|5$CM<1LB`r@BXqF22}VCzeF%{ z=+>;$*?g<4JOpHZMZkgiU-=tCz05F48Zi84M#@)MwaV6|y}l4JsY+wX4)<-P4XMvX zO*0Y4()Kp7!Bf~s`>YLq(4sGHRks7LJ=c>|t6_ytF6JFs6#(8kp5Gc~Ri)p7!=D&Q zB!u*!pncb120M!&ld4A5?ldB8*1=956!-$*J$!hj|a-=A_4wBx9aeM)52eZ``{N>2w-w(eU zRm<#qtblw!S-QL%M|IoiOX11{N3kiF)VTbe#E8ffB>|Ne{a%zKE0GEH_a1~LvWWTj zkH1zWMjPTzVg~9te4<5sxVoMy9wUPreV~edp8TG3(>~GtwBTik8gZP>wSNES11vV= z2wuVRfsYi={wfO=$S=#9wMfiQ(EoSGF5Mct_4Ni7d8xcU0+n4yB;Hj9)JZEl^O0}B zmDuTaWo1PbG&XN7MqEE^fkk?lMUHRkq>6BiWG;Zq38?B=N7^5}>>qO;X_6t1_inQ% z;^Nn6gA4PGfabvHJfrPn_TU5d@UjjL6^f8O!HMOI3{Gg?u+GppZ47Q}hF;iB-u!$~ z465P1PdWjckf&XF2*$zZ6$o`aU#(i944bdPO2usaT!%0b9x8oE5|MbV5u-^kWq$Mr zIXW~?N>G7&Ox%$FbGwz$-{X@fD;oIXfQA0YR7VeYM|6RSSz${H3GMo{=*{HpPV0J% z$~aGM~j@{boa$~8)4!b;~)*xXqMewrS_QS2!Up;M~oIpfy;Uc1uqJr z;S%F7kwu(rK1t{*I{Un=0T*QJQ@bgQSNXg-S#VmW{WHkaHFYNRQpxOxtKj%nvoVtS8p$z9_x~F z{D|ON+ubNs=4Da1sq5eEKUv>!Rn=+yFWqB$6L8T;%S4Za7FPrq$?il2ctUA^;P7G% zX~l=fplY>dZ~l9be#sX8FD=cI-dfo;dQ+fRvVe5(F(B0ID!R{idB;Cw0M(P@=*VHf zY@tgmmi?az*hA5w(hwSRSpCeWr}vHY5RMX{K`P_7mOLCs`Ys|>KHao(@wOFFA-^Aw z&DA5q;lOwQ<>w8`Eam~lcpKU=c*nto{VXs~lTj#4By$4YIY^3oou!hbQv8Mx{rvKB zO#r*)%Ry%~Yh({C;1L=DpZ@*%y1}|ZK-&JdZz1+pYtZP*e)&4q{dfV#=c~B?c|Oc% zH6(3RWZf(KJk{*~;{ue}tjfu;g|h|6r|O`_Ady#v3>7oB^SUAh8pyniz-p7jgl6~rXmM9?Dle}=Gi=|Y z^$~WfaAf!@%;34#BiO+hTs6;D732qvwr#R4UiQ;1T9SY#5>&=`Hvw`+T+~M7O0d8K ztIg!W&yhWOEl{%@Y)nkhIRK*x*DqfZA@m6So6Z`gAJIbsS&+0-WoQ$qK^;X?oM&Hl zj~fb*s8DUK2YDH}YT*F^&)f}n>xx!Pm)&*byjxo8i)w2dUB(s{_hnzm-w3e%-VJ|^ zXK?O^OY?E2#DL?JGMQ`FJ*@zW9@e$L+?uJ!4iHv`1PIvvy&;MsL=OqgD|~!sV#YP! z^q((J=#D;ER-l&`n`lus84Fnl^kim?|Q<Z@8 zliw%L3lCp$murIMx%xMy@#pY8QLry*4`PBqqRg*s+5n4WP`2rj*A!B@iVG3=i6+FXsubj+ zAi@)EM9-yzt5~BfdG-?jNghHK7#hT+XcHXmwgj-Vva$d!baQjFxHjbFb6Vr)SE50S zAJLe7S4~Og*#dX_Aw!i_EpKhUW8rOAye)B5A{%H7u<&ZuS-->|3P;LEBD=o1eYriw zAWeh3FSocj%%rN{+qtRP6Dk;QNdqRZ_phOYOkYCi^rOi>TzQ40%Y+y^GYMbG0l7c(mF4=}4+ z#nmHQK1C)%AWBVAC|u;)b9c-SC!vU7xc|NBd?+9@=lHE-p3=*{z%W8O5Lm^6kgK_R zyG$1Jh++D*{P!mpC&$Jv)$brCk5cmqT>z82q(MpwJhtfd@n+%pFpx_n)Ots!_a%u_*6CVbjttbXjy9$Mp4h{}kSFrF`%e4|; zg;6pPrnf(f&=Og4e@yyMDDqt~z4(QmWz~qH9~_k=!epE;xeEBB z=;-RcNm2ObHluyFtLhK39R9?}Ce|v~i)!7zyNvp*Z97-lA<9wEj7kZTf$XbpHJD{= zY*-HJAmG^Tl)FUG6O60%mLn@ToH*lg)W)yA6#i@*yADQV_!i_c&d+`4_FRVxGYDjJ z0eK!sV+C=Gpz>uJDA>}ixKX^SKwxZFG^F2?nTbM`EwaLokuA|IEk~e;k=@4c*Gl14}`&QprX5lY##MEQm=Cn?ThjO zSyNoEfV#~>SX@=$|BjU8SWmt&$NQ4Azht4SUc1)S;1|bFJ5;DlgUwsQ*j+*NlD;hN z(qm?M+gZii6CSuC)CY@x*YLVs5h<`i^DBQ@6o2)*kzKAm)E6gtM~8=7b+ZP~{{r?W zBX|~v&B3!+9&WtASExR~K-*I@UvKB-?Y+b!XL5FUX#dp3YRdMzdzOzJRM;_W^X`_@ zsknNPzbdXzimgt#_^*da8Np^vYfIL4SR0x4TTw_2;zn&{Am+F)Z<10tP0q~pf_TEY zS}OwZ-Fk?O{QC8kg;j(3B`}S-JsgKi&HOlQSr-6SJm$k0GKK2E!f_d* zl?W_v0d0XhJ=*3L2=HbuZPT0mQAU~Y?%Qf!inBLZ|>=0p$T6qtJOUSy75Dck55O=bE>3QVQl6gCn}=O zW;RyZ(C1$ot`^M0scSt3wi7~L!#cvl%VtJjcFOZ}zA*@*bJn1XN`B{VMjBisRzj;?n;pFER7flI-2moaftWY7j3{0!wuURR&v2PX?c58Nug$OC5^Qo}>Q{nw0<;|9bh@vlch>hZub9Plkm9(#&5 z;G~!d>aC3}#3kH)6~`MOV>96S;Z7}})#==b1Z%S&UpZ{YL5Vs!9QWf)L%pB1v7$Y{ za&#)_WrBOb<~)AFKPYSDdI*pVoclG4TDh-@+(r`O zD1VZFfZVw20Xt*u44Pty*MKzV2>q660DBVn9xlWz=3EZd#twyprUIGwJI8YQwm}pf zz7@4^QWarTPcwL*2|A3%4)T{BbRbjk-}QFj@mlf)dRu|bLAlaBYU57e9&$|@M$rBr(n zHutw$5?4}GWN#)u(T!>d%VIC+c4Fyl2L(u)})^Lk#^k$v2B9w0u3$S9egC zb+HJqqjq7uCpvOIB27#d(9y$Rm8>AZ(}&$xfx4OS?9n3-Ol3r@M0P2M!yz# zZW#5IHgLz6*=2rtIo6m2TyHKwN(R^?0Kg7?|JbHl*D2(x0sEMViHS9I?AF#+V2zLg zvZ&VuVlyeN0jw(!yDrNOx)o5BCK zuy_sn=d%AHwpX4NyBX}j5>$ohY}J(3^gGU@7#?TU8072e$f_f%Vg>c;%Qvo>1_3ty zNQ-6+9Iu5KJAE+a)W}BPd_$VxIHD9LpYYCmH#%)b?w)^j3~3P8Otb8ipbNvG67x|a z|G$wR>7+9ySy)Kt9r43-cO}1Fj6`^s8k01bRdYsLD9`3I7s#IFM%X!Ye+^|csk^Ff z_*cW&-?}`M=q0PZZz*YrDyn<~H#NxnV5rMV^lb5*kMmIfr|fB!Cy4h<9-_pNTQOkKWVnF&y{1HB zL9;mTBvNR;cNq>tPAp_|&|zsZTwyt|;R2zdQ!> z`*h+a6}j<#F1GCcyQed)ULvik8ppCBKc!%3n3E|hpZx|7D=m!zFYYAxL}02C6%_@5 zDY->uc^Hfg^lA&C62Z^eW_A&GyzXdGK~o*svnG~+GL57Mq@e_sxT>w{|zvua}!IUc6YOy$t2jYM0Jqlgz~hU4Ly|U4lyS zF2EB@-_V{_$QZMAUmtUgbLow`D^H+SITfIn?V&!W^5()nbEJ;@dtZiE@n0^T2X>0t z<+g_z4brBX%bG~bqvT&PY^ocI7jj=>FrJBM(vFQEKTx6xW51rTXYCG+pvJ#BUNv?8 zMf}$19|?_R-j4)M8l>FI!&zQZ7=0=3A*f~n0RhcCoEZp&6RJrT_^UMC#fOIZmUzmf z-uWo!|6m*SM2hEUb`vh{L`ZyNq? zMOcFkyJD_D-k{=`{!6mpxMTzoGg5PT6zSpnyZfp?Oxr?{i z{3b2DqeClnA0I1(7hp7BYju8gl{C1C0J@(;Kakp;FRTK<<2fFo|cN{#v@7 ztak1tdI+$$1xp*im|$T9=+MM&?Sif z*b|a5I!S9vhd1Oz4q_>OhTeAdbx4UNQ|)w}I#!%Hd64`bLAmk$37(4&dE^Jj==g{n zt4omXvAo&b@|XSWI`mg?1DlFmRvzzk3Y;VkR60;((e0{^RZ{!)WM@gx`PgSi(2F<4*t0 zlO!#rwn=E>RP;60N1>8-(KMa=w%PR&hYE)gpoLZU_69k+&|meA<1%n*b857{^tCN` zG=N*gO1DVemr)F~cRZ|+KKheV5fJ|$TC^JdcEnLMyhl;1xF8)w8-f}Qz{TbgRaX_? zfm|>kAS@ouN9oNI;}|s=<_Q2Q%Yx?rwUOX1jV~`h?aslP7@SS!6cdp53oP)nz;T z??Z2R#D$jPE**&$BJI95hZA3y)8V<^kncu`sKVA5MCX8vv%63H!3n|ds%6D#!LFgH z#GGE}o%OeV-?d>%>@bi40lQr~+LEHW8566&J%zRp0RbkMjNIP*DtHuXmg+61vxga6 z%rlzEWsNAwz1-Qsa8U6FnQ_}Lw+9Vx-4FHnZ0CMWe=1szM5aPGyTB zIWRnKgmKGcnJ6Ns!=~+1@bf1C5_MBas_Rseh?LxGk4YI`=KX`Z_VdE`8Y$#ZFE)Jn z0*ti5fAkXyGqEbuQ-A(|k#Zf3yrsg2F#-wOUN&|8q)@?R*Z25%@7bXMayTR(;L;{u z?$3Vyv?(l1inSg`?s&~|=lUT(Ea*gQx`6PXK@LjbL!~gK_;KuJ*h#*8<16gY(+r}C zGb70HIAO0(=hhhYr8Q5VpI6Cvp9jH`%oqud@5y_ddv-B=ZUKJZ!D4^UBI%%FEfo9S0Z)aQsggFncn?vzaXi-vJvibW90YHc&Y{>}7>| z{wx__7-JB>e>*DDHO#*<546!8||6HhlO+bSE`>V^csy z--~{s9v~g8`pwCJ8ytBF?yBENw&+4#mCAO02)ct1vmoQFH{9I=j@9q3{2c>U^23#x zTHj2USbEl~%azJ(NJu7iPI}@Xtw>%@4rLZlj^ibJf&6Ab3P)6$9qRJotvsHCm142@ z#QJpKIf)x7$I<*5Izh8#9nmlkY&X32I}Kv^P^n+23bb(hL-Ci%Gy3)98?5FBFyj@} z)un(pz@&-B zd1Gw-op+;EmUBF6-0OfZ<3b5r!_udAH3~|H(`pz?I6em zlrr{*n^!-8ER%Htj5elCQ+iN$DMcRVZGNsaCAABjbW0JvjZE!P)NPnZgs5G37!{p) zKGfP%yq#b0sm@|dFF^g$ITN9e%=z&YM!P)JB?NMNxp(d*(#GgB_^vNHBR zwi%2O(w#4#4r{ug3!}ciK4^ac?F=k?o{S*?dKds+siXljCPH-fU2NR%8fj3KNkkEY zQjY(kh(0mD{Pa(&+4T)zmQzw)_sgY$wosQ`7xHMy^Bb9eIUFyB8z`p@FhaCu7vN$a zyhAZgY!EH9h-NLgVdUs1jy%63QhSs`5XB+%{m-{k2Ypzww&D^{+ry=`G}zDbB?HJZ zGUaFU)C-n43MTcmm`@}*`&l}uKVK*vl&pj|rn*Qr$^!4}6a}f7>@mcM_*?vUl@_Cv z_JHMG-g>FSU-1Ag`jc#G@rL{+9e;SOZ1uld~}O{wrH zTx~i6?fYB!*~Z-ErepP9@M)MfRO4OuY+x7{QoHC%#3{p|Hf ziMsE&o<%B?g%K{k6_?$!aETGCBOknlZc_u|Z!0Sq=u@;#Fq5H@;_TlkpA4Etfe!o4 z!*$MMIzZY1Y!9mSZMew1lpzM{Y0FR$WqW;CY<5>`|N=)WX{M zzxO;bzgV=aLBMGQqz4_j^j^=uiPM z%9-ytRAGU51aHM$`Y7~(0_NwR+K3gA3&IYGuVfsp$v6hiXb6udEh}8$U=0$n{wGL@ z^0$~pQ>~WO-fK|T!~EVWwaj36q)kla8*kKCE9aHpDR-L#uU*az?_bJqPKy!NySbkQ zp-^os7v~hImpKDw>G42Ml;`@J;znQ07l^itby3q~{M`AiSsbt<-=`k|LGLnzr^!iDQk34{a&mnqNeToFYafb4DV=n z^c(dB#i+6x40VEB1nN($r|V%&z>JML}2 z6~1v1Tz1(^84|m9^*c?2*2@P z2%ieohuEP5$U%2sdNC<8`LI|>Hu6jo$PE3`zuUQ3sp9<9?JIvf@^^PcC3^*y4j8pp ze8|oJ9~U6{_~t^d+4HS`!hmD;`mqOnXI2D~Z=KgG{n)OS8f_wr8l-^PPGe1(d|T`n z+A~w#9Q+PN!}VMgVNq{iv3C7^bag$xozZM~bQm`G1XRap>y!YAuijWeYHSt{T{z-O z3qL->d~d%XR=^O;%El%TEBr;Vj|(|`2kO@EuU1BHF5uv{*kdKUO6}1bT-!bo$musv z|GaP~NWQgdnVf7qwkq(=RQpbm_FbJ$;ebfl2MHj-zt6h4e8YcN})=N@82 z>lS5YFg0)Dr4}oKbcwH@fy5@XW35drFSg4;Sg5h4G)i@UzGuFOaf>(#R#hCvd|W!C z={LR@-9`Pz*Q%u3`}S6_x4J)#@sU4$Bfu5;mgxSw zZ>0Lcn=6bz7CfK3D4eWSB(4{yVGTV|x>U%CHH&q_vI9z!W`iZ+|71iPepzf-IHvjs zZTiFT#2ke&w&RvJl)869R?#^hgxzf&1#HZDy5sYwpSLBjk)f^YP>W4mCisfHl3_Yp z**T%Vp+FB^H#24>xf3J3D2Pq|4{#+`jk>#|?Ut5&jsj2`_wLR-Z^%}R?qezR?wUqV zE?q`)OAA9pcX@J+D%lUz!3cA$j)qXG$H>e1YprH&<`>-EsLfjVNtp$`=>Nkcww z2`*Db<{tkgfAJpYbaB6nQfWyVO0Pq~hlAPn-e=3Mzu(v%92V)790$euMi*&CikA9} zoL@H%7@J2#A3RchuLqw#wARhgTk@oVO0xlcAt50>=dr%FCsosvvHc~D*|RT4%gXfl ztBvcifMMl$wd7u7`-l7C!tgN#$LH_!WNWyKK>Q`cXe(e~O47{K*H2Vi5y&rWb+(DI zAMCEat}#Dxc6s|+5WC^0q3Z2a3GD7>HYrZ_`ab!MYq{YlT?CT<56#_$%7D&6jt@*k z>0mVCfSN*$k7MikOk%q(u0^Ou%&)C&SnhwlOviL#ep#N*6%=UfXw2RhHeuyw5Vi9! zQ@h5)&|iG`mwU0&E2RVty4TMG5F7^0o2-q#R@63}nQ->QOFy<%*^v#%Q5D{exKF^G z83tO8wy1=J-@vYiVQ0e*Tb(ai{!{y2)5klj*9E5jVbG}j>*a6j0On6%tfp5=I{W>3 zNH11AMDk7$e>EnxNBm`!4{y5JkM%JN5?izv@|vZv3N5pGyR(5J#?*qzwAdii1)n!b ztL+46^)C?TrU))${-fhD2Y>8!=4U(lPH}fv+!D=e!w^I}n_0;wOq*Hf&d8UnZ!yci zPkVdFm2}tn`rZ}PrPNiC@DHVROs8XRV__cqh>Y;MY^m{KuGRHNj;Kelpd(Z6?)(jU zoilVU8E{mt+m}B)yzfZPKCs!yoVA5wXD32{$z7qhg&``c@zt<1_$GTw__WfO1`Y2 zGat*X=|Dly_v$Cui<>QePjVF4C*rBlEVXCm%KD;`$G6d#WBwaO=?UvKTK#^$Q}fMT?~HW@D#dm?5ju^zf?=$b%{u z*VfCi&x#oe=bqsWU)8qsk~Sz(<3w*$gp5a)a$<*;A+9Y^Jt<`O5K4PlaI!ZjL2tmldT7k+=DN85?Lf;7n7BF;eQ;I!aj{+hrx$S}&6PJ|Ko|-_c)CkW23L?)l zhd-^EVcSEw4qHmGRyO&BnAMA%0-o!#ezw|RMi|*U+`_sRu>ows5LCOQWL5bCW?!EozfKC-bDMoH^E{gJ%J91BM#pS42sjrcu}DrifK=NFpp zhTfui?i*z=K3T#&jomcu5PC3^n-^Q* zmuNOsYpk6+r|W|E_fQ~Bf>2A3*;o+!Dnv4w47Vc#Hzfl*gHx}=Lf6echm?rv-rQwoAL`oo(g+P}^bz(1sm>JrS`D;M5rKA)dC1^wD*`6bnc zKI7SprG4!^y-X(29~m>SQguU2Eq_Kw8!zqjud{a??XhdHJJ1Jpc?HErd8c!y2qK`i z5HrDSwSzNGH$6JA_eyv|>tPR_sO;5Ujy?t+BAXCu>b)SAf3Qq(UFH6{LsMT?sixGz zX@}v~0&DT*narJr_Gx-&BHa^> zAsS-PqN6i6J7t*} z6)C-cu8KaJ+$i`{)3hD&I`krXT((KwcpAW2*Oh*XvY|{o)Vn;?A9Dub47Bo2_Ogc1e872BitfA*9CgY-}+qo0I6U7Ojm$Qf*6;7cbPfF#%ajwZK&4fN>vLVDB;?ed`&CYt z(vR#cgdQ$UL&F2~_3Ms-pN*e+cKtna76d5lwFx6o7QRYB9}Yn*P8swmtmmk;XoZHW z&hyFi<*F8<>7*!CpPUY+&;CJ6$LxUwKV*~v2GuCf?psWipBjt(Au!|PZLMhQ;h<4P zFYzRZ(QLmD&?I3Y?R-bWn`D0Zz@D-;Su(X;D}xz{|5b6nofNfln6uK_h2cOP4-?;= zTug)YG{q##ENAj1V7Zc5(TZf&4GA3K4)h(jE5W~SR6)MtV z;2s#ao@iRmkUg3bV)gfHb=q<79yY_%xIagdA#)J|?CWa9U)*Nqr!kl{0I~s~$Q~2C!RkdX z!k9dHqhozjZOtX2*|VkZzZy{MdrT4lPl`Vl+&jRAExbGg(mg=`tEG$$7 zWm8smDj1cGQQ+*;(MtxTPtOL4t87=fiB_Gmbs?sDNI~W9QCb^njzfl;h^?ig7FAJMw_ysZdfZ%ZZJJ()`Pnsg9^H!BjNPmnV>E->5qau!IADf=`T`LK zsY;Do%-q@weY0? z1aUj7)m%uh`f$*FFoDY7@|MF+NAlBgrqyKw+R%4ZvO7AdGWB{}xrK_?O9ZM|MiXtIEbAZ&w2a#YJImZ+47l0hDp zRQhpdO5{;|d{If_U~(PY3_{FP%b0kF4Q-Au+?YY%jB$}NY%>i$a!^yo;mDeIn;@Yh zOU4HMOYO7GBpEZz1;3>z`L732+X3*uOm$x1-{`dp(y%M z{y=y;C7S=LkbC?u`YZ9)fDps^4N86lBCox5v9U#rhX8!b^7S3kknCJFlJypL zDN@{DKhr%})r-&7KR| z7AM0iccJSJZRsOh<`dT<4ZzWqILnLKVkk?P*7vxI7>LxDuiBt3Ku>DP6KRzpa=nrC zygw?g37F#}4BlXY4n9F5>g;_jH@BYdj9qaff?=SiC73Ka`NYxMebzx;YIC8r ztjk)>hWoclXE@NVgIYhe=cjebc9-!8JGALn^}iIWQw7d`fN<-cdHUhUCE*|mlxdh4 z)cvl81lL+sixIBfD1}zk)f%NUei;1B&Pu375OrcgEiq89O^kk0AMmV`w*o#`qaDiz z^(<=5TIn^>OBp`3=IkHjJuy9*DMO<2|8{!4U9+2JD&V^$WDqT@O%THkx! z%tX8OPvlQhL4#+We7)<0c9}`GnP-X&lo%l|FpR^x zU~M{uNYdnCGO0bEQ+tT<(Ljr(ItAMUPZ0`c(6(}t1>x?SBAbL>8xbNSde%+VPQtNr+5l zGO-7o$iFAF4JOJHVPRH^k(jx0h9lp(iH&}l+!%NC$jO^%#_Hnq@Gb1*nr2pg5#;)u zBb||=NFMaq&g7)mRe&4=2=a=oHsf+4tF6dQ4Cpc=yG%GsuV2-~A|;^W;F;7yee=Vg zDc9OmFV#^@;ccG^?=xIpcsfL~&}=i@NQ8TM5_{yldH?_Lbe2JJbm6upXprC<+})kv z?jGFT-QC>@?hYSLaGT)n4grD%cW02(Ik(RJHTEP84FXNnpfm<&BO8lNiGf72uW+e!8st;UeeF3+yP9`UiL^D?j2 zRcWbTM~jM(GS_AHbdOfSBf1;nh~L+j$p`@X1c=fA4!HO&Ah7RH8*9Z#CNGX^&#bRG z@Xhk2oBn8dFkXw{ZynZiilC$onts5J6S0_x@9{Hn7&0Lo8OCszrVaUMCUV3pe(gO6 z-q=cL_-8!CLqll8fG@p+TcfeCq7iCfO{?doo)PT$;PeKo_aPSI^hUe-%DIOx>4Bf0 z=K5v|3?fsV-`{9TlY_a76<9QO!y|+$;83((`X_umyi{(Yg%Zb+)4 z$wjlZ_<*rsuNUhFaH*()BFf1E)=;~~(SHKo{Rk1_ueE}AjvO`G@q~f;_bWI6AwK@Q z!}X0O9_r7suHyk9xfZpx{d2y$0!9;O0HO!^kA)AU@H&7^(*Mgm3EmZw3>Fz1cWv^zhl0WmHqt zw_3pt*l>#ROtyqWw(Z{{0SYp8mRXl|(-H@~M2R1N#vYV_fSG)1v$2yU|Fm%Yq&|A$ z?VMfuHXzSA#;*pj5LxD7+ItY>Bf;_tq3`qoa12g`PN+}sy+1KFTA#hyWJ+}o0s%|` z*5{;VdoFkPK6q*)Tv+COFS4`|qP1N={ zyy&9y)B44x*_Y7Dy#_AK-BU(J+=#v|hS-_11>orf9Jim^fVV<~XlRR)4aHSi8bSd* z_Sn)oCt;*vm}s|IwmWoZoKVixvV@tHi6O?6C=+5|P57ta)p>fmqtEEqbs5ho-pQ^e zDEa=?zR$VG!paSH5r@~dpD9)QNpBi zcsfzZ@4gZU{&_1AY#)4Bd2#xGsO1y;{pFLP8r#X zEFb&YVQ<5Z*dLsF0Y9V+c^=%21kP*Ncrf>G4vej4tjMnX=BGUcTIYsjveZvHqW}P( zrQL*g0-qva9nmz(E_5P2F}bp@xUX3w==vm{!B>dk#M*eRI<$oknF?zuS<#a%iv=xw zDKvPcMAx(_aWgV8Ipkf}w{k8$67kYt(@=eQj*5gR{sZor#}5~uyT%iEAEeo&*-Sw- z=`pF*saGz}>;9O);&NQ;2XNqz*8f0udtwU}DB$2VljK5PEhDheyv+I8=^lvKSV zS~~2p_gKLpEOL)$UzV~d98w()h5Vdt>V|~hAh$& z$y0UIoyJKV3jGOt<%<8wvF`K8H`)V5kJNe2u%4UlIDm^D@Id7N2r>aoSKf8|98nVC zX=lCutsGdX&)*v(QHO!ZhATmF8bXh7xR1$_GXYt-j9gj2!;Bynxe0`v z6vuG8h`y8#!3jLNFamhTijtDh>iXVnz{i}3%|_sB5T7$$OW1j^d6SmTsG1fjW+zsTb3vf+@}!r@AQUg+{K$wNyK|gFXxjH zZVzV;0nVG*>2mFF_Z590^5Cz^X6@_s81D)4Qj4(;mYWG~tv7Jo;$vt^2L=a#h4o(w zSb!V7?5-2tSPoP$DCk2t>MKV~Tz?gwF&9pp<@}UcNnDICVQ|#zI|2hvn9^!^v}6>F zDtAvlas(y=_e@WBPQzOr>I)d?#3a`_=4nBc(Q?nYaroCG9< zSTM=d_c8$(R1ZB86)LT9~l7>o9BA7e}a@KDOrpc7gDGhN9Xn-@bK{%Dl2AnOZmI!Xeh1T6$6;(<^=9dUOjymC9;e1?dsJ3s?|=HfAz~s>BtM(BjG5Za)eu5sn(4G zxs-`6ag2S1jUc0fE5I0RnjUBs%N+ZVN)Ry?^Bnhatem}5CE2i7$u0vpO3_foLQ?{yh%U1OY#$ZbSx1+HJ77 z!$hGK1=56=^~Ym)U7y@+>C^056RcK>gW{NRk(T3SD!?{o#DFI+^X6ft>%Hu9%S~_V zGd$y{_n~`W601)7cWP+S+w9$-Q2AagCmrP*{6Y7Gcr2t zgn?HO1{%iHh9`}Qu;~spazhOuK$4cs!F9zU6txv@KKQBN;>tiuUfCv9LWE+BK zLaK6CLZCT`w12qrGr_H4=yS_q1CjyZtG24DH)0fuB_R>QaBR}It(A*lmaTUpAFva} zUr+v3<8IUL+MLGzorDeF536;DZmGd9lx9y?J0+~cdXqfrZXBG>_u)818u-*R`BRI_ z%VNEO9+rp3k9{NiLx4wUt^Jx2I@I@bByokRHEC)`ydINM)t!JQ(yVwx!tkox>vXxE zApXKxA4gl)VA*f_QV()R>+ALOf}Z0M*h}|Hb;SxD1=T8~cetW46~}SxH-btWTG&`A zkZhG3-N8+Cm?)qXK|#2eRywS-hW?P%RA%VSk={2TOD@BV%}}MwlVW?OC7>4W@Z&6- zKM*h3?q_+S$-ptu{*YmNhA&i>y0T>Z2s76gC%NJe{xtzEotY!r;Nu3hW+_&aqZaF9 zj0edL@+o3Y@DWy`#tMAbG}8Oa2aL>tyuvmpZ^~t^ybm&iI`8RGy?TRnN@DPI~O60pSC*IwvL=LG}ms$X$Q#xy1)SV1z zfNn_U+KgIMP_(xWLaqwLJ3^-aWTPyvRjO7w`7=bQ{0u!C06=lX-F3=N z;JS_F;?#uED+HadFS!xo!=qaZzO%ly_<2jhM>m3Em;Q_qQMGRPFK^`Mr`eoyR?Q9t zqds$|+OaFx_^DoAFCFuUt?YD=Y{lo}pp6f( z(uhGrvAze~q=$It&8$8v6Xy0 zc}r@2%RoiIc05Eph?GvDOk6cAz4Ho5(q zcK5(!dN|DtxHqvF^xEMUIP{rqqMK&TN-~s}@>jD<7bu#jzPsy+URj%XCCR5Bt~>mP zLrM~!`GYHrV2P8u8`_!Y6+QhPed(lT-9JI@$ya8n@3QvCMBd=uhYU?~@$v@{KCTY- z=20Xb+HK+B1`&JJO7eqb8=q)p%i2(*Uxz6bGF(&ab47OK-Nd8Zo!`QRDBTO`YTZ>meKkLYE`-{Z`I9dY^j zKYVK^+e#1Sj{h@zcaI@DKfa(0E31cOhG!`4pa*_iN&b+nx0o)sFMfv%CeF6nw0ZC^f#Ebjlt zfFNfoqJfD~=^sii0Qy-u7<>2qg?3vi)ruFlaYxyy0s5u?8K*JM(YU7T)8W&KWGTvo zR_k^)z5xe1Q|Tzr86!tPC1m7A#xt4S8J4rrc2xX8a1E_vZAK9b0pzOO*~iCOp0}T# zdC$l846mz&Tn?3er`j@P#uQ`^4yrhL5Mn`zClA znrcndo%OH~J37b^;p%4P^m$dQoYFBnOYj@(t$gq8zC4>uDwp-)Eg(ouYUjW4vLD_) zGwlWE)<(=3e3X27_Ny)tYJK24*V1`@B|@>auQ_vk&f}gHB#ahdC`i>sxY5R^{E-cU zl8?i2oSGVH-2(AR!jY3%=m8>)G^W~!vNG{)Z3wV4tvKNwan9tl#g-y;XN$!tK>GC$ z12e9f?y_NjNt*1H3Lt$C31^1mW1Tj6X_gfD{4uH){b^dFMRzECe0pVZ%V{tbVVigq z;i?v=!ggdK^gKPA)`q;c(8_#>Nr^u28drs6vA5M|F{cZapHPjhOgHGGhu-7t>&b{f ziFI{w@F5nzs0xH&%MgGf9Ma_WYI&DKmrLr5Z#gW#KW$w6yD}kN(SbJ!vFXkfMCwgre*nOB=5(IXD<- zG3o^bsOLBRv5i;786L1Ru58&rSp%FZairHf0PfL*+<{6f3jf z>-$JuAcVM*2ZtFo5-7(1PXEU}ge3T~EoCM!gk%-|s-folph?><4~P=!jZGUVjR=D; z*!@Q#xddAtjck(qhB>3!F@KA_NvndnrDq z2yo^h4H1lQzRKjv8H>+UF=_gYWSaHXK*e}7-}%326)9Ii_-yE!0k zDl%%F_!dKR{}iMh&NSd_BKRWEHlHdTIm323d&@k+Av?(0^Su<6Jp7Y?0a6v!h#Z1& zXRT_~99f)0r0RcUq&*kF(j*1j#C$DpOaA?_Q8FUQNO5U}*5_^qS|unJ-^Rc17ebXZ zIhWlvF1+E+(E6-3q~_SX|<7#!ntWW_H)5xk7J;=awTW`saw* zuK59n>w%}~3Cb^h z!NEl&S9B#4Vgz~p^a1tD8B;`=qLDodWAs2!R%`$uo-!9LzSrn^1AUA<1ip5`8HQWo z7Z+kOWf#C72Nz7$*##2Er2=cui4m);ONG=?B|jB39sL1MwO@3>hrrXcKu)X&v*beX zthQ2pk0nz;orD&qjjh{IBAw=zVGM{BEs~c1mY`-lXE13$XBodGCC&}SE=_ewn#v2c zJu~~;kGRg4(=oUB0nCG~ap!qFLj-th3j;GO^nr+=p3yW6jlq8*(W zB3jaXO$x1_YpKA%ot2TXfDBt#4ELfB%h6zlce|&&TQK0mcL@0#fr#7$@l`jX7U&%g zSj80Rr(=gGWEr~h{O@pIzcP^^Syr4oImvS#j~Ek!L%^^{|kNKBqCK}++}^T9iEr(Efz zSatt)u$n^_=Fld8!Bn5zA5ph(r#DwXI8rtGLHbyXNB89geLRNqg`exSSdBuIrHMs(onnK2LPK6)F$R&zUAGB1WA?30Q`#1kSw55Y>@3*2ve^?HthXJ*{8%7V7{IvyqC#&nL zb^Y>7DkE0Al_d!#Lou;hKP_Npgg|jJsZ>Ch?qC48CszFg)#G)Kz1#o1>xt=OcrLIv z)y;<$V#Oe5@8kVabXpMX^e?Iv;C&=(aKGo~{+^It#TW#0bR~8R5jEoYsZ*8+?L!VX zKj!c}UN!L7<0ExeH}u4M&?T5>+VJY_Td;`%Y}rj%ksPj%mPV2I`@J^fp^Igbv|hM5 zeR1_oa#3FT~vgI9~z+rdGG=>#$O;edf2Za#$ z^PmMnc&gK;m^2kL^i9|ftQ{B_Ro_aNy?42N)U{v01(5~!950Jq>4Jvt%6uDbrfes3 zmj+8^)Pkv8Iuw8`Qcw)V0Gql}a*%$ws#3`!>*@nOMd}PBS2(16KGIK%T9Rb11ifi0 zBzp#1-gHi=%M<_?*z%Q-;WHpQXzSz4OPy!Yw&}5l1A3AOPx|z$KfD{~ zD3b&J`;Ega{ER!H&zDhtplmN&4`*J-AcjcwXx98F;CN4!0Dd4z?*bd*>sLVyNB<& zm->w;(SfE5w{RY#7@WVXw11^P4PrW%&XOeNeC!)!`2X0mh|yG~VTGX)!13{OCsb`` z1JjTWad^u|C@mzB$q;T}4~u>d=d&3wO0R{|25RP;(oaijTub_I#R+X0hnnjwI*8JQ z{cK6cCn#)`kVbTP>CQA-Oqa&(yXrzc-j4jOEsegPe_55SL}iGpCuVd*@=EkpM8w~w zg{SD!j3^FC{vrh*jSw0Tdg{9olQ z|0PfFQ0gb~g&C`?2K2wvFeINz19sQ(RAx-cLB&+j9&u z52>uP@mx{0N_Xrq5tu07Fpw=dLw}?2Fg_eH>At$lnnwpBe?yd(MEX;tF{QI;R zsmu(SGd_BRHv>Hcn=ndxnb_*Da)k!J=inOMM-@L1S{c_TjK-Syr*{DwtSE}JG-$5^ zrzZCFd(R&yh)RpIP6Dl)zsxi2A()I31^&!Q0o80g?3RL~!||6x&g*jLd9qYLGwmMa zS(~tD#n_$^?ZB)A)Cz(hz$%qf{x4PQ%o(`(gCoc9v!UDNQR{2}wrGZ*92x!fK5X=x zCeY}8Wvge@mj&P(L%##wyKkR1F9W2gQfVJ_y|{m9ma1ayq!*|7oZcHpB&7hiEI|@k zWLBVP!ELwU?9$Ts*&0fd&%KS{Qy<228>g+;Wx>Z}=ugYr;gcl-7I&MqSZX9Ogm6(I zB{H?7Sqd-b%?IzCOjCMzZ}yKc@4Ol*1Jj5CwjQ*7Z^C)GL(aK93Nc*?Z#HQq4E=;& z$&0i~Jq!z`FSPQy=S!w^m$iSZ(3h}}kBjP;_AFy~-4|7) z&ZEenb!?HmfAZcRWt`I3j@Ur=3-3!VUfb|~wxKnp0TzQXXN`>Qf~|S`efEy9*#`xy znydT`3?-dmxYNjcCF_0~D}nk%A88k75{}e$<_S&=0&W^VKFbqdby^|e1ZkDzo_2GO zagEOo(tQ^1*AOv(|9HWDT*m~6M#@|Bqs#uvZ3dQxz9B7H^*SNP%c8{-+?>i-JoiOb z(b@gl(@wxw+0QcQu7C5~10bSc8o32DX4G?Yo?*B5B@?nciNAdL0$@8l)~)}|)H(oa zEAr;$ZMT+_)_qA?DW57OnlTQ8Eu*YG88+B(_nMwI!t7)M>XQU(e^V!X$T80}zIp$5 zbT{K8jEL}*wqPnsLjFsAo@q6$WgYZr{HT!+lntgN#R}fLS+S1e@|-LGNOd}ZY)Sh= zwphKqz`O&`MpBHJUgx*cpu5uWEjF+xL)i$(@#~G(I^(nhU(($39pCW^6KpG?MhHH? zQa7AS0l-3zTsOp=&cKN~p}@p0(FUG*>}Nxl(+OfY4@bM-eRrET(8H2 zu_9d>EZEdBquR?shn2pDB7{`m-NYRqj{}vMF??h=dMKo<5@8Ml9X#ndD~x&;vG@9A z!$1M`EXuq`8ucz7blS;(^$Uu?=Lm+t%V_iqH;v%?HI!D*OOKm}0gRQXKh)U%jC6$~ z%og;^sKw@k*Q)`+ArT4i1>!|c1kbN{gL|h9HRf-hEoIc@`gN!v3~x(_8~*^ouS|AJ z#UX-#zw8A&K;*nondZk3t$qUXHDwQWX%gv5&}6kyg!Oy@C#fU)+&rQ%aqP$*fD8Ne zH_!7=x~`o@jaOuz$BQ8{O2+KM+L(du%FUlgP@=iEIq3i<#^kJ;YAJhajxD5Ngx36_ znHPh%Vymv0A$gC6{HOjfUXMnt8bdDze-K_kl@7kynrhAL9@z%j5N+yf#;M$NMJ_k5 z;(U&H46VzgnNaZyg;?B}b80^BU%k_&d)_QWiCAa%I7Po>Mi^^BA?He73m1dg(4CR8eDlW0wF@OMKV&F zS7@!aCY|{<)%3i&c)SmDYZ=;1+*vO`IO%^E33zBxn4#oR4A!z^?5)4*rft7SZolwT zt?H7y&HZFB;4Tz*Inq!Azkf@O7J(r{VL+1Cn>IaN&uTt?sQe#dkV1}N^r_&Ct|Q~# zF~D?RHAVSz-X`|`q8T}s%1oWsiL#>bBP>QJWg<_W$&)2|@C{l7cEw(-3c7Js47!i$ z={vkyIsb!HUd6W%QmK%yd$E10$w@&e@d!W z$s-DAV)f+Sd1pCxCEbPybmbW-m*4|;%esSew2gkmDKEQQuMj=*&~W#!c8p6Vq=K`Y ze>-d-V=)!)+${uNI&J!cWunBxb^i0{P8axId+tIIDe89QQrcqKf~wP*Un!^_y0&b5 z-sP?DbjZJ+Q^2_VEhPHahV`YVpWJ6W6U0X4J(b-@SO+SwZBt%Vy} z;uiwJz{HUhG>`pjxlbD5iffz zdVXbe)*d9n@PH%YWDzw)G;oVtQhloOLr00BH3S}` zH}(?D!SP!fSJ7;<6RzQW1$f^M?kUZ!dLf2G*64Mh^FRbGFDGd+%oIx?uaoc-1xArb zCr!Q6ubsgJMVj|W(z$cWn#-AXCD}dT)1=YHmniTD01uq*kVP&TOU8C<^q!+7VU_l$ zw@d4}Qs?9FCvxKF&xwLBR=n2D+O5s|aAc>;fwps^Z37fzB^QZ9CRl@SgV7jSKx=D7 zK>%MQfy-xboxZNaX^nP+gFbgEl|X+u&U-TW5>#*xv=X~lYs|5Fv*7@FaAh`aWX95! zimZ)+JLu$smZakPjN;6!kAXY!Sr)MEU+&~RN;FPM9lhk@I9jVrA|@60Y?I)-PL{(t z0{S=Ybkm5!g)Q>G{^iv2>RCSM_6oG%z%rn%BBa>wA#@A#FsIQ7JhrU2IfnHl!k>3`Zsg`%{pR z2JP6$)G8wPD+1q9VSH=TD8%ghI^BAvlrBAa{^xE{q(aau15UqOCd1ToI2LKQ?-EcfnppLLBJ6+1-8cdH@|HdnbsZU2N; zdv)>^IB*Y|`ER4Gu9oG5*PaH>b>-N`uwe^)+C`NSni3`p;NvqXl34D~>EU${=8Qmn z)CZ^HO=3KaJAd7&$p(w_?hGJTQsme}b3uBO4BpC$Z{>fQ>_{DK0{^+^NMfYSX@v;i zd&Qg33A^MjR7X03hUBl8ZqiwM-_edLt8MtFj@UbI z&Z9%)%hM?g=W^xUDf?mMpFQEPw=U5x&`dtos2*}~?ZQ~pQGN5Dx&sH^3PX6ArVTMq znDF@|Mlj7*MCA^Ck9Y{uKdUSbXFX=7olK%25Pyw{MZ`H<;D248u(!dkUt0ZZ;@rq8vto8 zzew7t)3WzdS75?mwT$YD(r_zx+PdW@K@945?kZ1xkr_NvjQWP?`w;V?EB@Hw;Y(KE z)`1_i#NzI5PJ{j7H84Qsiv%iW?epF>@LJtQi%a$W4?L}BZh3aXFuWetEGNdA+&fY*GoH!!z13=1#(dPE=SE61 z3wv0Af=K`u2y88j0355!B~2U#99|HF-y5)*OdJAVqsFu63NEOq#}-&C`fyZW5C^x%oOMnN(6*k ziV^ATJreSX2($#Ff)gE4>H1)U(d*bz! z>;=)ZY*}0QszLaUm6Fq$%#2V&=i$kL(aEK&T0SEG4Y}CYi0Uvqj6Jj^sPaJTJN(E9 zqO}t52}3bQlH`+5=V#imB9o1({3}3uI$K~%YFGlDQ#80&C;2sg{3Uw@hWT7x3jE(V zmz!OFMMM~_os~)%)tqtE7J_RhaGCfFm2y$R?r-t8}AGfZ9H=&+`Ma%|DqfVUNY z;s0M)zcp~~Tgl$FatnD2A8mW~n|Rr{&FNCa=z**1n3f8bonP4QqvoLy?nxc+=}{&_ zi-pc@g^fhrxS++zwTJ_=+^LL1u|bPair`m51O^r~uu`;AsC5DrcpmN^Y4scKZTdjz z5X@v=*EiR{zenfGBJl(s;0IbN4`BM=M7w+V(F3LbJicH-n+wfzAivWJZdnsG8jdJG z(su9hzdk;df|6hXo&zMC<|DcZ>*e)GkVto)hc=6;WCj4^Pu$Bk3oS^ z^SvqjEWazW{D2c{gJZ97DNX+Iw4WA@FH_v!P7iil{*|*wG5_ZU*iV)~{Mbv_D@bQB zzWLo@2708Zeh3|+|4HyB?kU8!(R8!=P@W z@+c4rByuPyYZls($a#x^lG(L&&%~6;5$#{!jh^onas?+ugMNsJb7PpH*WU;9B}#Qa zky&Q&JG#AP&vLs)jE1ee1j^*+kVcjskqjXSw5A-b_@C;EyQRs0RJ8xYGfpfQ75d;;J+=iuK5htq`#Lo`n8(5B!}E9v$Q8d z2598{O|v7sVrif&=Pg#njF4iMd>*p<6b~I-bVwQ_U#0ObeW|oSUlJ!^5d7_-;vCcJ z(yF2s(^UrJg`C#r$YbS^9>1sx(>{gSFZ3+$E>6>ZmxmZz(L*J z;@RbL+(}lIU~UT*z|K!u0N^~V8K|rka=MZ5j$X5zeRr3OeXY#5#gEh0Q``IZImm>w zddVNCXq-%cS0!p~;j>=jg_(N0E%nz@~K@jmWnWP7Fp2-O`dGy_4}RtkqZ> z*)492QR5Pypg>k~kge;P@n%iBGNp^zev5W1!hdTx552&T|QpaK)zz*`(4Su2`B%bzgF z7lSS@2}vblB?vw>+x%&H%?_1KQl zJrH|`>Q@vaxE*)eEc2kX7^V-id`bsA6{i#hSpXtj!@ACOiM{#vrav6dN585*6q(84XGl%UxiJ_MRlTK7w zYr^ZgqL`~)K5hieQ^g0Tz72#K)Tbq=vqr2ub$*Dyk`0*2c= zk>clp&oWsE-ndN4sRc-3S3gEAg(72*u17>3O~SBxrQ^{1;9YvuR$)i2Aj3FAzENyC z?*l`}|L@gCW)=K7EG`h%Sll=AU?;Mx2G8Rp2Qn^!YfYXJ^Ze&DX6I>Xb zpWOP3O{S#ruD@c$oS~&kwS<8nk`D4qT4D7NhBe7f(N`NZ z!r^(Hgz>aFlrm+t^ZMHV=ro!ah-f|HI9{SrbOyC%CBgGatuSw(Tgi2>2~8AckX5K! zP=<%(W=9}v#qdR1tZ3a~@NyxN7^jxj&*YE}Ln&7Q$Jm+a#-Lil<%)#H#6IZR z9gy`DpV9tG_v;r9o%{h6Q2YrP7>g$OWL5!dj8vSG6E;c+k9s9(K+d<@`zq(|Y+GzE zEqYP@YBhV%5XYr5%Z{INuJCu;Yd;yknm^7W@*jbiMg3T=p4 zkZ)Zq*c<0iH1g^k^^zmesV!+AoT|l(_<>u{kAuLof>XPbS}TK4z#vRM`2JJe&G%RR zudb23h*L+BRzAtgLtks}pW#*ZjP05Mp<7gurEh2k-RFMq`ycVACO9r<@7qN`;s3sw zeJwB|Y}3VPw5tyJy-Y#-<8$9q%wh|zpI-xMCc&TH4a!W^LIYLkTc|}zi3YMD*sJNQ z&wrsQgitDMiwKT|D&SoyQ&{0NiOwro-=Hx+&PFO?vtXGEbTqN_PRt8en7G6cDA7DCJeaN#oUcI75I9YsTBi zzug+X9;-WD+h)Kwh;P$bP?S4nDr0KW8TKjn^JoulV%cLacUlv(HZFlV#UozB!pyWc zWfrA|xi+LmZB!@BjspWu3{H_I&H_n=#yX)WFe+rTM*aQDj5AXWD(l|{7&czJYrWR3 z(4bz>okBm~sw*@{UG=X1Qyhk^bPLHg<|Xk-jU@_3pgjy>y2Li}hQxQuGlrE%+k(SH zZ#x^~c0NbB+u>!}RtXBV7&mukwsK596Gv~CsE|@hA(Tfob{zcr1DccSe1oF=SS~o7 zncy4#`hPm~8m-umuuW3MX;R{upC>)lnNCyCXO{MM+f+}w!e^bh0o95A)e3)Lp*tY_ zlwl;2XovFJWSx&5nYCTFD+_;0>*#vwLRY|4dLx{Q#9sYMdV1UqbBug?dP;n$JVpSG zj36++5*5sT=?i7S4?(B6g2#Svw9l<3T>dZ?*c9QmH832gA+)$YebgVS`lUYx=ViSq z^z%>XHmUa|dik^9?N)D`^=Z1gma1+4EX60vPiNdO`-+o0z`Af(L15n78Sz`piDALo z^p-WzBA z3?NYTpQlFS@h^qfk^QmX$umE%%X6%3>|r!Y{K9|E_j&izrqs^pupsvHlI{q}hIO2f z^GzuW7~`VvL)s}(gq1t;yHFoWZ|758w?U78U!B<~bx=$eB2#*KD9#8z&<#r!OYx+P z7SQn18&O9Rx`Kx%MK(5-UPayYd|sVdOAZM|hAAtG))zpjQb+iwo}Jcz-~sK1q#b(7 zA{rC?_^PEbWY3(ewKBF@ZrZUhY}>(1^lyzEj&%X4#Dve}I(#}_PkSgC(U0tV&Y1#T z?RDZzalz6TG|pm?Stm{fNkH(!s(Odbr|WM(3%R?Cja2L{L3?gdj! z>j!#aM3h-C*~0R|973~xiam7cFkyJh8(5~3Zq%-1BT1CcWI@Jvujtvj)NmHxB#b_@ z-e!;59`MKoi^b5h?PnerH8MuwEwOBUt|~I(3G*ck9cVtPK9Jb(^G+bcnRJnq9j!bF z_iH~TAMczC%ii`hSRn`7T=ZSXWp}eu05`SgbjkS-lSSIWl2#gr=I>uvTgt+bX=g{p zclq>|GBG(7y|HNy7BW{P+QIak+kBa*0$*p;WeVeAVbRS`w$aE#chC#T@lG6lf2H4< ze6=3sO*k2m4ueQDk84FOJjGWOF!e?r(eVY2-Fne@D1uKU7}Sbp+y0M?sg9;-fLV(J zz)b#W7(m8fIIl4^Q(+v8ZmWpQxXYaV7CgC+l!xQd4|+uVp;gFN9jX3Fgo!ISuv5vY zh6Ep;6mHoRI~WI*1Lld|PgID(SF{q?DC8v?VoMgX-N`qK0*~r_rkP+(S%kXI)y%CZ zq5A>|udc?(y$kILLzC2J08KO%lSZ%o%KCJ+^`*3m!mn(o3uz1rl>-)2Q0tfOpX65$ z^!r5gv33!(GweV9zXra|lY2X)uzZGpfG>oo331Ypey`*QPV8R_?1k->y}-T_iDCJ& za$eTjbz}D~CRQ^{ZP$nj3P4F%A4l3S)mqx%d!#-Qb+u6uzeEyp)LLWHK`XD+lC+L@ zJmF7x3m7-U#i{ao$CDg6EED(d)6s7!@jhZA5TE?_Yi`4!z9fC)mU{RwSILW6-DBNt z8)_tORJp6Awcf0g(Nl2C2?=X%&KRsEQez*1P~I^vl<{T1{@JTY6_j37#nB<;8@bkA zr;C&qra8wX(|_8y(?&wXHK-^zP()TKCpJX7?)tqQTV5*Q^2Ga1&H;$W=6TjQLS(8#q19@KSFKTN0$?3XJM-M* zkSV+gVuwbFQ!HQP7G#D~N;_4rT%9hQM|)DqbEY1WEq_Fb5G!L!Ab-E(YItb=qfm%{ zX1K8`)T~1PGO~u!55Y&8N%V{U4PJDji6pE66a-4$aBxk++ycQ4OP1?;hAJVU|O8FyLM{VkMa zF1?9wHSsrCY>_1t1|`zkGG@bj*EhTyZGZ@hwNu2wAw#5U-NGcJDZs1~G<&a|9xiGO zvQK^Sj)6y!Cpr2LQDdN{YD+wEfo5|TtIEE()M_Tis#m+P?kuMs>#vecKh}*Cs5l|3CQnC9JWEvhN&OxyX=Bg^4NUt}{U=;mgwZdT zcd_`Y+`maUm-ImKk%b}UiFb>wRIMxP_60M^HYj6?sfLHWrNlXY|Iy9S?n;z9538hN z_crgbp3#b&<5XReFg0X_-nPLfxsht#EMQUm*C0?RXA5rtjYAS$4DFK*yesEwC-GE| z5rQOO5g{`A5+Fke{D5hdGNHJ-FO*$z=qk{C`tFGqJGAxE?o#_1} zbr)XPXxL^98}+(-8{HX~rp6q*4-Ba;YfQ=b%I+6}@ zWRgo=TJIX%SSfMx`&2(hegv<~Om`-<-tZ~vaj6!J7eQKgs?n^F+6EYF-dC%i^Hs$_)2Wmjh0p-wGkx=+8Gk?0)GKR|*q;n}M`XnWvgQO-F3< zMWR0LNAE{7*}ql{5Xyr{R+4D7jvkJA=RYPI=j~-F(1GWAzTv{D=nA7mKFw(Bs6Xi` z`w*q;gu99o~7}v!04_DI5G+sqB{4$#2A$DFvl`UdE=&a|-6jRd&?`{!l zlo|`ddc)FI^9hDc&^1!(5jUw}l+=IqP?X!t_oMe}ay?MB+-vWB%e&I>>Y?X}G;R#% z%wbldMwO<9_S3~L6$9Q?&vWO5N58Ga5OIKQa{v;f4bn-GvMeOBr0VIi$GT2Qc-%4< zsf!z?KDTK9`he~nbyOT|X$34xsYg6tbEV2xSL|kyLOSS5`!7D*lIMx`JKs!ng-=85 zA3aB<2QWKF!0i%K{+!8ywufo++s~o#-n9m{_wI&Lge|7>-WD~6p!|Pm?0;O3)zBu3pyw&af2?Kz>$_NJ@1~!z;m{SI z18_$G!tXz@GrJ`+9HAR3b%7rc++hCaK5DO<02CIWero|}nE)CiSdII`<_LQETG=?} zGM^P;@3CN<8~%r;vjB?njn+6R-QD5RUD6!_(kq4uM7Q;&2!pA zqGGSP{er{aYhbdCUw?-zMX$rGA@`-ihA4lS))aCwa>8+>$8zTV3TK3T`L^39C`Nkf zYyS(#p)%ggMDEQ#we{?(oZ#7JQwJE5;_~tG+fhVsK4#{cRXkm)Sz{+vH-; zx1sSHLpFg2_K;-1oHSeTa$y~^sY+rFXKWxQTp1be`DcR=16W{K68)V3wn-`BMFyM6 zEWcV6w_7U@a%Ff3PfYoi>tY%=gox-|?UqO6bABYghr2Zq|FGv`3K{M#?kDMQb`YAX zto@~3aTqmw^M||>R=D0V#o16+yR&kmGefFc>H^~HLeLH*^6lh@)K`UYSH3%Y0-OXE z^nQ6_>@>y$J0!A3$+Rx&1+ror36!#M_U*Rn92=iGLHB+?<{@g**H0R`>oGn^I8<%Y zz-dXQ4Y2B@zb>P0J7#qs^%MR+mSh<3;OzKKg$=(;ec}aeHbXy}?Z~}-tyF3T0z7S1ErkvQIsioO?6M&yCqE`;WQVtS9m_RQ#|U&ukET}uEXSA!#{c5FhOJL z!>t2v z#wWGk{DRG+=1&rvIxbs~l4{C=Yp?X|PL#o{a`T*OL)%b&7Zy-^QcSN>mDMMUx>7wu zDfHo5pW}q9N)91}|9qPFUey8>x4_N~y96D;uP#xCi!3TVTZZX!b_rJGcfsn~L^LfLHbX#+`eh_v{PEYd;aps+bl9 zDx(z(-RM3Vh-y&lx`Pf|dz1aKDwrLX;n`mo1%x`;3oNC&etj z!$vH(o>o+vAJMM|KcYT?L^V*oRvh{INhS?dm0z<{CRt)$$RuB+2$2q7m{%iJB8+BM zHLOe<@Aw8;P3+_4r_I!JZ5mSnm1U!bx*j`8m|v4%`1+7(l)9Qmmw;{KKaH~Yv@2E@ z{%M}WjRj5Kgl4m6iHOxGmzn;*6gY6z2ywgkUh+73!$F1)tKr&|{^sp|N`@$#2qG0< zw)_UgUn8iqNKLDl5@IT(Qo=Fc#j_qPTtdpB?*%`>6}#fT%33K}%A52D3|Y>WCk9ck zWXKms{v-OHZStvs|FRkO=s_L9Q3VurX5|1@rehj;ynQ^9wexuWHt>yD)}IN_;p{vd z6p%vcq7G9c-pV0`hijt3c;cDnzFHJe5L}NNOo8buBJ+e|)32kdLXG~5jn)I>=wq)1 z*xaq_xEYiear8brFb=AA9pLSBA

  • #JQBsAfILk-L9Z66z?lDsm&!HnU?vbB1( zMp$g&k)o1);7QD3H2s84VTK*)v?^Hlz!J329<8&Xd&aTKsnT&PBu#@^wHP~tZdWkQ z15YXEDsMV`YNTO*-Ulvl9OWUVG4H*MdXDxZmY>1j!qf(>Fzhc`vxKLH$Ws+I@xT=$ z<{KTBSMUqc(^AGEYx1a3|4zf<^fc0Zn>%f>x0C&yH?N9w{K$7qh$fq0@@1Y!jc|mr z_t)IZ`Y)cO9i0$-&hRxa8tc5SwxjI; z_Qf!%8)_n*vgP&eD5?9jII~{!FJ{Y$T+!T*aYA4zYH{j>%?Yll-M@A<7LV6^jg5_$ zfJ7G9onqU376AYS2f2Ycl!(CM;bPty6E5-#09)F9-gp-QO{?29BhX9YHp2>5%m+q)%MJ z`|Y?GVqfmOumPjX08c~-D^7T8$18Ga$uN;9o1~9V;9tA`>DpiAt8$an@A@gQ^E{kM z8!Ca$7ilpexs(s$E~Nf1(at=yqt@V*j2}sEF#bsW7J`3#%^zsdxVV3!BZ0!;xKbtg zRhvoj)|s*DwcKS(=}}%?N%S`zo)%1Eo4!`#dr!nmuGlvlSu@)>Q0(DR4U0!p?u*1b zBv5rvv~eQ&cfI}bz17L|Pb7zORZcU>bthz-6O@ciJ^E*g%%s|ed+R;-EK!ZsCNgoA zuy^7TdEGt@*Qr)PSl#YR`2S6{#odlh5w`NMmu>K{ET}0gU(o1m|CWl?+ zVQ)mp^gEcAhr0p^Q}wDG;aVjgf*kiciE(~8u7-DGu zo-U&~7*hFLS0(g5;ZlVnvPu9v>0Pb{3EY4efCP-bcs}idtdjz+BL8u;E&3e*>=NG9 zzs$_cqw{m1&5HvE4Oo2QX$=APuz*soy`y8rrZgL%PX1@E!_C9P;kK`k6Zqz>tE+2^ z%@smv{3nCwzi|Ax@hC7PtYBxJ{!tvqNT3EvWBJvQ6lO3I{Rpm)EIw!c}8uTr48u@deZ_kQ?^WWP%A%n;Wus;uw4A{Beb{@i|;S7 zXpvLU!r@eqFpx+w0dLUS*kiA>pJl8ioBM@*i{ZFmh_psZbY6lOtP^80so%;5b zl51b4nx8+#=a)r?yT2vaUcG4Md4yR~7m}G@v8&552seKG<-BSNsA2)AQkXd#N&h4vOEoYb#OF_Ct+IFJhT)p9nQ*ks^1905FhH^^txNW4}9ngVm|o4DUg85PX}hIwfa)^29Q(hix-`=Izoe+2{mMOl zX71Vc<)t)h;=mQ2*QA{4FKV9+3Rj%>b@GM7a?O03Z!<|{f%`!}lb`J=Ab{&oCCwH+ zEB-fl(RQJ^X$HA5;uSu`){yuq&D(HYG$UjnrNXNA$s;GuL3(+acobp5Rg>88Xg4 z3V)f$dCf*oIPbcXw!_m=br$WAF-z{+X-O?IEdqW7|7!AhHYXCtOcE~dXWzYZGorhx zLlqIZQs2QdBclP0-dJW9?rURr*Z(Y8PI%Q!Szk1SDrr<;$esF^0!#U}@dt|Dx7)@w10_Nv|dL0w-Nqrxy0J z>N<+6(ge@(bHIvkzy9YE_^#?D-16P!lc~RMlP;t{sRJN<`~MoXNJpEMj za6qz8&6472PPn?{cbj}V$%YwPSjgi5=Je6=ar9{izolh*37=K9q?^C?I2qM}K1J%? zuqg*{a1k>y1#8cwdsl&SD&@etKNJaX{iE*MG)#m(o0>k?@Z2pexIgU0J~rZ(cJ{!+ zOQ3-@FIR^rMfC*Zxr|_(-u{U1#SHC^ptug>F+>m(TIDBS`GTveA#Yj`XPS;0OOb|# zf2P@1`D$Go+p8oNXSh`VMK|(!)@MC8K@&X^&WZ%)Qq89Pe(-^m@90jyEgfneb&sc> zQI{^IO<`3QpT4iL1`f;EV5Au=5=miH)lt5x;{0@OQ>`k7B;L=f`z|W@MIcIzVh6l3 z2d<#_OI8zSCRCn3ka&#>crIxPI}*#&UAh=DwH2XMs#WXNvQ zzR7C;-NJysL->E$?`ANa_x+Iqc>FB`R#N}b+P$}<=m5AG&iK+9(1843W(YuFEh(WT_u7Qc@!n5w zPpcyn1FwN!u7%<#5oKu;H3wMIAK{Cv=|*|Id*qbl$FJ$@)s_mS;pIMQqcrS12c$RN z_~%MdtJ1#ycX|XrV~ufg$H?txhJ-n0+SoXSyU#jAWApr(R;m|ubyP@@Yx$!4olV%D zL6J=Hw(*|*>OQJSNm=t&9EHx6wFn^ylyZ01-gD(ey5up=@mS0o#IMy=)uoUrf>w;{ z)OCZeu3MtgS|ygn=Yn@oh30hC{c-&>fY(l~F;Y%b`mScL-<9DHS&0C6$tPdf>NdKc zukTl#<{lUICjL3_(kf>Bo^>Z?N)GWj88f4Q2EFr2GukAxE_ED58T;%W2F^CfpnTEA zO+d=r(~%8UKF4Z1SG+bnXYp6?RXn_On$;8c9ZY*x_aWzt#cBJd&?k|a56Q%3DERea z;ZIA&2Crn0y6*coQ)Y<@UcLeSsLtF+D6Qb<3hj!LFuAIoc3d&3w*ULk&nmvjn#e%` zFTf{$YzgSak`6Pxe<_{YyKk%33qS{;rLLk{H73LCq$DVBN4-fgys5gvV9lf{|AGZ7F2<1!jW6-*CbKP3H-^BjR$v zUZyE!+KtV|bVs{a{luxisK zgFCyf6hWmFD!&_4hV5gU=SRHfN9vGt<0fSyhGk_V$V_PF&1D;e%b{yibvYTta!{pu zw!))k`fssc$D4NiVC(+vUr!h2sUEf(i1?7WEp>Qooe;f|aHcMKpxL4F_j~hvs(|fq z8WtD#iu-=LmFZXf{~{kCZ&>{2lDo%bR9^lAM_CAK$)oLII|dm4*?$^0^gSEoKgb#Y z3>l-;qJg-z1i%pV%08m9*WAbC|Hz5LKMyoc^GZ6U=P-lU z7U3*-LUeJ;!1Od9va7OBKYioXs@56(A;$%HM_2?Gl$Mq}kf7>@;|8g2tu(!sFkBN9|1t>QK?E;H)`&@YLlImqKF z$*Yu!vL`N_OYx2EHME}&A9*CTY?yr28^P-$VG@7~xT?4mED&e zHMi;?c2nu}5b;b+d-35A^uH<11MpSOl#Sm!le##@@+;)M*>v^3O!>S{T+kb=t{Ztx z--VH#(Nh&@M3T4j;j!2@&dA6TlDU3CA==TO4;u4cJSq4dtBUifqRPYDPsj)7N0U{( z-#H-4mldyei@N_(7{+z;x2~2qJf?2?e8zsj3qR|aFp!YTG~D8A766R=?`6(Ovbh-HtP>lsB@om9D0f=>q_lMzh4l|iS;oP^|Qhvar77+Jw zfBLitN}1>AR#g;t_jb#|<=6cu&O(d^qpOv*AcfqdBJbT7&Wh#NaI9Om(#LCaZa2_*~ynYpb<&jya;4N zCK42Cg#}VIv9Hkx=Ye@bw4$xI2%XkFBSupqBzJLv&I=3LH;29(UjX{>>*L9mvGr zTz=`ufn??;qBv{R49(b;RTL41>sZuVx=Ia+=v4Mum7S4qoTKfDe){gcJzN;WR+7@iJ}-zn(&N=!Tn<%2X}`m8X8&XQr- zuyTF1zHZ1o-tR(6tCXd~LGDv!O(h@QJF7l?BLujv4!S9yYa8^uG3N?j6BRy}59VIs z+Ex%Bvyl%-`mYU9D7dPl5Ii~EJc#WEK4=&Tc>_%j&`&uybXaH5#hVvo=ED zWDSaL4GiuVtqT<+Dvqr`{h^A+xX|UH-8>?jpv*)Gk2A%F3w0u_}hBr)YNjX4vyK$^8J6R zVSx72YWXL_kCY-;E}c8=yqO$uRA`w!6w z91to1pnA~-`EQqd{U!%;+W~+^6Xc7-7l4b9LSa@D+dRYAjkJ`SIgxgZJD+ZJ-4-q# zgtxbmk(L~qCCB(VnS`c4EoJ#HHZda(>-Z&8yRh0cdlv^cH2pK{Fk%_yOl6ZEc)6q& z+TSD-NGPxGnA8JR)O_<5GgYI*>0x(iflipLn`B zc75V=6}O~}3TrB9lZw^KT{+zjamLKa)Ur5)EeaM(tCg3Wq6waSRWp`# zuV@BG=64}Ifg@Vxu8f(O5A(VTt2pVx5ryHC+&o6INS<1|S;xK%{5EcrlHuHfEXtBQ zMiUNPEk;uBApB*5J*%sW-2#0eM}>{5Z0ZFi4ezu%vJUCy4tI!YI=rLL6TFg<+ySnz zgX32s6u_+0@V~$X>N`>FGeRytU}%IO^ggN_048y44gSxx^*=JN_su?FvHB9SzrW8i z-!Cx4s4#`7*eOT7+%w4@bWMPTe)H<+c@Mho-{uDm*hlmu=yFyRzBOo_Q5>2eR2h`uUHmQ_jH z`(GP$ypIz}-+y1ZhZ!)x9hz1@JmQ`DOjYkS2ONeGc=>HfoGOHSh`ut+2?!wS>8Z*m zOFo)6tW-E8xj9u+9hrcJ)l+HU*}RQdPOumg`A()>6%QXd;4!;C>|A;AOC{hY76>JR z>S|W0mdY4@j0z!xjd_KM%=HwvWKx)r0=%7iVDR|Eh1#P zNSI!f3@Q7D^YYk{iaS+yN{UWrS| zUGTT2hGOK|R80S`_%n?0QLltd0y~>HB9Sg!S&E)1pLJ>W;$p$G^k+Mx$ijk1)n8?W zO>7Yn_-u?*Epw{alw)m_0#ASKqw!v^ZEnYpX5QO_uWeBY!{r-&K~j-*U?F{9J6RL6 z+M+F0UpF_%jLvWC7CjNRa8pXE;Xpg;WA7GWQ#bgEx}f~YLL0H#rlo?=thlo)NLyBB zLQd+|3;r*&=e{%~E*`^pSgCjIr4qi);)u1#`4Eqgeoz5!@07)bNGrgAWp#!f9u1H=Jf(qtok}L* zb%2%>`*l)2p3I-k#3Qve-F5MYtD5B@sk6Atp7^a8&JhdAH$so$p90~Oo7~a8Uz}?A zABp-uAq%}GD%&kE{hV1@8C`YiK{E<}esiaI7HY&W$UQWDkAPTxZ^>8i3mk_$_5jqT z-FV5g`y*w5;AF8Sj{*(&D3OXNfal+HyV&B~Dw$US0g|t!L#dzvy+Iy~^q87;zG5OZ zTQnv8>UhCJN;aden5sBtUx0Qxh}l zc_N-!K-4G5a@yC8e@;3v-0*$MNnC$^GMtlCsWYf|@XQ^5bxKwKe4p^1r9`LCN&sY3 ze^*yoDv*dwmB8rrKkEbQd%*JvW^}8j1WHPD#znKT*y3t^RFZuz|3>}kB#q@bfx*UZ z)R1}o>Z|mm=!w-E8d3O{Nv7d!kCD3px7&6LosK>gs}W4@*So@;Ap5|@HeQ`_ohi)| zin*v@`9*66P6-6D+nqgysTT1>W82)(-~jdxj_m{N&3Y1&=6`7m{(dy7k~}gX9ZD#^ z>d5}u(Ksv##029;68m)~Y_l_vv87(z;NcMkdKjMUB-}2iIR7fGqOvZT<7f|TknE~wXd0RbT)7?vyPOp#{^*;@_24~Z8*CDN$5HX__Gl&c}LExQI#>0Z>xDiHwSG* z)(9V+ucR}{S`_r;_UEm^brfuuXLk7G#D)e3Bpav%n#d$v$+SLGD`SkSqCt^flM1Hzk$yaBDSBjri^}a&qnT<9{T0sIDBiS zN*&LyszO5v5l<_}6=^?VP0Lr|^-xq)L=z&%fC+}OwX@rTJa66kY+ZRV2XPI{Le^7v z>_6MaLtXoH$=_`Q-+(-8rimCPF70u2L%f6-zc#*<*05x(eOJg}St^-3YMfV=kki(5 zG32MnvXhe-aRVI2>~m zU4U>XqWLXAhqCr-(=5Kj==biKlowGXQZAFdb&+sV5~O1YK`(_N_h>49=>mG8EA zEY&u`pyLC0t-d2?-7+1eFe{zu>;gKU67wq&e8^S-_4g&VghRaql&3mt)iX-blhM;L zSv3hd(1VEnLtL-O`&``Ujt}22Sxhl{<#;Jw1>=;ckpL|T5H?F_rUaZNcZf6ny9n+i z4nh5^(1+c)^nZct{Xr&zTAq8ibt+3MgHj)cn@Tywx+%aT36DIegwbi+-;C}=R(Y8S z&a3BLI_f)oUT7ZcnMQWhhAz_k>~Rjvl-&w8b*>>P`o7%$Ea+hywVr2ddJ1p%g!0d> z-x`BQ(i=-f;&xSPvn*ng_*r-J^sfZLwhb)LW`JZuqo20j_PKNc$>zn6wsFNyB(cgk?4 zYxoO6ULjX=$=>sq@#$Q6ef@zxh_plJ2-lBHgxK;u_~Tf{O(-p(gJo{T&gSeNmVjaCdu+?>ap*_vH12tjP zEflyt&Nk4wi_J%hE_7Y_S;K!IGh%>SaeiUp>#>JG_Tk}SZ5d8cg*X_Wb2lN2&A?@5 zVWGI!>Z=UGA&qJ;#D|YMcPb(_HrDY#-Z}GG4d#V;*!Whg+dK)LzLltKQ% za=gXfqX0uugteJ9&Hc*BUBzSkqp*%vU`-{}X{2;Uz=YBa)lzw9%Mn}!5ZR$F4eIho zCZ+DwTG+%-uae-PHImNirIV&Cx~PxfQddRi&b@~tTjJOz4V=4$TZ;ER@-fdlSUqLS zgRXA6^xHII4XVj)7x?;Y4`Dw7R{H5%qXEM2qz zrFbp^pAa@gn@iJB#_Sp5GBc96OUpP#q4v@SN`*~Ae9n=&-dr!vVx=*~Tj7r*iEw-7 zLQMTv8fn%D$8bnS=*YE?Q9^@Ng7YG!jMEST_toY+31|d- zJCAi!JBMf#f5P+*F!%Sx5!X0!8mYjmlDE{TvVAr8EP{QXH0Na8fD zWB0%S_FfF##WWDei$B-H;n4)qL)-WW!>Slw!ufim4-6fKhLKW`1WynW4&5KlDEuhx%$?$8K;_otAb6$9tgvo4-pc>$(U|NWLR*mDGL0|QmD zxlx|%AK<|8SJu_a7Ugpkq=zrbL{m$e7~tR2niSV>l#sT78k4WWR^g~rB}?OXy}p^% zYE=11xJz^=CyHqdWSAeqm4uGpYP+PdyXhc*CK3N0-smzCmA-ZJo`|zqeYQWmJ32T7 zn@>2JUq8c?mdMBeYl$) z|5XerhIDB#0T4>v{#W3}22m*Vv!n5C_8x0i*1bbN>w&*FbOYQ%M{nq|fKmI^@aYtm zNA&le_lV-$7Z6~A{Gn$9p(n=2qHU54uFn6JJB})Mqhltf#b5VcKU_B*gNJc(`~a zfzhTv9EnuJ?$_d?Q+uvo=TZFjd@LO?R_MHI>OLZ*cMK?*3uMOeeb;u9PHTK!n zkpWLG(C0XXWJ>MqoTU|~4G)n(;#qdO6*o$pDY++Klv!8AG~wI+O8x(90S3)8srz8^ zUF^7PTI2V$@JD0WgK}80Bt||Vpjf6qa-b07djxA(N`2guLwjt|uuD=D0GJK+MsQo- z!W|udWbyeH&A<~)s|`Ydd{E-q0ms*&3y2vY<8-D; z1kc7M?kDynxCgH5Q`O!5;kbd zuOSky333ZS(t8IhtO@W#P5~}}MjiX<9P+QJ?-KxzlnqRgR*ou3b-;GlgU+w5yz6u`{&uk9I9bea}= z79FilMaU8txgcHl0x`oF3ond?gLsIPAUJd>(QMF1F80t)i|&)VX#;P`cVu7rkpkgj zHqYLv^ECj(C9KtyE>{1=_=BgsG$bPGsbUWzz%c zm*w{vq1p|#TmOp~V#(w=Ja~V0_+4$xH(3lL+?l0FA)|^IpE=5$mf1IbZ!}@=RuBuJ zOa+MzRU}5Q2pk?%=mt`yz^!XX<;tHrKeni!eG0^eO%<9|ffMH~$z%y81k|&!zYeQ# z`qwS@uoEE`r=Y(1%nbs6;ToWX8LcpvS*Tc4mI+b_0b`ph(k3Fp!N{kJ8>@s^3P4i{ zFW#wWaKqSQrdsF>WN2naK1ia^k5gAeV4AdUV`#P2<}Kdm^OzWP zemLNsb)2ifP6)+32uJEJ#~d-|WH;VyOF3Y_c=XnJ=$C+lfkwd^aH0DO3jPaZu-Ha{ zuXaZ2pfM5n1*Ak1Bab^xYdbpt{c`B)$*>29W8(C%{o(YcSHxK$JMH!oH0~!PWCFA1 z$lHyLYD#!bdGmXiZhPCv5Vd9r+-r@rKL_GK5c`>{p*Z6CUeHCxj>^2;Nn{5_TKoQH>sZtt+1mxmHSdONizP&k z`HipyR^mLe%W$Kq8MkvWTnPv{7bq`F6uKrHFgdbIJBi&HExG_{-@ej~BKa$?lyfi3 z7;0D07hy|a>sgwno!CaIlOE_Mg+LKL5=!7>_-knZb zKh*}D98EOtT2aqd%6WR`#r_CienzSNlp2tp&Hqs=MkirkQyf;nn4DXbbY>s$GLZ2zbZC{ z>2F>+QO@vA{Ap}x7;KSP1R*j#lh@gS{Rll6m*c(aZS{MlqDd}&R zn2CS;lQ^V#|86B5ppQV|JF9^?;2?)*)v!P%?amprG%H+PJba&9|1}iZTTm!WALohi zg+Ei8J`oxl$qRWaYqyC;C0nWV3K+Hz?75n}b$SClKhdb~RujFA623r}Wc#WW&?m;r z%)(~5QA@JZB#sIZT}iX;U+_{C%KVg|#HV0)2SQq9UWx{>-o6mkQwZ?)c^-kvm8NeO zo=|odf+vo@`(FH7`#!f0_i{VP2p#jpG@+sVERAq{i{R8%l}s-)M#i>ewPO!`YMG5oBsax~EaJzT4Y61^ydMaI+f9x9;jVQTM3GpSqpDp0XtbUc7 z&e@sAhSn|0C|veJ>Md(p#;%8VJ^gFi&m1m;oX%btHiNeJjE@|F^;0LASZzUV)NB8w zJ|%V7e#%7RR-BgGr=2!#)P+g2#D4aYvD~DtYpdhOa~<8Kdl`T5=^rh!_wIDEt!ll% z*s6a{)UPe_3@3_)>DfpT+M{Ww4$Y;Bf|{I#|MiCwDQTckmX$0%h|j96zX}|dF>#*u zv&q$JLA+9I5zFPFem!#OXn_gZ4}@@ne7n{i^OFwKC!g+i+rmvYN8O1_aVKGeM2pmd zY_=OD_Qa>G@5Nyv^4*D5;}EPCmp-;xpbT9!V1P$KYUQ}ZBqYGChUs&{qL9T7E$DeF zR$mB)Z2&V1o(M17~O^v`e6(!XV z=KHtj%HZ0&bEV_T?OeSW;K&mGkN4LqDX{v;(+s4U@@Uj@04*@Tx?$%RS?klE%3z;O zl8u)Sj_n7u`tDcK_}G#@({AK$ZKT~f3i~*D6z-VaqP9u4f!f-s)Vn$uny^5=X<#5a zIP~+;=}V6&at(wVu;>NszY4m$yE99L`Wzw#f;AY6kCTr{vUfQZab_}zU-%Qn8>`V} z@(ruiOXtcXg#~A)_gpxtdaIjXo6~N_ z9^Xj34v;$~*sXB^f4{YplQz;m4L{|D+-ahQx9kG6XrdYID7p>vxOY+oLEF1rh-|+s zqmdUHQHDHrynRm&u3>ED+J+KxzkAs%|jjyD|qf3pRaOEljC=i7peZ7lUHA?R-pYFz37Yo*`GM< zL7lTFpYRAfBjf#Av67iZ_xKF@tLAgc=yF}A`woC3&NW7V0C@(5qR)kVJ$14?Rl>+~ z!Z@ZPY9e(M6j^JN`j3Pv8) zP*;a-S^Zh1*Rq{Gw;}#1b+8Mv7UMQ4jG$DC13aTolyo9&rW6{y3Q5ADYnEbkm@O+e z(`PtgjXJjNTDSg@IGAky!ltb>b=yKSi=wrJ;WbUqW=OSY9BH2nzdmmOAk|kaJcCFfdB^Lry0<+fl{zIHq{UIiM+3HhTM1vl#!Xn-G*d@rRBA{*cvFr-ma3n zlhac(3oz~N(jgZh9$Bg71Y)r_e`R?zZ*(`?(EhUV7|t8w3(J~OEjqDqteu!4I0rFsl8ELI}-Z&NC6 zZaC0(fHY*&av6GU!LPZ`Df$cW5~6Mc8#c=;v_L~kvLBRIUP%r`@8m*jL0enF!~)8r z#lweU&Z8D>xnWMpJ<%Go(_1VJMBnW*DrcTKNm*)%rwtEQp$2lpi zqoD&ydh*Zo=~D9-+Glk9RKd#STF}u~FW$mFmnW~=Lh_jE*b1{B4H(%zy+A&AZT2-S z8N@glzAL_LmQd)p^7}dOBb0rc9|(;?VQa^{FuY~e4@ZHJc~G!=-NER4>}j^{E$VGL z^QjmaZ76O@T7;t_-42(&MJ}QHp=lfVYl@VHBxtL4`VMt?9gmb=uI%Lw2E<)h(O|jq zPx$O&d1Yi=)^JVsep~$2hc*zNf0v?Vo-o+?cyn2K5D+#MxOJ1lgBLS6|LiXC4kZ_q zy+b+5*wOTH2`?FQcK1qIFq=?IFNRjfO$4Y2%i0osODp5q*G}$q|AK0y;fGM(UrO8e z0}|;9o13)^c*)}i&ODi5!fi?9Kx4Hg6YmM5=JNrmc4}ZR&M6c;!g7tVlr&1Deb0`W znHdwLz(H3vf2!e(8d8LE<^=Qb>iX%v0RCKowsNL1g}KI4jure#CP;GiG1#JLTVnl0 z9;+2(T{QazgN0^+@S5DXbUuDJTnYVxvGUFMqT_Cls`j`qmG?Dx#!>%?3Ho6&!>_mL zW&{ns$}r5n1%!HfO*eAm%W0
    81lx6`0p>llw;due}@tBP2I!uoi9>>o8CA+QEL zeO`C3rL0Go4K5O*ocWmCG9o3me7RnOcz{-wRf z1?E}q$@|?GML6$)Y04@qVWB!9ZIJ0uTEC+WqyF!oMIxt&a@8F?fa!&MKO8C2X0PA{ z98{Le(-GotQ!ly)bSUFvj1uZjX8kOL2Ev@O?r!L-hs4NX=v=l633BMic;L7iLeiFo zHRu-HVM0w(b_Et8i6H(o%xpVt?WN0?Tz7X$0Y5(AHh>E9?Pzzl5&r|oBF>bH)h-|X zfQmeN6YBamA%vzz+sLSu&0cOlIYR zaf6XRA1`{qwWlSds{;aqIi^E9yyHu5ZETV^D&4Fci(+j!p|`T{e2k9>;K@ zO0*jCA1*t)=^an8;~<}iO2{}0QyHv;v4}j4UF9w_dIOw|g&yxPwUS|ud?M+xPw5dd z_T$2W^h~HEn8$ul;!&&Qm&%uO7LB?zqm+UYlSnLs4+w&J|_i zC}p~WE+TOrqHE5!=gz1;dcFp7eXckc$fSjX97bg^3>yN8hi3V_XHCdL+{Rp zP$s~?cy17G8W@+&IaSrGyejaksIpIkr&e5K{jbE`oHT8cA7vaLaOjtzE-I zL-VqD^&tgZvK`mk@z_y;{~O>OR>?CzJskujiU3D>Jm4dPn3_U04_Hng1FVsF5|tkV zQej(S8Rxn{UTOh3-D1kOt4+kZPse?cP(8;S&Dge`TMj_GzJ&HJadwMVbyG8f7tF9GLyuql@xsscK zt-~?KQserss9;@D?8b`F>00$qhnw2UPzns}`gDG`-CEdFT^imUS*%@mmL;xvbkyGi zQ^zb+UQoNJIeo^`^CProp)H9RN@$*|LRWhR8`M%xf|ZM;@zV zQg@voD*Ne)F|ZxzbZAe0h+G_qRuoVZibOpxV3)ubsJ62l_u;^8+;F5?N3V8zXJ zb6@zp;OW%x@$)@y#E)QCWI}p%$Qbq+DofsZU67%2YU*R|QVgB;ye@f`-Qa67bTu(}(uw4=|_&hOT1F_>w^B zSfZH89F6HCisMBSsc4)+RjflEL=6{YT5lSDo*<7)6p_2RXO*o)sPJY0C8X@xfpz(a ziLi;eQ{pSzuz}qP7cCDHvXibL1N~P+2+A8HAXYdT#>dopjyw5VhXzzF3wC2t5dCvm z9P~ljF}mSJhLgefCc2uzk&PcxW4UVn$H&M0Omy8LE*L)s_F~u&pxg^^aL99lm;!v^ zyIr1no!7??7&h^Os1Zn&=q6t;C7DH!K=95Rf}YIez-H6c4#g{?QP(!|ul5($w2~+Q zAj$Bhbh7}3t$$lH1{x|cP>^Uc=Gq7z6jK(z_4M%};N1JbbO)Y<+Xdh(=N;8RxEt&aFSX4w!KOBkHl;)GED z)z9NM;=^met}8!qY^9^8?I?n%OTeQ=W21dMRIAK4;Un=@0{H_Rn@=m9-dsg4KRF)1 z)r(pGEmw1|7vETNMc-Y%aazI8hDwr(=*)$d9wc0~`Rp_D#%`WkZJQVx+x@|ugvQ&V zlySx_c!Ym;SSg2T6l?t>-#TytB|d4}3TE!s+jcC1rn@SCl_ETK3tgUsYL?%eLfsn3 zxv$VrvjM*yTF1>?g(V-By?wO%Z-TI=1B0~4h~4epx{BNeQhO>g6HV}jYtC89l+WrU zx!AQcqOim$=hZjmP?@5^iSJ7d3ZdHjajU^uDQ@<%%yQQru-jw1+fZYPr0w#OwC&BX zhj<*=W4Z82*3U5!2HhHdq4XLbLNym)B6v779dBO_@y;^t1;&?YFjw_ zmz5CicJ60zaQyGzqIr4uAuz$hVS-4dU(Sxbz~X)!#3V{Y`^m3F5gG2NHl{z;UUn;sEduc*(wZYI7B5Oi={Y z2fP43=lPYQn7!e)&Xa(gfq!1*w8F>FZ}GQO15^q-tUEuk7j_B6+*0A$$%4X-atOge z`*oBBvHlq}`EI7hgWpXnaM-;c3^!GQk22V#8g!tC6PP9 zKh&LO5)fR4QsEbTg_g-uux3QVk88*>f(^wTlt1kMq$6>2k$PM9P|ha8+VsAxcEfM3 z-rh#BAU6tq3h6Vpf&|P-4Z*54-Ux*u3o-M`V=iQ`PQ}#9_|qS}+0m2pD2j}=ZJK}bqY_G?lgxifrurO?iu~S`zY5v9qrfB>h((b$BsjN= znpEk@g_!vkXdqbgejiT5AaCI6j{1S$zohDK=^IbjJQSqC!|grg!C5z)(inAK} z)|XywbqD*W3XGxS)0MWL1aLBnH3uB$EolgY3T$4DF=Zl41Yfj%#U#f2RtOW8G~7$7 zj0}e}rP1>SR8B%~`Acm_n4toqfD!)R5(~R#xq`$~dAWy$l;KA->$a@VRc7dDF zpVl0{p=O$W;vX(T+4}R+G-G)kz}yENHI#dXqzzQg!jRRU0Ep+beuRfO?OA2OdrEry zD;I<}QD&-V*^vSuXW>H&#tCqz5!+O!!PgYZ>D$0#G+k_T_J)Y3Y3|tY+|aKgiv&WZ zccv?veuLG{FZ1-PKIid^j{|zboW7JPu1TsTI4FqCNs8I7@g%VLs-eW0)T0ftwR@M= z%f$D|`iY%Qm~vWElYjo?S5d_NT6NlV6?baiI1|Xq%EEW<;&P#1Z2So%KLCK&oN)5D z;vw-8p`5ab4>jyb?o71kdl>drw6Q4(NB{deQC4C4TIzm2U*S6nOV#~4!KdL_QkI(IV5CY$r)3)Cld zY4hrSC>6csSh_9CMUeuP9cf}|f31+4VTij}e{Z2ztM5#PhU%M23<>}1(VNy$Ts(3K zi!hqYRZ-Ke`l1y-P@{$HRuRY*6<41URCa(943;!xE`1y{#IfVlhNr`vWlzLXrYvzAXyMCkbBENfe@PnaZ&* z79~Z@c>A$5m9&4%nOV~twCohn(CVY;b#Id|+i=-H0^h<>w- zJx`AIeC2<(cM z?Q06{TE5_57iRoGJY!I2N*TgcPuqutI3Pw9m+%IALr{AksH%zNjEpED|3TL1$@Q6f z{)}H_t^S}4kj>JLc!nOZg(2D#R{spPTN87~h!eE`j|%`x4oeLBPET2c{3;F8uUOGM zd?r!iRj?ZT*ToOtDbV-m`wjcr`Oy)|w3Wi)%^Mk@O2dLQUR8iyMqNgqNREk2YKWn* zGjV;+X43Z%xtQSIU&$7~5iXehG<5U4zoKc|9mLvH#7yW99UWD@nrj979P7H--7D5` z`2I*Gv{8TBB=w{0t0A^bXWv})o7=uA{NGMyX8_M984C-G zH`IncJHz*QKC@JBko&)^O}g;_;$^d*80>Qusfz%)((lQ+xpy?kn?4Xo$4WJ>fv*T< ztWuaePX{2eNLg6Wk;nTz;*d*_dDJAj*~|P+YletJflK`9DY-~m83o0q z>Rcuq@vFNO0`vBG)Q?QAkTxdXA%?O_-jTOu-?Q^w^0OS$c=Oi{Bcy0Ld2!&eCGn#o z*j>Atk_LN}BT7-z#H(iB?E4v)@I(99>Xl}SjCFDGJ=|w;{6tDfBkW-O-Ye`^IYRjD z9YdcSOgx&6?5YM?NPCzeO0AjMgzB30#SzZ7yuC@M63Lrr8!27djk1j5| zzsw>)=e!HLUlN<_;FX7C&*$~@)BVL+zxX3gWo2a}@QCnruz0@u62#->DZLSoj*f^y z+sn~%$OA;zCTTa5Umn9u9?vsozgwZn;jdRxxeUz$ z4uODk1*vtpw-Wp*3%^L8A0(ns8Tl%C2yPEL%7gn~T9DXqjasb=I>jeU^2eTuyc`=tjUR%%iI#g_4UK=27DYO!iEJ3x*ez0D`k!@NuVSdoo&Pc+cGI$#qQXvRLzlr z`W|=Y9qJ^7PQdGfcq$?~iw`)bDrOejDgI2Nd~zrp-uj*>=u$awvwZ~yfbjp!Y-_W! zNQ;ZWJNn!v?pW8o0V$NAeh_&4UUM>C_~{7hRm?RiB0QMH00yK4rMr_|%@H*G>Cgm) zfV3&>NUDG^S!maVl`2JeJ317YsDw;BFd8mHLnFv!VhD$O=~bm!|D0AmccAc2#g2QhUnv&qQB<=hZ+;7sjDlifkG8dIGK(}?M&09{NLct=q^TneyG!f_t;OmnnT>M z3s-0nEOn9|H-;LQeS0bqQCa}e^oU-j;D8-E!`|;0XI7%$t}UpTT_d7HneUW4%j_8- zSf{1MY|o-?$jH(rGNW2)mLakj4?^EDR$RX=KIk#kMSjPq_j4!?@I7_Si6UV=I<7e4 zI4BbT{T{Po?3Hi))zlwrE=L8Ll^H`<3?R@8F#u-&U=sv(G96D3C+tw2FCZ0qS(?ATwYz%q-V&iZ#ZI2zHmyfGjGjFc(Yi#FhXgQ~Ew5CM3+AU|8`Wdlv{z?REw zjTyqS_YOttzj=GW*ayMX7<`WN+8VRvZbBdXDSgqOZGb5QuFcTN`2HuIw;kB)tpjB@ z^w|vTeorm1`}xXv9&3QpQGY*GU>sX@t7fp=a5{TWHQ>Hv`|OvYAcfjGI{tEOSc-tH z1X6*m60ltLq(Wc!Uteb+1Kyz(k0Gh@E>h!5zoK)zRS;xP(`Ht8<{Wex zh!{W7Oflj@N@fHk-$0j>olH@fpdrdrC=1mH?S5$z4tg^^1J=PHpwz4{?gAusI4ca( zG`b9?J?|l$_6{=4S8V>to{CqTmiWVd;fzrRk1*RGBjb`(X9tRUhCDh~GMV)Y*Exw!&3$Z%ZY--Cvz z6fK=ON=d0pIWBky5@nl90%(&Y3=GIbDAoAChi$OVU>*G3kz>VZG&bTOx)12c!b_&h z_FdZanMn!5Gvt4b2gt%#S65CgOW;KR_y*T*%|ilaCct6u+PNt6rg5f+VJ-Bw61X^S zy9jv57`SA1df^;ZCNPYVTHtb%%d@&{X8ldE92U)6soNAw zvX>l9^GmZBxnPiFNPFE%<=pN@kfJSoYW#HvmQ>E~@94BxTpnYujV0d4m*SLqpqebD zIVY7uZ*AhB=9{=c@ftZh(#|$W)82xMisv$tG(L@<7s-wS*56aBs+2keXD)B4jTT@*wEl5c*8PQ28*+CqhYKt zcAJ+ro|lFy$goqJIw5Cr(Dp)@ZLaQ*6mvOOfdrQ!dPQ-#Xfm`L&JB5MxRjC0U9?*( z35%`%-y2gq4y=U?jrYXX&dbVW>`Gh08e1dgg2{Ak8jkp`5i&uEKUG6@3kpieS(=BW zKtpLYi$msdg>F>=|Iz#4cRK~Eg%ylq{AgLX%X83FzwCtV<|fx#+A8O=z7~hJixsQfdC>}9S~guc1_xumx#dQ^#-@YEY~6UoWOb%-Dw}$2MDC# z4>OSUhQB}~1XPH;rX~{Lb3yqN_|H8Xgn@s82^^&1$nkv+pE-E;(E}7oE|0@m$_3!? zes*B;L^@*%UJvVc3 z8$izUbb)J%kdTl%c(Mmmm@K+NUg+>x5Pi-S(8F3wR$&C0=VQFRsnVkz8XQg^R4gHi+Yfq2&fspg)d~iOdD}^zuJ03~- z9K6PO9$iM=CZa5ohquP338nbZ4m+OUfV&~u-`W%7C!@v3!UgV1D^jTst-+)T$SaSd zo;6Nac7PGWN}c9^JGB05fKW=N{^w8g=c)+AtuBMOK``%;4pFMZyoQi-mxiK+! zzqz5E-aLp_zt#WFBP~USw0|TXF@MjoFsYOJ4fPZS{Ud;`twa;YlTlfPUrFt73jGPN z7oKjd?fbrb`5>8w7cHEF4uay>Mv5Xk&?#Oyo5#*K@W>G1r78akC;x270hS9I-!YOM z%vX+5amlre<&!nVx@K1B+&HU1gABwiwx12Di zQivs*4pKD*YPiD%@ouLZvn`gsr!c>*K3sZw!FkuedokvZ0*|7VPfEjO9{)jUCd}V< zQ`Rmyw7?Y_e0R=L5itJuR*Pt}y4E8(i%QY1^tK?xlIMaIZE}2{Rr39A^+=CoTI9P_ zMybOQ=CIl1hjjlmL}@h(>X{5wa-HPm4!HM%bOQQR5EPG5-vw1+q1m17xkf8f6@jO6 z{f|7=uSqp=$Fh~3i#1>|*!y^Qk^l^EF~lGC)XsXS9GA`$%bi4h(XawV&p?6Tg4=8ph391!&@#& zZwf+hZv_;-hdqo-ODMVoIj&tRVCNhq?l_UJcf=IF`ilxFt*F-Ox4LFNmj7oE5k22% zM%O1MO!(y99cb3$P6n>2(~*}Pz5v|NjsSg&kgnd{<+z%KtQWlzdj?HhXDEP z4`?RO7HaF`Et!5D5~xm!ppFsjqYYHB8Mm#%`&pft-*3hXJMDPyu#BfU-VaiELLkPV zp#W$0E#!zu{DOp6RyTT z!Uug2@Q8NKUxqYkvnw;1rOf6?rW($DX3~6m0I4lEUuzXrfxw0 z&|7rzE%eT3`dd$p%T@=ZHK9z)02>8S`_9c=J>-ru0T~SRW%6DLNipn#0X$<7Ik(EJ z81!9*J2gp;=1b@nUlT;54dRg%v8Ls}D@NGUn&nqx{FKLS)|926Nzk?!Xm`GMOGCXY z!*gjx+KJyef7!yPYp%hr8c@6gnL>_uhT=xQZ4gED+IRgu10b~(+tWmNU87-b$e?np5yUrOmJv95D{ zi8Bg);X5DYk;ht?kJ7SZ$tXl!0nyQe&E|&;j^v4ys*cat@o!+Y^#{KH<6YSQE`h#qKMMWRxVD;vn;5bfY93Ot_?|`YNR;9wQt{ z^U#OCY52w840F*HJq8ccjz%%>nO4>8k05dyRq1W@t- z2@9AZf@#MKSYv=NdwKKTD4c5$(-k7L&d2blPl1D}Av zanaQaIErz(?`x}M@s{-mXgiv!z-J-8+Iq{-365B20pbHRObHt|i1q-5c(ODqF^Ig& zJS0p4gpi81xO2V-5IOiyWP`Bp!9*@=WRwG+s5NiCl5nyTR zcYoHuB(*-$xwI4X{K<0l5VM`hm4ry*$nQTyt84S)U`Z4ysb@|PLAxBFqEZ>|0A zq+cyT2sLBTok-Uxpox^<*aY{jPbTv}Y4{ez9}G0VEO=lc=yftdIraeW?Af_^qX0El zWkMABENy7m3w0rtcspTQ6oe?mB(+i_$%2z*`fJ@S1=CaaeIIJlV6zAv ze-Bfj9SP|X%FmCCO+H~Sk4*zyRjsYDP9=o3H;f}`;jSUzh^@`@MSk$-+~$u&5MOPim&{bCZHys&u8vD`duId+DxvoZ5t)LfFSB8_ z_&26*bLJ~L{KH3s68u4p`uunPH%C_dCxF}|F`r2L61YcG`t56d=?3Z6+%B66apZ!y zfxtli&;0!S2H+x_PJerI4eNON$fEUi6#z%F0CEDoC={?H{b5T);Lvit#{10Y*d2vK zx9ZZATJo|-B<&@bAD@w-XRp8K`5H8`U{&-yh-Lz(_~-17XQ=BL`O={RCfA~^=R<4) zt3e15h&%{Bru4tm0K3y?=TyM^znrzZp_A6SZzl9J-1ut3q5 z&~m`v;?IZ!2H^=ksUO%=PO+%^g^pF<|RHXNIVxxA^u zseU_ClSGh4E@!YQAlJCyV(X_F-xb=)t$l=@=Whc?xBO1G?W@EhoI9nl58#F%I)$el z+oTd0ed|rAZliYx`LExMu|D`}C<{fM?<8$6(-qQvn>#FK51`%dSF*B2a?FS%-euYoXUn8ebP2jwLGM|y zNQ_ZyaLFRxe3NGtv7{(Icbu&Z6z=Z&`M`h@r@6Ch7w1xr?az5!UbH5CbyqyGsPmvG zb!dm2)P8AYv(Qw5-#!st!nv_zvOisZHCk?ARG(h1c4w?;9s={prpPB*h&JB6s+|`ZUEn_(3O+OcUfM* zrq-#S!n5<>s(Z_YhA`G_tvj3{ja-L}oQ{|&<@7u)_nsc%J|K{PA|!CwiCKuHlZyut z*qUX)^Sp^f+(ik%!`^CgAd1FSY^~u)Mg}bF%1ZvV;*1cl+jn`Dl@$2^&@r`VbEzdB zWeYn>%J;KuB>8Egr%Nm+mLxEoOidGoDUpPDo_U!lwmTAf`dEBoF?!)@n#I@`M^f0S zQ~q+636})1dM=&wX)FUM8fzZzk223oSO#)Fbr6Z(pH`oO>qaLG1+CN`@BZJ7ALvL< z?;g_W$H`qo>Ul*k)6Iw*Tk_$0BC+&3dAp3Dqsjyb(QH}T1T|o5IHr=DjogN|d=6%k zix%-9kvf9AT_wn(k&Cm4K?CfuO^;H&=#n1FavlhvcK z0}$`QMF_MXLJ0@+0JlzVUDyf*q&mMeSNanZatm*hyU5k?#`3HHNlhz{F%pcHOWnzl^+b*4R9=*ITD;q9B#vze?T=bnMJ)loqr9jeep3 zO`qRC1NdAvLt&_iUqctArwUy>>%05}(wCP#OhYKEY}K+Y_O|*T=lrJ)4lo1?eMvDd z1tM85H4j}^*r<69#Zq)xf|e@oiFqT^C%TE;D_Rm0BpNjL(L0rFfqHYS4x5x6CyiPN zYky~0?rn_OSM525a0~xS%IO&rb;`!Su%LFiqiJ=q3^|%h?R+c=PKA%^o@qe=RYs+p zXp%bC#=|VEn{Rnk*tlsfoR|xwu&M44^MW@xw3>ln7nkk-Z%$w%?&bLWJSwQC64a(}e9!xqXTR|M2kw4yi?S1W z@mq}sdx0EPl`mox;AD~C2Z&cSZIc?hPwD*6W+$Hf9h6}c&_L>|{V_oJN*{2D9$#E^ z82n2wiGT%=o_{9qJKU;{N1taUPD2A7 zWkO+DnWFcRuHy^|R1k`|pW8`6K>;y^7Si@4?F}Kp`yujU^aO#26_SIfuqD`x94JEB z;AN;xU41ml*Er_MhW!Kl#jj=+0n*7*k{d$6#v%P0!|AjO$RPw%YTfn}R9su&Ao=VD zr(!|17Ja1w8U!@bt=K5^QOfF{j-Gl_0@W>?w%^#4|5V2E--EKl{TYO*0!xw+D%fU! z0*%+^a%z(}%6H`nD=AC()!(5vV0@7OX8h3=0P7H^D;>QuY%PG~13L&i4)DtYaIL0M ztM7h`*Ln>T1VUu!6&$W&wuH#P^q&8@6UgLnB^hX?^h+~~Z&amcVQ3qwoBIy{YU5ya z3Vo5jSc?!Tc3(r9k)bN8Q(5vNADa+g>kC66RY zv@L$o{MFg^Iyn}G{V6Eh%JSh}CBCjIEcqx;k;@o2#n3bPI(0`uDj1cb>O&cd#gm(h zY&kKoCjh8CAWdjfHNr@6mEubdE2`j!EqP)@(qb@|Q;JX(;^{!^PYIxvVKJ*x!CbW$ zpUIgX=>`iGj!`N5{vieVGV7}eV%!cZSY9GB9u8t1JXF5lMH8rFI;4XyYE!&q7q37Z zuf)H6ad<&4Qy}5hT@-VRkg8{pib|n#Ob$P-|WT$ zs&D9X%Uj*{k5u=YelW09Bns#-NqdRjgL^FB02YWKAt1l3tStGxjw7}TyajG=YMzM* zr5;2eSTkhd^48i2Q6iXDVb`Sz-RJtKDtg1?&e+xqOxk*X&scrjGa0rP!d zuOeQOBob4=KN*L&-=S)ckBTFr)-Qp9In{M96J~FkURAf28Uy#k_UE%RAc}2r-Cn)1 z8V0)OJ7Ck3M!sl7EsV1Io$Au=cz<8htVXQ;pM^@`dm*_%Pu_H~27Cj~g&1d8`~hD) zuD^bxh$W5)8?r5fO*`haj6jussNjDy2A>LQs!)W z-fIIc8+d`(oae=8-uev{`4ikW@=hV(>%s2VDF1sLGXGIu&yuVNbMXXw9!0?}!)>&r z+-tD221q|#k0!MDjKNz1-W{OGO0wPG6Fw5dX_gHGM7?9d(fI4GA2OI7(5{oSYn# zU*-ZEmy@*t4?eApeuB9Rfq~%U(x&rl z*j{(Fbye1yP120~?8ARQ+jp9fFUiUO>-VpoVR+3XS^QRJnNvT~foW{5qH27Vbmx)h zwH8b7EJreh4>6;loTeack4h46Vs8SvksOZ>>n8>4p*#BF3n35aUn@*Z5<<0~WvLUP zF#KbKymP8+pO7^mCOmS3-$oUgKHQ!hjcu{>O}~Pca_D4G^KAO&`30cgcqY&kV@ool z68nVMzF~Z;a*1v`^szn#8?_pFIfT82eSvPlTwYZMTLTqeR%MpnilcZ`y&MadBxD>+ z*0z68KIT#LzKsd%lXzp&R?KetZ2*I2XQqHJ_|*>$mKTvfz84|oZR=LPFuwDAdC_n4 zv&^OVyz5=Q9N~rnbv+%jX1PQawHg)ESX3y4 z)sk593`h|mFZYV8eC?IFa!;(pFnm($K+*v6nU^74?l+r}Ol}}xm7g9l-_(;UxQh2P z&eCQLPayO|Jb7W<>Ut;)2?A3vFzzUxZGTV&?Exvd>xgZu|B`#A=fhRwyHWD{jnYE= z0Y~D97+1AU{)}O>jXt!*;ZFmW?ZFA+kNUs%Jev%62i!ZuqKn7af3@!HDodBIXEb^Xmc?Mj)hgR20Zjpw~vp#RGLMQv3{2H`kpoI~elF*s&Qt^0iJSrxnbL0+ z&b@N)#l*9KzV%AC_3)}&+zg)dHJ&S$0E8oBIGIRh``8PxTtJ4mJWbk=`9zUkl1gr| zgf;vj&~hZ{Uj*D+TmxmayvU;f#B~10JJijsOx#n^>mBj_E=cYdVWJd!d!RmhzVi^s z_*TDTiT5sU4Z}fJNcqr*jlJMF3Afj&z^d=0&bo{Fus;3WWFn827uz+V*u}cd=_j>7 zq!0c(!UDIxD?L|T)FXXzi~R3!(4T0kc_pC} zf%wPDmNjQJQ6`?gnVzL{krVxu>@SoVZNMwE8dFXVgHh%#j|L3g zWuap*9<1I1@zAqr0w7iVXSUSbEuCE1nqEbmv>B=Gs$fO7Kyy*L%StV%>T@S(3{-Rz zOl2HNN69iVtusR#=k>S?1|rCJc)Ld*2hWZY#tG6krC12oZPjvDmh~CJ5`W~YAnxVn zG|$j|>}NYeoQg&l=K6u(Bv}zQ02#s~3G#=xeb;A@f<0G5xmIRXu_srxYgR3V@+hdxn_3rrIT{TTQd<=rV z=0@GW&GtSzI7VyGlpt_DEdPP5PQ5qlA4)>=VP?U#Svt2*lWV+H) zJK383S2SB1k^jBH=)q|23*}wt(KpS1Emqj6DET4Cfj^32O_AlD*PWl6aJj6ns#IQm z@}2Ui$N0phiUOHyO2S3_1WZotU7=FtMo2Gl(bDAN5zpU|%M`K$ZZ zT(R^lq-s7}NOyk)#9~0AkAVOZ_!4AM>05~l&yPgE4_S*@Hz6^#-7r#8@MG4`{rBi`xxy7V=SMI<4!9bp66jcrumtqa za*4UVDN1Cx8VxT1O@^2s+T6h&VbYYC$sou>u@tPtEi&lC zwXFtxaZgwb3zH4Ud${)OV;{_^F1b_|3(;Tqb0=*KoYV7LdI>734&2jAB$2P{E4U*O z@HL~##Ru~)+mtrb1Y69Q7%Oj!n^D{wR(CLwm1BK)P?XTlx^|_Gb393ix8BV!`zI4oMad#dxXb#H zxj?Bn9|4yBFG`4AMqykjY~aE@StfAhOIXB`O zZfLR~pP3fYozE3?b%WJJcqpYF{i>&-E1=qRZi9=anf{6mtb72Y_($#Yw=BFTEB;QPDNVCNhEf9j+V z?Mp)@=FCCMR3#8)%pzfkwN&7%en3+|@5R`b;5~Y})&nrE_7-I4W_KFX#%VbFcE_1;9162 z1&bthZbnw75=ZYeTy*Mzsq5*LNa3ED__ko_8Py|2;7Bn4KnFBO>aVZw#DHJwGe`|c zdc20qLC*CXTmiRUtpRHXwga#7F6LENt2q1XwuaoW=%ITOM$_k9(m7Yds4#>qo zO1pg#q&dK)P1y8D&YfT|u5~QCLfvu=^XU`~Fy7Ygo)G$}?PGXUf`FblK1Hm}Xp%ys$z zcVmbJNMl>%AR)uAki5pyL~V0Z)33#s+=yu_;9qQSCHzykF<%R2O}qr+%iD{!-@1s4JzlTqx?6 z-A+mh`=~wW?0^2Ut@>6p-CnO;4UF}PO2yhFW!K|6UgsamrFlNZz2$Fd*^@XL4YML; z#S(t_gBgB=L^Af+~JR$^i6hno6{qYn)Af>bhyo1jU>s+0#rar7cJ)Up^ zZu3(&Fq?_%>ywk+1Ph<%-EN`$(+iWkw_@Z=WhDV<5zb|Hu_}L!3=BSFiElX3CMmBz zJzPDRX%5qG#$~hi_x6M3F!b~36-JE^u9lPt}WE$eP(iiH z*C_&g9^c?Ka>hhLJBiwZK9cc4f?jNHdjXS;{{_GdM7p7gFQ4H1Z=UL4$IdRPI=9za z{yBS}a!1%NYE$eAnuFChT?lx8!VaB@j0w z*M~)Ssb)y#KfGWuUfwWEo_Ar}1`(f97;-29%7K zmcGC_FYfeB>g>&*6VaHiuC4;Fb&}CBiClp-C*nP~`CU5i7vLz;sUa=ZfyR=0gk=o% zDpKn6yDaO&dt}qZZTzAC{%6*wOBu}U{`Kc}Z0FVe$y07HSVeU2_>#{Z2GU_)hj9li z2E1ikv=8c&XK+!hO&##(P#q_CuEz7}yLkw>Tv;&rFR)OML`02Q^{2vFEYs#!?=kB- z@Nj;`c7uSD@X=k4@}xK}d8TP` zRz#ye(iOi=K)R78W)2V|-*ja+W3bd-f2YoZ8L3WtSCrLYw>_bXT|O<>t?&Dw9ypA{ zsSArEsFkI!841rH63$0u(?J`^IZOBQ*>lQ8)Db15|E8kgm?0l3g3)+NU0r)QYAU>u zgF>p^?}b9Ds?GxUmg6#2M-1bbB@b5wCEKfk4XFGMcHgEoYT#3P5Xwd@KypMxh}Ub^ zxj$8h?{l?r2DkE>J3~7D%S~A1`~IFJxt!FjhecbeD5qx4$3BzWxaGl~T|%YzM6mw0 z%KWOWWa7+~^|D#ueiatkYe_(1q~h0T9)U*m3Z4nYo0));DAyxlW@d)W(iTt_Skgtp zjq+tivlBPg-bQ_6C`eQIA(bDL(0+~@aCerl@j*#(6HJF*4vURApc+sn^rL+4as2?1 z?LO&3K+c<*GP|j$UccUme^v{FP1K*ZuVnUOKam2L9%cYVS>U8~WpzB?$Iz+krt#lA z`)sWRGK9F-SL_RaH`>GR6~ovZVe!c2WgVb<2n-&B!CC0>U2&3Q0uUNHY-|uAo^!(l z=^TyEX*^hJIjt2IivX7kxC1i#7>LnHJtp6~FQ_Yo!^0QD0=&<&UGp+LRu9TjliY;C zxw%0d%{4;Df)&3u=}v26a~@HP?_ydGAREs0!(C~7@Bq1d=64JWYg4VAWt}Da;^7_b zXVn_a_)b&p{^R!n*{G(+zzFX4=|&v*LcBzAL>-i-abX7g93s4m5+%MrZ>edsqTVaf zuguQc#$iB_4GpQ!bCL^TFj!%JK3vw<{ECX3+;LRy0%94jqE9Rg=E^a{xogf#__*3Rx-pGF3TvuKTSDFhDbfI%1?F8o*-SIg@?^0A=gN!bc-)uM7p zUwD{yE)|1wApC;xPa;k~0)gY}jktPQvtorHx&-oEs?gj*L&Vi4!BYQnt?iE0!S*JI z%9y!U)GKaGL|nVZ3}{1WWHD{au2}IoueD!Q0^(mGIgW=$!HM+~7b#I6i=)6)J=)Z` zaFE#S%kf@6hYdNvpM9{b7T>=}pagdxMHSbc^omDADxwtbZ_(Fea%(GA8iTaKwxgOK z2{?axW&|B)Slv=tsUlkCjE8?ApO4nyu`s6OX|Q;CF>6sKY3{Pzjts+(%3_pkr9R-$ zq??}+)BZtO_aTphoat-tDZ<5FeuZRq)}k=tNc#}V(m|M0r^LV#+mK4KK=WTX#%*>vq~aV*Dw^}YN*b@fKvY`Lnjl} zA>SoLej4UWgojX-xz;WFQNogtNlH*LeQYO5fgar@Zh(*0;+;HKG`R?paFVIa=7k|z zwiAQl?WeI-WKaU{VSyI?M-3a-ew3hk%LC>*-{)Ug6YpexV(tuO^0~7DhgLTu`Jx7* zvobB`uA7~W1!0fX;ZNwACdyrUr)$jz)zS+M^EKcO{m<|k8*HBI8aI>ma8N|T+kD&P zY*`ZeEjFX`64gM0S4}GCI_ZX?vU2PnD%v%KU`Rwngpd_^ zE=kZV(|tkOV$WCS2GlN43$VQaIVt7L!H5>xIj-yQ$zd&y7h|C-b_Km@r2U@H3l zJs4hlRV_~c3_h%NQwX1~um9>>#En*!ab->8!R>)vUOtylnuMssk}DbE?YrBEK)*Ai z3qwR|m+Zd(KBR#@JF5Qh>Y4hgYDYb_2lPTLc# zq2tvwAJa$gWu(`WaYe8-FXENk?FO!cUvD5mGseEZGsWkxuu9ty&u?0362qiudRl_2 znDWt?QG@c;2e5^Ja&&xR!W{KZiy0pqGxGTd4<#=z_ z6J9F(Q6~<5OO8p7o0Xj>cVIQRc$eA`+Q&A1GJHFZ996O}b#vdi8Gl#@nRP{?_`fx9;~+*a0E?#PDmrpZEMK^H zvSea+O=IhWOt~_kBg65C?ThF|Nz)^(?~#`NL+n~j`#p4;orsOO0qU(YUKirqt9XKX zW4K1stl+l2(Jd;{I4*Uh%-KfQ^%9|U2}`-Dj*6H{s$jYX7xfzJ@$G%o#s;DQky0NW zy^NqXooeFmdVMV2qnWpx>QEw8M{Wn)Tmsb|r8GRA@?Z;^9>&@_*1t(ZVre^JgXzir z;dmPGLDBjR!=c=Bh#&1VMwNS%;)p+JNKd}%UFVje)7ZtKa5f6l#mkj4JXD90OK61E zpr(Db@1aG3$Z)beB6I!cVpt2A<$bXWcj~rB?oGqeZJ?8)6&f0w!b8%SR^!aeh(UF* zbMptK;sme!1V=aUbIvBVt2wgScYh|gweDZnodhop8%uF4;q`@(I;mM%?s0Ka+%Rx} z2O?e*dgpAd8nh@HakHfh2;xDHiiCvZG-zMF7N{yp@buFZPWAkT%l_7l-1qRAawO&H z$xj=JNwd5d*O4Veu(Ed|??2en6%|c|x@I#bjs>}{1L0w4HmyNqx+_6<9q!@~YI01A z!DI&gpN9#+-d0+`j|OC+0$Tt}rEO*ZY#ytaX!Lq`Cdd=pg^7ZdmO%Z5Ht4x8udebN z8i>H^1Gt#?&8oNE{X6PeU8UxI{Spy1wY3#F5Zi zyPn(w?|&?SVeOv4NcpgD)W&de6>ZxU|I#MKh6$f@P=6ly99mV#-y4_oyha4v%ay!)t@z{n6L>G@C>uj*2Tg zG*se3X6zLueC+(%`b#W(S@+~bx$fV8FsG{gg<+S`@h(!qOIQKM$Z1<&wzylUU>l0- z12^j)W!s)Vm>ZR_ZTEmRTuR*YYTJD`~W#L16w| z4S|>+xXTFh7E^a#{8x(N8IqQ1%3ymc<~oL1QM6(>PCXV*_j(+XM{ZG4ASXD{`c{Lk zoid0CUbKn~x}vkzFZWGZR?4X-z4T`4@RwvYw@krePjJTEyH^75hi6?@ydfWc~{F>U|8*_BM1fLkJqIi$Eij*CJ+}s#}q@B8~;lbo?4u zIT5kYxF#5)Aw63_XBEJlxu`c zZVRNU=6zO!;1G{GkgpARw1E4R-_k;M<3|}98VUvuVz5MGG~!sBKd6%B`P5s*dEDKc z@U2I%Lkw9jU{h()Yw{z~oMMp!7qN`1Yh4nR*}ucNJ}-3_Yt^@3HCdi#s;etNiY8w3 zWX30CpkgezBD;eXf@mLdG-@#`R561gqdzgan-|{qTu;*X)cD=2{O!SwW0BvgHmp!N z-Exsk@&!(y^jxJFgwS^#RAWS_jno;Ty0kLIL|8#MC*BjLEHV(T0UZ*)$gvk6V)1%3 z|E|ikR~-m^N$RC!%r)$c-k7*@u@SCTPVR-Q3U<&VdPPXXof+M>scTI_I{XQ;mo*DRP?3A5`Pto7E4Z44D+PM=4$0t_y!3ATxgI@Km_I?D!EJ05>5PRVSmsgqkH@b7fYDTkhT9;UKPL3j*)HLsv` zvA_D&lB!p2o$OZl#$Q4vVP0>N$DTJU0{>m=|F)_`#OPcU*Gd1`5&nN%fB}{_xjm`_ z|BtD&0IG8Pzy1N~P66q|p*y9KE~QH(q!gsP4&B`X(k0y@-3=ljDoA%omw<%tKKD2O znRkY{mpgZi;XKdY-&pIj67zCG(;C|TIMGG3I2GYNQ#>$vwoiV;@k#aP#Hd}R<*HsV zT654WYYKeawv~A_31$u1mRsSwNM)N1?|45}`IVTBP*5Sdk1)kPt;#fI&Wzm+Cno5F z$;A};H2Tjf5*hR3LpcFtxqngdM;y^qF)BO7p2IV$goD2esZ9?b)ffbl(@2xB+YdhD z+I2eZJIW>z!iy-=oM`mt*mo`npW$s{DA9F=?WdW<1m3S0r$eM%R+pQ(hOquuSN3ca zpBs_M)o8Mm00AM0AGXkM9^Q~f-2Cz37(CEzUmu^k!y)^*pY^zqy6s9^oU`~oyf7Jh zFzy3gefFQ#5U3jA zHqZSrC_TZQmH%%;3K{ari;ACt@C(OfZ9W+R_OO%Q5r;)HKjA-cRYl-Y_jUQ*I-RUa zZ%8p#AMNe&DjDR;zP{S=+*sG=9^x;3oT7YX@*^fwePV!t)*Hq2@b z)N+6~{m=1ALQoJASR5YwYD5Rg#9)9#PEP(TAV3P-%sj%v)`=aTVm|B`L%v|nW8T1* z2{IonoCv7>{337R&mn!#hXAnHm#sk&{K?CNaQJS@##oP*FYkNB&20e>FD(F^Ed z(y^5T3QcZghklE2pZ#hs#7KPovkOsn`dT3c;i8d_6P5^#z#H*jLf(mqC(4*#yd&9s zwol~dHd*Bhet2E;LJw|Qrv9Ga-iML{|nZ0Zkn5mekT>iMQg+N|rFQ zAYTh-O6#v>xMz3Pc6I^-Mq~F3or)v<;o?eY=;(2GqT=+O7h1`-8Z!b6U#PYk)@IR= zky1P{$pklBT!L<`Lty3C`14T@kA}nfqnAbyL8}Z@Oa{uTvaN)n9KA!-fxIH#n>s`b%z3T|~^MQ-{^MfdMW49@(ba z7h=2&VWorgkG5fI*(K%@ci=?ia~kTfzne=-yF5QT zy?mxaAN+En2@5{4U*b+|s%>e`IvZowJW;KyDa_uc|2VCNHS>KzdBlQkv{p0_Rd->|_7H2)) zgG3woQ0k#yYV~{jQJ)3m5BxmKfHV$KWB+g8fcPMORqu=TF+!7MzJPO_L`?*>^~ixr z*a_nM=b#tl4aUhqgY=VY$v3IP1`3R*#P@2z?7iw`BbdGdovz_?tZb!xFbrv{L5xJu z#nBVLmY#0?J08D2wCWywV>k5EfHxhqe@pS7y(q(ZLRY2GUhtkWp0b$+t>xT&TF6Z~ zt{_l=;J93z{q;F0x+DG&F1%nf;h8kkMD|*Oe{&!B=Mdc!1UO{qMYZl>T8W)-<8S2J zDeuLB1 zlH9=5xbWB|Q3Rc>^(#h+g|5QpHV@_#%9zQq$o#-ome*L!I%ma@a70vNUa{QVWf*hb||)IpJ;oTl3mIVEo1?7P&CP(&iq{IKxgp8~ z8os27twi?2wy$qoy{dXhD`|WG7$%u(Sj4?;o{h?z52L7P3FxI0+uTygpth`}k zPikxkXfc0Uto60yBm-9a@|-3WRv3@d24uYyKOpnrw)ugE_GUvdRviC=7V;r0E6xR2 zE19%1mCVjegxz)tzyajE+JgkD9f}+Ak%gc$M~&=TV73eoN7Fttn-9xYE5(&*YKH|L zEHvW-_4Lxx((d7*JZRzjgq<4%(w>tJGam(A-I>(~67L0izwLPE*}W(@sjR9t~gO!iN?mcn#5xprwN5-UyW_Tw6_j7ait3YYG6 zXeS9}P+Cc-y!;v*so*9p)=aLFb3aCh1BWudzG@oZ8Bn_@LorG%hV76%;ITwwfF432 zqY6wzWJ%W6(vE%~qq|W*4eMti!3y6c#EXdY{$k0ez(v@G?=`{-+?$mlA8m$wwq&rY zks#sBk0o4{M}9Rs()O+K0N1J_hT@&%nr)m^Wm|hYm@9#H?1 z5)jZy@%|90ak#i6rB>~6pl%u4WKB1k=CYPiHI_iy;N`CYSau!oF2fM1=dW z0WsWee1iO?qLyKdw?Uwd22C0}pXH5PhNp%0jZ0LQ?oMl@W}LplK_xapC$iPKg;Q_u zm{ zXP@h{jpAlseDxZyM0%Lz8-rKnb+4fc;_ygbX1{8aGeRqW1O$x}PlmaARX? z@EgS%QTM){0+Et`BnA&@$;o?qdLR$i!%~HnmDs*lNAix2+#r_~81kjX&x|+E(jslo zR_U(qB#DtmMiprOgmt?h1*HrwY6mH)Kq^2liTNku9jzqn$L_`7hE%;R!*!Xg8i zrj@XuMvzq#Qoe!5on!uI52vSV?#@|W;|Mg&Rc3V&Q`p%qzY zW>XzbjwB7L(NLp61`R(LiL+)YQGJM#XAi}xS|R$@x;1cW{(Aw-e=1aHaqD3Raq(~~33VHTfM>MaZt)<7}t@f{hW22F0Bm^e7Z1hD`FKt;}V)aHMA5F8X zv_c-gOeKV(@$jV*1_f+e=~!~~vcZUcyiJn|c{U)9&n$m<;-u?AL)k&o{+Wqg$K-KZ zXs*`QXwTpEmNDOt-%hke-K_UFsMW2OFQ4}_-UfuiPww(2Q4mV zOs;3zVH1gts#kvOSlD07k|NxLbzQOd;VAEf$ix)229}vPEF0e)j1h zTGJ#Yz&9>zY$OH;GWb6VHF(eqnF0c!i0E6ZlU~%iPkn2?(&Z=Yv!Qhc&@=d*JH4oz3&0h2oJZ)U=E zINYmq(KU1^vx7?5YhRn0o6JKQ?!o<$S7{%}jXhHH-R?2T9gCe2p7M(}NvvJwN z;1LBsm0&!&`Cn1)xVX>!BpjCOkl0n0$u8h_U^d4>5{ytO`E}C&hVUdeg0u>TD?D$N zliO$+eN7C`-`q<9scwq^7@aloVL(O_t;fll@4;@yeQ89{JOVD6V96I{$%pxZQte_H zl%jW>tFHdV!5BvD4NsvmxKu~9A1^k%#bsVN(aSvW=tqfvYYg%gcRI0%@D(p{5)AGj zp)d3LR~5>|o@~*vZC5q$H1}YEj!cXvIKJA-pnQ6BBvQ^3xveP?sb?4eijLkO45@(# z7nbRez7Ra5LA0(#w`O%PUuT=%>|TuZq^AzJY$XPXLmzF)!BRbjF0;1*vA&C?4=>h2- zHr~^>h>d06-OYL2z)!GU1`cabOv`C&rw|fhu@I#LWC{b|E16&4n*f&4t0@6|A79^k z&tn7~8}SUz*nn|OL2WHQIA8!b1#MInMv)Z!-2p@}feVxuth@n%4?NOjjFnq)lN zX=L68G&TF_(O{4LjtnLy(xRH=Ppytszm0QwdnZk~`7gs!zt@)ejpR05)n?C~bi`3~ zM3ADdqI`9xoS{26KHEF3xOa^gEbD!=LB7#Rt1?%VS14K&{N3T$ffY{rdNNAVvxHYS z1R`!2GauFDKX%jh)HN#x?D7BToh7{tAxcbn2BMvD*YsutWW8RLXnlP9h)m)9MjRAr zh@Bw~6-;#G7EGlwaz(y7mX0pE8$Ue@!ok7m*9o#F|RRDM@;rV>r=)H zueX~~nbKhV`JM*9!iO2_r6uzlq(6OO&kt}7VlX{mDaMpV(wsvE;ZY65EMu4yYJI=I z%ZxZ-+0=f?Ged3fAiXfz5}{ww*UGEt(3Y0PV$<7V7SqA(Q+8UlFi%(SC!jrwW0)`C z>R*Vdo+a!goDwpOgoO{!)EU=bieAJgxr)u#X@7fEYB(jqeQW>c_v=LcG}%oVN53dL z(F801l$||Ilxv`VopDgI(Q*6@JMegYN3QOGJs@pUgv7vM-jHQE`!;u3bNL} z#VGsWjC!YEs`_Fswg+#&YEl?Q6LDB{Xcf{yrf+^((+`fWMx?440qb5m6Cena9W8bd z$GCfm+CzW`U@Ktm^4zNAwcI+Y_s67kRnZ)wv82F4n;RFZV)>?_E) z=hl{*eQOl0k6y6+!OZNQ5!%VOOqwi?QgtpTOo|n#iA9khft>yFnfPN)MoztjwNQc2 z3)0-9C*!z3Gs1u*zng_+xprTd>OVl#x#VFbxC`Z$ps7nrk3{`tIl%|~7D zi&Wh|uN@Mausc+^6G0-NK<$B5G#O#eXek_|UC%&NIyoI3h6m}fANOwRH=%xeB z|NHn@5z#3L5t`|lnmW$&0&zYM4-bN(FB^eZ0B&z^z$siOga0llpx2(Gf~X|F@Ijv9 z?FxC7n{I-_MktN-7@{x`xpV0>jYJ;*iW`-*^)`Fqi-f{vyuSnSFJIzeq-JhMl*|0@1bllt)W_35e3kKW!%|M`}14bS$Ct=D+?2C?Ne7}agEDzttkWN zc5erK2WC_K)PKQ4@u6s7ZH+6Q$in8GTzIe8I8KiJ|E{AI{H= zbY;-4hJ+g-a#c2F6v^QjdhA*&YE!G#BPa_n2ZOMzWV8HTQU7?4`SD4pO^pWonU#g6D0&+-ZjM}oZ{4jvv@QKN$sPo*F@<(f^&CHr^? z?TckGiQs0uuX5X1&UKH{bl?D_>s1!GVVoWDbc z*>D4&){eJhAoLMf$L7%@|4_ARj>_!4<&4>C;a?ak_r!53!HxBAYRHn;i_f&lY`hAj z<}uIms{0hmLqn#6vDJT6{UBT$5Q>NCABJL7o*U5eCkKlW@>NK4;K})ZBq7G&p2y^H z(bH!Pt)4lN>X6dgYIUNMM|*8)f`g^M1-nbt6+1hhhFX*4y&@dQ&k|?SDJX?BL3rV{ zkHhd@D#%;DujKb|oVE>GShG}Pmo9OAX;apu(krW>eA;LEmP!Gdt0Wh3qto%OHs1W# z)|)I98tNqe80F!O?v6I{zA=S^44e$R0E?VeCqHyCqTw^^f$2Mm<-vizVj}){7%&X+ zwg8U{elrEvyU3+>PfBDtKpJLBkp{S6@Xh~5>Cbt0fkQS~s6Zcv^ztZ8DF7<6b>yyG zh}@4t$vCdtRQZ=J}u($HzIFI<91hYiB8fnzn!kV8}Qg`z6wD#Yu zi?}&O^~s?fW0W%SQpdzsD6EQ9<4b=kPE$5uQO;ainqRTr#heK_-CAln9O3q?Xy@={ zXTGCp$;tlm8G3Fd#dykviYDoKF(xmqD^?+?dCy0Nb<7_}N%-&1@WJFOJAMR{Jj{XL z+jexnb(QHDKW(*$2&F1ikac_H96oU(baQ>))@m?>D#U6zB`i!>(PFPQh^JeF?N2K@ z5vGZ!2c^!@zO>>CCT^N<`0YYWH6dla!C@3ktl7_YkqkS!Nf;j$>iWhnn>IO6p>9N1 z=)AsD5k^{Wh-rR>tU1VaS`iv~`9~%~o1Wn@dg1xw4D*fi6U}LF>_Bh7kLPNu!f=AB zF#J7T={zfBN2skuWTuSb-V`XnvcKqsC23*OH*{3wDOTp2;k~f=v@z;k_LW$#E3=?ht7Hylebq~ zEOWS#P?m&>;i10hFJgEn@PfVy(l|$$_w-I|IBHI_a;Gf@`c5SLPAo2_2>mF#Jp&^{ z!(2gMpUk2CP{?kst~WBE6Mo}j(6*oT(Uj zt%WJzg*LDFQ<~n4=_AH2`_;|sfWKC!`ER+?x87k%6o7{jl$p6MKe6{5FM}uj|1=_4 z%ypn+F!I0I0-K^hfO7<##?YJd9SiW6LKyQkSV&F~)YM$xBSaDkFu+U!xFEud%dTI8 zAaKXMoj_fC+I8}TJTwW%8`i&4hT*Q}qKcd`zd7sL z@SeD?Lqa)N#gPC{xna!dX|e$7>$AU!9?DPyqVL&sTVey=Vsb|_f-XCvS8R#PkMG3E zURp-dro~mXLJN)J%ilef=vIj4am!BNpH!xo#U?CvqVpUdKTWjk7;_z{Nnn#!+G6b) zS9+y8AVllAXIwxecx||Om8$YQ#g*GW%|oRyubFjn^zRmxvsv6(`_x;m=gPHE8+5W4 zI+Mt0Z!u{fQHaK2Ygs;uOPJl47s{fhCpVZ#OA{_28e}6C9D1TB

    zHL@02ep=^*} zgrrqh=4QlpikC4W#g(&-R4-QQ$bn@|g;3;3>LpsppIdIxYvC3~Qs$C)IKkvtey?qI zGdRZDV-p-^B1^Pke)z%A7#peiwX)CVn ze8M)pZcQXm+?;G2>;ye~VI>+(LlLlS`0c_9z!40r+%K(|0f0Ax*bU;* zPXTY6gv`W?9s%<;2luG$Y|S9hbw`bJwc~`zAOWr!&9eWkz1?yL1(o57t+>Zby|hXxV$BpH(QnHcS6RdTE1mZANh!WJ#2Tq=zvJ!a@GaAGIUT*mPuh zE$8}A9Wh_k{3jyZGD)t)vJSMWGn?3w`~o5kCWhUY+{f6u7%XY&Xc|M0Hincm4|aL5 zp&oVMjdw0Jo5=2S;Hn%=(QKNPk0aD?bxeKzMC!NU=qGY>g_a5xRJFwK#>Pul7QZ|(Y|uewG48K zfze`P$#Z4!XZ0(fHba2tIbVIw*I+@=#^UWRZr}(U(e(H4C=i1NOU$m5Fz!_ZYct1l zISSCQsSsQ-kZOVfZV7+~T;0xc90I>vTzotp*c)1Z2!G9EO(DAgn4AN|>H~lb3V|S) z3ZLzM1$T8Jj6w|LIDI?ky~kJJoA?$2#;uJK@<|# zlc{FGXip02N~nbY*a1JT5(jrM497nXX6bFp$opj{{VHTgC;X@8VdT#J+PNAs4mbDV zM*C`cUN+A*3Y%lzc3R32e75r{%R?Do@JGl%Ytg$NZssa~N>J~dL&F%oYs=-tZ*qSo z>zWp8ls|FYD^D5UdVYnQw&kHrAGA>XLD748{}KxHNVYHHX=}A5XLV$#ew1USFy_fe zJc9KhF-Ry{cIA(v{6)gXAs*UF=67+qvQDUE_vC-onZ8j$6ynttH>&W21@j+K+3~l1 znIDRKH?p-Z2NkC{h5Ol?tE*Ro7(DbA0%bzdEtu-uoZH_A*FCwBy7RU&T?4k^!qC8_^NNEuK@>bcVRgkS>lgKF zzXxHj3LeSV;>oJMy>Ja=VPc^92%*!j|ch;teI3D_@r>N)5e~&&gc=Vlbfy5f* z!z;pwq$Tr)(IroifTsZ!!REq2e!cgtL?MF)Vr^q1jSv}T0FiTkP0d$fDbFJ#0M@y< zy0UnaWOWN|1E;w3>^KQ9B-6>Xa#YyPfA=-;ZcjCbguwFY3T=y7(ju4 z432wOs&rp)mIHQW&8Y|pmh`N<;;ecmAL`RZr$-2WpPQQ-Kvlm6T2VwSg!3q4`g0Yi zRYPDX2J}bdr_}b(n0n6pQFfaHY?#=|bdPw}pKwKC(Pj24BL?$PD26*Y`2wwuG2QC#A&M3Gf*Bw9Y(~2x#?osD8+e~bp zvtQ6#_CZ0SIjpc?8}Z^@=xkovwUztI3lyNnKnR=e{lQmCI?gX8=r7A4mDIA-=Q~k- z>^A8}5Z0=^uB?Y5)>oLX)V~P##HyO6G znT4NOoH%Ku9iefzhjgSqW%y0!mWD*cd!S+Fk0UmcbK=qZXp>h>Je^noa_RN*hna5P zm)71eLS5quk4;{&`VA!lL|L`VI&+G5`FGV_m;IfRbM#o8-X_ns)(pX{Mfe1jR!7;u z{(4;`QPVRNp64227153UaWb1cA1LWPAb(9C=lPxrvPWQ>oMJ$p`Tmu&k}$d!HbhNO z>0UW?NpUX%bqyC2H`Djp-!?NJ5g8zmz(?qKs}oOG1^~@50^H4;jbO~KLv#ji)i#rh z13=_NGn<;3u?S_i0rUwVb6)nlGS2pxx5*H7X9JKJ?`;3Sdl?eG9=byNZSj7$f6Tx* z0r4J)=71tefKVE6PJnvZl>?TjA4M9uS>VI~q%2^P072Xr0Fkv;5J4j&nWqRa<|cq` zB>rd40{o%Zi#w9~x>Cle=*(z0T;@dNmR^hy6=-TiQsHDa-Fq|3>q_0Z#}4T*B=0#o zHK@wj2a_mrCO+NIrG`5$rQ*yZHk{|Ki`qRZy-mv82z*yXoySC1jDXG4B;G>JC~x=?+I|JD_A(!<9~w(XZ#j&Mn(flZmPi>_5D z`Z4}efLRbz#Y8nSkFug!vaDaf)+8P54 zrGd}`Y?eRu%4}T?~^cVSU^0i;7SXS%dJzkXHP)jK?>rtr}OEsuT721U5-ZgtAyvfri(071*zl z2mgM%wCa$97|d(1JL2L#F@G+m5f-bpq*&2FPBaC=^OqF2#|QehHbyaq7BW#3_!1Wc zUnQ=LKmraeqO$#DGjp=&I$4l@So}Hoqm995AYT7>y8?tPVZwXGDL@T#S_C2@!GZ|v zL@lP4m+_2er+@v50>^J3_{oCZ5O`QSJC~B;Kn0JWoJNzf=i591h5PAlQG)s9?;pTV z9jQ=+K$$xC<37#r?4$;oWkl%@f_pR@Hy40>8T8B7pch5VV-YXg%}(C%u;d?J(2?Hl zDoXW%s2yH_W&83$5F6mkyZ`>EomyEjP5EPNAbVu_9!AS75(Etr5fHG1nnz{m3|{SA zDmSD&gV8friHM915_QcOHc@_97zo25B7&8dpDEC5rJQj&`3m!XT_}2ZDkM}0o)18x z0w_f=0hExCm~yAieEw#@;N-LS!y^kk-~o1Y7%DkDocsI+_u=0$99^HMKsnrZedC$M z@B;mHewY|!7#2i%ZVq4G3c;OuPVLz`~i z?)B1ziHPKW=T3tRgo%lC!E;WozA=PN^4EqiziGxQ8L&@-mf`S`Slqyq%WS0e2B;+4tI*=$559`Sc4esB!Z>DpiSj)$yvkQ!$g_ z@n)Jui>|s`s9O8CbzZdP`>D(1Y*fno&n}I7>LI2Zp&M4czf%%qB$&cV&E~MEr+1ZZ znRzO1mbWk3V;5gL!QknYC>6LIKnzpH$rPI*Z8@+b_0Jnr7tgbVaF4rgxj@kziHLgg z)ESm1GY$n$Bv2qO(GkQ0ho_P2grG1ueG6=!00kGX#Sji60p}SnijJ>uJ0ovZgDWUl z{;SKseG5iB$binxhrks=dO**b;OKvzb^Yb7WXSvXj}KP5X{W78^o^XulHOW?3Z`Z6 zV-_M^V-?IwaJjm!%@K2?p&J*3Fl4VZFCIi@P=jB<$;m0am8#7X@Bqib#YHIX(@p(F z;F7f9FNAn45lrE96QA;;zs5S~6b)fNNmi;Sl+{_?M$W#C2ak*J2!dKdZzI0x?4V{P6&K<${uuL8V+(u{+`@6tJqAT3Cny zp*JL0VT5AipcG%_Ai-+++)Cjnen~=<_m@Q6gu9CbuU{K#7`4gFs~jGZjEs~=wingo zc|LxVZrMSSXKBF39weLGo*lV!KI-{91?ZPZJfeqUQbyR+p?fd$p@}#1o95^cxKt(z zL=Fv|*W#~RQ8hv~|Mcl2bo|28SpJierll<^-q`*b~!V}64$F0f7wjJaP7NS4xJ@#vf6pcFq>h7@6yrIjL|Ip zzH#if(9n@eZgJ**bU3SK=PKMtR%>$uIe}zS$3i?ee~13+Ls6m)=%f*PHLl8nf`W<# zO~Q$dwN|=-*wLj+w)SF-brinl0ZYXai`ViO21&RUylPtqI^KK+QRqb9_QT^ftyxQp zqjOe?_IPH8Ws6R2FXDcB3wqt^Sv~JlVSUy?YG%W1`90Ktk-i97n&AnO8*bgYM#&40 z_6gm*!+dDf4W28FVQF?gJ$;nxUjVTg!+cWFroe7J(skmh7?O`<;H8(E47c#BO1-9x zlvX4;HBUadl&8Se5LbUsx*y~4iA+kk1=v1!mmlTZiVFA{z(k&GyDswL6;voZ`#w5| zN6q8w9;vE)kYQ(5dF}Za^X94Ha>`cMF%|2|K4_FfB0ypE4*mbvN&>~CQB6x0Pr58u z7N_6WwWX`&esKCL=$xD;1W9#Bo^&<~WSxLVsjW>E zjB|88S)2!f8u3WbelpNoS4*F^ zBE_Ek1?MzaF@pmelu!Iy6waEy;)vkeP9MR*q*m^0E`McYGAvYJ`Lh1-CKMft{QT%b zkMMnVcF9!*fgqc~kD~cZ^#Lw#Q37dYzs&*aKtj2?PsZ}m?>>YBYA@jUu4P!nO9NL5 z{YX*^FwOJ+Z(|75$j0p+X0tWM;r3d)NgGR`S?RuC=mw#7>^va3Mfgv=7=fcr?^bWV zOD?dLg3SOOK_GBa#o^}c&=0gk(tA$1IyLBGDJ37ghvMc*u`!IARMzRj=1y7}3q{Cr z%&o0Qc8ML+6WFi1)|Mp%jvM}ce-B2DJ3)`Uod4J@ezqobm~rp8X`KY)S+yQ8{pAHs z)U}BZCOCW6FT1Z%FJzE%&%Zu`bWlanfnK3z^gkmh;(}Z(fheI!<^UJ~n2LRDOWZgbID-RgeN7`AMUDsy3$Q7ya!DZi_W zrt$40i1!%;hE!alyoB!G-aW&H(Mo!&CK?fsz-t0_wrfsa1C5TL+JEZI&kAh zFVsPuhR-9k;1UW4h3MarRhxuPh2kI2UA9sM@#y_g8Y$lLNNndm96;~!xvKdj%b5Es ziP^1l$*<@)&_0c^EU*l&H4||RjWP5`y$wqd-SrVO*ALHF_gg<^C#1%>d%~KbWY$O5 zXWwC3+#GpvMpyPb&EvG8Vv<5xUt)Y&zMI@iQGID*oFw2eE~dBdguQ zUvjti>av$cWpAjg@Zt8BUSk>GE}{r5S>!O*IM zImrTwL8Ug_Jbw((g%XBc3*|!UElz8Ne0O(YWUE(Xu8x22{I7w&^8Ug6;&C3nWNovT z!zWyKH@8*rT2!?C38B5qKl5TC=?g~1uJ{b}l_GeQjJ%G^;#Pj(UHNDMiW2^}Uq3bV z9>F=EnR)3<2~5!G8^z*pI{2h9Bd4Xvgu&EwLkr+(auQ)P^uaSK&kBTsl4KsCGwX{4 zjd{wt7N!!nxy(u(m%`jzPxwKMLrNluN_ve^1!DnoAfN(5C^bRjjIe>It0!op;~x&} zmkQ172|O`@6K1xFa==$^>+TPm*D?jMdw5v6l;IBDux{`B3$~P|^ZgPpde0QsNyypz zReQ~sq!eFnS?$wgV#b7i#Cv+H`Batt*E za@(}T2Znqi`m1%uv5O)MP9v2gMT^LnJ4IwDg3X3J*scIi6|W~8ujJ6>@LWU1@+sM) zn?((3ak=!deFcORABT}?7B6ULKG8PB*G>sZYpeYAPLph2IhEt&*o;h#*v;a4euw&} zH!an0yK)H%w)o#4ZEsvQB?@)EP7B!|@*O*jmZ1TRAVp&~GEc?@N?arUEf#pE{QE)34$t=?^M3Y4L1IId9cAp@JHLNd_uu1p7 z%eHiR>!6Lp`)U$H7X!o}Z53$NRB@Poji1gp|K=HMrtH5=j+9SnLK+@PFO@!KX5oBc z4Nsk9#)(KmX17H@D%T{|v{*p4j)})prxcsIJ9%r{WXWYJ8^141WkQA1hNdx6FC1WJ z(g&3BFBg8Y%j3Pi3&ks)jCt1`^E`ED+H2h@z|?bX-MX)AFjluxFO6Fu%IS2FY#|rm z!~Pqz#HR>yF%e&LIp+@O%VVYN(j|;95+=h_=<~hKEJ*9WZhRw#VX6+pqPRU{R2}i5 z9-#BH8SaX{&>>vaI=}?11R;Aw$pq}Q_z<9y49CrUK17EM5IeE{lR07t`V?TJ2-IZL zT>`RAm<;e0D%3B@AoUI@*ah6$SAkyTQ2XO+aGLy^{}DFQ8v+TWm?_P&OIxekba0kD zs+bb*s1?{Y!btWw&jJ5h%ccANIFH?-^amGQOiTZ0Bz?2dh>VRsHXgXb;k&Z5eTWr? z)W377h=-+PsNBBwlBg=>^FJ8Q8wMo(kF@4Go-TVma_l%o1F3|e`lf!Q?H-4Hz#|N3 zNc3paa3#VhTJ59*IERkehR#)Ds0z-8MJ17>ZefYaRAS;Q}GjYSKye4PX=i2JfWSGD<$#Y5bmI8+ez z%7#sQStVeW2dwsfmS}e0WT;DWYQ=f?MINc{KzPii>r{);GD-4 z?x>3m<#7=|s z`s=u+-X?iz@y11SR^JOfepg;uJLHIxx|@x?>^x&MCfCy za0o2`8jres7}FL{na@Q_JNeyN2CQPs!SS!U$4mh9K-hU$9{0(k%#`3WOT<_m;UW#j|!Fopri)diLC8FDQuhjnbYQFAKS%)4Jj(!QDnu8f z)Wxi@g}MXY>bljZR&J;9OLd?{cZ4-PN%WdsNkOt&;()Fq(huvQbElctr3<;Z*Zsrq6&mT znxXUV6g@+{=+*M7W#03TU_Qv%0KFD2cW7eBNr~4J8xj#NU<zZ- zT3vT!xJmK{H%?ML8ox*M8#s+~UYEM>=LcLAUC%Zz_uVn)_QX?*DQxPk7S~?9UvnMw zv|30S`NprXrP;6S%)Y+haMjA@iP^;Hd7<6iQi>TR!uBm2n-Nq6t~*~5!HOrDlklN$ zx%DzYSMXKpA3QtY;RX_&tA$`$I)@|a`}hRz z2oj;8vGYQZ>y8h&0EB4Vd6O2PUL_FiG~otzj8oJqqF4{~tmu~N&ooi*?6iJt6d$Zz z_lnKe)8Y?MALvvI_U;u=L}4jkt2h=l%%+bfNY@b~w`lM%$)H7%>tazn^KM^{T=2fG# z$7o^@W?%3xo1;|Jy7?)YPRmjQ^|DX`el3)dF>2h@547@tg93m_@UL4gyZigHrlxuH z8DI{-+ZGSHaxjwz(|C}~mB&EjO))V+bFhMc2hy1pZEY(XMJyazK}A(f@>gj_z{vNo z>AJG}FZ*J^KVbSVF9q^idxFM}6}bnkG8QiD#H;9NjO}GI7d6XeG)XC=!2I)y)^riW zVqy9nS)x_(EA+T-yO3J%v(THE?rZEtmvK&FCaOH30YPN-X{(703V(h(NppAbR;nMN zXh9_UfpAwjAhg_0Vs6~NqQ9I4a$rlr{I55V*e|wb^2;+%k|uF7ABAI+SJXLv5Xu(M zrrS~WfA3zlTq!PGTpD_TyuNRWx@Xp#CqlK@ugth!UPGY{nzzW>O+rB90G@bol0rx% z##s_H=m?y2YGEeK*gVsPzBtsYkx zar$ugis@SoE7+ph`w3}WDqguet%LQW(V;3Yz~ho~Emt(!0@|;Tq-42;J7D&G+{MNEu@&Q3wRSrdKUGb> zb7)Ug5B&;p3z?$e3-&O)_bD3^khjQ&1KA5K!5Hfc;r}q^F{!6jW1hzRxc}Pis3DSn z_O{kwzY z+%hqgVYMUY761ybftKr&7qf=Pyu zBnt?jKt2lJXwfAXk_40(?{{=$+p3wIQ=h{*TFHBNl(CfHZ@ViN-c08GpBBKRbtX^d zxiUA(LuSpDmpCHa>ZtplKO(m<_Anntmk!59I# zi9PveIBS0E-T}oe9}UGq!K%S1YvN5>E{B%z#sP9 z;D{6+lMc?m9A@%tmGLvYxifOnI2Dp(`p}IWtS4@8f#9JeNZM6c+EWD)P1%)^$hk{V zDD~HVZxKR)>{aWWVFsEaLg9B-eHaB6*MY1zUa;`F!rSKszm#?(9Sl+LEJnX`(S5FF zaVZlQc~_rl#usqq0$@D@A?$BjoHQ8-))ZiZVcVKfcydOPygY#;0rzA=#;&+NKE8w% zwNEi5Km_mwzs+W%>}m>9iDC$epjV*2i~33apuvLz zNe?1c{`3U~-lXN8Q*c!LpaLvV1@mRXgwXtWd4Rtvq>Ck#ln=KEa=} zp*(a$u5?T+Dh1}R@M8cBPi9noCvmY642Cu_Tx}R+#%@W@b{j)+ULfd?@aAW8o%Naw zI6p5AeuaGgsdvYdDF@3zg9xZ+7G^WEVnO=X@~o-$a@Q;-|G9Ewq|qtZCqG52mS)v} zY~SYjA}iAe|Ncltz9{rN})U(z|I!wo0o<-$XMf7VTQN}L<*r|QHY@NmZ z%ToN*h8p$$oCpPtk~vfu8Q`!NsHW|{Vnh~x@z+>&V3s4W<}mc5W5u;0yDxid?%!gp zd%0S15n)V}%xQrW8UuHpLk5p z*Zb$D`Fc1P1P^6No}U9#NiS0DUHi^JrR-0!`P*4ifr>|dr5OS=L29V+r#yq-vs>+D zcUhvSrmf`LW3DWnrxamy|4;(++~^vN_^&1ryHY%cMU+(lrGcbEvX3LtUt^#oXMnNr zki+uv>}=6xw(Hcn)V~lJXpnAoHF&#r|ITtz8TdmAyf8+Uh_pYHW(=TrSr~>JCV4mo zC)y=DpO)iX;b|OpY@@IydC1Kn4LZqYM{ZskMj+ipD4CS0C^2+4BchLlnDBX-88=72omHat`Fdy$GQ7)Q}fsTXhylCuP2u~BcBSa5;1)vY`F?oQCiPyB`}kpnwejx zp=1&hbX~?}$4BETBhZOz8I?4V3Ye5lQ=W_ga+Q#dmF|G~ot8>s5SVdFm-m*=GsMIt;du^pjPBs&@l*qY}jjZ|& zeBQ(g(QjKK(+>CVEo?j$T5i>LBG_!<$z45-R+Sez=#5 z(5u8^`%_0wdbl>#;kf~8JS;(lc)dU1)zGWWIvH`HY`X2!S!*AcnSX zr4bdl;hcKc1dv+(JBc18W&p*m{AznfNG~0j4%CBBR{Z`8KO``S_73767dMjb;W5zZ z4C7b6D7`&B$->`ImkkL1lL?I)iL%ZlFi2i*u%}^)c-DTp<=_HsvRbzp7cX zR2EpbCZ$`tySuv^>266WC8Q;#yF;X;yBk3X>F#bpkd)4Q-nr{rYyQlr!;74A_TEqJ zC#@c{uH>)bk@-iUL*k^ti%&_98Vh!9qRm-j7TD8bZNIme?5 z517rlxllb*Z+HxmGbj-ANBVhCn^uetChJ#7_(h`dl=XX5vi0!OoRWXL2E8N7ThR(` z_3^)fN-9fgQ+<#MpbcMa!Rx6Oa6bdtroe)9K7<~7 zcew);WWPF?KS2FHI5}ZsmMN8qafSKig+lT%-s`(52yO*!qS=8ECi2!jJW8$gk?z;K zx_C-VMBq{dvEhU_mUPLSIZI&J1yq&J3MGthoz|Ng3o$ zt&F(0aUK;MD%z@7>*Md4C8cvbrNoRPUwL?xA0|9CR9My{5*6T%RkX#K)wB;V6J{y> ziuE;HO!b71J?}64H%h>Yo{S$p1gCUP`CLp8u(GWoL)9**f}83Bj}H2ySwz+T7>)4E zWzdf_zh5&%$ueopI9qIXA_h_Y*50PrDWCAW26lo#J_z8oou_2+A>wIB(A6b&B0=0h zzC6{hH{Q@}fdi+|L_zN4CgGxMzL>(|VPIFF6_=pYU;<5Es$LjPwzY`QAp!9!%Yb@Y&LEQ7X{4|lA!7;ExV?rIE!n+$wZ*kE zkKZ4wx!YSHxk_+4#tj}P4$E1KUqF9$Uc~NKhS%Kc%(>-qF+^_^MacDsYoqS(zdKCi zQ0Hky`nO|WcyA}e#dx-TGCvVP&A-h)e;!U_cG(Lsj)Z820iMF_alFh+g(pr=ip2Fx zG_mNTaai=06(hZHP@>Dt-MIg9)x?my7@c-Y%#NBnJvI^~3LIkL{qTW5!n<4;1Q3!@ z43M~?s*2t1M*V&-0@?U9%viEnR+7^LD&0BY4xk`%IB*z&SJw&~T_96sha&Q=qL}ho zf~E*kNA*#06STR^+9%e@&PitcY;CxfbS-QeAIF*3a zv;eV?(}z4FElqvv9GNaE@MAD+U!$TAwtUV zigXw=@f7}imy+X-lY&dqy(O)#^9Q(c<+S8)F(Eo@JB%LSZGwXd!m`|);(2}j7aFRw z(Tj7rSOsVS#Q|#IQiA{k4fk0R{L{PQ$ipB%D)hwJuUM=ki`J2SBJ&qVjyi1?rU?(X z(tHoeT>iI?^hJEQgcU-Ezw4x}X)%$M60N4Qc0*Ss93eJW;BbFL-Ds?aoyDpBk4XO< z6p#dMCH`Fx3Cg7}_GVQ$B)pgj-$NwkAE~-Oxj;p=+*qH@xNk*D9RQ=qCIwG2v#u)$LVkjl^ZQ3E0S|XCu6xW z{MWOz`~t6OuePw;BcMV&4`u%ZZR3*cHr}VW7A9=CC76XKfVSvY~NI8ApQH35B zgyTDJh2n3Ia!>RDjb<1`tB-(A!twiyRG^|70i*wgrKVLvPk}K%Q#`V84Ppryj;^V! z?t-QQw+?AC8WwcfoH^_>G7lxaruO9t)#XnV6la7$~fH$hz-s8pq z>oL3{*LaYM_||78E%t8>X`Nz%L)voPu=m!iE>1>*22unjISy9AD+c-IUzl3R2y>Xt zdm)Gh{5Lt9Qm~0YvVhFYjwV!sOEDB@jyhRYxb&WF9h+h@tm|JJEQQFpOe2al9Y%xnI%`zW?+ z0h6a0M2%OGc&1T|zAne2+i6LKbr5aJ?tgms?6XO(Cew)WV@B4+vfkI}Y+sMHQ#~GT zaDxcv&qGTzHO7Bf6dEwwV-YS+P6qCcr0cO*EpD~$#Pz;do__D$DILFlnQ&yEwx?xj z^F$@EwB+c2Wtl)bBh5kJMafQc_6kvyuJ8;6TB;`te;YjfN)(tBpMo%@P7P5|;Se~+ z%q<;Pos;KQJdU5A^|Q~H3NqJp(#=ngrfKawet+e*9Ud3Caod>iBzr)2uQ<9Dc@~VD znP~{ylW0~qDAkpd8%BZ79OY<8N`$Sr@E^hBb-ivD;&|Mb&k@@v7>k9~OUX+lC{n32<7n2y{IIA4>*^pH8c17U=)j!lobg-uw9u*t z?r#v(3NkWC8S340g$B7Gc1}*#yMu{OA~VtmV!83ar4j?=HIddMY3JL~?5<{S&}gt( zP8!WMS$kqAl1c0(UGA27HQh4|qzDsfU~CrJ?A3~y_`#y~c0sv$!?k{M9E$DrWEHv@ z9o!npPO5SF!urWL(Gz{Y>MC7kczAdL5+F4@gu3*xTB~ABc90NTK}o%LeQSj>hmYw; z3}3X@wYRZ-Y79HY)&3C7gSliOC;4QY*Y!BGVhcpCl21WCEPxWLmaP;<33H{jZSC2Jc>5NjMdf6(6Ec`f3>h^{*fE2l zjvQ2&F=@n2%)cCDbR#616YZ(e1Dg%bd>L?vzPE*6_CLvErY)V=$}yo0j`=8M{K@bm zw{cLW9c%wQ?D~h`6^t*;toQB|&aRR(qD8?3B03I1DPK8Rh|-I^Zw?AsRoIhOdF(DB zc}cuqhIwt3_`kuOtT>U(M0v6&s6^IN*R~8nH=A5+LKw@afwS*+8$0EkdRX?z8oTT; z(@t;Uw5O$-+cg@x_VS7n;bXqKSNS}T^o8j!j9UC+U=~SK0148NmFFM^1IOCh`t|GA zlb>9;)yUGAQo64HHTiJ|eGUY`JQom5fR?cz%u=Hrr(MbdB&sNm75}QSNx4G4r#Onz z^p@7PCWa>5s{A<6kD35RyAN?<_wT-=EtHki19D&Byf9gT4*Tz?dpnSydUxVEakM%; z@^Bh34wl%Vtvm@?P8TXZ{!t6C0FuYrowogm4@*+YmegH6J#4$*>=8;#`OA}jMFgfG zG2aC=iAoj^t{|807JoV^9f_Hx^IncC_wTW4-XqXe2S+kTC=ExV|aVw_3aQI%?XO|Nt?idu%f*g@y2H%s< zRed1}I+<%FK#iaf%P>+a3wkhq{TfEj;8JcksI!tC5zWBht(=6Fraod(gb+e~Q|eTk zh0G=@y;MO>LgXgzgP3N`f(i!}sTFTr=9Tsy6I!`eu1AaCc}Iy=*gJN@(%~)(GVe<` z8@O;KD{aMn^8hT8)Ku+BMRK-~A1Sk>4bv}JLq@Rbsqf`^jb9Uc!xS*j3jV3tEfcv2 z{O`Q@p<_8WE;+^!@kW8I!C!zL@6ua*zJ1O^zXiyFmGl;kDZ{zP#Oq$=W8 zLUmrKD@Qdr@%^=A0iSZmk0c<9iN~kYfc@gE_uF*?WWXcyrQDW6w8B(ZX^>YrhU;;! zO^3B4CV1X;(imModPBD&^)rT8hCT}=Wud9+9kz*2yN}AyiiINszK~qxTpdPlns+)|y zE$))VG-&#a?G)KO=Ytb0!a+?}e_Yd^of(@(QmA`l6xKO9$fTr$Ku{*NJK;*nGkRS_ zA0pT6tH~DCl(ULrZPku{jT?iAdbM~^TAdd~lY&snLm?8QuCwOdl~R&Sw=^iKRhb*2 ztC301b3q`0iUlv)~?Y*0b{bR zh(ReE8<(qOzoEn-D<76qbP0JyR|HHHQ=*X91v*=|Q4_k9{R*p&O}D9IG*Bs+#W zm!qQV352ZI;H?7v(q*0_;GSBZo^N6pnRit3>gp1^U;NNF9@fLPb>MGD%%V!Gb9%%c z93eus*SNS_ABE1nL{d^xKy^f&lQCoNye5j1jc(m-T3GZt@Bex`NUiT+|IvY6qe77KtnKJgob9PwKQ>P-~`2 z`Z7b4EJRf`O_~G@h3lGXl5WuNTe5&5%`sahRX`3eT9*FIb;+z@)D`-UmU2NNL5bp$ zSH{^iYvv067lXRZwdV)Q38Utxv7(KW`{!%9r>T|n?tCeW49fKLOn5_`ET%bE<`t2V zeQ7?bUWLR-{L)H=L_)vVoEQzZc2@Jo4Y_MgIb>vL-dg5+&W7xyA%avI^=KQ<^j1zP zqL>KyyAKV`dtKJNVH)Cch zbMk&&(La2CN~)%)hy*GMMoy&p7m|1FOLF~K_tWT-k-jxs+c7!>GlO3Had$|X$Y zn1B$j|=ux3jmpEo6^kOwi+jr*Zi8;YkNZAgQnii1-5zFHX`C^^ksxEnD#i zLfdS2y!e5gdy%p$jJ{71f4!)wltxSR-|ON_9!tMhMsq~rlKmw1epTRCJoyA=g)ZmO z)6LZ$a1=PMwWpeMC|FujgP9pU;9*5lTUQqo^;f3Ql{>&n`o^<`m%vy8c6Qi;y~L2; z4TP6VuI7Ak`!a7 z$WBn#dA;5G1uHEDCs{ySa@{h`TaYe+{}%KlAxHanEIO zB7dXQGO~ehk*(Dov*JgtM7auEO*eRuihW!7DiI}gAGsjVHBj`_!WGkyG8FIV|V1WPdcatq3yHN80!#y7Aor+WF=VipFtI@)OtwJej? zPvwWANBdkhQ#n)TgC05dilxZf8n_Dde`F>c1Zm zP^#IWLj9h|ok(Lf^6KWkO-BLsvg;3CtfeVr_tHb3voRsO)64%05b!xq6cS0P?r-q%kz0o)IHpCjNu|84)L3Np5V z;s)ToQ|s%h;P|47q07Dtf@*obZdtrpOE3OyBZ^}zK_ZW(kGFJtNJ2Cx#7QNpog}T} zH|S2>_d?b13HWYFI{if>^<$h(NWb*=fIa0vn{NXSCV-QH3x0+NsP++z1D?=Q(w;+s zz=-d|`X~sxTxxQ_2cKtlcD5Fz)Rx0;{-GHoG#Y~#~$U?P;VE68!<3X>jt z9o_#8rwIscok?BHV8IG-pzQ=D0N|34dm|)CA3-W9H!Nx5q9FB%dF&(!`EAsIO;HmB#0JDblVjCQm}ba76Qy=f4@mRwCB_REEfqw zj6sYmFZZVsp!t|Y9K0C#x{UHQv7Pka605xDckJ;Z7Y9)%*ood*Wzavq$wqsDrxn4M zz#A1x#<`-lHUS`A?Pd?yGQndu1$lXae%DLk0K@}2sr$yj#?Iu1zk``K-i$1Y|3|M%ReI7y#JXQ{P}ip2IY0>lYQY0oGxGNE=q2m=It%Pt5Xe^jHdUHa zRc%MamJW%WM@B|=ZZmE*W{Zl70y_i2Gz9i-gPmhOd1i}7LwHtZ2wy)=D*|&Y1Q7xv z-K)EFTr}5gdlk!)Z8aCCqMvcxVYuJx_+FctvA|+>sj|SesR-phyeBg=|%4sY= z_y3)PKi~#T%mAeDhWP5hD;n^44l(Bc{eH6!1p=(Xd{4jY1t1!>I#YrWHO`0AZgD8^ z3W=QkfQ6uaeLF4y4J3~f*hU1d{^9NZXkfQS2O$yQESv$%Zu6s18)!8I!9uH7{`FmS zm_d>yGedw=xz8S*JzL`ILM_1c751GK^3izlnXjRE~h#gc4^n6y^(pGjO&}waF zSmwBeA%m~eQz>0H4cM3}4fTe2iAE2l^;z&hE1(8ObV!wLYDz^bkkc?URFbzPeTAjZ z!pcfZg1+P07A70?$4WNz`Afrubvj6Ne+X#hcbY~)uW*-{h1qm{g1c*#(3=bWyY<0J zwrCk?$&oMH>WirG)sNPH5!4xOd#Rl!Irlb=g4y7(!URzx!EMF~lWh$%=l;IkQ3JOM z1Weo6*-cF_N}2;Vx_OoPT=q`Y3elYywv6g?#br+r6%EjdSOw-=Xa)a`3oobUdSZudd+l zC=uT8IeKvu!24KB$><1LQK9YDSrNBjy`@0t?0D5ZgM`kxz?E6B0;d=fjHN+|!+a=m z37?x6Y_traP(;b%|BD!?uDP zawaBb)U=xE(!ubYWn&*umv>?Xxu>}!&Fb9_4N zB=|0`!}{6leGxynDFK_1n*#Dzc0%z@&1XwBKHcr5e_b~yC4kT(kUW~b_M_^Z+Fo=^ zK+qU_ELkredqCW-=t2h+&u8J{wXSL=OB07P_ zzY3Mtk}E$!5&RyEG+UU;@bOx(;IH@3oEhv18R#p{V)9qDolfiD5*S{ zM->4hKV<}47pJBq0sf?=3Dtg;a-h|iZ<9F^q*|~HRbMm?{NDXQ3GDTBW$<|X0m0=L z;VH0(7=dF47WD#$)MPX|J|5oT3VL{+Cs(2b3LF9K?7AO+xTz=UY3IK<(~tUeeiYv+ z8btyUs)G|>RF5VCeH-~t3GBak&F0Er0i%_lDa9XktN@6pvX_}nabGm3FNJyM`{*a7wv+?J0*080R4 zD4^cS%uj%aYv=sZ=*^d)zJYqIqGV65j2eNYU~75-3~&Ml_Urf(U~YMFWcI4ru_OV{hCES%sa$wCVZ*hcjRzj zs#M4|%S_LfX5!ALtQP!!_B|N{>w@l+V^2 z2`$@^VZmI-UUkeq1F=-sv@L-vCE27$y;6*IuqN$F)~-=CKg^I5~V1&GxIfT0FUH4300*#yye ztkdEF2l?T*ApdXzvX;1a%Nz*u9ybxhH|O-s_JA*Z4t5s2PbD*vBYR2?FW^r@Z9e{+ z0B3sV=D`32&w#cHQP}gOu(dSEwn;W}w{7Unuq6UkhlX!fN zB;37{l2V3vfPXs6!E<1(9~N9tEjO0Il-y4#UIP1+I>W>MCs{6D}6?XUNFJL+)a9ChL#ka=O`%&mX89i?N>Ot|Dd3r>CnsjB`FrX zogef$n}8&-?2p3nzTLuy&fq_NLxPS_r;nO71|(ie)Reo=1yc;@;h)tR3T>}z#NUes zWIyRuo4WDJSBk=9jfE{7(Gtaik^#n3P-7u&*WD+(X8m5Y0kVqoWrqh%T@PYCv+u9F zHWhwiU$cj4 z3ck?R4ve$M1{$Xdo;jvivx}dh^|L&xgtj0ci~i9YGd^Uzr)ss7GaiJCRqDL#8@K0} zG$~S2%OfAL&U7lGK#9!9B!FVM6KGnS(kWvql74PiZUML}_$m9mG(2{zWZC67g-i3G7a;WtoeU{V^>Sx(^gEvQA&;E(= z4VlYq@il_?DT}34>N<>xPvp{^?{K=*=C0JwE5^#cka=5B$A2JrwcXaiJ~iW6n@_q% zTzm^cm;^TiVNu1E>5?5+nqvV=c>%)6w9Rr9Xc*Yo#><|-t|v18+qb45C$G`NgbjZ` z$CnKX^ff9uA_gy?R$E;FU)o6Dkt`pFDVtORS|*Umv0UTVzvCj>0a&ZK*Py)ywT1*; z{tIa$$=?uBXieT)CpnM7+#zJB^X^9@I3yh^Y4ot+L(BsA*=A_q*d~h)f7kd~y%aX< z_$AO50{VU_hTyMDj;(9&zng|3rbsK5QNmnElLGko;=&b#^7Z7tJlY2T%*&Cju}K^G zX?x%!vfDlP?NDlo`nTz0Y34KdKYSFL;)ylq7(AS-00{0^P%=O;E>0()Fo4S?0s=!f zH^aw}i4uW&R&9d5eJ;@7-*0#Q7U)&(y%|%8r~)19^lx{KaxqbgUNd%YyxhY+=Ysv&AtA2zN}< z7mnTtU%R?E-x*@ll+>mr*La#}P$tHL;8y?{~mivPfqKE=d9r$P;!0Ndd-mu`lN0K1H{yH?*rk(m!k2~Cv8D>1Suj$Vz=T@FSojvS zBVWWjI#5#}kXQ%!d;1Dz8Num>!cY*!76bIQ+kb9d0rccRS2g(jPy+-fY&Pqivszc+ z>oPJieFN*FJJ#YBj^-Mss1p%^6cm)CnLjk3M~2J^(01T3gAQ=m=)?E^faibYqNS*R zWHTtUTh$%j4od1ADEU|+cSh~lH!Lx*u=MT!t8+in1;m~Aank}MJ`EDn3GAkOAjNVE zycM>`<`bWm@#lz)MZq!W8!JGQGlxktnB?3Klfa>u6*2k`VW?e z;cYNJ;_ms@8;?aKY@KZirI^boe6&R$o9C?`SJ$DqaP=mhs@Bg@rf_8-yD^3}f!v@7 zsSTULP{PDI|D=3mOM!2}QEad$=fl(@{`<(G_4EUdl4P_j)Yvfg^X5o zUpF)l`Wb(Q(!0xNG{mT`<{ZsAVZnmVq~Y=4%_m;93sC|5xe}~0wq&yMrp)%L1FdKA z_@Lf|Y+r5*=>(!78Uit81TH=!1Ia^Qu{Of|MSz5a$QJ4>(a)*CWm7{mEUfng0 zCePyEjEP*_7Jp-}&J@XV4fs`;1@(~FkvfX~GRO&Kw+l)fu|G?aA zS*H*ARExE5rNOPI{OchMl<+&ZJMpIr{xF7tvddHqK?qFevzZQiB-WmDaAfb5Sq76E(je#x= z%ps(}MQGWubQuFaR`m-c3IR+!e?A@({_d5{=X6@;83z;-1ix@{suJ7ZZb8f#K13Fj zHbcjY7KEQpgY~J^gRAd1Mt&dxpvUd`jyt>z5Obe)zlfdRDn6dadqQENl1b|5;C7R7 z1{WDMPlB&7vIhz5iS7p-8#P%xPORJv%+R(#^k!YLomarlUM&9l=A;?U(}Lm?b4)gJzB_o?h0!vH5VIBQFmM4D>)N3LYB@Q9Gp!e^bH@Ye6Mi>6-4F9z1&}Uj%VHD21DJ5O-z1l=vt>2@bN%@gI z-i%Jk8a_#>IO@6ojyZzETg8xeAt`riABX0;Rl^UWL8>m%ASKO9Jxp3wg$zYM z%7kcSO9Cp1yy#f%!0Ib$P`!SrNWPVEEmcAyWD?AKb?lp5#CB5^Hxn_La5Ganq2h#S zp+Ji_I!NiB+b?LBvi5$=bg6a{DgjL=p@5}#Nh_Z8QluOH4VqY+G$b#t)I0O zHElAU+`Q%*B`;IyqT6cwX8;J;>IGh2K7UajV+$&`{xx8zvz(EQvAs%EdKxA&J!Lxt z`-GOcn6R-DQZJ=vml1&flWh81y@lIh{P=FDQetPqYGsQCyz_}`QZ}5NxgT%PRT<7q z%3(8$`#t)$F9J)ZKm(86bQIjvAZ_#g(tmc;uGAQSedU-GvKts|D zu4Y+PRZ&-$Y0DSvCL4=70zf4ILFHN+L!tus#qf`@@Pgb=iNR-K%=<>tA6;1W5x}q&vf>!_#`FFJ~*;zmZU?5;oBLJxUo^bW6h^(z&;z6&B zF0cs&iMaz9@Pud!nZQ@G$88_~tBL^27V@!FX5F)H6g-ZXetd7Y6XUehR6x4KP3+Iy zC|XTKpAY{ubzvj%8=Y!=tPkCZ6OS|WWd*zN0CDvzRx7`_dDM=f|rLvFi{s*M|ltLv(igZl^{ zR(q;MgDu!(8)n6&$ncu#KM3w4N+VD7cfmiB@6PiUl7$GQMKeS(6S#N6lti&IziNIK z%IqBMx6S1G>g!XD%E$G6_3~2W#H08hMG}Dy^bXa!U!zG6~52deC_V(KF{M4vXUr)!RapPFDcbsl6(q zRvQbX5(Dsc67={Rr>E25h~?nl)C~=nX_>VvaZq1@5e9&Bm#*>M&jP@a<^=$|4i?~Y z-uDJYuJyQi1@d3--BIzzdK#u|mmWsGm$6mTWvX!b9e)Ji7UZil>sD@pH0a6bg>rXJ zt0c**9KFa_iEk>g$pdqSSmtr@G^sY(>R+sj!VK!{6!c;uTx7}Prwymd*}D(J^*|Vw zougwR*enXbFC+W5wf8`U_{PA1P*zqpB`pnXfdKo#z`zz29S!=_?Ou!#fh%pjeKFLk zz*?~B#s*~U-CvO-!hsHPFM6ii{K7JMCW-^ZQ24!(iA)cko)|Nu6oK_0} zE=X=RneSf>w${yn48CKZ>hB&@a}Ouszg=A}2gnj)A^@#KKWg zQ4xILgm|tB2SHKkVDEN+HKjK?q$fezq359D2$mz-5>Sck+XCxr2n1bez!d$R3jH2- z+gG%t=ch$ot$SY@+mRKrY8E`M53%C`+itl2fju>+K1Q=#P~%Vk zL0wqo$vJ;%Qn%uJ#?RlyMMFtAz?)t59*gjZz6b_y`vy~{8c#*kiFo?Rwp3U9;?o!S z$s^I{;KmHu0gEBEr9pIpX=T% zY`MCeEoI@)n>Vko9yrK3PK;1}abq;NEVvXY@(AfrX<&8UWnWcar_7g1DJzA1%!?Y1 z`WS53_42AZSEc_=*1g50_b#U+<;DW{TKvPd_e*NJ*{}C%bDfP#$BV+pgFu;}n}ud% zOFGucRY3l>Wo70yArlK8N`ZX*_+r@E13yS>1iGEf_rOvKBA4O^l3hqaJF{>!CJ-l5 zZwV0YCsivbnj|C^bQG0vVTTi|Zr+DK^IY}FJq%}z3UHEKgB~(4!3qgrLTW;jA?`^w zMVA^Wj4*bS)O}a#F1)+xi(f&!eGBVPw@7z3G?j}P-47AoHZ?W1!xU9j#R7hjDlww# zL!G{gp1@${3ph<-VK65hHE1O>Vg1|WNk1LaM9T(H^DWkcTv6=o#`{{qOmI< zITA5t zX1qntTDqY(2?Uek#$m1i>;jL1SNpd271%(fT9OPR#ekedtFO(nrFG zo=_^m_o&YjHnK;B7Y!+3!1#Xb0lG~9?SWn2--~}m;TGHtsnJ250X4A8?@VqmO)?o8 z#sS6DtGzRu{#KWr+x_I1-SB?#KL4cb5Z*-HUJHsTa=56K<6oyYGhn51$?-KjRiXls z0pfvujXB3+0Utc{%Hm?ieKl#~bKBS0nyy;g;ov_*y>HDr`-Vfp4l}dm^$?pPKB0#8 zX9PM5(pfIPA{L^IH(T3Z{}D5|XvsL$Cc(f77entDX1pMs}b4-d&v0PNp zKSa)QVhaZg57k%3iZ2J<+d2a-#3~8{RsIeh6X5cuzwlFqYJZc~DgG#*|5jI?8m)pS zVOg!^=iy&lRi#WymXh)`+BXfqePMKD`Lt(U{6fLVm2~ zbJfMtIjU%wpB$u)ui%%SJL7%Yf)20nCjeY5j80WhQ&egB^A;~@IeTz%r* z&BK#jVVI#b^tHa|P=ChW6+B!S1;v6PgbOD@Uw)ZVEu>2A|9jo)?j8no=U$Mp1oDGC>%}N5 zD|-v_{Xv`@r~p+9shEX|;AsS>9)(RH1H_tZ^Ns=NHQmKF-ZM*St1TkK_>o1AEctC zTHZ~?`}f7-(7TRyKljHvIYA;*H*PFfg^qOny=VRdK^I@z_5~id!l7?}_Tx7INs7IL z131#{)AV3?Y&xma#@;s)Ao=yarDO>uv=^jz#ghfHF)&b&po4M@fHq)e!|V|4s{(Kd zy?Ex2qZ+kW=2PEhr4O~#LKW#qS~_#X*oS-3uFw+~#B4@7c74_y=mVZuI2KZ>kjZPl%`bwApe`g7XFr_N&1a99oQ z%9>#l+B@^$qcAC8e5q*GYWopWs7{HnY0V}1_<`rQ$_{_9#uJ9Ou?1@8GS<;6!~;nO z?>KEEDigx|+0g@}e99Kv#vH83M4C4F$hyjgTzd`S&*MI5zoVcF0==4lgiLuZEc|(% zCq804P_iF%OCAv{?J4c<`f{3sNh-H5&qplTq?@9VCD-?B;ZNsqK{^Ko?IB|IAQXfj5RLsn)Sp&5i?Yl8DPbh>+h3=JrmL zb3W^l5rwa*d2IUfveuzFjO>TF5fqK;ssh>LJPtGxdha5jzKz-RUWA3_zFh4aH{Wx8 zDH!{DB#>^vg2*%RU~Ux7B+L~;Av>+)JU9}{@R0(&vUQ3IJ^ zWP1OBjtyAZJ_E`IeUWn%*R&=b7F_@;@M`bq9O1DHKU005j7*DHqUJtvX4T7H~%KeBIJ-1bk(+7!E1}hBJg>7`Y2QE$>iJAMxqKN z5*UmMTc8_40@fmqmNgGzK>6&0L5&v3%Y=>M1cEhgHYSE?nF(=8`lI;uYB%rUSN$f| zNS){ zqK8-i!gA-4i}eYLC62egzw~T7>oMTr{h9lGX$#<&WV$!s8XHpv$aCcs6`=>nKS1+{ zJv#FukO|zXRf37r>`m@C7%qnZ2H22<%tgtF?~6aO>kc>i+W5)Ib`ShL_H0Pw_OzpG z-o)j^=;(S5svl?eaa|Re`bCmE4*rA>%Fo~x)c!S<^&H-Fi$H8r*{bW#YE?!3Ca6yE z%7NhZ)rp!znIp7MlX@!!8-?gQws~IS3JnTV$7JOMQztXsP^)FJbc^kaeL1U;MC+6# z|KWd@vvS2xdZ}!3gb!__I(bB`HfrDDy&t*qfAT7t$5Rz3KPaKaHa?M1^#_Fqhvp+w z%Z3q7<-boa%aQYREQaIZNeU|0&fk6iLjf02R8Mnvxg^lXOz(l~{+Z9``nK3|(Ma}+ zmPWJS8@9B2SYX-?W znEUkCwm8?i{`HZ=qG>?(ZVVx4i`RNhX5$4Omuw9-|O|N!^nohw7=t+xr7U4Ld_Cj$^B}DlGp0@R_ zVmt7g09SlT9^DTtbJjC0{O31<0s9!9k3ssjv1AI?a{T=KKn~w__6_A6&)0>1b@cw2 z<^8HNwb}Y5ZHvf9lynn+5X3VE2sbd)17XZANW&?ttJA;;84z}Wj{G(sFaC@HPRYOK z4+A>dAv1g5?s9w;MssUUchrL^66Y&TdX?F~_nq3lkevb#b12f9D#~Ph8ATzS3r|yP z2B6p9n{}jF(Ma9ln>o{P)K|vPTW|(v^LcnMLYeC7{%YyEVvQ3zWFU!)g=l2?H&mAX zg26wH-E16qS?{(m0tQVy*ZM&O@dRLN+904m5C^pGr5R=LxL`w_+^nv)U+E%Gu!WHS z=*DNYSZjBO`ug2p^q+3^?xJk;?OD@8M%~M^Nt8Ia9r$P%uReos72pftZxqm=r!6bT zbYLI^#@IIFdqKbbZ0@#yhvgV6{;g1MRY=lGJe*RrVU82@Pr{O{fa^cf%7k zrJI#B!4rUt#_dWe@x!^zJ~?F!dAM|<5$gL-u?*I9@pSHuJ&A_$SBVe2pOuWQsANa4 z8Pl&v@2i<=zS$eVe`I2(@O!Q(Pgajp)zx-q;u=MajY8GvJ}HHc4aWbD)QoOpPJ?fy zWk-O8x11J&pSuYASz{#%3}MRuer~uz=a3@~!SlVNE_f42_Tw zfv64Yn8U)MhX{iIEv5U;0Bo)K9MiM^#n9PaI*IS!y0T*)NJlSPN~eIT0MGAfR+}Y{ z9uNY~xUxyM%XS#rA`e=}!idpKF<8z~X?y1T-4sxVBmONh4*n@V<@e`m{whYDfYLDh z4&@C*i=e>;WeOm0?!KkJa(OQ1zqSZCUk4dqP3gpt^6TmmN1*y*{a|5c21~@oq4Ic_ zl?HT3@4q^Hkpr?YFkz}>a)ky5!$9=1V5I_h+v%|*Av>h*K0*1ghH~ne^!oze*5B$5 z0`K#F0U~0A-PLx{asc2Zr91?((E&?6$K64*~}`K+v%x zWm>nRnE#*q3i|bHb`>#L^|iPEydH<%8;T?&%7uq=ilM@@L9GVY4&;^g_XcH!3*;wj+o|22gF7VT=YS-qX)yj1}#u!!<*0md`HeRkyu2hdN zn|kcYc_>l(Y7?xXuEUBfni5>)heVB1W~@VW=y72yO2y-YWz4Ikm_hooj!k5xWxQ-SM2UqL(YPPtNP!G&o2~C2uTmhUot_$OI>* zn+}t|@6N`emII?4XyXAJ`KJlGIlxocV{AO&`-|DC^ApK zd84Hd8-7>!VAp`Ao@mOtrjiKR{>kl{4~1GKHFC0Awot0e&abz1`VhpZ>h1&QzpG40 zP6@`M-Me>_PPM>M#FnnC7Y8Yd7l)n?FX(~EdO4#&B?gR>bim92A$ft|3~=!(fPe)8 zaEKussLc<9R4eA90C`ediy2sdXunL2)eK?^ERm649WUB^E~V#!STte?rNK&ORi>e( ztL*^6T2^};Fni;jtSVmZ4$%-3c`;^&$iV#dsQ$_m3BK`K3t9Mo``u%e1`dmje>ko; zx`FgS!Pi$97Jhn=}%ZEbvtx*v6gt+dC(omxEwl`7!qIW`kKMoY7 z-Dzb4aet8tHIp}=Ouv3nN6Yo&3pQgh9s~+{yIhgXSoUtz9~Uk=t+V^o^JP5P4-^rs z0FcX7lM153Z@}L-;vneTbA>26KYUm?Y65V)2`$a|lLAc-D1Bpbq`0#S;dkpdJ#e2x zflMR&fLn?Nn~>nbb&9Gp-E2In7rpm-O1{scE~X;dyscb6A$3V^!Vp|$Elzi+tN}>>ryQa<`EYTS%4{{Q(5#AcT+W99 z8)>Wn(?%gkz)Y=;dSkA`mKkSXTzXH4`r=K%g$P$#T1p`SRrX5B{8_;W0cT2Rp)3Y;g0^{dn;=4kLE0F+}P@_-8b5vHy>zs}860{r`sP>F)07 z?q<4cINGMBJEnU&&J4p$GYr#Ach}T(Gu`}dpYQeiV}H2jIu7S~?&tk}C34?gSrWy( zHbsehs%@avJ2=@!l{6wr>aTUhb%hk{Z>r3Gn(#@%-G<{Hm1|atBe`&&^JOk7Bqm1v z==+(~+}y;=6FWuO04BHb6<79=N~2c(>FrlF_J4D)m+aig&UHkgA2c>4*5i4hOu(b-5eP;4 z^)D~x*WLgN(fbF&KLkB4~(04qFJjBx>`3`}$`F)U->bV=3 znF?biz|(y0CAa8ajc{FN$btD`HHZ%*>cprJe9i65!(*gm1Qu{o^ayeZTyY?BPfN?e ziK8dtwkDFNaOL^X{D?3qI_bQc*ADpzg#1NCku8^hVnB!|aJ9`{EE&K1-1F(q^WVsT zC-Afp+yGkiS>o)am^r{6P}RG2l%&Mg4dnJ72l`9d@4;;YVlsAuM!<83M`isOLwv~0 zZgv7IZo=s|ax6Kl!K5|jg*Z_100n7%fM3^Qw7q-cdp5*t*|@0Vd3zC1zx;;2!&(VX znT4_4cO%j7^8U>4Dey4@kEQ*%-gUv@&h_qa;X;T3z^i_@yHY%_NA7Pd1WvjPLF5O< z&)SDiAR*r|y4$OvhS6&$Nr}*RO5^@|N89-yzkF-|NKcl%!^!}6gm`DvFvDInKwC2e z%!0*q-!gtfoLWEmMXrvYChFp3!iqzy!v&o}W|#aG#rJ1n0W4@fly83mB&!NoJ@G_i zRw~E;2xS6Rr$zO@QHq;tiZm}xD$oqnQn=YK$3B(U6B41EJbn>Oc~~O=E8vnF3GX|$ zv?$ZIvfo&Dc@->A;g7{xRFPdrNwnsqYewm>PrF*9T%~m-2@`qEn}F?AfRs=BU6F@z zgVbCza#*B@qqj)NNxRJ@=I8!3Nk1|Dgs6~?q4U9W7;(%r4C-I}xNv+A!2^o05Z1z^ zNM8NV)^qTXDR zte6QD?Uq>Fzuog?ONU*BmK9F9GZ*dD6@2mgu!}C4+#jGxPhvT(3Xvqsyk*VH)`Q+s zM6bj@Sak?aU20J-@bV<^X^UzIUch^&%8{?QSyHzlQjfE!S#Kova!7L}w%b*Wfliz$ zHvNxvW^gd$GrC*;r^pn>PC?nc0b_6&Fqn*N^rrQ$ca82}riftDS6!Okq4U zVFXx=C#I&l-U8&(v^!cGJOWfT0qbBas1fKXYQbtj=s+&139rsKu;=FiGKS0=zz)tD<^scr)% zG>QNy z(W{-ppwXI%p;838B)$~)@KjT1RgO9#`6V3;j?YZU$L?+O6`7vq&ee9u`u)&P`fBjW zz#C2+2gpbF1@7D_1zJsBdBDa1zA~0fI1Lm)?=RdwJpMdu2L4(QCr}oI zOt&s$I%qo9;_xaJ=s;=FmRPYnsn$V8+$9M7__P z&hC3@UCTH{jA@(JMjV-5Kl(FpzN~n|V}sR`TdLDOkb5|NPF3!^cXB_x4zJl%xFS!{ z!+=aMVIf#(7>cQ76)kDRr=-^VPc3~so|xkX1mBdTxzpuuQ2KcWyFh~n;EGEKZ4*YP zk8qLr4GS5VQEv!6B24-3j2!aY%1LWPWBS%{w=?uT8ME!=?znM#p|2Xmd^f8Xy$fPkSZ|eiHwpk>nOImXfP&yzNK?On93~aoX$EFIn-43h%|(%L z$1Uk_A2D>xCwgsb4UyqBG3fDQW(4)%{64<=u~_}324!T;WAw00*qW>xgJ4}~wqTYh zkqY)#HJ3E{h!80{tRsKW=3sF)*UN<>jpw8UfK33Ma*ywE*2wKepv~lWx}j`QlFHdZ z;E9{7wqn6yFd3)}Y>BcwwE#wP+Q~w-?Y|)yJ^ouz81N3yme^ZOL2}%)E8tWc^&W|@ z-f;^Qk+=@jtK~}CDUjr6+&KySPXh!rH42ktDl$n}M%zu#Z7$|jm~nC!XVPCfVdXl! zH6%o^qrMI6P$zx`3U2@;5ENAw7gOQKaPEpf<*sfd69KXb{K=oO1CZ$f3{iLI8NfdW zBnKvy^@BD*lnvM;2u1{%2O*$%cal!nO>uwdy)LjMVY=Xcp%XWrzK8Z7rlV52G`Vyr zA4~X5WvUix)u&)zntcpV!_hTg3zVeqyI}2Vd2=XD&mG(MNg4CyuIy`?svN$|;eUo< zLB0)I{YbntI98!Cgi7UQB*2B&7ZnI@;(= zbm5eow^xLh!BZ#>XR>7{w!M9x2&= zlu7!PTv|%!=IzIdu7b}<+$m-K=KyIVIFU~aO@XBiFoVQn|ll_;R{GrqXQ1q^Lw&*o&1E(92T zOQ7inR7MmSu|)d_2?U;KWm%H5U__Gas5Gdd?<=og9sto2-Jp}V zUF`0l6Od0ry+Tn=UbvuwBJcb6a8Mu&Moz8o%D@NcJZBd1{11o}=6^ZUOlD{Gup~oP zZDt>1FD@@&z)1qc;;O2BlI!3HEI|Gg8R&QZ+FZZ3-Pcq8!lQxlJLWSIfJj#46S3Is zBf4zz+#SjTY!+{VL2nn~fJ*f!F>J7_p1sNfk zAz{%jXKNL5>;+JOP56}};=tv)aN2nmwM}8@z|ZJu-JECw)n=R`+ef<0Tmg3#^jhlW z2f=KRXyb0c=K?!~M`;}@&1Q?jtrI@3uYLSvgoIPm8W;H@v8AGfqA|uun^^9y#Jf8fM&MT~M!z9hFsA-em70Ok(KX zM`&(+6pQrQ7sGl<=oCn=JtG)X4P@xLSj+A|GEEFBQN ziJ%K^Bv46O_svKGcTOp<)i?-FNE>j09;nUfp_c0S>oghb*1pJixqP1l z$cQ5PqgW*Su0`kXS3C~y*4pP0&4C)Y+Z^~Yf7chFTp!gOi~U@h?pX|O@XEeWKQ6Pm z*jtD4>`IC~xN!m-zbt4q-5tt#QsevZNJrt9@a@|M7nlNzD=TM1qNs~lgU4|gRKHbM zC&_SioKorfNtM=Jr%z+!4YUmd13Q?~j8 z`1jgAYPCH$fc|WtI4hidLruQ@Po83PiB3u1zn|{DbQ71pd2_o9M+V)$2gW9$Q@wV6ep zF5+`niK&m62CFUzZAf|1hPZjzk^fosk`-vdZVMzgUsM@JR2N>WOzJnd&`nQID`#*7 zfz11``5GH;;Kl|sARv9X7VCl0|JepnVcZ0U)#nr7#I9#@Z2aTG;dh`RO@q{PY}#mP z?!~3yi~5?t=X8hs4QQK>cR;P*Wex{DfIwwqQmHrEmtOBKlm#3^OTo;f==twIR|Gf- zkTz;Q+fIY*Bxhb<|Ao_qco0E!bzSz>y5aZt=B_r9K|mQ@qJp}n=EUJgH+gwPVBxs- zYjt!Wi0`d3EC)CTI4FQJ*c2?X#s@K>w_n-EXAfWaV0mhA7YH)~RXuQR<>lq^6zI@m zkMBQ4p1q|5KRrT~3%rpB6QrF`xNk>sd8*NrFip}XQNE==gp>Du`vx%aLQY&}NfzMp zhrT>6M;MVuHzmL3Nw_pwk+IB#K)Z^B{_$m`!SH!Hj@9F1w#a(gnxEq~{81sos~?fm zj{Mu8$SN^gc5H-VDHWKAtEyw@yzdE7VSiJAV7y6k-3VXedI~9b>83&?P@kxR0D43wKi!Xwka=un|So{X}p61v_;B}P*=S5B#ZfE9NN+~vcUU6 z3oK|`!}7qGQ(rwQcBg6R!vF-~RzqKI0`aXncu1!d6}B&R z&puw|+55r5p$Y569}EH#!XG^sR;;d$yg^t$C(Qj>j+)Dg{}o6S*2j+H0*NRB=o!B} zUf%)ov6sN4@4=B@ZN(WehM5H%ut2(YS`Ty$`%m{61T)iBcNLQjiN%W^3m$TD#Dl`e zWtQhVhQuWCYY$fs#@aakK~sK(m)q$tzD0t}(kar*KJ`ciby!oJB}nMt13w_2TMYGTOkzg6j^TwPs<*aZJy3&4#Z z6Bb9pe;Ofv9|Xn<@CKe$gHTWz^?dO@JzS}25duy8-u8T}-3+FK-MYB%u?jGx0)g(v ziu^-n;z=UU;zWBPs+d)d|J8Us-uh4X0MYWNrx|XSn?4?1DLXqB(3$c-DciF-i4<&6 z0;HdKP^mciz=YVlPDP5oAC|KKun}-jI$sykt8UElub@T2Q$W0^x@qLA^UFbWv?Rd! zmTfA)eQp5?R`&Q3sd{K_KZ0aabn$zqLKtH>OqH}UX9r);OQY$!tECl+ zrqS{FaeIwg<;(SSNRqY9))zt7?+4pwBBR^=3}D5P=Hk9Y026t#YT@8*Kt>19#ZF8} zSy)(%-;fXzel0AtiCnEWQB?~412V5?_jQ7!O)lSzeook@OI2jbEj8>DHP|YNtT|m_ z<+k8TcxjG_I(;Dzv7rvjsIs^C^}AQbf1UzE*=;w$#j1BmCU*5&?f_Z&J6fWPMFA=q z^*bcR#DAOB{O|>#!I}k0L)D_O<^xW7!-M5|Z^nx1UghtY)?u`arZ!8Qx4CoqM*cIU z_Q)WE6t8m)C%vz4zX&^nFtY3L;Fm^xns<5`*K#5zV3fk_P_&{}dWp?wfr*}KcN8yE zmRy#tIfl$iV^C@H;gR9X{)rUR2WUSve000!aFa@{l{^E98)pZjt=pz?UfLWO}00FVq}=^Tb8$T!INv2Ct5KE zzQ=}Nj$QGs&_N$e5-oIsH!R(z1?|%UiRIcomQ zud=e{R_;vd9{(bCg-BL|@o+!qj#R8L83O|i=H^tRrKJUw&47&&;3E*VEXCVu{8kPJ zGF>||n5*T5KCARin)Y5U8X8QbguzV^3BxWkxs8%diZ3Kw%1u0CT?5u#pcU+Vo;kx` zkpLT_jmGy+d?t*#95p6=sSmQm5c z1mnPlF*!LY4Jxci_#HP^BPe=oYhA1;+kt%^sl9}IL9IHV4Pv`k%mz}JXfj@h{3hS1bO+fM&E97jV*Wy)dP{vjPJTY`gqd^m z>?S-b)vRVdMLvAVkpVvj3kiN_cb944fXk6)O!g&oKdGNCFMNolA0_#5;MnC*JD6=} zm#)0oq;eoK=~Qn$$W{Tr--%J)L_0)r|0rrGV)ZicS8p>v3i0|OuVyiP??fpoBwz+Z zH4+ci@tcLC?|AxyC$*xte5`fg=A{+AoVHSM+SwW-0iFrlC-Zr z#f>!Gef3YqUruG}gA+w&dFpS}DN0RQTeA9Hp0KC7Vu@`DLFnL*pqZH&WV_>r+id~r z0Qg+>B1WZ7kg$P<(6Dwo=>2dpi|o^4X~CHqMwLyVTUuN6C6T-eLp{(+lmc?=OfI%> z_KQ?%K7o02;z0ekO8<#B+#Uc#-S8G_#oJp^np$E7- z3v$1Nr-!-TYXz?Uz=u7(X7{V5Ur)Ds_Noly0NCtB6l?bu_W1WsD|v79j6eiJ7*RIx z9TS3&HTRJk&SvSCi5SiaH3&~R@d8gN@McP5Uws6H2f*q$|Co3va(g8ILg1>|6+Gtl z1OR;xremNRq&eFf*T!rGRxvPl1EV`FHWeXSiJdCN3cy~td@m2ovL-bX0+dKJv+a%+ z8$d&y0kXQqE2>BLRRxMbvPN};5Ch09U!Y3iZr>(l`Z{KPCh#fUv%xpQ6lPjWoAecz zmTE~kh>!z?;pEB+M7J+tU-Gh)#D^jI4Va@7uIM?_AcNL5d-saSd^Hxcz4FzY=hZfi zkho!MmH{aeJG2N(Cc1aAvJ~*^4oHsStF5N#`wN!m@X#`j5gLm(9HJ!o7LJd!Et6qr zgu+3ONdvfJkI6TbK3^~20P}8BApow`BGB=5) zu!0zb!H{v2hliS}o5|w^p?O~NV}xUPwC#tyMI)%a%wK)XFBVmmQ z9|J%5Jb_^X=-~b*Sq7CMRz9rbV~w2EGW7c!pEGEbZgQW^KyL0hALLhb$DhC}DCdY} z(dbfiXs>9CJ>6~#Zq!QuP$r|51l_K8M|V6xyaOg0k)v;bn0q~gEyVujY-*5) z4D-{-gQ%&p0U>i%2`D(8?yBN9!#=-D0iZZ|(_q2__YZMtNzy)rk|xtXBk;URZu14m243tNo~N;wJ87$#)%5>z|0#; z!Nl})D~b2#c+c)=)`)bkNLPj0!S4r$dS*#@?{R4n{?IZ{0n#BzO}GO?7U-MFt*=i9 zzi_tSgrrawpwC_`Uy1E!AQMSw%%ma_+szEEgJg0E^H??mJpySVO{PXt^pVS(YbDm6n_^tBD-JWv%LVLhc7gUJ z$NIO%F-b)DNbt%^Iz(3m@o^~!6Y=tCgQRKRtZQLI!c6>hXKGuY?^CL{KZPJkN6AQ$ zO?oYngrkc7QHNNE&Tm^=g(^ldF>?hb5t^X5xeSzju+FATE`I9l$iDtPK5p_QE>ZXn zvUl|aPh}x+aTpQevKcq@2Y0O})}8=%N#Sc64q>dhLW9LYo*j~8DbAao&4NEXZGJF3+AJF8 z(nX>Cc*4_qoa!si(|UGT%$l8OnY~A(u})`=v;oz7eq^bA{iEqp(E5~mYog}}f;m)% zigLp_gH`uF@pjz{;G&!q?Q5_(w5A+8KCoRq?wbU7_puxN48Q`H8VshW&1|~mnKYVDtp&x$x8ARp4-@mxMyNf|`y@9G0p7{L<`Op}z za-sqbS!e{gPo(RpgEe4{elFu#T4>=Q8hetFn-03qo~#8SR@=?8AsD``x;igX#s!c* zndfrDwu+EwI&d_AZNS11d94j3=jeoY zdP(?c0Lc?D>OWf{0UQdxKRT4sU{=8zb(fj8GNFtDSbNri(4{i)&~EYOX0!$vlR>$K zY>TcnBEo3QJ=^#WR5`qWjLfg0GM@F{RGzF1H5PbDwbv%feE93dH1QifOj_?Ed*^{0 z>$UiMs%knZT9Oy)-}|{nfj)yF)`~oxn8f%WK%&6gML<9RsGxT)Cmeh0oh;k^SeO%< zrKBqor+! zX+JI1#wKZBi&QnfWzO1q?kIn%nOUuiC!f+CNQf#f)e0`GN=eOj$gh8Wr(B>3FxKCz zPW_z8_K|)yGt@z91n1^ea|x`N#$UKi)Z|uBZ;E3?;! zE`*=zLnRpA=o&%3Y#FI!;=JH?DIuko&XEs3*{h$w#!C#$AL=1w=QPdZSUf-`6s^+i z@0H}@976JL@z0NPZ@3&FOZIc5bzn(_awRobbAbH1dR6k>yVt1&8oP@rIAH@;<|)`2 zL!Y|s1Enu3;iJuinE8vnp9u^o?#Oar>3>wXs`{`YF|QI z{k{eJ7h`MnY?d7bAE8gnHQd-BJlyL@Yff`;9hA%MS+9kj94C@SocMdNDkTut1P!+2 zr?pfP|Hvy9sw}fz(TZIrs%4EM?mc9L_6h-8V3}UT#p95Z> z)$MsZD?mSyesi|X{b9M;dB^xw`>zx~EQP5bqucA|Y+IUaoBs?VYMRXW%cFF;plFqC zk3!F)rp|Eg7Xmw95e0X@(Js^($1epGoDyPUa}vkFhJ4G%bV#aA9Jby)JnX*3VL5Rl zWzjW!g0K{3c@Xzf1U8@kea`M|(6stYLptoTF{a4o%@qgb`Skt}#$ z)w=`M4ox_?dzUR`a7qKV!U#m@f@HFPAO3W$kPu%>K`0<+K2hD~U~d5yssUBZc!Zj2 zb-9D(781Z|J;w8Q%|3@P0Otr;Ndnp+-iSz5tQ$3KMiNzwY0C6qC-Y;$1gS{>4TO4a zm%L)G(>k)Qviwkj30-(j;|*}<`_(jfkG&Ji>REOA7gEOu`q6;h#nM1Sbi3$?bl2>APnEw0aB@Y6Yt^4LGBINvdKiwdxEtTeu zl~)Ecc$|6!!L+_A5c=LCikbklq!y4RsLdA<3w2~>qt+7CPUbU0!MO;VXQeZMSjS%S zJht-7_|4dcVPMEn!O5k^Rq>+|ZK{8|=SXWS`WaC0kj{0HwrQQ$?esELakEev*)uvU z!lj^yIWFDcZO_WZg;HubF*+4pZ~k%R;)x#jcWWZLfp2LQxxsQTd>WYZza|nS3=gVS z2|?-<#43@A3p7enK4}~j)!FCH*Hjus73XapO7{lz-7|)05)t1z@3b8snjo)7DM}J2 zGkN6`@4#lw8_m?%zf7%GJ-;%5D$yV(6i;ohO0-q(1@5=$(O9=<68rgi0z#J4z?y~?MWiNj0uM$+UQP>As*PhWxvkPV z7lSenmi}8>IOvPKn7pAJ@f<+wog4=~#WWq83{9%BGi1Ijoz|2&-^~k?(Nc1&BY%PM zZzk@8^Vdy@GW{seF2RG#PW>PLFF;=bmIp|d_o8fH{1A{F2yuNCwBVSZTdx;I#>H2x z9qlGmuHXj3Tvm=L%=zw3>EYN2j2-#ORyp*p&i_pZ6M)!lU^aF9=W{dIa&>wnfA)wN z#qJj*!`!VAc#8vbjL>>t!0rs{)vC?!Jf1E8Vi)~tr$MF(Myn!LTtwhP2iI0&Gk6O? z&kR5xz>ol67Gg(anD)^m|tosMiV*nKbjzIejMbV^o?K$H^KV}lX8-RdG>{@)_gO-tRgT0*!OhE3_6He3Wj36PMZF)j|Ld?>1awn4eB z7p6HGC(QTJjEZKRAudH2I>tAAkty9tr{0<~9|U^EiPZOE@|dV-u<}clxxk zv_snl7Bh~dhWz2V#5y@H1|```-Mtm3yzL8*bIzoySY0M1-xAl@ylFdQ7oA~y*X z4PJQyN3CS=+t5fw+Jeqi$~V{%(~>a-VZetX{TaQZk(;9XH9S@Ofd7>hTf(RAe*kP2 zZu|FgE87Wn^0+Bpo3b5fSeRDOKY~pS)Xsqi2{Wuwhj}gywwa<5s^|3d$r+Tp>hc00 z{?Q_^Aa(e93{)i)qGC0Le0w3JL&OMsrjIjM- zQK4sZEj$h1iq!IrW$<(#hZ$xAOUuPch4G;Q$(w zJw^z1)&UE7d=1EJ@&G-^OW7UA^`|RO58@(#5jz0Y-h2C%dQch|@n1(m6@qv6kN$_X zbE4#6qz0^{4N&x-9n^eSJ-d0%J8Ur8&ma~-MJ5NSxge_N=J3PQNX;lYut7q8gZO7f z`ed{1k*xFc%Mu3>M^7w4_I28VCb!&tV)Lc_3-emTR1O1_tgxIxLJ+G359q zMT~l9EX^;?jr?HhkXKZX@{A*`G0F!cG;l%Riw~I5CR(pYRRw793fGC^?Q#>D{Jzq4 z`$-V!om8z^){;mX#x64JS(W#Ym1)JPOBhw`S#S}~!n3o#*@x%LnGs2xs;CU@_(hQ= zGtmuGBew5Pq}sIUC&L_t*<&R{WOdL6g)y_Q(H6cH5_(fkB9n>ys^{?3fCw#`;4mx= zB{(cY4x|5cX9N$KT+YP^Sz@VuTJTpZs?wcsyx-*U`%`6Ro#=kT4#TLq>Hb_>MK;Bj25}X^$mcs)8|TEntS7^x`nSTh%9QYeOhUx%V{?90xq-)dYPA%rs)_eGihMQ3D?AbhA9k`5$-Wjm~p1UKGW~QJ?-8 z%dzJheBa*5M&_r}wIrGSo3#L`?!!uzMFbZ_+_Mv5A{Ub-Ufd)x#-k}~ zMLF|3l8232Jhe@MIJo6O$_piC`+uQdXHq>D@l~#8*1C_Y7)IB*7|w2#5{?+iL?5~O z15Q2?+zj>S1l|8wyYP;Qg!oq&u;L57*gxO(LKnrYvtRAiDm<;#j#fhmQGVN)QW@HL z?{(|Obs|u#UD8J(N$@gu>?P8=U(ygNr);__+Z~UObKiZkm{L;`)8GGMG!$Wy{l9B6 z$zm(j1zlSqoud)oh_2LMRXJNA2^Q$G?D?n^PCh$O0sa->wjKvu5u2iTD4UJosfqiZ zeO`!$iGS9rzfhRnf+)+)MQRNm%mU9rpuo@u9&A8Y0Df60_wjZdKSEfvI9@1a=CmSx z=4P%;uoc}OP832RXk~m;3N)nIz>hvzW1dfHaew=Iv>12J-VGksGH6$;5H{i0>!8jx zaOkf+d`Sl%ZVE2d5ZI$*6u(7X)Adq6q~=glM)pxcDSc+b=S9^h2ui0FA6{M@ELJ7Y z{UluRnXTXXmi)<8SYW@bMxgAN<7mzak)@NRO87wbP&iAKF0cPfIv?;XHsUj{X5DZ8 z)^GexxU1K>jA-2V_tB&A@@+@-J}aw(jY~h_{&xGKifVm+TG#8+74P7lcN(9D02G@NY_Q8z z!;0qL@aRd0JIpH`_&TPitxLPM=Vvlr0jyeVmubUL)@s6lFITcGgW$z_=~SU@dK`Su zL56LwY__n(xPPFCsb4^bl|E4*#W8E#AK@!u#MFW2T@I7d)M}xjE<@u49vrSqZ3M&T zyTAE#fCWGUt*5D#&-KqoO~+!-oNK`CWKOkZKQ=%EddWOVLCPL4@L@iWy1-AF0!#tV zm4`J>t5VN}_8{9&5Zt&t_^%B^hpn~7`~3a=pR32eg9D;4C*U)yHpEiby*s#n4HHj=1Y)h_&MLJt^g6 zqW_(RT!I+I#Q~}TeE@|Iq$@<4D`iOeTYg~~qR01{^vTj*}^r~2S zuJ|8Ab+L%#z8}Hd@8jbGnjuSgGTHutguDAMBi6g8ciybT1%uXbF=64sPccXsE{+>s zR#1~i1%4y~jeh-4idz{*o-SnWWp6>k0{MUnIfjzQLHqti(y;aXcvVQllB+?RrReZ1 z@8o5h1IUyILxvJ@!~WTuPaw$#H;TyT4m~1YA!WS9NQQO#ifP+KTuxM2p)PY$G=ie; zDPaZUJ{vvo(MWXDFPf#$xc}8IiT=~IkH>=p0qbB48+p9^Qg0WFLXW{#>$EM<^(cRy zT0D_x(8Qa@6u^mVX_)G^{FstvSoK#fEr3$|qmtg&ZcGA;Um6$c^Xa*^u~iA2Y4n@e z?~R!|^HTn)?{U+FW~8qSA~X5~(w;6{d-MA9hd>GQK2&Cg58nC!BUaf5y92FavHg9b zKz+1`N5+m=TU}>>bnm<%QtRNM*i_cG=EIqTQ(3`+8iWK=x@aCS5lIvDw_% zZp1r>j-=5p$~M3EzOBZx`nZ>8s<=FE6Lq*m#?f_GfanUlOELg z2rCm$hDM6qj%RalZn^EKYj|wud^wZ$l`1wBuY77^()OI_vX4+TnOr~oAa^a_U z5pVp89p8&bRh+y6RhCQ5o{;_g_RpWw#M{pT)b2;%9yyWP3QDMx`V}EXW#YZ*=Hs)- z!}Ckv@5e$wWj^=qG*_9yIh5*RwH=EYk?9D9#8J_@w9(AwM*21lk6iHw<`@?qul-8x zt-4*Fo?Fo)Wnv3$iCy?j^XV@EA4%zmc+T>|5oppu!SJYlbNd zzSq;hR|I5-4oxeCM(vpMXrx(8=06&<>1n)Yc@H7bJwJ?FCN8MPu*{Sk-zIgzqDcEr zuS*^%QvbL{@Wp)#`W#sTQdvf~wKf_6XF3}SR0p@H>E3bie$< zh-8Rw9K+V|dd%zBtgK$`3Vdm*%llA+kIdqDadI*De0eX;l&(q=4&AXN6uVmP2Uy%1 zjNAlCK^&}-ac5>t<_rDV)=w`hUIG=uv!xxRd4f1qSt6{YP3rJdA7s&!D`&iWS4)z4 z)gxyY2PM9EBte(O9(x)nBK2=cF^gW;f(WI@eQawZfsig|@0GZlrmapiFZ+Fq1EXpj zCA|RhH}m{U`3R?LnLo=(B932gG?>`tYX%MvxDY}@m8Mg&(d3}MgMv_Hb#fxtvk?0F zGndptc?(!Eg8?0A;&#Cd5qfN}bnydG)YIw#WTiC;$&B{26c2jFh3f98O=l= zkt)e<=<_hXGo}97jPr&ci*ZQiMzJ7I5&5bh?}p{FK&B2GEt*U^wEYO%gb5)Mi3=)P zafy&JfX$KZYVn4hMls5KbEu&g&idG`^YG5H8%389&Z$8@-pWZzFhf)+&fw#1ts}lR z2eERR=MnKGYe|1B$;dt7VKZ?Yk|7Q^J&^r_-aJt3nT$;n+BIKog}QRT#qYfZwE-9{ z5IcfG_<@G)?6=dcVa-r6|3)xt;!Pw31TrlJXxx)$E|l;$m`3?RA*FKs_Pd%({reata1Yq ziTYnhnM@-)Y9a}_MsDxNxt&83@D&2BphFO>ckWe#z+Q_I7JXYV>PeLxRy4znVQJhi z({Ign4-p!65Bf+9hqVF%GC@lOU`{`2TsigijmndEe9w}GK@EYG-x(1m(ys|8I@`7| zu7U-}aGgI%y%Q=$&ZBedk0Vs(7==GS49~=Pxwga~=129teNf9|~YhiLP^LfvRMY-WOC@^S*AEda|08A;k(A>d>>25)+Sz0amPuo>S z=v+i2%$A`bhX|mDAR0P}S(G0@D6=cqLRZ;t>?3Rp^IA1?U-;-wziAdzf1s3zl5vUc z;nLb1&^&m*12G(IIp0h4?Kv#Hkz)BaZb=?P9BqcnHFXLr$${OM?w$1|Gqz}>oN_-_ zdyHejhPO>`VcDskU3O~lvgb^P>Fg_U3d?9NDzO}Afl=KX-gS#ukJye=C*+&m?HtJ)$4D)f1@$Hr#&-^n8rvoyN8Dcn&zy|cJf z#pn5&F^7loBH!r)t@p6P$~elFwUsR;y9eQR=oj%5MW#J@0@m06@}q}dn|YYv+?Gl= zyxX?zt@xtPkqBj#)5s&vRbrrFfR#&pr{86_Y9gvpkY!r5v_lzw;ac!>!6ZxHerUCU5T zmx1Cks&Vz>x(%P@)C0)56k#x34XK_0yakLEp!2%Mex3`@3N#ACXfu5VgTdgYri`Nq zIXjp8r`~mt`U18?NJ`%ZY|xHJ)9%jkHjopn)>(X7O>eu!yUX!qdk&qzkHJeUn72=p zp!}+!Drj;NhiR^f*5v+MCvPI8<7@O@xFnSf!<)(7pUmD?^-n2Y_cSozl|jc>bXU9# zb@UFY9&RXF%(No)4W@wU^p=hv&Dkq*JO5bk$?fs6v351bM`RFx2Xr>4->+2YIFeVKeCkHI%2o@0A40UL~mJ>Qk}F&$JHo37-Rew}G{cAkW9V{~?=-0kM!hZ$VuJ29-r-KN-j)j#_d zx$)%^Trb?svUjJ

    yt(l3Eeh}|D#S&LHRU< zZPsaC1za^#%@eZR#^1(=>(2`Q9ns?Nw{P$NUhlUV?rT;noCFaFE)Aqtg_?goCb57z z4*~jT22}BZZW_?Ev%}?XC{?iqG4mQo zEs%JN*mFGC>y&4v=wBgE`{}2H|DA1Qausus*<~<9+B*e@OO9D$hX^4bkBgr9wAZImKmHBF^AOeZycwcFt`Yb1j*Ot9rG>fcdzIIuoguB2Vw2Tb$b zW)S!ZY=|}2KWiz3%FgXGcghf2NaNVveGGze7!8u#`PiHQjtZ`b*ttxVMh4g9o7>Z=7*m=w-|wZpr3Vh;G+Q( z6VA-#%46DkFeO)hCKLIfLqNA#XoC2nOD-Q;VHJYoo#N z%0`DBm2~k~8dOk<8Z#YTkP>xWZPnc1OanZLT@P0^&D?>_TKnH8s`BAVt$x@iec|ty zO625@$xgp`vRM)Wj}EZSKT9fd^jYu6Y&RQ&UdU#|^cAFUB?{6lBMVtVW3f1BQ6=&Y zmmKSv$>{u3-Otg`mWm86kAckf?g8j>pT(_H)8nGPd|*Zfon+(_Bjrcqx$?XFhYH19 zed#FG3x`IlCr&fK?UM!Np5`MNS!}mTH|aUmN(22o&(&PE-& z33XUO^roee9FRR5sJiZqgg{05y{#<=;D;b98OUR!WTGox5659)Hrh3SPm}NQK%v92* zmwsb`v$DQ56IwksW)xbC)wj&O6D-WtkJs4X|>!&B33uJNr*6%ECi zZ5~d_D29-_72~uapjpa|q=h8(UkfNacy31oW)#Zw%;mv841o%7(%4ISpT3o_G=chD%GSk3O#?7^IK*L?TY z7bV#KP-S{{HvA)s1|wDDC$6JLb@-wxY&GnqMU%iF(l?>YGLnJ+N7GqGRr!6<8U=oW zgoHE_hwhT@PATc`mhO~}Lr6DBN+aDM-3^k`B`Mu-H~)LDL%%p2GR}GTyZ2se&H2pY zTKb`9dMwMLbU}Psh5?>g!d-hkGwaD*OsGsj0VNNa2=hWOR0emf5f3q1*)-QVZdoHs z>bXpLX}g+T##A6-Sb`c{w^!SBn&^xNDU7#DH2)K4U!d%}irffil)*(TlDVI{XEcgm z;7)M*T;Ea3K%a=A043kd--QHI%!o|FzalYRsrf5{!(psWEus z_4dxmf*vK_)K6r2pK?7hYukACov}$hi?Ou69kBO_AhM8Y>Uxc#zMD1s03`oqrgj;_ z+XA6gsm8Ntk+U<)oZTAj=lhyOWSQ9#r?VHHsV$Z!yqv;K2b1n69|amNFRe83*;5S3 zMef}VbE^lfjQZe&2BIvd3#&kDo5b$dBZ#_z{R#T#AX!QTNbA7t3#^RKmBD~@mi`Rd z$N)7!lMUO+(ofh8=4Qgoxa67g(=#(FTP*g|pE$9OtUDgBHbJPuSPJohAM3Jh18Yij zuh9^(K`Tkd&A4wp^aHQR#YGQDEfEE>^JP`n;?n+xN`hKP_ zy+$mT`ZD(j`R^0K#kjJmV}opUHF|k%I0)ATR(u$qpP#?>bsInbjNm2Z`mjBv} zth#9}t3;JZ(l9!2^gxUQWl8Q1MfEc9JL~J~f3y`rKG;xHcVhbhpPk{(Cr^p?-KYCM zo+SEpS-UoIMhqIrlqq49CQICHE&&Tc8}8R!xfC&oQi2lX`Emq@-%EruDCwL+;BE8n za4ZteS-1bI`8sG#hCE@DchkqzcMu4|E&aI&&gqsr=x2egt@ZJ0X(WXu5QyxL^BCM3 z>=))3Vb@%i4n}zGiQFD<8Qs;NH0H`Q^R6hIz&?Dw9{_)AO&+Vb!l)c4b;WS5K9=r# zl5`&y865d&4)_k+SwuEzH*7jp!WE>(t|1u&{$XzZLIwlP+aMFQaoVVJYP!3+tI0O~ zcgQa4JJ_aIrr*CT_ia1UC@G6!aoTFNXs4bQ;PKs$)O_Skht^N-0_k|?!6O=gHN%pm z2RAn(4VXdMI!FZDkz%+42;!xQvRMM@GUT=1E?5J{0pQj4XrO=D7I@v;ciudaX2)3? zEsFE+`wi5ni79*Y%gm3Cn|G?E%sVjy#o@bc+n$5RXI-IZ zrazJ@h-hEq#b{s8Xe{dKu*%|yZLw|69}QN2zH`cnL%){FB0bZIH_yQnE=BqfP(|+6 z)2MBbQA5^ljt5tQ9}+s5wd&YOdZ)v9Y0JLIt@cTiz3tKQo?6|^nw~{jSajSZO%Ctf z6cw9NH@$IQ2)=Vd3#!EZVJUVuI=&>G{qLSg=^!A}P|=YbvPuD?hZ$CuE0Ul{Yz&=T z4}PNYl)BhK6QHGqhm^;r+pUZpE-;;4EjelaT;sNFb$~y0Z&jRL9i8(J_}tRUJQGOfpdFGN*DA^J0SFbB{Q|51slu-u(`%=T)p)|qzQDD{}oz(2~)7DO+E+i=K= ziUv0KX>Vzr91=Q4Q{d}Drd+DTy(!2=^n1ub{JBiPpum>9i$hLcWsK;~`0kEH!b=c^ zDhEM_rB&|1Y5yyC@BJBwAkv>rkv{dYsK}NFqHwYInw80~EQ-*(Q0h@ z&td-?v_eO8u9`EeIfYM#M#Un?mmj9OBXSd>x&ja$M|!W)za$uy-w6qCfbVzyxQ1m^ zAPS4Be696-Jg>4+;luD;$CV3=@4~q(NURi%nv1cIGJ2&*LTEiLITL1$s*SNv_ z{YsNasccim{au-{QoX)U<2JyTBV%G?YsAii0SD$P=&8EM(z(XFuyAN!ENH|2& z08)XA3}ngB>aPaOpEpDNUjcPpSbt!YcWN=%@?Yl7k^_$ z?WPD5?`K-;?`f{Vd<>Egdz0%0SLQnAjs1Eijy8KS@~>0FIcGg1aQl0xEu;iXM(>Jd zD%vX{-42-Xwj@l7WsJDa!>r*Y`hVCPv#$yQHQxiJaxfa^x^dX|szv3kZk8YeYo;&X zTd3er$inF){uE@fZ1;GP8amgU#D-y>9TFZK4l5H;6o^f&uc(Wal^C80jrU9#zUS=| zkz)~Uiu+h_XM*gD2bGIJ?7!nSPD@onG`p7HJnv2!{hwWc3-`pjGHpc4`1_(o`}FMp zb+~~`Duo_s?0^+MX#v7J_1|0SG6eNt2dEoEtJv-kBa^_vkbjRu$SfD33UVppdH zt!7do2tJMM-;AK18?O}Lgjaq`gFSpN3%87{O}lAZqmH=b|UcTR=@ZJnv5E+ z@%#}ln^1=-EkKT)UXGkSc~hELVUZAuiC95R*ihBssmXfE6nh&lQ}9#Q!ua^eNjetd zu6Z8AIXsBATsY>tRwWE5C)H%jz#o( zEB3ySaSAbV_~Jeqzf>e?P)xiplA`1`ptO>V>4#@(G5(c+it!b{atzd}p_J0mPa!#N zYSekSb6(+(d43vw)cUtL9&X!_x6EbN1>9E_*g;?hh=K!j05+Ezol!w|EhD`^bxh&eNXfKR}2xknon=x>Jt*;%8)ka z_l>#m;7~I8CZ%I#j69kyBVUUZl!?_8c~~0fW?d)l0DN1m&jfXQ2tQKh!`v!yf2mk8 zi+fMmp-M45y6!Kw|9(c+<+Rqar#-5SjNwv|=IPu@urU!DbL46kcWEU_pv1r0K7OUh zqxdBs3~YgfQUb^kBFZofMLAWlrDz~+$V!V2v*!O_3&5JHLS86lejoq`=AZ`5DNHCT z)NW@nem0=fbk>7e!+rP@XYYW3o}d7;t50fOXzd38nYfAH>{bDJC>Ti)ql12f7)gG_SJiwmm4M`@f0Dwj z*i6>)THR^!zwOsU8BK;wwfFc6<2Tib6zmk3^s*a@f}p)dKnqM4z^6J{nuc+0-%$F>Ulsjsm3CGO2S$D zeVW1U5w9k%69XVA2)-jHTKm)AnjWhB4$DJoFUX92f^4jp4%h)`$ehs`#8PAml!xdf zIjNK7P&;X`kzC;O?6pbvb!Ak;Q%LUPo(_CipBT^OAhQLPtWTaznaW*pPfd&ld#@82 z`388Jh0HJhfV%-WtSRh){5SpbV6N1uTypq853Mrmf%Z>Ji)H#;U+Q?a^i-nC-1yzQ zirpQzRpeh4e_DW^f_}ahX7xW}a7ETQyxl~vOagvwDd$1kiI_hr#gKE&YtPB3eTtUu zb$gI{;SMC)D&f?ctJLz&uRk;q>S9B)*zyh3l4Otv#3y82$+?eHH^cNXcTdKjGDCG3 zoB4>wY8K}IOdD6vb#AtfY#N@+GEKIfv^&EE*2<>_u%(jYBGYzY7%%l5BGYtU-b=wP z^{3xx{FY$GR5_RIlN&P!JDZPnT55gje7S4Z!awAD;-4L92NJJ(HZF}WJ%Mu8YmCrV zx}dSi;0fS7R0|VKQt|kGE>v(f$eRRzzYfF;C&&FnKsJc5kj}CYlx-Ch zX{8v>RT;$3prRsDCn7;sk#F`r<-jE}xqDt6zOsDnsJ^1HWc?-SFec2#Kf zKYUO{^gI$B*QP)(3aJVN6!Vx4r5W6ECRz3qlBtj~V|vjNB>aL3XjLoG)o*T%V>}Zb zGfJz3r3y-`nV&yc7Hy#G1~W!|cb5m;`$c(uxlG{A{CnCo?o+X4F5)ar?%7@|y`tj2 zSZfL1FA5WSV>}ImZUO?p$pL_O0gCH%nS#BeBh~wOj-LGMFfu(#{5m>_f|N+hA3ZUN z;a!*-bHDUy1-~!?+Z&dnqw8wRY05-?F#Qk$VDD1{G$#9ttD}z$dLv7ftpT7FW8wjN zvlIpS$f}^L2#m;O$TaJ)dqzfzUnVSk+S(qJO5QPuV@4;==gk$imgNZ5uY5n93 z(}yJD$T@wVZHsIX=q_J zuQIpUcsWXs^iqS2fs)b0A6B?RqmdRYcCAgo70 z=H%@+tD%9l)(r#R<<|+CUY|c>wz!?B<(HTU?M)!+o{F(xZ1hR_>3*D=V`IZlHmz>E z=%oI-M^So#jB=}uvtyzSGWB$IKLGLQA>fIFv*`tO4ytevy=Nr|DQnVU1Z*JSn+3<+ z>2Ga2npaZM;z1dG!}#1cV}X`lZUoux+n9&(cQnu{>wr#s8)e0A^`2(o?m9+9qq#7T6>$c1mY53vqo?U7l7R8~?Y#HWc;mz0j1!O}!~<8b z_itnpGg&XXQyg*{tViaRG=-;*t&n7C1gOjw7|b@6s!gyq=`2#hQJJf~N{Cdo_HQ|K zVtw-AY`GmZ`3y|PircYvpqhi+o9*hg?;b~}$I>zztorMe@hZSirZ!25@@b;pvr;<# zkgsD9?%O7G+a#b9P=mj2L*K(*V-6Q7pqPUZLRLa>Qsb#+T>SW3vD+lbR}c@n+g;QP z)Sq%>Kkv8O&S0_{+Q`%F}RZ_qqAj2vxu$0!KB|8X|0hY-K^cr8D)EQOa1hDG&{ z*SlihZ>MAz9@twtz%V`D^HhI_uG? zrJR>HJ`-3i3(y)HZ$Rr{6m-~V9Cwa~sERE^a~cy$rpOv82t)_u+H_(OWc%>1JUwXf zs0O1`pL+lDfuM=TEC+|abMrN?PDw|#IPlKI$`m9#O9Iyf!0qWU{*&3(>Q zavaq2brDUb!ARy~Nt}To@83(w9i|<9F586R-^h1msA?|H0ig5r{_&+*Zu<0a`_l;C z`nWZo?6?_vo$ZpuYFz>NU|?DzM=1&tZb76wu-XDUBcS>z_k+_?FR6Rt`%pYBpS z0B+W!YF8Wt7;FSYP(tWwmxovxw*9SEg$nD$9lE4E=jagd!5x+3;j{G)6AaHY=%O! zRskN@&Cya-dcu2HE}%P1l$)w@q);ICqW=wxYEV4fTcTRJcXGm%_QtUyXiI?{1IS$g z4JOrXf-ghRshXxH{Kjj8>(EvC@5c{+od+Y|L3_LMKy=;O(%+9b77IKOG5opYs#kBb z1kqdd?4DNk&L=OQuAQ#NGWoD#&O-tEJ%8;3#Wg~kcgo4L_j1i05e({~0NQTBn6P63 z^E+{kpBnV7yEC6}4|hfhs|;SfAfar1_`z^+h(s68#5kNSkJGi3ciE`GkOPFkae!nc1jCHjy2D_3N_i*taOS{XQRoG*%@;b#l%_7-p z#pPoXHJkC)?Z}0PVrga*%8EIb@@9Oa^8K1d;5Vv(m1vCaS+Ir z+m~{>G8fba9Z1U-6$RX$Rav2T;}-WvjVEFyInGUa*kd5TYX z>ic?jhvQPgkyiDbn5@owsrurYdg`#wU;TAB$m~kF?anHg@kxtAVhwARChm0D80k2l zqvnP*L{B~!H{Tm8RTL(y_DuQgz@(qu6aTnId2CYJ*UX19RHGnA;G2yP|L>NKXM8JH zl$crqZ0;iZ`ov(~KQlX9Y;g_P&Ea4ehyiG?;A*TnQyWHcBztpuMI28?T<2x51u_hf z0a%g+>mzx$5YsHkbq-0`cWBZ9Hr2!e7?0}3zs>-~8nAk@JFBj53Q%L4;Zz*2|J{yv z$b-ZW+lHF8x;gjFy}ZO{;2zp+=(t4@$Yx?fb#|+9J%RwSc2kDeF|F@eJn?z^b*3~4 znj#*avX%^_P@Ed1M+1ev*;raC6|G&&n!xI(nb;UcJ6lUiSM?Q4A*oO3YC->^#UOyk z{yys9;nyT84hF9jghzzu!X$#|9TeU0I(6MY~a=_>E|an zXoAtP8Uy4h8|py!vOScT0aR_k%Ax0Tsrq7*ZofYs&OW}w-1R-xfgu{^mzb85qKc>Y zIAV8s1Qv|k$s*b&ih@bd0msPAH%R~>!`*Wl(!Bd{+eM}?y9*tH!!0Y9jQjkTwO=eY z+f%O{x}!M%3Ejhfgijyn*(AK~!Cbxy6|{dCN(6aekZI>rrYa43#m0B}9Cnm*OT)4Z z44@MM+WTqe5D1U|5 z>x$`b)p7Ax-)uOR!#LP#F?|I0lZi>wKtEzX9(>3~x$7PbJ@$Yq2Q#)x1OgFVr28t? zz}l$@J6yF8>jyY9WA3R_c8R@%$=k%9Fh{fBWGsY?iFnH8seh%sIh+GlA|Kd!6%zSA zjmSu&P}RWW@-X%OY%$p9@43$%;o~6s5j(*eK`0ULoOffORxvD9UkVK~x?kuusrdcD=P{JNx>N{f0#Fy5FGWAzR^obsy*bTFlg%ycQDBDN_#;nj^;>o9J1VBZMWCVzvLQXZwn!>%E#p7CaI zT8fe=iZKY%lmT8I5UdIq4Zwj1-ex7Gdl89Mw`U(4E=Sl{u^`iRQw_pE$~oJHrG%eX z_m5z_FV3^y^L=LNU1&E9?T~I5aM^^9?{0$etK(s5<M=&+MxH zEN^&z-7eWbRq$|B=~n;*k`^C9vWT+TDiB97XrECI`E~?eU75R|k17~9JZIB(LkW#9YaO-yAq91@cX>D5c8LNEBRZ#j0Am1JEZ890`*GR)Eog$B$6pk8_zfIGWR zJuF&39QR41Dfd$dxo&3F{`;_k_!F2hP+aLJMOz-ME zQS^Uzr-R+ngzM2cXRyC#uhUTax z>_2_LDXQ(F00nAlNMVMoKMR}aP-wW&?xiOX^YQ@XcL@t26Y}o1YuP??OnzIN>IAcB zohce+@9Efn$gO%+?zVm}oL+M8N27-Ksg!;SLx+f@N0b^fxVGVBKAFmO|AwRN*zv%S zXhrI4TI{kJ`hCF_6ZNb@O_(1Wt2tM{8e+kn-EZIG%}GOSRbCx`gn@DKw#bAhH#f!; zLsAimV8_o>Zyp;XcYn#v$4=>YqkoLd4W5iQ;e$unY@02k^eZ+`W+X|bqhVKjBtRT8 zy_c2<;rZbxc%Ub&?v-qrq&V5G$&&K-GsT(6;>5WcBbnJ$*o7DO&}aewC!Hirl+kJ` ziL+>P*GOYLILP%s($@{)uWsDUEEAd)@UxlB3JPWTldU!JpEYqm8E7<3g~VeeMcLU5 z6ii!Ar6Q+_Z#opgO-9cZ4#L*NN8h)DVQ?bRT4w~#-_mA9vNbU%790J8m62$O!B-_+?fDw8*C55!A%S#RbR|bQx8Nm9^B=!~-5Ku=4Hg z@5jl!?O0U+L|b5?0@zN#?*#p4Eu~v;0g{`-9W z3=Lmu$Wty|;B=ww=CmO>2qAEPZo8hassn2gB>aIqrI(%RQ~KCu_dA81e!-^z1p)5V zc=@ydkoT}|Kk!Wl{Xd4QVH*y~EstNq3ciNZ1IFK#i*cC^U|`>% zij}Jk8?_^JVP~r@K7@^j2Nb#MJDW(BqV&vv#76-^v5|z_ae#0gf{Yh1XaYXp03U{M z2Esj~DPzb_UyRJV4VN5R^xz$Lw0kD{FJdXpAXGaiM|jZ_5lWaSBMweADxW8AT}B)# zzXukqzkf51oMjw^gv!-q>1Ye!qp64Xoq4W~R>vczlnYf=e!8y-RiL=-L9fNHn^o=1%|3?~<~7c0LP1iS)R$+y{)JGQ;k9 zU6mdJyVg!%X8>T7zTNXvugc`FbS6vh5BIzL)?jdgIu2&6*uS8@!J@=`J_*9qXg7l2 z1<_al)Jj7`(+OId0C)$e%T1?+=`c432bJ;h@nnG~Q{3ILs?<273M zV6|D<*nD8s7eg@4d(sXh{{-{(UkCtE@;f*T0tR5oZz=mqRV)!?8S*Bj)YP!SI!PHd z8yb#hBJxgFd_v&IH|d*P(bI?Mv5+=y z`2ENIbo%2nW3(opBdn(cEx9oBRKft^57=<>;@~7Bc{24bh{e&54XS9;_L1 zO!@rw9F>v4;Q?zX5+PB7sh@HsQ1qzYD3;%-N#g+e<0*`i(WtzJGpxPgio=;#Db%CP zg#rkPTU#SH;58BUn;x2UP5T%8QPXp@lhQHx>G{2VQ@hXozlORT4%|i&XH@ID!=;88;1W>7es4e7i?iwXPdES%Z>Hl0qE(&*SZ)hd zt3X#KD~n`y9xs==@uPwf&^mk>Yv_Z{Q&NLfB*gkK{JZ_`XEx5Ab!;ostR%nPXLO6$o-%21vYf#w<3`w zMQScNyGn_o#$%b&*m~B_q1`!d?jmh%va|QO;kc)o+pSn|!Drrdi7=DGn=B&=%& z4jPf8;HQFUM}OEiU`M53XHRq^AXv~+>A51XHP|lGl=FD@IYxowvR{L-YrDh-(Hv{y zf&Lv#ItW6hhNQG@S)ENypp27J?LO)bsq*c83j;3w{1ICSy(M#LbnYx*AhnQO_OGgsrYEB+s7$_4X z$_^^2kmf%chwvTC&{d9%$T>PWX;wSa=#QjywzFFg439>UAOvg45L%z=JCuWNkTdNE z%|d#j^k>|>q{v+HS&{uP6=?&6E;Tf$QN_yk`Kg=|dh?9R&fm+%(oz6=aTK6E>Pcv# z5$f>~lioq_Y7k`S2$1Q$`oOD^kv<%yMn@(QX>hhRh>XVy2iVf!xU=CP&J{pE2cos1 zbH;%UfTM@8;_l`R)yh$$21

    zysV7rFe~0qqA{gByfBp1lzn3X*7SdSJ#~!piZr zcQYot6t0yIRfwSk7ZH*8O6_X%@Bn98AFK6`Pjy-EH$y^m0(79@281&30{{$=4<{TE zEl|FqDIVC=E^JYLSGC@FQa;Z z{F$4NJ4R2R@=E;D>@(y3@*MjPNt`Gge9`;#UK8i|NJM`y>QcyyiloN*fG{@*JQ=+T zi@S*U9MFy0HnXn#7;hnltrlnjRC%)3{?EwFs-7v(jghgyyci)H!C3as&Hh!9enX(R z_GNGou^3$!hUA+&$hY+K)8{@1mouI_l5#aTG66?7Abw3Ww~(LxP&0XsKh zPXr_IDOSr;+XD79d~d7icEm52q&JFFd&o*t-+`wB&g3y;yhD;?-{wZn324IhJuHa) z%YvfYW^$jL4eQ_Z4f|a4ULQ@0<8ubbC^8_}Okk?(F|Bc77-=*`VZ2$Tp&P8y_MUM<1 zHP!La7f3bDsjvUMJ6~hHATU{g6_r5EHYsB)b0dcw@aE4$3~Cgdw1W3uJ)H6D+qo=4 z_Xz&!_u9!)%V1BE+xa?`S!wpOgtt)KX}Zb`B>()Difai?HKj?sQ~6fM*tMw^*Dq7P ztf7x#ydqC7lJcqLo013oVy7Z~zCKKU$w!J4+nS9*{zgii@*PLKa1fO()|)?af~#hE zOmsm~veZN*+iyAsX~^t^vrg{NS6~XtdDk{*_-aKzHy+Ih!3sbp@5t{T3B^S&U@GCS ze>I8wkih|!f96NH@bkW}B>S%Ifj|2>6Pza0OB=o(&uTw4v761rXd!>rA{Z{!h;2%7 zKj3}tx7Ss-RY_C@K8`TvI#W)}E7g%d-7=p;=X+S|enNXIEgtDegET90v7iH=BaDZ^ zxmY~bJOAe4@9V~orEPFWZ@v;)lAk-fUqnWYW`+I_+ki)v;Bq383}ZFfuT zrENFLT75#v5TPw#f2JKxfYYU{$GzoZA$b6nVi0*;BqWG+V6Za6ZYErYqqDPpak@qd z(9uK8k^cN~%#Vv{0a|A`OCVhY2eP7Atnp!`Ml&C{3dSdo;X%?=tuiL4?9^@`hK+^i z`SP1*P$+a&XHy}Z1n|tsKO>`LXTKQ-8bQ^LgSnTJk zUx6Kk*Zq&-_sL1Nh1#gXlE!GpR4<;FI!&KF(*q?#_h|~KKMd*!p+E4kIKy|{7y9$V zjnRek3;0Pe0dv^{-U99?^!YJ;bg;V!92})KISV)FWthL+rFo7{E;R%DcKR#O7e;yF zX9|6VT{a!XZ$D=gqv?z<&ZlQw2RYvSGX37qZHH;M`UO6Yt|g+CGwr917@3|Qc!`Z2 zMk$_(D}KrKAo)Rr3(#K2r>A?8zC7ADF{TuVjpwo4zDM9IAIU|Zc<_b!g^tRcGE7Gu zY+jmg)w?1YdX37Cjj<;wgPmOt!t~6_dtV`7_gxQ&*qY3lYrHQWIn2C9v9=cr)#fh* zSDGns{9(Oh3SpAphr!)o>frP{0ONzuWJ5?VLkD~Pz=8DO#!IiN0*gsrh#YuHDmZE0 z%Me9^&WV0kDqXYC-LJ^ClSjMr-l<5FYh1^&$&cDsU?&0f77|Gy1+1vdQCpeNK7YlC zW9>_n_ykFhG|}(klRbG{63XxWFY|Ut4i0iLB%d67AD&p>TlqOP<0u-(tUtVN&1u#D z5QnRPZ3L6-;w5YB9@<3NZjy>k#q0Sa6ykfSVmDV7r}7`w?kJ{{vV{4k+~>K$jxSG- z-s})%j7AmxAQjl^#P$`{S=;s_x3HlBRZ}ldVlUl^FoF4mJVl@OXiRCQ^o=LS3VVuV zRQK|0U)??dT~R;Q2i;AXH!fFL=2u}${@oLq_v|K|1AlI_H)v*$5#gJO`+MA9nc>H{ zqo!NP??b zW(x~G^yt3jroo<@Q{P}&ntL|`El5kg+sxI&$qI05!Sx7rK9mRwIhy}5^UCfKe@H}( zUWxq^+bAM>;CbdToOY<;eL2Mj)0}@lPg`(Xx6LEggUovrGxa{uz5Lt_t}h6pHeaZB z1xXN=jKCXg0WN4ZqsByp9R&OSqrXAom+v4YT1iSn?KZ~Bf^AiQ(sCq2t9dyoxG$66 zZ07?^y~1iR4zgSI>tE9^Zf~!An=HJg=RPVc;yIxa9a&UT(!K1Y9!ISuTLwOY4CqV1 z^4VFl*lnZ}xLPsbx2&sPyFk9$z9(0#BdQmBavIiAYpRi(nE1nhf9}fitRy!UYSwuneSFKt@{&bJZY&Jm@t<gZG z=&;x_U|1A$bEaliTx?PmeQ?%lX6h+NdXI<}SZJR__fJ7!R&c|_m)5%N%C?7O@`rK* zx-dl3qhDrn3q%t{IWhj61C(H;>EhKQ-eJ@+^YZL$I@TL0`p#R->L1J5x|8v+J_N-5 zD+zYFdu3j4>4|wi;p^nMq3hSxnkD^9WzQE z6}GXv9!iAZJ^G@8Q42a2TxAHKhbO~JX$nG#|JhyO`9f?2!HH7goHaJRr6h9x>n@Vl zaiK9xl19hIqznwc7^-P$eZ24|t+92D)Z-|L%Ht!*^sjYTc@~0ouS!#%s1ioYpl+{z z8&{>Jz^SwxAhu~^bhhezRj`u$Y(GYxZl>y`?$oKSH@Dwap_L#7TdEA@Nezp%D3<~ZJ6{bojZ|Aqqk0Tn%P1mY|UfBx@c{_#i!-`ukDp}wBXCv zIQfbk##KR$rPG@w|3-A*=ea#wacPn_7kpYf%KW}NyudlEq?kps!O4<^Eo}GnM{Q-i zHU8V%^SAy^2b7J_qWzTGqm)}-a?q_NiaW1E??zjw6e08z`i4=BXFsCfda3$9G=lMh+iI$u(P^bz)^TV-poL-BTs8Q&RgSY7rG%Fl-VhiPo5P0t7TJ`x z_IC)0$K-5`1nWhr_lZ8FKV3)2(?!SWXGAx^+XhFB{C!qQi)U=Wpy?`q>1L&8&6V*2 zIXI0DvB;hTLqN{Pe>8=g!<#?zpPo4|b*5PjMz3WKS^+Z@k*o&6d9JRm@PI0fje|(~ z`|Vyv(jcUuMVK2H+zQlAp=RNY=Ui+LA#(Bjm9dBq0n**!0$)p4F*!|yHj}BV$S?vR z4i@YZ{Vf+>VxIQiVwB+Jf^~f4cM|d1iHh~eV?0c8<;a9?Vi45Twz?1SQR?Y%8JaEq z8!o?(B-1ilEa+o;Gy1R%8Y=qs1d;XR>FN3AhtP$an{?yaR->F7)CL zO8TogzIa_-1Q8|xDLdGl`Xl-Pm8mHmDmK1T$usfby_c}9f)n&!A%=k)&gmh$m$dky z+`DfVQO2|}G7EAJhlcp{OOo;~CFzl#ySsC5q;l)??so}3?ZT#hSm5?N)7NaC#MmS1 zt5{{74h?T*4KZms*JJ_~`XJQDP_TU+X)KZkvX`lpb z%)osBdq3@~`@LaF;KEh-0X|jrr%$C_UHReIoSS?02g3ShU&DOpa$yhY-w$hXu*kIk zXWp1?_HHOr!~HMtLc45QQ4FdJGAm4S)Vpy0Vp<@ONR)r&G;` z=ZoclQEujn7~Fi2;uUGGIGBzXM-E8vPuA2S`DTH&E%}qOpTG9m(r`OWP+)UE0<9X_ z)9kDA$ON77 z4(9umP!#6Wyb;3gy2cBa@Svz)xrN+u0v?wpOD4&CQr&y%0mV`mq7(gDUc2PMl*n%+ zrK5cZh~_gTQ_%wEG}jFrxwxfUd;L|yTwSlcWYRFaYm2DKpW7G|UXeM@f6ci`o{c3I z;8^5yI{W_hmVX^N4o9TY2vSbP`-#>?#h_fU?SA`XzC(18u#$xO;LVn9Owys=rS^V3dbD`?}S&1uJb>QrMVvzp(0t zO;9Od1w>yGERXpm7gOK_+1T61eTW}eM=n_%ePXVq?Rsk!Yo6$YAE}%ck=_eL|~!&FKF8qNew5RbmkLqvWA`5uzKG z3-zeRmn-uK_6(vts4vHdzC(dAMa#(mYz_aTR#|ib%L1wj`F0VAbAxAXcr#}Cpj=Pc z$Wg;H>vmHp*{^n~yy|M5z@ShHG=4^DiF5(MyPMLq*<%uPr=-X_V735D0ofK(_O%U=IBhRvN9 zbIgmX^PK8TIpT>@%qc^$)CBtI8R}9o61@+T7lPdlqV4;leSGE9RgL(!p7EY|Kr7uD_dLVzWKAoa;L6_jX1PEO{Q&pb~ZoO)cLCO4J)zI-?QNs zY44^Kn8_1jb#sNe$y#jRD2>!J8LbIzKPJr#9Jz}{&G=z$#D0{=(z5pzWbFWZ=4(z) z03@SB9f}k?rl8m>?0LP_w&)y@ElT-mc~7qL`+fB~9HBPu#DWMlv#nM4BJ4qPB1A&kvF6Iv?kcp{pOz7&tpB>#?2c*8?!u+8#=izKXS>7BJJUwx|*YQvh&13 zVXu7RQxbV%=cc5Ivi0&=x^?k8Uu}OGdkil6k7oxj&q~8cPd+zvn>kk&hGa$=e+GG#KOM3Dsh^c zSNA?R|GOxBtI@U3*rNX`U!^LOkN}0C zU8D^ABYgY|K?8AK|4IyM{6@2Um0{r;`SvZenZACjTbyXwuj>rKBfbCLBe`~5Vc};} zQ9=Il6@;fiwtJZsc1`mE22#ssv6Q!k1zPCk;Dq=&)}G_oGWc1)^2N-z;9<7s{lH$= zMlYS;-4ON)y1F=V*}14Wh^h3=Jh6v`P{`y;8%*v4znD|b1nR?xI}-2GrB2{GGG}Jx z<)J4G1PrXNxO28B!z%TmifJP z@;<$};>XNJSIf9Dr>*{IB0nZ%6rMkLF5s^5f^$uP^Ez-t>B}q8&6NR5v$o%pXkZ?< z%uXL0#%Dd7-tYG)M9>4z!~>E%63>^B|qZX|T4eKZ% zV{ZS>pxbWx+bq9LFF74Fl#wkt-JpBZllLgXT0-RkS4MFb_P-n7JE*c;f0RcP zZ*0cS_N(0#ZAA!jr)8C7j`%XhvARe*3Os!nXh)kyYjqshtinL_gu`rAPn_iVdsyp` z_N)NK3cnpMzhMVI`Y}TAxPjh9$FJFxv|ri>9(x!~uJdwABtR#!y05OM_Yr`tkeCc< z5G=zdaKTt^(w;C?I2-)-v~UH#AW$x0i8QMyC);AtNw5gX`c^jDcS3bl<98GhzF$VO z7QR)<3VM`%G2xPv?P@8Q8~{M&yDy@mqJk*^kxWMpTivh4I9)hc4*H%Z5D^3$R@|;E z&rg3y1BSBm=EB$T-{Q^SMa|EU!c2eMAz`&BEZ8+)jHYiqXn=K-9vouFxz75-Vck{w z!j!jf-po95yr1#nl09mYnN=@4~`nh@75d3`}_l-g9-WqInBfAQYAey_rJv4IkM@QA-R^ z51^B@8cK$Uc?|*y?_GYgDD>jP4Q5WC^1Ct0Shs%BMxoo=+p};=qX$~_dgOk_m2&7k z#wU`6F%0>Lv4%$5uhFc>PD@B|pkR2CKRXQ!yoZ!1wH;! z-N8}TtrJ4xwJ!Nu_SZNzTnE;7Vdw_KJQ#x&7ySlBF19$PB>R<6iXuO_UjX|Cem}k> z6&_zPPy#m=+;c}KCi)_L_+ktkW;;8BOUGtr+qvvJ5<*NHlcH(h|P4T;LI+{ z?tIe+I1MACk_jo$g1~QrNNlluMcZsMp#VT<2p-So|RPD*$C$q4#w7(ogIR@WgBQ>&@0F}cc$)bxiFe8>8 zOq@+`PajTih8tO7<|{u^>#;TG*V>jLm~Fcr&eNl!_K5jQT3FrToPZbT`-)A|kP`{*T)(tMl}EQSo; z$ZM>4mai>t=R4!Unwx9VBJ09NR#MV;CJ5*ztV3)CP?B!ti3BR^W1nwo`08kF*oE2s z{5`v|TOKPO`DV!S&`v1+(VgX_JRQ0ki?XcD(=!GcS)=NwJQmjz+g5MH8v^f!FOw_A zg*J}dy0n}BHNS4lJLr$Gr0O`;k`XaUULam3KHa?G_MJ|ydU5kUX-Uga_E>MVW65Ek z?%;f>eXbkE_Us1b8{(%<1omIW&VSKX1N(y1`(ep4`9T$kkAG@cKZWf9MhU5^zZTYK zpjren1|nK6J>4%$;Nki@rjgFYj|1Eq2%-)fSO+{JB8{0Skk#ay1#+*Vmwp_ZNwvcO zok>bj=alrTfV|krOS5pA6K=ref&la3E+Jx*J0-<;t?dq_x_1h1sZ9V=L4x{mNrGKGtl0M>6RBjgS*nxZYXU;wAR*)ui!$cK``N zh|J$yPO?+L}PdA+_M)6Y>m{_BjZh}P=g{rn&s1- z#;u9>URjdf2E92Tl(@hTEUoREc4_840&bC1l9Q)}9+TGv6^;iUA`r*LUsH3kW&L<(x}_^yA*lB1MF02C z=bZpF@NoT6sJxTZ9UK1CW2KAn-?_c9?l8+)OJk!UzENgtq{xFSGGI#1w)nR6uSIb? zym*mbUXDonOI>)2lvwwM!GPFaVPFjZINYMKmtrg!Ye7dbE#~}C8l9b5`g=bPFjim` z2nSeyvkK$utkJyf_hOu`JhF`1w<`~B&A1XhAxE!Zxp|~&ah$OAisd3wk)whp zX1mjCP;4kCmOL4=<<`xRg}R4x%FFYDx;Bo(e#a|!#>{hrl#Gy8R4(zSgSZt}iIcr_~l!-_Af+SL@E57b`r5~}+Y9hy^JJlONtu2w$Z zG4$^LHYib?%X3WqG`N6seKpLm2>uF%nYmz zrr!O1zi4x4A1|%PHp}d1joR}j=KLR#X-{(q$=+Df@W<|I(YSJ|;w&x1{FvQ2jrsfe z&m{H1>6DW<4-4g_?4z!L=I}bvL+ek?O}^SRmF<_KNMdi&tj?Y(Z(R+z{kXQvsnGt4 zm9FfIa*{hUki9aZ5T?u$?xpQ?md9t&;FTH^O&EJ3az9h1TVlJmFANZ?PKSd6xN^qO z=>&QWrU(nLCS?#}BiqSlX+Vw>k%{38)-?m+W?5HL{+fv96gWRD&(F6=10?~Z0ejfm zEVmX6o*RpnmWmKZBdb#-;Zc~~rvrG__6alcMmQkp#EJ&QgwI0wpHXSV`T3r@ z=E3egbldD={{$b5kNF87SWb_QxT?MeKG>PAbo(g+wR2Yn?Gr(`m3N**e6^lpBR;=U z{vs4tf-5F}*ioa$rku?6j?wM+QXypdsi-K1Q%h7L1)1UUn{}f9$Y;CNhc^Q+1Nim9 zC;f@yab{8A>y`Gc*9GOSf)qAL*{K&)il5-jL&Mqe#77P^_S)~dM@;M-@Cpq{T%mUXP_;gfraQxKmtI*z)v*+&dU$o^}uxg)_{otz&)ble7zEI^cBP+_I zri}Rg6d@{CAxwW(qfdxDwDtPydYQbh<-^{lJOfMMIieYbMoatcX5I;jR=k&`WSDub`K|KK#$DWTp9-j10-KGGpFf|CKw|I?&_O$vm!RmfIk5(XE8vY<7!ueRSy?tRf`mszmg^E zjA)ngm1%RR*ZQmz39KnIg7^~0>R8mnRRvwL-O%kdbyFLUmI~WQn$#+O}>KpR_VDLt!d;8O80Nn>nS9oG__sAzwej% zky@T*;A~AdwxB)e;5V$ZP4AR#j@O)(D&}SWq}3gB?JaeXs&o8IGwF0VsI1q`P!uIk zoQ9T!dW5nr+WzRpw+r3p8bl@VQ&PQ0Kx}TwIKi&B}g- zW0F1l8~r0&JpUN(e(7|FgRrnL0OX23^8{qxB^3O1Tw${+2W1TeMv1s}ll{PXUG7t zUDkU?o08fpcLpl9YU$T;QhC5XWj%?o0&_xvFK6=+joK$40=bUr#mn1l#6CB>j)#_^ z0ioO59>5|W$&e-uY&(`1b)7EXOS=v}Z@GC3(q++{y^W1V0fD|N=QjGSob_Z2$_FB! zr1@-5y z8ft8vcSy=aY!#3OJj<@J1aT|K$&p{zX zaX9~yUY4B;j<}s0sCZWN?8-b)(5ZJ?uhWA4oF>+(Tk)&C;o5=k&~DomYm*DGry?&VMzh+W)+rBKCN@I z^nv>6JN=oXUBMJb>T58YkkK?WEbVBcL@|mX;ZFqiAn=%fHGpZwB1=0Zn#faHZ@Ahn z_;~+OF9sV+M5ps#w^LQXvxA0~zcIqPK!y@RAc~IT2*cPPUR~1iVs1Ci^@LbVuyz4% zSr9Cn3S=md`|D$CsDjPIgDGAUBEVmZ`EtP41H2Lohgt-jA8pE7)#hz$%vjm2kI>lL zfxUA`yH(uWoEik*YUtvc5mRqdKBmkhT2qS3lmE~rrua-mY3H`$qZ?ynXs8G_o#5^H z)zF~(0&l#P0Vu{k>9Mk}BQw|$!z2w4M7PWw7LhEp>x4dA@d;-cBR`$ zPV4Da_*)Jl4Rf3rDd3;c?uu5D`R&(+fkv=wd?8Z(*-G^+3J2OqSmNfyHN_iou7suo zquXa2TsyY3;k@86%Y(teK@jir6PS*H8y`ycU|{%BRh0gSksKHG&lNz0dNF1@F09ECkX(i75%jEm)oZH9dmGf?PzXUF7>wg?1BrWF*BR=VJ z7$!B#a&P9-SbvVXry`A${V3U$^aI$e9OSZ*FE4X)awHF_Lo*7R0Lrz=OUMYglo9H| zGFmb{@P!Nxv7YXKp~=A4U<#y+C3=?N0$5#(NI5TcT2i#z4_N)+%dfagwLS?5e++nP z@P$Ld08sX~ipt7kn1&!q)w=i>5Ss#05#yzt{yzatbRtq?HW(|Jr(wxaFjtA3X_PdECs z*WP^^d}S5CCK;#Av-wse`B>!Rk4qCx5iRRp`Ii`7XhQm=gT8%IVqyYszr=ATE7@4= z#R=u3N7Jlc+rVnkx@uR!c;0BiD7`EOh>y_7@v$ybI`hN0*izq$hMqnC(C(720>Q zCf`(kukLZ7ojO99^0{-d?hPkzr|WA%#zZ^x&Dm6qms=jyg#ts5$H!cUI-=W`ZSIdS z?Z;tUT5H>k6q$B2l!l!aJs&V;D4Z;JG?_Xa-DNf#-*E7Qs3cQ@i+8P9F5I;@L&+vcWdWyZE`-ohf{)=S6wuXr|q9ib- z9gu#&a!{iy5nd-koD!OE3x;Rwy>Y-x`r+ne?f2A_xCZDEm^d^b_J+DY76khDZvA)< ze$6s$)vDGxzp8to+~s`;SU9bg{Qr}R88{NI++Ni+l$FNxgd^f4zw-V}+l=iSWY^}! z3Q(UTf>=?x*PSJ`JOlO4qT01;pfhHTfAx{o9X>P#+ucz3ulcU&Z}T_HYIa ze%i1FV&1B$$o%TypE`-_SO>*weBeK-fRmlaxp`oBq2LdW6CPDDH zSwdbus!DeObVNYP0zNztrZ)UXA_5tYAb4pc=H0t4^>Yxd%%B-;K)z%v_ld4jCGj;* zhrDqidl7YNNTaPdz1W2iysBvbEt>34T&jsq*ALrFh?Kv_(iU- zw!JKunGLQA2W@PeR3yI-`KZ1@ws9f~r>X!U%bK;HEliPRtw+WHysgu!y0GM{3d5Hx z7O=YlDxC^|_sUa96$hU>m(>u33A_%8u|io}-G*L?0m?$HUl=i$*2L^5s#Q1qsHe8* zs51Y*=Tg9v4IS;a`#s#80^Qlkvd>I~-#u(k%sqn7^)#oYoZ@$ktg?=HVAd(eRT)R} z9^G~01T7+f0D#py6Pjd?&WbesL})>R`Tl2+p!c0|Xu{y`7)hPmRK!SxDd-QIVaA85 zIAIMr-5}qNPw7El;$MojbxF~wNoY;(g@$7WrpjXYy*ukiZ6sr%_*j5VJm$GL`Pl=* zL@3!dO1*HTZ{B!f;BuWf>yL^ZdhM`so`V~XNkzGAtA%9V0>-dnk4lSg7o4$9j zDG4$CsyR9NCr{U#w6kP9e#Xd{z0#B>ag@im)eS$wltx+2R?O`OPd$XcopV>B$iw zr}o2E|D&AH`4)-ndK9LM&%9uz_Ws-TaIIh7xv*-kC^_6RlI@A?|({eU7H=ye)O40L-s!cwYSXuVocRu_sCNmnPd zFKTOQoWbA;`rG>_1PQ;7j=BFGB^7fCGpHDRw^F0^YoitG7CY`}Yx}Y=aCa?wOTqwiN02>YvmxK8q0u6ASR|h=% z14X?WG8Bbl!cj0%SzWCjbR>=nwh*A54|IVULnt_k^<1yu(~%ud+n$;&ZU%g$3xkDD zPkQ=8kEiwg=b$NDOJ#R%E@mc3!Gb>24w9ZMlK+)OH*WaK@ad-ac}+d*qsj}-s_zD0 zu*G>Gd+xwu52}BldgTPx6lgy3>}zvxh9~T-%;)z;F>Rl(JzKJDVK2Tv57&W{b_=|P zHa0e^?LlyF-nV-Nv>Nbl=A zA+r3I7Q;dsw=q4WxXqW5cW-O|O8nZ?`53SvEQ}^qlIk`{N6c)vM0vd1@CtSj&X(` z2GT%KodLlYSXXf}Vv-5T@R4kRX38E=Q=y8!YO6fDLIkaWBgmIVw$IW@4&Cs zv3Oq>2gSzWQq54fO4&c0%zzxol?5`uI72F$2>e9;%V@8yWvWuotg#w=opJExmfBS< zmRAM8tDoYfk|kT$2MpYow^{*RQam+MWtu&xLrK!9kr&v33djk#Z$FS6?_Eq3MhgjD zAnDBo#{JYQa$;mZ{k`ADgy1Opa%U!yUK`mfz;r<(*KJ%ZAfq&PW`4le{=G6irP~iC z!d=s&06nrW4|}ek30IBNfzs+H+M)#NTgkVmpEM*T1&F?5@SU$K3Dff%_y@JEG?TT--K{A$ZLg|u1t(tBewe8j9 zwl&>-zCBI&#V=9r?$cT7t^1N!L!%DW4nIWWf2VZ3>ea5k`F4mNA%~Gf42BOO8lcmT ze#NVVz%Jj~UhA;%sdpVJ@72@$JZ$v~Xw5~RZ%0Y^J_LeT>7#mc!t%Bwv*GVKVNehS zu&sa@w3?2N3{V1s#U8lQO^Cu_*GBobNg%K=A++*|kDq#R-!uPl7bN}4YTiMcGWNy_ zJ?W?=W%&6fuHrpzceV9-$dO}aS&>@n$-f$Q=4jBZs&OFO&_jNJZx3qf*x1+&+jE;Q z-Q<2<5i2){f4id^a+=aUFm!DJysT>nydx(%N#ScIMn=`QU4aAQV-AV%9C*z1s+hI$_}+Q@(o`Vd@Dyn`^KF&;e@VWw`?upF|NXXk+bz-lfBq=zSiN@@~#o=Ivk5> zB-Ps-#};><)0?P8H}!8}Xj$s3^%ie-U}nMtmrf7V{&-O-wd2SHkA)Ko;E*T%pB6wN z8>*TOfDYa#-tc(Scd4`uHsfdZn^`(K0gq!!G z8GorrrlX%$S>gzevX16NPt=$aept&8Y?YZ<1W7QNYu^3ag8$)|h1l z6rbSl%xJ#R>ged0_lsIq%wcgBrhPNTSc!vZ<7BN9+=nM;gZ-jPcD8v{uGYfqy~-*x z+&Ga1w{XB!2USs|N_#X3yGLVAIeBOHk^Jpvb>(O=z+D=^IMdcchg*bWCOt`bxo6I& zV1eFT_2N}L4e#uBw=!%NmharqNPlOF=w-&t7^E7vaF%GG{k*WiAkeQ?z@evNdQ#oH zC1_*7yI)&IlYB~*j2J6_P-jEFm894~yY_I?GgSr+rWG+8EdCtm#3jlyRP9!Od6qFN zyA6NlEZ*E;3Sjq2L2!Em7xq3>2k}*_JvY&`{g(B%*aB)!Z3@p>ZRdanxBE?22E;!= zu6w*KBg4W3{-H(pWxSFtQThF;GU5uZY)AHJZybE+{kz;P`Q<-M8N4+ik+Xb8?v5hU zd7a!h?m}JNl~yKV9^+;eC{a&mOtHC&Er&U_LveLHSeH03v+)|4x7xILy9?yH3A?^` z)T~Mt7+a^!t;^dvRGf}7b+*D8cHf4Ga_+L8Z^@yfAF6~^JLCJ8zocUJsujWhpuG7E z6%>0WAi)Fmn=q*zkT^Hr?G>jx_YfNdJYIskAajo`^tMTYT_tB>?_?Ol*Weg<0;M&lGCOv_ptwDbNzw*whC-A3vuR-+}B8 z-@e6$SB&iJ`StZgO-swK#vYb^q7B-}tes!qKOL^{ZKthRT$dT9w>Z4wi3lMkG%lHc zF{TLNg8|eje29LaG|GA@u&Uj)T(1JsgY)fXg$2sOabr{ySwOm>yL*=b+rPr-aKO-p zJ}aP@5UbLm=^t=4M1jpI{gLv)7$(+o(XytoX)SW23^-82fi`9^9w+%{Dq{JpcH9CAi>i-(!AoYlAhY)01|@drH^L zlw|=dH3mZ0X2GXF1_A?V81a$oA*u)U)g!_geH<(RnX@Pht^sgGp|UuEkM!3s2}YXC z{f|n+vZ~EA+7Nh{MwUK3Z&lM*Xvjq~I zQ_RtJC&ASRigmI$`eA=rti)+ooQogU{rccZ9T1Rff1fI-mgr4+9oV_1a%Ch=hKiD} zPm+oPuPWB(-)NXDQtRRr`3^eC_+^fuWPOG;nLr&-z|wSa;-va|D*~~A$Pc;M9J9u`)5?JrtG2{& z)yfR6eI`-O;XnuGx;6ItkDd&=(g!adDhaLjx5p{H6O2*j4AZ;W97GpIm$b4NE+IQs zxjiOGL0Ja_@I@HmKu2R0_f7NVqpo)UJ))GFrMlgPx3R8L?)+<9lCkS^KD+nlG)c-n zW#`vOh*F5?J+54)VgWa)*kpHYRRMY1yUq!NX!|byR2P)Fzgzcv@uxCpkeezWdK?j7~^?=f)^p+i|yeHf&nGP&DyTQa81Vjqs&ByBP}~8Cj-Zn=z^?)c9IAkP0ARwP5zo**wvhKiYqIrp z?$1pDS%>fSmb=Qrnjm~Dd|9uVdmsf<|8T?r#2=)}Sx*+gww`BX=&-c?Qx3SpJ8mJg zo+;Z-W^ac4f~`O$vZqh>f_Ji0ix9TFP0Z;L=$|Fv?ey!3(j=PKuM z=$pT+V}Kh5?(V($-5JUGsq%zSV+kkBu;{1;hq)e-16Ehrb_d~NDLnCP)E8A9n=ZM! zSi3Zdooh1sbLFG&DPhEa_A;`(VPLH}-AY4aV6S`aad6H=FHxop28M?+uf)anioSw{ zt~;>hM}ryy7=r<94@k6LpfAfiJExznYgc+Yv0`9g7EmLnzRTmzV-G#`l;&F48Kh0)|Ou-*Q}nLy0>e2D-f>(h{?eorHt z4T5Cfg##HxETPdX)VP&`ShOO39Dv6@@_D%P-wqTOz71eqMVOV}28fm(ZT9MFT9=C(2g=(;crNZ%?oV=K{cMji?3oAd ztM?{WxSrDr&uC>_4$H6SgtX)ss|V5yE;Bk~L1yQ-U%ImjXGt81SL%(d$pu`n<@6^# zaCr{DMRGpHv~NI`g~M$pngq{(>;%AJSdGkouq-p^3VW(f?dy}AB#TP^vaD5hm@{m@ z&4HaORaT4m%T16$)W|ny%f*3CkGAt%aqiM`nJ#Oz{*S+v6;&nYoEFC3YsC`la1SpU^w{ms{#lk!V0pAq|m@QhohA?s!z zp-r%^^X&EpsUwUO`eJoozkby~zEHmTgGGk)lpMuwBrV(TA|U9aO^l|(68N3$rEtKq z5CrtR8>m;mr16oFS}4kNc9AJ5Oo}rZDJhJAz*`Nz&(;bip7uefT~k+;?djrf&jtn= z!GwUBYKhC3o_)g)=F7VTGt5i;ojJVXJ>^%rpB`yUUZIN&Z4IMM)c^}y1eEFw?!t)8L4MaB^bz=J zKo0`v=6xz2r=v@mz#N51Rp1)z_~7hL18d_{LV-q?qim0X|5pzLl4*RbJKrxWy96rZ ztxx5SGt{{YI+0YAV1y4ug5q0h|G4xYiZ7pmI%yl+L!an1@eAWhN#3b<#!KqiY z6Z^_I zA_86l@we&B6b4fxC@ShHK1aI&)ZdVcM0({7d7l+mmnP(GkskaU3Y(*Rk_k}~ZPBTJ zzF1=%@052^sc)OgndQ(`-3=(;Z6l}S{n+_4?)}Qs7bUuXRJf6p3%mC_$%?5SLZM;& z8%=FIRW+_uOeuSv5$xV84nJ1%W%H~*)QQU3 zhGRdJ?C8rRM{0sJ;4s8UlX-{M0Y)QWPlNek+R6jnjG?FDvcth*L(+m%TLy5oAGJOE zi#+Zs7hi)>QXj|$(FZ>^ohA<;ak5`Ks2<(QOLH^>orc(W_Fg1?Ca@#lVgT9d>3T1h z`<@0M-f9~-ziaDt0x3RCE01i<+GQFhMj$8xSgGluQh>QCO9QvR?^p~QHFTGthloDY zE7%V3t)tjmzs0=bJ*&=ojCS9jUUO*xC<~yu?}sB9j&q6x^Mfl`RCsrR4BzvzCP1(> z*_0!gnud;{A(?mG>hMKLSgxvk54(w?2|8&%Xvc#slin4wKo^yp_SJKfSKwdTQni4B z=p($;&4xT4^oI1q)LThPtS)oorx_G%m>st&BnkgGk%)YQvV_F5P~mA*`Fk_Sy~v9M zylHdjVw=B`>-~5Bfinaqo8QSC&8!cVAbDlq<@yb2-}tt{^JuG^FkxCg0kVHcv0$h%0V|l&q%QmxCQ4;3WOFM_5Abv#JIdWKh4`8ZVK_&|hAZ zpb>MWYMV9Xrr0wd?i8P2zE1QG0G_Vg->>0T1ayovFCBnjd9=|TO>N-^@+(U9QY~g` z>DZjgO4S7TY@9*(oI#blu-FcE8U9B$)eqQ;O@BPvPw~8bg_Xt0tuq$K`e6;bsSo@3ch^=q11{{*{K&n-`)aK;5b zU9ILHf8hEE$kO|L@!#tzE~|R2uOy3sa2voj_-g{;=6X8O)1=YsNc7dw11O&1v$jk8hb%A3v4Z{O0`iP)(4PCdue)M3;15 zIVZaxwU%=-ROdXs*}<=IU%p30M1QCe=-W{~j>OC>-)mA6Bn;dZG#5XM!26U{=tiM3 ziPccWjVNi9JC8<_C|L#;(RZib6ASULhq-HE0rx9Jw$~Us<3ZL2641h~bE?Se9# zoPI{>J9{-X@;JnckjU?GRYqwO4dMOKLQEu>uA9l)XA@aZcuh+qV3VK=2v9%|2r`D~ z%b|;=4&c-41hIg*S`c}lb%d4#pp$60-AYRpaA$%JDZO`dQ@#oN@PJ{I(B-5$blyKz ztiA5ipwr+&3jl9k%e`&Kt@mI|M1zgYaG$>NbXA9khX=^B#G?K}PA!)N)*0>uV7>ua zjSG072IequSa=*4`v9b}9|}s@NRS5LyoUp8(e)545u#ZW|7d1{sJ~NFxh#>uG^Ux1BEpf13eUm8askI+pn)k-$-ia1h67zgF9}ZnN z6^alVz?8Xe2I3(w+pY;-Z2oLiSM>s-EQ7kl#6S>Lh<}~UP@$9Pf6kT?1>#Vor8zaU zKS5AVryNW}HLyRZj4F-E;&Z)t5l7$ocgeA?>iI=6n;&fh1G!tEcI>YR{wO)|9x1Il z(aG`PVKd6*xqi|79xt7k;!e zRcY=J=(OmtCAq!+Pe?{b7EkPNCB1(kZ$Rn3=?VF}S3NA_gtoLL&{#>X{Ne zD)(NWf|GK|1|o#`$;AJ8_5N9mFdz2lM;u4{lYrPdbC*osOzz}F77;mnvRO5}z)yMW zM1Uiqfwbj{ZL%bDQS__XkY9;`m803O`95^$iE_ z`KBTru%EP-C|Fj{@m(*vCgYfce1H1%aM;kpDG2tCg3i zxdr-ca9~$Gnr{CQwiPTJgA}iohb`W@79UtCQ5I&n!S5^hfeC`4@itE;(=MSK_K#aMKQ*#p6G-X8Z{4)R=H6E*e%GK!Y3J%Dr{7Y=L~zG8>} z^e~rvK4mR$nf$$HhdtTyAou)D3)6Vjk>j2m*wu(CZtTb2dJFsQGiz+1m%vyaTv%g% zTcAJeENE}?bj5d9v%Hh*7=+<ot^~(hAu&}k42qzN`XG>jN|L;ed`sn*ICWFi zR`TTts47uWiGhDBa&VIh5A{^WjycNXcuTQ71qz&5p;K7ZrvRry>y0>)~`1LXL3PU!V9F2n1TMW0>nR)@a`VQw!`8j!IexZ=vlNrB68gP zyBSwlx&6>1e=ZHBkG(5+NVq{e)C-3;=nG_+^Z1gVAyga;Mz1q2+CUO27^65lSAI7Z zcmV=hOGo6ZEJFG4OoS44F#J+ZzdX9<#>cw`qL$5M-CF&VrI+3K-lsG8Sd5ecmZkIa zN9!l1gzRm;Fd%K(m|35pG93<&7;2;H!`ZD1+;u5CQy7y)=cgy$2i~(YQLxViDp6=F z`iir`BYSqNwC2KjGEylce!N$$N0s~)v2^vg^e2@$ZDd0~quo)=3>A*z$&KqXBQTc& zln2^v=Jts%jV;^4{td3M_OJ$00IJ-whXMAPUYN5qwEs%KM) zeHp{=&*pC)jnxYF{P}nEY+W9xkaA;P`P7gOcONFOJYB9YAGPBa@)r%#G|H6{HhhW| zG`+N8f0H%JML~XFpfEaP9~$vxsL;S0e_Sc=F}5xo=j~5zo_F#hS*Eu-iWpbc9b+t_ zt*%eRHl1Lz8H#NnkqfOTRR}BE$BPWO~y=?sPLoBEU-1I=y z;0pH5B(C=WCr1vQWM=7U9=$=$^+2ms33B!5~X2gnG3+YjHJ$Ug@MmjkGzKw^m^ zAYgT-T4zRfuKfVJaUca838=sO3bD!_`_Pm`IR;j0Lrtr&%l_M>Werz)%ilz^q@VZO zAb3QgTYp~bkT^i>Th5i({4Z2lfcG(w0|aO3=zK#olHVIOFHtRM+(39z37cdW$77?mwi0M>*#(DN9jmNK0MGghyEr9C8pJkyaEF<{q z5YSa5BZIS>1VoweN?>MG5MaD5} zNA(KOt)ipYT0iBl_}k=XMhT_LG_(v?pS%29BKTs zsq_^vKZ4PQ_&!|eL9;u3GM3gj@qQODoU2tC4Ayf@-tIx#h8Qc!#<%m7Y<4`1tzOX^ zl2WeL4Q)Qp%*p;JLhUp&Jx!n%njY`qm6J~{dRqsd^xCy)3G_b6zsyF$vBwO{nlgV< zoa<^!_8ng)Ki=7T`H4XHxpQ+MFBNDnB^muUzN2{qg!V_J=;&WV&LAoP>`bpC9b@RO zqY4N@#p3-g&HGQ?HA6BtDWCUhL8jodlq^bUXTPhU?+xa_z*m4dLJ1S!*7r!oM9cqmVpoB>865JdYULh{I^u}{o+PzKHOWi|PQ-Df z^Glw#=`7F2@poCwjZ5F`>96B~VGq!GL6QtG(@(ZI(EYuz&WvXW3k%yL0pH>toAIvY zYhm~q;h^#Wp$W{G=+QR6!L4?lnDaBn>cYk7jX&HIH}grkHz}Enh_;A`ad^c3x=L>m z5ufHErWMBIOXjS^^AY&3`Ibf`%s)-3i0&BPxcIW6d|Q#uh>z?GOz(PEJAl8KF%R1| z6UQsYIY=4r+j(+#cVL&(Q3e;;%EPw|S>-ypr(DfV8N==mE`)t@>kfhU+*XUuxwJlD z0&|f5HusA|&J6{xQ@Va3%0*tAnTEWwlrb-70u7;Q>-1q;G)hj2D7E!18k)4Pxv%5L zKVh)TzGAi&&1}zWfUmfQu^)puTuhGq)F-9)?RxN1V8TB{RtsG-SiGoh)%Bbxt#0_@ zWBtW;Ir;QrXyrQHj~TtabvcW6Fig<)TSGH80j>Odxo~}_7I&36N|?S>xxR3K_;LM% zKuDr~Pc0R_DlK~V0vaL?L^LLYUs(s(_5fQ6A#pDnfLsU<=4+y6jC^7mT(^r9&{2Lk zIyosLVq$4$jUTE?GX4ljaorx0b;OM`x3dR3_L99ew@$>TClER=OLMdMaLeLkzmbKC zil;-D3J=!Pr5%WPCybC1NH=UY$|vGT$uD~1?HY4PD(!XY(7=G2nq-hYWNT{+{w}~i z_hRRAmT-^^hQWa+O>fG;*m$M)ZorD17NA2s_)qW7QFup3Iira# z(mcZK!&?qyVPRiQb!X)I8x?ijsOfT~)uOg1JFqCP^A>8x>Y87Wb@O!fF{Lb<{A{ag zxMLBBX|+G2a>r_po)dHpjxzLIgRIc2FrBB7j(@KR%$vyqfhuDgH;&77OJOf=^1saG zgSk<)585zV)>Wld_XCN&H5afeK<5M9BQi5qV&QP;_Q=a%82+X5`|3KaDJXEm=CC6f zTQwKi{i8am`wvAiopMjb9Ml00Kkrxv&JnPT11$*P;tbb2%chlp0vi~bGY~C6G6DjT z{E3IDsj1#{s6jxg>sh%sLR)$qrkXsRJje|KtT~YQ4Q3d?{z{b~1Ef%8kPk2imiDyf z?_y~!(y@cK_#L!v`s^C=-KIdEnDxs!8WV380`<^P$5N}Bm!Oi!HE^Gr8p`y0B`nNP zrN0#somL?0h9h@JYY|=c6+1U6x>N~yw*gyRsgDPkFTqsfGSl&rW=4u0wyQ^Rbm?zD zVur%s@^YoTJ|V)idKsGRK6O9;Z>1$U#*G5fa(9RSkr{h7UH*=Zi2;X0b#rD7_me0!o|C&{7RCAvwG5?K$^AxN1!=GwG!DGJ`?yQwc*Xu{Rr!$0^<5#4@m&0-XLa4SpKQiXfaXCn;E zWJaT&sa1ocWeyj3n^1g5&9re%U!)ZATHq@Vg7%$jCzc({%?RV4QB+^;VD4vyJY|uXyZb_O;7C zf^

    8W1!V3hWkG^nQPW9&(^ft4$RR5K$I=eAD)HSq^UWp>%$AUF&q$5&q_ze^Dg{ z4TT1G=vNeHSjIC`s^0la6YRb)(>5Xxayebq2%LeTBR9LA&-I(u^R z;bMsfv0>UP!N_x_DT$ur1XmL~Q2WuReLbNcaX>>ZCWt(Mg0$c| z<2B54hX9|s`1hJG#y*)_OZ27ejhhMBL_vW;lut6*n6fq|R_)SMm(^>BXglkQYRD)! zM9UWIsbU68Y_#Spa3bBp7x^PHcAl=U43>_qb~V$gh~8}5F3vHN%Q6YW>Iz@E(@NC_ zx)W0iOD@XL1jr!kU!c(NAmWS*j|~tEIfzVGCgMv3{pj;hI$Jimu)J}~#8vmhv$dmZ z$LRmzB+7g;J()QcfBjRV(?W{u67U*YR0!C17P6 zcyA^{mwdka`YUS3$Fr3o`i>1@z`hGfa|W<1QVLB0wvF)juIn#xg#$R>2{7CR2?4`L9<3MCDW16sueG{s&vl zdf1@%J@#2qU!80AK0n**r2pwQCJ3^=(Ge#C`Cx`GrjGvoB?rm_TU)cW+!R0%1T8`P zSH1ocI9GAbo#JlyS7gOgMJzdP@&qt<@Fm0WN^&Q4B@~2X6##_R)^=<4be3FxGFznS zMaX^xw|seV!4UTZb`ngRpB$5Z=@ZJ<22SkK0I(D~Vk+k*!m2=?6021=YW>|FVXB~K ziryuwhg}qy7O>W>jF7iI`?0nCLxoZzF3$ZfRQ)dxs(p7iQ((X#6Pi<%AYP?sq~*5n zjcn!$jNHui?i2)xSMOlU&{PgS@Qnx8At;oVmv8UpXKlS)&E&Sb5m(2J)OTE)@mv`O zRXo@-YR#w{AC@NJRW%wdCy5L$#$SiI1=6fCT^Yje>`O+7@FMIGa>pr&_mg;2;dLZZ z@dZ2&Fayy}2$IpqNO_S5>_GVypST65rWi0VWnpDy(WwrNRbuUnx58yF@Di8=r` zGHb?(5vTfNoT~wMr;`@+zLJ_V#qm#G(kqu1cTQF0bZ`y4g9XfOV2}W`D)sYs^egZj zGu66o@1p#L-Ke@!sk|f)X=rjBMQN`z#DjNC+JICE^;34Xle+%C0?aMJ)K|zhu!mks z;0c030gx@)^Q5Vvd{RtT%Gr5L*?01{LVi#Eqq$6FJQ9tP|I#{1iDhT+<@xP*hg3H; zNtR|e7ddT`U5hH+pOm6${U|${{>YV6fLjan-rxU8*A3uy$kj5J3x$K`CK2G?~dpCy}aope`+7* zUGYV2^gr7Nf=)1gXQ=7uXChU2VPXZqzbwYB>1mFQk+kw(Puk(IF6Kr#(4mbs2oWvt zC&Y{ZtPAAa++0vw=D;l9YPcZyF^8L~=;?h&#Ph?k1v-KUkO+EwehYQVS(iVyD}a49Hc@Wfyp*N5C+9dDD*ly!e-@G8g)*I|KDBk*O<&Z(s-5+G3sP8>2n zdw-Su1}Z#Y8Uh6jZj97~c-7{j`yiEYns`|%SwU$r#3Ddd4#WY18UX0Y0Z(Ynqe+$~ zk@6qd<3LD6e0kG&**6ZVwSi*0vnXzyeTOy;ye7KK%OfGw(m;FujVCTF)aJ$rj(p0$ zt8YeH?W%?ogt|G_y-FE;2V~G|AHD$x#lgY`F&OObf)^Xi1Hl>vG#fw!77aYIP5OFX z1v#O>p9uqgm5NGsp(sf3g#dR2wBtQWC9NAq_=&PT+Q>?NWvTd>fm9k`^-3j~E8M^y z+Vxjc(nXP`*+A}~)>G|9T3N0%3*rCp}2vz28_wdzEq$GuK&%!O*D>3U4~ zi6tCK%$p2rc$*GnU9ML{J6^IrUFMr%G z-P_yt&RUUp5phouCe%85=qzf{&-!$@wf1v{R3dPcLAI{)d)YowvD9&IZ=B);`bK2&zii_X**k0_b?k%csL=m1Bf!;@P z!pPCnBMSxGcG`biZM1*>((KRRdqW-V!%PttRHREZ#ZgK4WKD*6#A2vzz`l1@(0K|Y zDN!U`cjlT^?aSFtEF^D)fhPqnVh@818?T#Yi7p(hiWggM@VJL&zb z6n&_rwnyG}LF?v@A7D)1*f^$n*ODniGnOhtq598vGW9P6w6iU=3&P%KG$NOU%9L57 z>lw$s^i^{#Pg_n;h;#PS7B&W+OYZntt|Um*)YJ(x&?5lchGh+`U?=@ORTVCAl{x{j zy`J!(@je}4Sa%fsZ=#nkIX9@}J2(!$bG6IfsP<7L$f@b!gtPQ^@bt65ifmoUk`2y1 z2k^ZKeFpc%dgOu=5`>R75u}Np%0mJ@o7asVhF5%voxD1S6H+g#@bLS+bniYrR{j1R z8Wx5CX&1hJAj$N@LzKG3J{4q!153D6^R4* zM`(3+lbZGP9&l69v9Ji2a71t3=Fs4gzFy=B>6EQa{Pd-|YtCO+KnAC=s*A826DQqG zXye@bVK(l`rlDDh$ZYe$+o0JCK+2Afj$*$&{_~KjRsUd$%^kcsZU5{ZGEF$ihUKoxwtZ0m6ny(Z}?ZzJ=3cwAW@ihDrb z^56F4c)XanDQ>%Cc3bfze|q?Xbc!6fS~Ymmx@LO76vNzz(ZK=V*tDjk^lwD)NNjt9 z=IK5R%}e^deIH9=ebxIj9kta2eq5RgM%V#!rZAq&COk)_Orc0Offx{ehK`B(mDAiG zB_yPsYZS8bcw|UKyen?JBCWWLL@EiaZ8s-#)%C@ANB%R_qyMb^@A9cPD@l6)OiJf} zU~xsSYrFLjI-R2ba2wD{@<@KrySPYVWn~rZBa6xozF6wRhR(W6K;qy}a~B*?U8X#p zk~=@T&rl}FnAq6#@uhWCq`&AGH{&#qcw`BCeN}h(@+VQd$QOPb&UOPMq)qoe59O1W zT_XP)+OJ7_UsGlHDkAzX%#ojcq<^QOix{tz1^x*a*VpDBKfdJR;==DJ#w*<9j@@7N z9@s~}<}G8lGv)f^NISzzIPSbo%3_tvFi&phF4ORfczqrs_pgV^`xOgUHfGFWm4)4JqfLko{FMQy0Mjd7^7ai77tha3X=?5WPGxU zS{cZXzlq=r&&EaHjI&FS(eD_A#lZS1oYJ5-h`pnoIFAj*dMn}P#5~gKUT>F@VOvM% zo^*FKS{wZ!Hs}EpEA9)*5yv`}iAlXq-GfqmR&M-@hUZ|khmOjBXrh9c%`I{s*1l0rnBZpV?xY$ z49K4(k(z%Yt*+dgY#6x+q7cW3bw~5GPk|tME6yh)v zI5sqY16}%wQtK%9Yvje_a>Fc$sbn!5Jy&8@vQmR4rox`j&ju6N5<1&%qNG0@E%Hxb zjzk*+=hY`#n)@4_kxV+uw871>g@q_m!R0t`Cd0yP9{n3-wY0QO7Ft@~WgC5I;tzOg zPJNptL&G5;@EORPrsLbr&(HJHu?9(Hv%dz1r)v(c%TUUF?M}!|-57G9c&VjG83iwR zFLl)BRvnMMwVe}RSydGb=F?muhPBCTXkVKXEpr&Y#XqD3cXvk-#`OKErN=>$I2hEu zn=$lZHM*Pa4UF?cf8J=kxmj)jr}xG)U)lVq?*)n1Ccc~Bwjdw46~T2^asAznLs&Q_ z*`AU>Q{ta5w9Z?CEGapKBdsnpU$qw!9g&M-SHF6N~)Z4aHYcKs>vA`=E~LU z<3~_*ulm?jX-0E_0y~}085XQ-`nFd-yUqU*T)CCkF=)mr)IgmvZd>^hXLjQ%k|n*@ zh2rbCBH~7aLo{25^?aWx%;*2W$7WC;n4FBi;lj^nh#5{s-Z2TMUcYyu$rr-)?P1Nr z!b)^u=&@2hTQzX!;2<0J4QB_JJqP zwHjZN83F>PAcFzfVEukBx%JG zFWlLI1VKTz=oRP5BZZoyKlrgiMMQ&teR8o6+oBxINPT<8O+U3$KGU#`It_4#fc|YghJ^&28l543|w1^VpU-7s8?* z<<9W3lHn%5zCyDjVskHM=Zd2TMkNGbh!jTDKt9Y`=zocbLhg+XL5*jZR4Kj}8&=G+G#e#terD5PHqqVD$?X{YOFU0{f` zz4cDr#^(K%LHqgOA<%Y?FtL7ncGY>S5^>>HW32jScdy+e@zP zQRjYA`3`*xZlmwS>>ZT+{h{?nK<2tx3~`gMPm>Osbq z%nBE1yt^kZjy-oZn`|N~7o7S?ZM`gSraO|DLX1Yz#_1y&`+jxiG~-w(;@Edv3DT~} z+d?)fvfxlVsOB8IZt~t1)zkMp%?mt(uP=wVha1P~m_8WH zw7Vh_H%dHO6y@)cIY@F-ru%=ZoltPM+x$bFJ0=7mT#Tz`Z8j2T8wy`dSGwX|_&deU7n zl@STGRqM#si-L(;eNX(JoJ&J*r_QqJ|k6GzgbWTN6R zFMVf9V-+hHVP%7^YsI5HL(RY+(O)I#8_?FxY5X=Q{0zhHihJFUMj@`(`wr2dyh}TS zLG^j{OUV&06?3s^=29f0lUm}$ne3>ZaI!ufZQ;O-3FI3J5CXrer9t$}CLC@LgUH}Jo8wFT>&}peRJaKxPhK*#Ne3n##Ufa)ViP5 zJUoO93N^AK);_<2r+YXEgkhhs$6N10-mZ4JKi_?86@sQmCc@Ww?Exw}WIv^4U*7T` zWQCnJjLj$ac&p*yc1_Dwouoc>$A)QcyiOX5x2g3?{m<~fzg~1{Zy)p$?Rw3BpUwEY zmoa2l_BjJ8$LTZ6gn*`V%E0`yY}R@FBYG0FgN98v@IxFd^%mjGq{66n*uOz0c~Gp~ z)7aQ3DwJ1bO5nv-BOC4!&yPzDBBWZm0mvh4S5bX+_{j0?-(sFy_yFT+61<646Mvlh ztOg{g?rwP=9-g-Xk1@z_-Tz$)cDOOzdRU`$3O*T)_j7ys860J=1laJ66^-2oe)WLg z-r{^4Vs7%Ynu4b zE*j%*VG?nMdmnhuWKG1^5K%9{C$qPckYa2r5lEo|9i*=BQ4G=_8!XOQTWUR#Z1q{2 zKv}dHzGyybKT-z26fBHLpV$@@7PkGDQvS2-RrEGav@+-W+0CL^i>-kgLi-M_d~VGu z)t07>uknba?Hnmp`%7_)yL}Hk4^w|B{}e((LR(NrxYJ@88X69CLzif$aa2#(4(I!B z({7*`IZh>u4v`!Gd=w-B< z)a(76QAKPO>10DxKu&U6{|Un*78?a2Pc%UKVfuu4`_J*B&6Of|WTgEE^Ct2Unk0%a zRjhFRPdBj|n;(S=)4URn2l`j0&og~%HrC&tE{!8julOhkQ7i@&smKl}`uBoPI%WgE zyl#CYg4RUXjZ;mCBHA{{|$7cC!Q+)&_$7c*vg(<<98t))iG%8RdHhdC;# z#@unEm5^_-flBI}QRFjh%A|csXjlaIa}z%Czt?m21mQ%vCs(~<^S8fUy(u{0s&NMJ zc_9XtObu#g3(PS%kF7~;+Wf|jGUcn9(}ITHzMJjaldI7=>i32zG-ZogI<08~jyNlJbArUB~kc%S$D=Z!p{ zqfAUpy7u>Z;6qS@auQYOi(G4Yl&~v#ES#$t@rMRsZ{_5n8AEY{eI1$ND0Kz!T`UTpfd;}r#5Skrb~dj#Fhl?Yp3x9lD7vDSu{ zkPbN)8rC_#&L5f(RGQLG!PqtUz!oql$c^B&%&tG!Y$`M9yDcwOybX36O1IzE77#`( zH_##t1dtt`ohAec$eZ>4L_grtbq}>&mJb}yT^;uB75bqTUDV6= zs^0FTCha-EV8q|PeIqW;+{QRhL}uJ5)ZE#LvvWQi4#^63WWZ{!KJ}IuXgcB6cY0MlnieHeZ8Nf#~qWB!U&d<+j>I}!HS>tDymR!^X9Jm2Rn`62H^}O^K zU&w}bKyfaq;YmC!WHC$zA6^foSeaIs^Es;B+6l#jfNSnK_LzeV*YEanTTon_ddP3} z-{xl+E~;Fv7&Mn#8BP5*-O8I5D>5=tEco9Srbn#QT#fb0bG1)3(%mIZF{)%}dc&N?0bOfJ#UG@d)fTDCZbV#{Nl!nNxmP{e# ze88%CCvcs&cd)KqXZ`7TjNipv}M4h^3V)`og9gpX&)N%yZde2w&@sPsS3{$e+HLgn zEHc26u}9N!epF|VB@-xf@9|t@8@i-cx6s^fOAxJq5*j?h>vyph3mfSrv|UGI=<>ZC>+HV2xK~$#Qc_8PX;ibo1;E@Qar-U4 zMz(F*Hl&&oWIl(W-`DBkOXfy}gmu@XOC&*~=XNHN7+n6ho;+$(;Un`3SVQa$^4t{|@gdtc)>GY;Kz*$){SW1-OvKXjCRt;MF}?KrE*VIucdrL1Fc-&>m)g(+yw>s0By?2XmY(Ign^U_L%cKF_v7csP_% z-4wnF-7lw6fLD46*6{LJvc6h2yk^ud8gqc15l*Z}kK#FmhWu^}AuT8<5cAom(gDM5 znOIqyHA-|_9zvP4g^aTp>M(KvhExn0X*j)GUuOni>Vs~L8bZ@T^`EDA8$GBJx`lo0 zSXjxDkp!sfZ1rRrNU?zrJs}pRrt(6$kLeB^Hg~R9v)srr`YmN%qq-^h7KVwQIH}QX7`~2GzNhrX6xfa0XQ6Db~IU1V-ZL2 zPaybLq?(+@747k6K3VU8zX<&fOY=WbhICzhdl`h*6-q=T51kFZ?RAZerr8U!e zhzAz!=oOd7APgkJJep}KC@BTS#Nxnk(ACS8E9u2!)zByZIei|&4B z3Woi?-s|f&;>QrBI(9$4esP?#G%PaBa&KQ>TPrIF`0NAH(2<#;J!U3EwpXAUO5)Y< z?S>G98ChcH&&e5gy12i;-*?yEmehJXbJt^79n33p`z|zLD)=fXL%nK3hVS&T@{D1T#$Wbg)w;=|LM)DlU5|IRr#~Pn>2KEid4l&(w?5E+ zJ~x~HXpgyYDv7$Og+K8(ES^A2)h!&{rk=n;i_HvNg?{|#67?EK;|zT0)X?$EEo{9V z#!D5O9CSvA;a<^ZfLa^et_&|KN=6-)WwmZAlP%vurg#xDudaHwEh&3WH+r`fqztxZ zbwHSvpg7j1uET717cE{)X^_!PkDT0G!7E*%Ct0F!;WhOQi4xdo@mB5QWYq5i%&s(Rk4HCH${M~ECum(*%S47h?YnZWr@Q9tTNM_%!e zQW+bU*WkiRR`4xY$9DK`|JfnS`E!ygu%Vfa?0MFu^-2ahp@wCS>}5t{o^vGFf}t`$ zDma?EwiMkO5;9u^Cwqr&lkroEpA`(9drX_?(F)(l0$YvkO$A%a$g}OKIsB8EVB@t* z|FL&ItIt|}tbt|eK75bL+=|_%0)S5`DS6Tf9F7+^Mc3-rKE92+Zn^66C*u^nAHx+e zs|mdvK7an4WB!nntRF|mhnoE@hZG3?IX*Dcl)y8ZmBylaFd8d)p`w+>@+Q7Wjyb#6 z*tLx~6m|+-o}VJ7))nfEM3}WGZ~WDkuosIl(csbfV#?hRvA?vRdwPl$XfD}6^YFl! z&yw&Z>K7w|ejlvVAtSJk#})DegMcA+%+cgc!q=ahLC6NSEb=`S<@cwUECyL+eNQca zDLJ5@)AF8;jGWvU1Xc3bH64dfR%%=uzqTAk?_whBPlU;muyvT7DThH^shGWJGd77D zgLt!5YPB*+iDjS{QtvmR@pBVj-@ZvBZgr;f*Z3PEIvA4D%3s&H@Tqbo^pa`SzRO!! z`DD8gawuIM++tZ(BPC+a&E6Zl>I!KipiO;UX*0(uEh|d@?`9z+?&|h*4Gm>AfG>hD z1&wbtd6{lV!SFj4xiDD*n?hD~`d6g7NBY~MH*XYxum`GX{CKtL!jVBC&3p6-CAmM! z&^)M&x(u4Yrj1<|#*i*a5>y(rXbTDnMby>`l2vi69v-bEXLN>==&qbUNp7xvm#&L$N#yhTi??6v`!n?jGbWH=7f@1IW@IkXCe(KC3+#t3RJHAR0ToV|Q&^ z6ac+jJmfVLW&I)|mD59Q+R{PSodKX^utmsLLup9P5xxmh7+YFSFrr~nzo%9~KME>2 z12)*j-<`t09Rp9;5r8zcwMRgC&>08gsAQ;8Z@q(^T)$2zw zu_p^lOJbnO*3RK>V*|Q;o$Qv=aAO%uuoi4<+b?)~fjpMIdAWG9C3+vv33>QRkf$TC zE8EnyVeTq{qI88c>47pubh)UUESr32yFCR~kta=^T|SulD3gkIm44?>+r)z?cwV7h z*n2wPZOfBNjKD#NYX%KX+e=kbQcz6J%s4JufwJ-%nx_4!07z3lIL*~DeZ z!!GclJeu>VtLwf$kp|!14w#wd=Ek3uot^BC2sXE{P?0DQ@qdhdo`KLg6zwORvz)Gk z{*Le)dyP<`_f0{&wZ9Vs6z}g0-Sv~3E7*+Zg!Kyq!DnnR*CTU=fA?WV5B`Lkt08XN zqT_<;ckBzKU;WUOlk98qN)+`s-yhQa#imc#vidasBS24c6;d{+&!u}h8hLyeYQ=TLu`Xm-J+5m&z_?U+>_&H6I< z+4uKG5?o3q_y+{EO|Dcho7n}kL}bZFmW^EM)m&e+b6GnJ+h%SWXGgu^hSh&>U^m+m zI14vZ*iti*vh)vCvCqqUYIhTY$<9A_|5X)$5j{uZ!_z_6sIKCf@E=ognxzzf zt~&e$nuW@3dkqX`(Zo{83aD=TtgXIGo+`w6Wq!qdGOEY%27lZt+j>UM|LpMe6tv{D zYWq`?Bwq$Cx9JMyrw}+0rfndFppEti0qTpO7eUr%|KdD-`fE@`!29m*&TDBxyJc1i?M0 zs7O?P*Ne>kip)2xZb6RZ8t_bZDiFD?XiB0jkBeU}jk%xGii??mG7mUZrc4cMfB(5A z3BRE6Lg{B83kdfY&T)X`$_|**TZyf0LhJ2uLI4qz<4oa&bx(45Ua}}IZVIwo%7}_m z5<96?q4jt9QvVtAMwQdmO*NgFo`(CIbC3ZM21`)j7{$;57qa}f%5ng7ouhzF3%=kg zj;vGYjVIRNSkJj~y3Z<%J%emyXSpvto>?tz^)2m%O|qm|f@7!>8zZ1kA`~&grw9n4 znU1r^*NLDodfd1a^L>@E!vmRoar}FtmzuVZZbCNIcR7&X73+A{nc}>{Ag0TaK2rK{ zbKf5hhDwj9yr|QZfQ72de0$8K_!dXq!E^sqYSq8n)-l_%bdXh3e@Kfwq_Fy(#ue8@ ztwOPtkTwSe5Tk$^eb0BSfu-$uAf$l#yS?q_%ZZ<=J03#Z0ena8JP)M08tGJW@}pYu z+j|!7xvjOLCzU3D_7}V`YC$CEx!sarqjQv-YG+ap6+fJ{+}BL8&0S-@ic2jgvcaQY zY~VGU+WdnsHV>B#J$MCMnJUHp_m5dzM(zOO{|rA9HTRldbLwj;i|r??j6dYEP2`w= z|EO0|=Vc2;2&Jxk4|(}cCQCNId=LfFEewLmZvl6HW|VqNTj5QFcNVQa2U#B4PpfR! z){piwvrNmx-${mF5f!SqW9ySV8m?Ygh$E%oU=-s^Vq|7gP8O55fBeMdssQn-lYf4O zXT8Z{)^#+%oDl`pYB7~p_i3uFFcsEu+B5SrM9rL&x7k_MQ>F*I1up*06!Az0l62ng9rc5i*dRhj0yQ1*wd-J= z+I<_b``Nx}MxZ;`!kmc~FF8_18;!o(Q6ukR>_7n7tb5|)&sbkD-C+TgbM)i0voo83 zfcbq=$7an_Y6zf~I{x*MUJUP9rnYvROPkjQiUQU7mCr%X3Lk$jC)qI~GLnibo|}hV z8J-tD3-80y3pfbA*mvy2f%tvPqgNHW40O+Dt`)yrQ{TUsBv3RrTur0Kh4#()m`Zj6 zMBRj~mgT`yX21!kDmBo$8IXi7e)R_ZYObDPz;j~h>HILM-@-yjchZMghFdbo>ijE& zc1jd2KdgTKpbe!%g-JCfo-wy?rZ9-a(tl|$f$xES4;}}uFi;OGsY&BE?b}X=xtlsa z;oTiQ9a>rb z_CIi9VbD^JbvI(Ea#XCibKOmNd}j`HM`7VDVJZHH@?dC7Kwuz1>duSW9&LkrR2Zf$ zq8qcDAqYB6ae8sra>ly0Hd=9dpZ6_1=NM!K(8zMyg5BMhZLNA;cFf^5Ue_1YxOL7f z&m~SJ25h+}DCb1{Q)XxSlbH?jFy=ZOR+@%sY~J#iJh`%7O1Sx^GkKdB3yoGg<`{No z;CPUK#T`x1BPPiqw7PC3EzkRJ%61!e^CHPx7s5-o)v7y&%Jg zXH3fa_=y#Bwv4CI`fk&<^AA7s=<7w!WCvaWkDyO+YgV+!Ldv4b`8iOWeqeHu_G7y$ z(^thhLUW1bYozvS>QW5ztdX*~Rt$UgHoz+LaEHBk*hQh&mwU%J@wslQf z;%62rCR1psKi0FoLeqOJF~msCHUxtZpC)!s*E!=a(E?Q#Y)cPEiaDG~4;i&cfVT)+ zW1+k^Kp;|RdsAi3N~tb;i4`x##zP?Ii@zT%`XPx9TiqbpmbXR6ySky6NF?%J;{a?t z%y;k_zf~$#y9YHct&8Wc(z*#eVY=ArJetg6V}Hw8BoRGWXnk*!(ylFb@mLLb-H0Buu0gwxu`Gwv1^KZ_bC-R(+` zm{tXnb*rRLPKU-j$>Xd>srXM-zq;q@#oLa10;i^6L~cRIJm#p5_h+^i8TMa3X2ReL z+hSXSm)R+iKr9f{dq_G0bUv7*tSrOOtQuPe;P^p!b{x;|MqZtxAyV$k!nR-s;2xsz zWY>X!KahyEwOOB`-x|2iJ|U=pZ}X_1nC&zmdR>KgncL){I+}0Apr2F9VJ(R@8|$1$ z_IUsI$g-*g`-N`>RK-1S)Dx$dC^0edBKG-Rm@`viqgMw;bWIp2XRo&xTzmWa&`;m# zP;aAMebPTR`vHQKu;aK=6?=o2iX(3Q6Tfz3Q-*y5M~=F_V%AmNbFxz@hn1mMSzacf z_daiLZ*)`(DyvM7H^)9r*Xupv8GW}on?9pc$nQ~5sa2*?Yu)ZruS|0lLp4cav_M|T zH_K@xPiKh(Vyr&sBvIB)yhSpn`qx=wE6#N@? zql@VRtZ#xCs*vQGx~3?ruIe&1vLomDlbl&1xTWP4`?N(4afF3;!U3B$8=j`G z&G-bN;@Lf#({*?l-wuJe{R-~iJmk$xYk3E0%o?lg@7{~fkNe4`C#YEbf?4g!P@O2; zodrkL7t?WndQyQ8oc@%_d`EQyN+z!u+4B1Q44Uc9uYHI3XO|><-n1F?m zlUiw(WuMH!W7uW(2>cN+KY57XQ@L}S5ax~dJng@0_o@+h=W`RNkdA+(vf-T;W<8Qo zH43LD3FM1MfDQ%uhx9FPDrG8ODq?z?WNT~d{u3e?fB<%PAb-C%qOf&OeDS!JhS`o) z&j((!pPK*FEjvFw0;N%zq`)6X2wgf?iy5fbrQg0a?Okr4cthN-E{hPL;!FBeEt6vT zuiSTC+bw`LBZJ$-3>6d0Q^h15+DT?^_koAnh%eQVR-fmpNsl8ZKVyWylNR8joWep8 z;ayG=!FnrudkjEX zi~C@j_recrJb4f2Vb7m@Ol%{5g3n^tc1Fo^0dAxgorbZEJRho^K=SoxH<1{gUW}Y{ zAu0(tMLr`kt?yRG0u~SFx-Nafhu(j_puS-;Q%l!NVA*?qZdT`FMqY>~ET_$& z?bRh2@OGz*DzRvPYTRA8QuLDGznk!IpL!o!dr7ayHUNeajPAQoCveACIg7lCYX$lk z*brmmf6fISQFu3Eq~2qq5?fcX-FqN1@N^$bKv-5N03 z48%aKUG$@`@FBs$!LwgqQHFT>Q%kq{qJe5&_I6P9SQ1RBzCGTvL{N4dV*o2;Fsr4QQ7;up*=403rY(2%;Pc80ByLxNtKsfEP=a4*Kh#0Wfk6cr@nrm<5?=%<~8 z_cu#iY5IdLL+BZGwEWftRlxuM72_B@++++8|P zxom)V>eCqQYgwxqMY)lQdD$Lh$ZOGnjKzen&ltsUuM>N-H+wpYiQO(1#7Q0b<$Tq8+}Zu#wwq{ zeEKKTN$KTIU(`%Bv)y+y%crl=vE!|ht(!x3h0luJ?4FMe{#k8*<7Ip7Jx8&eSh>3# z#vJQ?=bT7e$?R^9n}+PjT?dn2g`n5*z4j<*2c`-imx})f2~2zByncR#ex~+WT3KO$ z391PtmB&JIOn*c3eqTzt1}!CD{HnL?e;Qk@uo4`cL%98*R;5Qc-OqT}KUWTG*#6b} z@W^cU;;FY}Y?wGB6vm1&Zok13aE8&3_YB(XcT&Ri()VyNp2oEa1z34$1kAaFzqGX_ zfg8oc&ridAdVTp@tj(9d=T%krL>BgUCFbzk+Yn&U1<)7?`VN8Spacxw@S(EYp~8_( z0bya%Tnv7UhYjitfB(AqNq3wt9a$e;SeVO(NZ%eF-4Xx}47477g7rQST|HZH6SY2o z{we}(n4qx1a}bfjAjoA90yJ1SoF?4P#n_kod3cj5*pZS1L0Gr-oBC~YzbdW=^TwoozGRqU!1L>QFn32W1cmvqqctf`oYL2 zW@v~bp2QV`zES(?^#^zna8FkuA=X}3WO_EyWX;ZW%$Q-gwO>lgUJo&tGC0>p+Jt9+ zD12rB9C}5MP&w^pbu@SDT>eR$(J>=b@MsSLmh_xyue)L!x0mjrdE3>|y)@A?^|#0| z;j7|*Fra2+mI$7YW~HG$)lF@13oau7hJ1H4com@2pslSWTP)kO}t3ZPpt0uK+EE2zMg3H}J#_vXY;gOdyjwTD7~ z?!8c;Ccbxo-`8gq=A@3Dl(-nzb7P{&9b_u<_^I)lC?;l@Lh-NKI8q+y+_-J`!GgU9 zv^!4?3hETD;fLx>$tiEZC~?63+5q0AX*26tn$EiuFwJoN`v=1&aJAIOqKwp*?{Y7|DJ)H=dEyp4(Xm~G=*JP+c^L(%z z{Zi3Hrke5;%WE;!o^?o+-r)7Br_I;gcL70UdkS=R@aMzbY{#hb;vXlAU#Jc;9z8DA zc*%N||NiNlkMx65_%td{u)`-$R?U>W&2zcpORV%Iy`+pTaN2C%HYT=cX#I%rl4_#v zk|oKhyrk}uHdwhy$uC=T=xZmSqu;wYbdKRJrT<)RzSE*lA|BCeZEBuNuo^;w9YXFd zjcaa?-hoT{V{%l;U;$;cr)J4q=Gun(!w0nEb1D2qybEM`^dA{t&Hn;DG_4K(^$$`b zNe#|lG?B;Xo~M^#=TfW(>io|{I8F3fOV)*9P;XWyehiY<&uP#FXt-1M8|Eo?$7WIw zpSt|bu>(()4r#Rf9^klR16lo^2Qqx8V{K!D3K>oMlSs*5(%H!%>3i7c0?0w&Tc8#9 zKnKAXgcD$T;Q^zHV}5T>fO&CrO=~eFtM^ns2=pKalmccCxSs)f1SQDe_HPHHRvt-~ ztFTnlP|K_`I5Wg?e_~<+369*wSz{+1F)`Q#i$A3crwYp*)18V%mqdi+(~TdrpT*c% z#2WrOvJ)~D%&;V>ty{UwIe>3S6xFY6?E8gOycr2Y7e&mit}?o||25j5tH-(wqW`~c z4^zVPOw>%NP(K~8qbj$?DaH0o9e8i417WMD*W6d(sE}y6IoTjSWifSg!`EpGHOdMd z2wO(Q;?1jl$3i5T(Y~#+K0Jlu5KWeSVML~&s3`RhqEI@p24p%=eB7IVKolky=kr+d zzz4bsXe%LIr;A~_@1f}JwursX=RGtqe-4t*!szys1VC=j>CJgSe&;x1X@593mue#;3)|X+;(&TfBQw zM(49Q$n)$pl+PNg^^;G&9`uj>ar?6PWNwP63rCuCV=Ny8t=g#5oJPmFTZ*FE944`CPKNSqSPXr*muP&LJMpmI)|Bu)<;? zc3i*3%qL#$o<4aXS*@`-`iqX;J3HS{NueECCvaVhwU*-W=e9BWf3}FUq>WK$xE1^l z+y)Eh5Y*-QSm+q2ByXVv%{r#*sw8b5Dt=!{MB!!GWqH~g{lqJ0&ff4bC}DFad^M}S zz+OkqoSJ(4=eR>X6%|z&QVdw)z;OdH`7!E!)0q2@r^eQPepG<5Ft+e7AEE|kA@G(( z%G@n2i$1tb;K$xK)rAqOR=j&R7NT*YfGY;S&JORFGBT$;kG88MQ`n!|t9zYuz`@Ar zGC|asnvtK$hvSpNuq%^RKfbvi+H4WAx3TZ7K6~0US3=#7!Pz5Fli%|kgzjw=Px_n! z>uvR#iF>;kAZ9_&-=07n!@><`Kc4z$;cdkfSxz6d@E!{Iz7{b(A*Y>2I)Wm#Y?9+Q z^-fhO$kHft2w8e&p2bE-E>rs-I0nuIA zYvRQ(*sk9`A~0uQGDjyxk~7DY{Qcj7b9bnQvb*#o_BH0?w1Y3@3D;A>*6beic%eWa z89hE4Xd`>P{rGLR-Pa&zNjy8XM|wV5YU^+6N7d0Y+A{1uE)uHa4|~I6TBYkl{r#zd z>jmU`!7?7jboC1#Z*R~Y#Rz)s!0g%>j{RT1dO(O=6(hLMND9Sa!B=M}5MbX42R%6; zVC*lo-aD-BZ@ompz#OUDchOEhG^yIk`QxovTd+&y& z+a}q@A3QfP5jd*8@0e3+AajEc**U*t4=F?%;o{asy&j#eQRcl0 zdfiNG?hATwIX|%W3s&Xz(4DVbRBI01e!IDhw7*Vr=nF`!Ao5YuR|pLG?)c;M0ynE3%vUWz>c5)uU}U^)v( zUSqTQxw+jN8)d}G`$%5^+mRA$fs3MNCt%MhbZ=n%ZTdC`qH;8C4*NUF!*%o|6-Q!q zn2mJt!Yg8hvbSpvKP{>>YGHca>a|O6T~jn^c#G<5V}#Us$iL3#WJbtUdgvIqzyC__ z;5sW#%ha>(zZHW`ho!TV1>8nT7;aIUd@x5yvb~Bc=*$cpNhq!2||R9jg~WcQb{8Ai}U6u&zI}3 zRXFb*8E(4x6H6I>L0mg9Zf7H(qP26%oYvax{qHEN*^Cxe^2RIhHMX@mV-JHNEV;F= zcw``95IK7o3DXhOU6bh%RBm2*7}ZFZT9SP5aF8il&_P%Ku8xH=!e6^czQFWbq)F#2 z_CRU%YP8=<1WkQJKzFE!pIA60WVq{H@?RRdPB; zg4HO&%}So0`iCgLlF^E_H&R6{9&#PZyle;Oxk+dP9p0qQ`(rq#ft4qnh1nevw*A#S z{^MVp)_v8-0%*OB9)?r}=W{ZxWSIv|t0Jt$ zLq7V8s|~D|yh8@+RG=vegy6hs^~EBf#@}}cr4i1p-yS*uVYbM|;U znFhzi1w`~gI?As_$FoxBywQ=g6k73Cb5{f(L%)HcRFx1*bQ*A6dk$VFf#yKc<57Ec zm3qP*yR^;hSqj{T_&D3MbqLOh$8&BT{w=ai(p9O5HEZY6F5I zp()jXifN-671HW^G;q&jgA#nv>znpHsdtY8!9>@m`A5@#fye%yjkAp`DFhDnHI)>X zj-Mc2f}chX!?)9)8x8xs9Q3rzTDMv8*ssT@i+*Aun)^x^=seW6z>)*xt+;$q(Ejz| z$#7g3ILH|p86e2M7sCQAD&CcP9E`xvP@q!^$jOb@HAw}uZl?h*t&xDgX|52}>`T*0 z{2GV$YEI|t@wS=C$OFkxss&ekg+t9rxsX@|pcP_1+0py*;N$C$31VDAGJ3497veCH zeAm+^=R%o$DNeT1Pllisja#GQD!#_;ycmQ`s7VPb16{2jYd z6(I1VCKRLUktF-9KKX*}&B1WmdD>TW+(Xrc1gfvA3E@OBTh7?Ke_mRLM@HoH$NV$; zQfqpc`t@@xHC5p&94bgeJPe&G_FS#@H5tV4*0sIn`N^AV5cKaw6B6he;p^w5XZTh! z?56C|xFpSW%K_$`G|$vlZPlsZqhA_bCU~~4JVctIO!k3c9J?;0g&uiPP=tEnd)^z)C4|ckt4wx@nC#PY%r+@_m(UqlW!q(MwJngNn z^k1^^B3U=JZ}*OHdVh3XnMov|g$-FnjGEuRwl32U9wztPF zxvQmvw9+FNGVU!?poCX=0qP<^qk!@hyjNyEF7Xg&lmL7C{wAXf-~*6cf4wHoSdB9M zHAClJa+f-jopg!HBB7?ZaMjNT9xS4hXFejo2lB2+8^^xJap6WQOyTMkD^3{<`gPrE z%wSmI;Hc`2=F~*tGK38I6KAnMq>b-zOSNxxeyS9Ptyx}5i-p~rkPm6*bMUEolxZ#+ zjYR`=yf!uGm~cYGU#G08x_HC-n@Bz>=Ok{Jw2e}|IrR^Rv;|Vzb=uYgFUy9*+|!=^ zHB`9|zf4ypiBYU8p&?W9Uj`bOS`Nl21h^KTXwTo8{Up5zi}k?7gaBhKN?2VOlZHAu zA{y_rEzbh!P(%6PjKcp8r<#sOgD+J~OdlE%)5(UjgSrKpy-iYedKwQIE+9CCpj?eZ zogNjUvad268%hKswDw-GWvF#*~=2VXO4KuPWi zAOS#~g3|}IRV!<26wvw)oONVXEx)+#4=wmN&F15yUpn2_Q13@X^phLsbcC)&Q@YxE8=d%+4wl0W3&L%zrZh4AEjRndrdx@7nI#$RNsEQoBe!)3{3Y(`T^l?q zxkp6i36C0xm}lHFI?rH@SFsykc?X}j`4NMe6mfK9jwV7c92^El^Rv-A$&~In3BX{_ z5rn<5wZPT(NIIb!(V~7fxxT##%ZxxvE$96;q(!FQGUDN49(y2@zL)J{GkE^N@ZEi{ z`u)hR9?+5mI9p~!_F>sQ?FA$jkWjOq`%tT>sMOTdgnjt%Veo{Ymk2y0PbZK;?nzl! zR|3F!phG|v0E$dZBt2fUm&+U`$2YMzLK%^;7ZB zTL4P?eIjw`5_sj4(ulG6kxz*3pvwhGX!9&(JH(xMK7{`qLjR$YxB{b^gWH@ST#re_r*8zUKO8%RG^=HCt8E_kf>ExWeC%gInH> zoajW5Dw-ZuNF&te0zW;(0du)M?C$jBV_6#^19pO~PrE{l={AL(jq~^OC(q|7j}sBy zp2R`!Z6+eP^!cg?n|{1_2ki|r7on_@=Kp&tE7U!v`RY;o5~-mQ8ADKjNVOjLhv>lF z>zsDZW3Vh zdr(`|@y`kLtx-h;zI=&u?>4QUkVyoul~hVvRMb&z91u<{1v>Yf6NnOGp||%PXP})i z5*Si*7#-jTb;GWr;oXETVrM9#7DGXoi5#S4QLz^5UQXK!0rGk8j$J4_ohG4&uuFVzA-zyz9x81AjvjaF{Fo< zJS%VgBok$1G1Q-LmKl9P$2iq%RjpeQHwykJJB8CVyQkc%eewY_B9)hMpdkBH9On;r zbsGuzg#(!$U}H?&3q%7fwCt4)a0rTtfkO_8z*kW$S>7eHa-uz5U12y5?+hcDaWJr+ zjlzRpwJKkj^06RNfr(|*y+|yCqiOCEdiFSRVs~p@47f=}O5X9B%&lkg5+IWOE%NNB z+R66C8Uld`0?wquG-q2I*izYN#?&7lfYvw#Q+uw`hwxxA2l@N-6 zb#XT{E#kk?%c%&+`RDYOySLJS#F;nkJj+Y)GdUc3M$lmK)99NLMRw>gqML4vkv8~Y z(>tiM79E71w?j1?4I&WGCMMGEaeNV=&&zKky|?huz$_$_R4Xf`glq^mJKBA8Ofubn*A>|^}_oT zHEc2qT(XKaUa6$0#mFwgPuP5{IUW4*{1rcChAy=W|LBh`P2wA?&^n0=ZbZfEo8>qJX<9D+_>QB6<{8+Gf%DZWK{yDqP zVKgy+3Oz?vDEW53(~GRU;P&;R62bR506^V;Xx2%dydxhhw-%aRhGnZ)MO@(F&SH4I zlscZJzMq`pb5|bxYt)mJK~l>v{HW}eVpeDZ-Vvr=eOsn!6;zDz^Wj;Irlp`3k=Ao|`T&{O(i{0(ocmn`2r}=od`-vl&pMkF0+>aO)G5Kn=1kc%laB4d+~+jt}OE9Iy}ZN?eQJ8I{SCTDRuk zr=(Ey_ASRaST^E*#Cb@@=*(1NM1iSC8!L}}5srnZ#Ai5PeY#;M#tm+FeY*dkIwZuBKGT-%R}E4UWQDy(*pnG6-1@QABJ=AWL|bClKQG3s5f_`YOg z&VeZym^Xoc>?#9E8iSlOV6hR1K5d)jP}5Iyt6aRchqdvGpJ8Ouzt$S9DxF1AncV4fGkg)Kdm~N5?n1T z4a1&t#V(TPjHBs_B|tkj;#;R}FJGi+P7c(p%AA`1THLRU&)7j*V}rbB81A1fAuBxZ zWydU|GWtnh?dtA*H)u(<)QNF(XgvAxq2Znvak1=$$!t} zlKOQ+>kISG08iS+AW3v#5nOR@C+^g**Rblp9^@bw$Hb(&F;fvNI;|7c3#0(qp4wQY zBEN`9IZ4bHQ}d~E7OcQvSvj|>vEU(4XE-?#&mJ$*aM-{2P9!7M_?lAh;k;L}GkQ>y z9NIb0-xeX~h|c*yx$oinM|SwT>w3=#n2!5zcW=QkWJN-F*5 z3YjEk3&a5{ohSDx_C6XYYg)ClrW)1f%+!w?@wI*-K6u%ftN0^DSHPlq-$;Q3>tMPO zgpA9k@0vwVNF|k88zSN1jB8hZpWYshF zlG?l~A&s?wNG1rKX;p%r$nSXRf@m$Si|KrdMCig|@-2PW6>b92UmM=-;IAaQ$#(Wn zTG`EAPGfmS=J{qm`@D2)E%|wr=<|?0;Q#}4+x!=hzM$J3ENSizG^MBYH_i9K%27o2 z5Xzs#P3KQko9@rZu={hv1xLdXqspwJ$nwjsBu0_h^?o z<6A6w#)7{lK|s`UQk4Ru9E8a4^j4NGl4+{<<4A_+4gV0szsQ{iy98SdUxfu%8@nA2 z1n6z3bRLe>|tTlfC``*-r9emuu^nlB^=7Ne05^ z)Onn5YucB)IRqKc6+_KA$r6m@TQg5zarPY#(Bw``{Zxo~u)FBz_4(qwu$0EaW>_Wc zEiC~7Rd+GHelMRWIb#?lNNGyLigP7lScDyJbh`RZ9}8uU7uVT>w%og8vrkr;$x1(m zs1bKdVqd5}w8TUB3fD`%AzyV#ga$BF=y8ZVywAM%@9+in=gi}m+tdoDh_WE_Pe}&m zY>F%jTCHc<_!n8hB}&EMM;`BZzw|7Y-+0PMMx(d;U`yw-|;E~Zn(h^=kCuq zy#LeQTSnE2wg1ZI}mf-Fd2=4A4BxnQ)?ru4_LxKkP0~}lf1P<v(~INcjnX7ms4F`UA1e=Z||<^sspL}zAjhD=fjsp_~1UU^t6B(ZL!>9 zh)yS(JE1n?x_l2f--nZ!SzH~nS!DG-7KG%px3ay!+L2jKnoJ^t4&nB(aw+P+eA9C( z#DCT@lb1}##COFg8L1N!RbOj+ihZZSr~Q}c`zPpRiBY}KK+}R1QKaCY_jnxJxLoi2 zQ14K)Vn+@hX{jgs)OY1*J?2<>kI~4YWM2nx zp+?#&ndfz6FKX#(S=SKcgQ>GGtAoGh{);lQk5Ay&2%Ctm2bS%y6zznMc}k$uvv& z6TSdh)in!^q0oVL$|S?dwC_&Jd49F?q!2O^?pdLS=V9XKfvQlPKtm>O{P#$Diz>w< z@&A4c5Juqvz1s3xchVSqm4p16rX1_)*0!p1!|ifGrTU>2?gokeLwTs5O^vhEzwQ%` zTq7erQ&FKoZpmraw-VI0oAf3{Xxx^u&!!B8@-hts~B4eX%p4-CD`?7BWl0qoH>+5TfM(Hc8~GRE7C zX_BUTMmOz7wkSH~?I#fgq74IyK8ioWDXHP&EFEX;1{epm|N+A)+e)J@=tH)qszzL zK6T#ws_cJfYqnJ&dl81xGnzMtR`$L=DPi~HmJ0Ud?80wf%K|6MT^(cDtZ!n=Kb~)H zO)PPU`VfTi#!Mf|Fyp-BkdhsKaY`VGo%w54s|!lC92>UJq3{e?ujW8c{g^~}>g|`W zWx?Rm7q}G2n&8@^Rq=ikdHIEGKapnW;>RZH^7#`MOs>39fd5oHhVly*MToft9BF0cfJzJjKS zer`%AeA^Kc$##$Ls{ek2f9`=?OoD@N6nQK@PwJ*QgtX#9Imr{31Z!yh{ntlzZKu|b zH+FNRfoO{-xaS7Bdg`9vvmq;HBSC&qGOtG|3Y!hry~o}*>$kqB?GUDmu-Fu2@7nlJ zNE*RyBqWk-#V=Wmo9@L~Q9qH%$*f7pH!pWJg=!y?+>g;E^_DqX>K(yNeI%Re^JCfu zL;33P{!LN(7sj%bA<@!30XZh4V`|8?9so%!36aj`kNhAWWO^y}b1qYHtZd-wi@>1uqP zqJgMuB$PO_y|TxlaEm5*QmGo<6ehf3!s?k!juz(3SYb|1T3=p`I0=5lNjm}ed3{2m z^3KtuM07-@tWW9(T)tXlmCmozy2^eG3eAP5#E)pO&`0xsm51Zt;=H2pQ^G>Rxjr{t zrR>5awBwJ>QQ!jXsim-Iy=e;ZfsgkCDGk>|Q(m-^c))j=YrH z!#k&)Ld9lLr^5qAf?BF%W6oytjcgb@;&aO6soQUw5MzO0swFp3*GUzbDc^@=NY6&! z4D~NLQuuK>_%xIH4Vn@ME@ob2>V&(Y6t7uyo=7r}QdVAnFJxOo>pE4!`t$>rjEIAe zlrDngR2VHKM(tU;vF=wBzt{7|Yp3Pt^cCYgg4@f0o`-xJ*#G#~ zjZsziMPF%%nhVjd7(Jm)9GkZ2n)!ecV!Zn;jR21hLOC$OBK9sUDhxf^q}|Q3-eLL6 zBMO|slMW(Q=!t7wdU0>87K$5DfqYk1B?j(;6E{*yrd?o1#^rnAS3SW`65dCvc(2OH zdwQS#02XYf2yEDkk}Nh}no3EL&McPmt3BRblTxb|X%620YLD`tS615*t4@O&Bgq@( zNxo$K(}JMh)6P87`$el-S<`-n3|6E_-`Z-4l}e7))*PewRyvsV6=e}*MKA^B7UoYJ zN>nSs)g_tfruseNPc?Avqdmekr`uN2qc^kY^tVyp?E2-nWU7Wv82$3a_Rs!I#+-D$ zXshu4y~(t_B6gsX*t(F9>r6%28B2MMw; z7_45Wx--ocbYf;&8ftZ>L5gWTIHW|!g8vIqHx=}sw{Yy&uj*ECIEa)A!=*XR1eG6+ z`YjlYtQLVi)5%R|hoaf5D~m@wMGA^&-{(^n_cL_z%xuJbh4I{stc34DGOfi#XT9Np z9tHuqV7(oePs`U5WiK0kuHpvC6^V~t_Y=G%Bd~ui7Owgg#{X!>kI<0f9LB*2_Zlk0 zPW}h#jp123Bg-1uWXKqG;tLX-@cGi!E(AFBNn z>pbS3_;>o3=c`nL_eJyRlsr}gzI+&-_{f5zecH!DD+%pjyjkUN>_=YztWXZib=Y?l zAvQ|?5P{c~iLju18A6E~r|E3oi9u?@+1_bzo`XXrsx*4$Siv1+_Re(LXlC5Zm}aU- zshYzB(STcy)u13$K^*oUj-fomT`bNPW32rdilt*0c4~J&`677!Ay1pyRW;E_EAX{T z;$u1%rPR#uw;~m%{Adq9iWNnvp(9>jH26Pbh=Wl7BA{yiyre9j`_UKzS7FSAJ0ra} zWq+&RtA>H=NR1-iM3XK1ORf65b7V%MCz0bG7NK1Trz8fyV<9iA35_0+sP7m0l~*13 z7?MOUlk)$3!}9kP7Kt|MFJjs7c77msqz=RO7i3x>A#;qdLp3uYbzDNi-`Rgi0Q+94 ziuYoTr}zQE$%Z!H;A1WgBsl9;$X=Ay@}eWMlw-qcdyYxFg{P3UqjBd0Op@ikkMNSS z1uaAheuRh3L_-$x%AXT#{`6WK=3?rBRyS1+AIeLvjvMY4y;1{jl)UBEG|I^iy-=WF zO(;E#;oI*KKbk{-awYB&7F795SqJUG>13b6%o4|~$ILPnl`~f|t=0VmXrOH_XV4y& zuv?^+!rGA|btJPxCqKK-xjM>24E&n+A<<5z60^_;XWhF#cO^m5xz#K|Mlrq<#b5CL!_WXc_EW+P z@1#OD<0h_pW(-n}lvgaP?^64GFj-Wcq+cUZ4KXXT8tdcdxxHBq++E|5_hhImv{kbX zz8k;-=Jo1x;tgLpt``Jc%E;NqG2WY=^ES~f1-pxu=+WR6{U?+ma^PIQ+eN)aKYl3n zK{sSYB}|YPBv%<#5*x=rt@A1ChGr)}-H$O5)>XWas9-zg>0S>><(z6Pm}O8E%Ca5i za~HwaBT2X~-aSeuakVT}?}b3*ewXQqghU=>uJO^os*R5UI99?1^IhTt&IpD~Y$|*R z_NS9MhNToh$*YfAfSuM#YQZo6eb*(O^?Y8NV5RaGezZTXXGZLog!=Rk-_ILUeTozL z;~s=n_4<8_LIkDDyWUFGNj+kNe6J$<2XI>GbKuqd)}WiQQ9;Huf!fx!<@K-{BQO3r zB)`}`Tce1c^48CRMxQ7pTEqD@BVNQV_J4f*vswNTZ|2?TC!#ue$8oQq>Pn7E0E@PR zf1363wd1yvoZ*@=NIv*cBcu4%AN@`V9XQ3Znb~UEwBS5>AP-{nKFVtjOCB2y2s?54 zuEo1eh- z2dkUNxxW;}3*z+Q0*Pa6J~cME`*&k7lu=bLxN*&t?KMgs<*L-aCk6xkn+U83Jp5++ zRA=hq*b0Ag!yL(OYkzkn8IBaYjkmc3it6>OgGuK&s8iAjh@iYcZZdY6(BXVDnAb2mxqUZA&Xqe+#O-I`zL*$n4k@kfJ zr8ml*9M}f-=$_A`bU#CBKY>tFrz9z-e1M+gd6(sH;NU`&ZSO@0ezPd9d<{!17NX9E zs$|)bI0-jn3eo$*qY4rI1cd$R zthEUfV={Nk(Nx2V%eCZH$2uxwJLv7B7lcK$lgACO-f~Au4j8wVjZN#h!DEU~Z!TP) z%d3;J&V-W2?wZ-yAT(1F)aXafZ;zZ^yR+HVX6*c@wi)b&CZFkRUTUw!6BOvk#d9!< zGpZUDs+mC`!ES?+ceTB{dG*uC-Vye{hJOK!E<>8T_{F{xg?L2p7Xx6oNc8)3s)RmK>0lyxJ-*yN1Iom(2l%E!CIBqo1Pdn1u|R{D6O9 z4R|T4PmD)ivgwH*JGpUE!gI8u1~0r6j6QC;c;%;RT?{M6Sr>+%WtiL|cFinEtqtP= zaVHmZCdaA7JIZOQcR>>KfllfzH%U)sH_#7RiUp@Vw+?=Jm%sLHcU{Cs)mtcnMaf<- zZ0?rG;GEk1ZR}#uwLFCefU6hwH+u`JY86#X-=xDqAoR?Q6{{nVBI8QI)%DVtl#Q}&It)nF0S)! zoU(P&_q`i9g14!CGe*C(9d9j`gJG}>ZFI0rxEVDCBb(utxOTdTH1iQyP3S6;kvvYn z)wdUjugkUi{3FmS^Aj48{X-rD%Y)@u_PfIrt>(LwmT^^ADPJ~^mld7GQ9fbqy%t!w|Ka!s1c@bFBiW!c~I z_DL$EP+fAm=E)3E(KcmTIvVc9T+}H3}!cukKUY_kRMfbM0G?YajfmWm6?~yl;93@#JzflvzWF zFD~S>q%hbBpy3xT{(e$IOML4(_#{U&KAa`1SHrk>7j@B`B8R8Cn|7M56pnkX!BYk8 zWsiVfnuBuID@t~Fw@xT?B6F~IFmdRAKlX6M&eN=lR)_iDI}DMFrOlK1-c_WOBTSLw z=O^`vFgV3pXiMtO{HHkYj+Utaljb*k%sP65`|02gqVRpcQ6` znImD1Tw48z^ZB%?PiaCtdJd{&a+Mq(Mpz=>RMf@wFgPapvi;!sSfWD zbafJz#NaA+Tjia-+NU5hT=qN+enA}yrTAgG9{-)q46yhBq`oVL*cJ(Aw2~T z6gIrsgeS^|D4%S9Rc+bb+0;M0n5cfLY#6@p^Zdsvv7dqjQ9q$dH1=Cw zt*vUn+vSfZy9f!;R8S_d(iqQ-C|K2mpC6A&9Mm6E+wl>{@_SJizoJsEXvPX0D_Q)L4>YsC`w5kZ+%6>6%b{=cBOSwloJG8)GySQP0-$#aF;%<+!4AUvvYsfIUx62B)k-CfAROFF*yL>NL zR(vIx2vdrdcT6R0r_Xc^OpbhKef(?5-=)6v$d$(|nwen2GJ5)+2qJ3V=m-2;C*%2a zN)r^TMLu#(zJqxD!o>A=>lu`6t6?s`Mmz=boLMl{`|k2q+d&5&0kvjhy;on&b47ik zM3cdf3l)*h(P7R>Ca-Ay+S5GwJF1*{wIO7}xM4o@oq)jVYwyx8FkJz@7i4QnA~&Q* zVH--Fix3&r40$vVOP+>Y{+NTNE#`l|&Z77*nxC{3RinK(ZtS$>5K&Rq+bYeFWc{@p-zI+QfpH!9@JZl{ZU)wjg)^@y$ z8?7?uWTx(|FhRtSrw`n~{Kg4ZIAU>_z-DX_d1XIo2K}Xi^uyZFq*)k}cskp4l&=KD z@`H;BJq#O;KKpJGHbGI7)W%*jM8rp5r3YZ_-YkIq#nq+AEK9ybq-v<*7MSa;RowMY z-VQej+vl{}kDpRvK1D_=n12Y6Gg875J2yo5pd|LHfS0Um>LlA(6@6U#K^s*J%=u?e z-QaaJ3#qPAMHp_+-Xd_mfvp)VN`rRaW_i{m4w zT#V?JTGf-jC|MMee#uS>4e0e_+`H53S6tD-L_~nqnpwNhwVY0#NhcS7iVdM=bE!z< z?qPcXfRO<=S;NgNP1hk!c1j;&M;e+pPMJNgd<6W%d2wtaW>I53tGqq6Jv4f>24Q`h zDp(g}j&(B@)_Nl(0D>uPQUrpDlab1UFH1j#nEnos0l%p?YWa( zNs&($kEbK*2bj2BFSq&Ns0b*NTxXr@wJgcj%w*(f6X|Wem1qN@_oIn^TFJA)dE>D) z@{LogaCKL4cn)kkYen{6**MIzgm(C%fBgCVdRo9+mzp&NF2)WYaR@WBk{fk8K`*Y` z@^Ss+=iMYsXnU!75{Gq_(sJZ$-uZbY`jdp}b@iOj;50G=ke|tWVeB~jK&W7G3mUjk z(0cb-nmVJgTs5+ZL9);FcY{+jWK{*GFXFX3ftZtpE7^y{wN? zFonXa;IZ)cNJl*k#>7`hQpJ6*)rko$*lV<;It7he!v}4z_o-HHHg*8CtlDBKp3eC4 zshE=`tEdb{3olg3*R`#4kv+o)Iq}iiz1>hp&o23k;~UGjy#5`D){XWjyy0=XvzP@Z z%jx>Pj4u{0^Uoe*(pK2wP~r(LKJ`;DsmBo&h(?3v%7l9bd{QVG9{SaOd9hvmwad$( z%c&*&B5YC02LL0$&u7^Eh{St0v1u;Rsa=+z%&^~lI{Hk+XnhJ9aMm|)U2N~}{L4-M z%bpWhh2iQ>o&CY?4($B$#QOUBX!zg=R&j8$nUQgK!+m=)>>p!zcM0>gXT{s*O4oc`n_jKlPQcC&dr3a7b!( znbv=I^ZD9+vj#re6=8aHC2~W*(9#rpb#+zmf5x&fzt{tO zR=;w4E4;UdSiRk|b2eBc!GO%waz#>BWcKPR)a>pWQUsAeMU({Fe%DMORL5 zWuhbP0a#POyW3k$ToIq}uB$GyN1nf5Mdpi|ylyVXk@hll+=-omUf6ClMh641`)d-K z)pxOFOQ^krnFQPWzR1PYAg}b+ypbZ&z{l1~U}~ebT-#CAzDvXR_a?T1=5FNICMF3eCZ@ zV8J}Tawl|RB1^|XLUQ_9)ziPw%x(P+rq@>z@&~sE zx?#Pd;01xSNj1{Q)?L`JQSS}rXHV-4T?2@X6{{O_V!FDD;hfMJ&-QKxOWA_A57u_9 znD8;XdbF`dr?3a#$JBBb?jblVWc4JK11y_Ih5g(}t5y5c`4u_l43Z|F06)96VIrn}!n2 zcUxVEitLE4Lw>9ezY5pYJsT~uF!bs2@Db3NkIm7bv#zFUbKG|JmMz5Cx;mA0{*d0f zIS@_fd(c#(w2>N-lvS(PN8xUt8mQ~2z>V0baa6@srkL^_WA*p1Bwqb`@j*ew#F9I& z28WjZ;KE(u>RrqeAhHj39s2zs9(}!`)5Nh~9o=4C=R{?%OuBa6w)$}Mbqa5M-VM`i zufN6u-@VkHZFMRLgs|z2gqWH}hOOg-55a+ddTj$E1v+{&sU>MJ(yM19_ct^-RO z;XL>b*78Q^w_%gByVYsu2tf^NP0Ptn%W-LVYfafJy6@Z!RI|bhwzKq;y4)>pO~Va~ zJ+tC1u0XWrw?y6+h#(DGW>B5ZZ>%r_k3y}a3!$E z&KN@la*9!(*ytTXs4EVz=K0g^Tl@*L4SYvixmcNdd9ZypTtg3!7@^oB+_lTh_iCC7 zd3x>Jij4EfGvoH_M`F5IGN0g7g->In8EWnnPN{d=kRNn}%`YLEIab4P>@j%81f#p0 z$f0`D1BqAPrM|Q9FHKXknK%@GfmF}{(+6J8zvX}OOTRrKdzV^ORsNnpAu_+lq9?W}_O&gPV=VJjSk2sdRoL*#esMZbH~ zkrVwffUV1(z>TX-pHo!{HQb%>lf&J&-Q2~*ES{nw-Oi(3%q*D46t;?NkxG>tr;*PAhT71S+1r+_D&x4;T2} zJ~~2dM#HX>16Dtm*R)|%0=$k;GF%ff&#EkP9jsY6*E_V}>fWm1Bx1pTU;Tiin7K=YPKv5XN4KqcqT>e#zo58{BDR1+k7MK4codwM+|IBjLB&8i>?s4yS_$L z98~zaoXa>~15EmW?cB1`XF@ zp)oTZEQ0Xm8Q=;NfMM8Em;n><>L-RM&Bfu-R{J(t`c$H^{iE_+SPQ#QI)sorh0K;4 zMJc)Y(jy9ZUuu^p-uc9!|M-;6%#v@L*|UEjK{rR|5#(vI*U7=tGgF`n1RD!=A>*x+ zb!01~?v@wQYr&0zCE5Z!f5q{ol@|iZ#IcmFuzbNvHu_of`CPWkv)Dd-x*lDF#6y@6 zWQZ+Aa$wWf9;H39n`ft70noX*+~)gd(_8YJi^P%XN--=!Q!_4S8?~2o)hLjsDNs}* zTwowesAQNN)TdXu8C4(K^rG$GvN3zbc$$Ab?LM9(&n^$1x^5J#g)rx8s6vjVfJT+R zpx&#~@6;R=n|IfrNrDS97H-ga_TNY0BmbK8T_k}(*a%Ft*UALAP2P)p<|z~%_EgJ@equllr4u4J zxvD>}z95RC&*blMs%co<6efh&&Dszs14`t&sEh3I1!Q$<9Kj|E@ou!O7$36-1tzMD ztCc{HfxN5C%|Y{o?X$XbPE<&y_pBTeWIvn5`((VW`lJ7z@#!>jnXa$!CUY&d+i-BX zj@^2dO!sLj(ufsCrU(Nk1YoAV7uDT#_IVj9x^Jp4JvK3^J5Ii6?3g z_HI7%GDJ6S7>R$=bJ0c3??V-@-TK)}95$8Ai(KWOG_|DatS^ip&6y8H}jJ5DaQ>#0`)@chRe2;p`jkX0d|<1G~? zST=;)6}b44#Hv8!Ev4n6ix+c11)Z%e42QJ{Qzg9cf0194Jp+e-{VN^sTa zyi?|D_r|MKHZ=*CJ$2KtHBDcmbuAF}k9-|m0mU);$WoK(UP2l_NW1=h)oI=HRKws1 zf{{6i*FFh0^}Q0Z7~SgUCvLUd0bh$mknhy(9GZXi!x3VEK;l6C#7gL@TRwWafEw#O zBPa~1$ORr%2Ob5|lAew{lHO!40vo&ncp(YYhp;*Ht1s$89CB1j=pig%6A(6|esv)H z&c39ZfYdk6Fc}LYycr>OLBQC-M3)R^jP4U;TrMC7kmP|q%$>CW4?>z3Y>1(Lzrotm z|D_&mR-hb#6p;Og5@Sw50bfYF_LOy5e!zF4+13hRVF?1kW%r-3LJ zd=CY{F<%fP9Plks`{?`Q`9Z#tf`OdUd%SlN&7@wywSz8b@_KVNjY)x(=Pu15YK?N8 zdmzIlz9u0-+T*K}g4t7~N-0>|n1Mp9$iDwB*@zlFNi_=W`)CkIJ!o~12wwk37C^l@ z4p2?H1i1M~0WuE2cvz`)MhzTa06=NLj|Ut;t$#-%3El_O|5q8kcBh&Pu)_t=Oh=&W z492(LF8)y74*zT8|Ckty(LoUc9C^S&J;EDM@@_Mpc|eG#O=LhJ8^QlgU) z`-uM1cbXRgwr&KP1SCx+o~-yKaQQ0&l(!=7DtffJJs%$%xUg{BIpfjzCfJpIQU_Rb21!fy-*(EGkH*Y6UiZ z<5LEJ`|W(7aO#UytJvQ^1@3bt9fR;+XVoz4I~T!4DLB||aU}%YnBxI?k7H0(Xc%N2 z#=5oXGGx1;BYGbo6BD%H>d$CwC*Lw{Jw9$2GYQvN)5rfv2bOS(Y<;42OVfcS={_X^ z)r6jof7`*Ml&Hp}A8KfeR7}~iBk^-#u1M7uF}MSc*?~-hHhKKcf=Y_KUGIoz_yKM= z-eaKr8z`g98dW4Q!^tPE`gR>P9UvGbgXDXBaV~ign)}`XHU*NQ-R8&&|IE`4Hq5kOH!k0D?pjhs$eKmThp*wmiW`@x;PG zCa{Be4yOMdK-r>O4ul;*W0~&&;bdxpp^8{0*gokCfY)AMf}+Cb&4J5+#w#$uuh$11 zvg%*>i39!jNC^lr51s4y%q{L;L4+%&CJl=mCv=}g;IXo)x zK343X@Cp#hC@2&l{r{Q&2TX_wB~n+HR9A=15&U815^77_8_>+b6!HAuOf5F&;UV^J z-k;(CYk>rHxfuPz!L2{nkcvs3#IF;IrT)yo7k^-4$xD~y^7VBwlfwUF{(wEdR9Jr; z{kEIu#6v+G57cNN>6a95%B}E+^Gz{ZeI6>zo@HF`6|v?9Ju~2dcGXxuF>n_bzf4V1 zz6;Gi`m56m+j)X3MrPeSTYQIqOGff)XFAukls;Xm{cFLp(>Sa#hGvyb4)5-@x!)B2 zqbcpQT`I9uo|l#Ik(T!ADZ8)sjJuUsA_L@8)Pc~OTJxRaa0TCs?jqk z{4?+1R@ly53J$e#wJv3YPK0sthVj(u85c)GJGWF;c14_S;8a;q$`iZ}q_c zgyOrqyF0qO6RKZ&IT5}72mQKJ%^^3ntTp<)KFk! z(&l?b0PuT!{8@UjeE0#^3=StXCfhdb#l)ZC1#sl;Q{SDPR)^ZWB{37Mi<}L8OrP5u z6xDL7GMURy`P1BN%{K4(mp2lEU0y;TzH*^q!&PE|uXu_%o)2drPD?mezH!iiVHJ=> zlahZ#9bbH7R{M>8yx=!CZyV;jDb~$1Qs}nav%t2W&qkw9IrARNJ(}eFSgothet7Zh zxVmV`qiz(V7Gtc8XSC`fwN&|qpL7k%=NIC`ynIy_Purl4UZ|s zNpX~~BCg_>O}QNUW38U?aaFmgCZ$!%UOrr7be=!GXUd)MsCpNe28#RIb&n>f&O}A! zh)EOJNvJuBB&i)7S7)Sig%GRP#B3Ku6zHr=Suxfu8dx1(H)K)M{G;b=c+qdAxYW%^ z2_z=WjV6Mlx-(5G7)(@W4(80PoX2sY*mQ@YG}z}0_la>8q4ZC*MGW`Y2Bs_edOI*W z+WuIZkyZ>glAZi5v>ZCcBZnVx)2)S zGv^xNOUv9SaMYK$*IzBQYEm?Z4P6S6<+CqK)#lwylfA}t) zR84a&Q0k>^W%;R&Oqq$Vi&UuRU%Y1%e6eZPxr`Of;1-WRSXKYx#a-I0Y@Yv}zfmS_ U4aQcZ0NBYJNd<}WS4Khq1Kie?0ssI2 literal 0 HcmV?d00001 diff --git a/doc/img/MH_05_OPT_FLOW.png b/doc/img/MH_05_OPT_FLOW.png new file mode 100644 index 0000000000000000000000000000000000000000..cb011b21b86383aa01c1b4cdaa7579b3d0d1a4b7 GIT binary patch literal 555738 zcmZsC2T)V}w=IeaN>f346{Si?2oRbyk&X%y5JW%-NC`bumEM9#iL{_pQHoUQ9YT{p zXwpjvRa!!??{MdS-+TA|AHy&ihI4ZA+hy&w_98-GSA*&X^9>Rb5-QEds)i&a*E~o_ zE@zTo1Aaqt$3z+UdByFK<}-5O%a7bToP>mvL{nAynRnXXdU)MS8;|qzvDW0x&mU8h zKVFgeNb=~B(gRLT)oZrxnT0R>p@oH&Gm!G(jMGYs5=GO~0q4f`Un5_I3ZE9LDL=Bl z$$guX^7doSk4m@2<5#99x6^$4*aHG5YduFyyw?4lIj{U&JN20wm0$W>pK)k{fna=4 zwsIOiHC80yI7UL_37GKkw1ysWQs6I5*(&-!zrBU#K)S15N4@6`8JEZq@c}Q-_6O6% zG}vS`(q)b+w%Ozshs6HpC8CtL(Fn=BK2=s(jlif&pm3`u*u0qK6TdSx**BTtX(HQ< z8i>8TkmmCqj7cL?s3qh7{H}xavkIeYwxj4Q1nWlA9D;4sLxbX@$;+p~`)1 zu79__`8VLyW!)E+;u^F1(q2>>Z){xp$l4=C7@ID%`d_EY*x?WqQLnZ1ji}~pfmo~I z)@A1XfUAjc3-c4eR=2Xrov_ITB&pc`-Dj+rW8SDC=KVRElwf3C*0_01#2NaZVLD-+ z1qnkS<6AW$d6xKYLH$k!64k#)24tTW|G=pK26Bx|r>g{7GV)NTGwe0K3#?s9{YFF6 zvM=wA+P`5v_P?V>iL20HB{iVCOa6#XtMFi*Cg93ou5Qp8;_u=%SY&Ltb*3Wz@6p(K z3x(J^cHm4sO_p2E{cOXz@dGF0hb1^Uvt?=Pe*}}Vm643hg^dBFSW3aWgxm@XJTajo zT&*gS=*Vw9Cm~a~DP2#Y;Txt)r%^@B`(aQ>#ku7BZFsfVy^`vGSAwXyX`52;O=ZTr zNFwlu^BZ!TZHdMfRI0+Pd53&b8?~^s0k74^wtWK_Zt8SC%I%#&y_S75$<;k-w*RqNUnAdJ-u7>?Do9usNXc~Fw z8WrVp2S#=$PD*vpqJxGYzlL{Ds^9r3?59wRP+O_ag>!Vk(r#%W*6y7#kC&)Wvs-Ln znW|wse<}=s6H^1uf1Xdm_5b@!>LAx_nj&Ot%T)?d|0BtSZW|IM4?FVXz4g{bAq>|B zi>ii(AQ={|x7kdCnhw!SU(cU|*1FzBzh{vf(`EBP0%5;(OeLCu z_@|xmez5z=P+J>zOHRgJdtFt|tEG)<=kKPn1!-r6$7>&7YF(pOFj5Vly!r2n=UQe1 zhv0^DX^YmHIivCvtA8@t+(XqM7_||Q<~v>eS(*Mnpw8xoW%~?&3uKR87_XTsjZS^|e>3Q*VlM(h8 z_z!7aJF&Me)zc#?)Jm7bmLrgH{>LR)MJlG`93>69f;GyK^P=r-9EBcM@ zzs06YqD-PKn@?Lr3aYNIT3y$IVRTGyc`n|fq2lt|@Thv5OGYLpTgyY*%+*#B1+m~j zP+ld^WPC@_sITN;%9Ln!$8{VtO(U(SHX?(u_-!s<>GdjmGt)Ss-n~b2l46rAZw&9G4AdE z1zKF&%_~Zy3kU;rWDtTl{UOTfOkhNcH8^O{1^+xR>uFD_46Dz-s z7L(6d^ADrT=mw$K*^$lZ$XylT595Ayo2SO}ne)nREbOf`o_ZZ>jYI=8pH)e1CkN%6 zn^s#*QeeO1zeec%v z(a4YCn@+WkcUnYyDK}U1?=08{g|D`Dxmo!6uuLmtQP`IMA|a95p`IP7C))~XCw}rJ zz@nw~9Gh2FS~a~@=c8bEtAu@H5v8VRBn|ewEuU5+Jj>2nkw1e;&e-k(fxIEY5Qm6%gieN%f(6kV*X;n$DJIU3R~y1wZ4At^x`u^ z{{U(SEZ4yK6*gN}lDRcJbNMqW21g#x>oI@0jvNGa-xJ54IAdX5pj)e;` zm8&D=TBbwPWozpyN{eHYovfzS^An8wr@3@Q-Fpmy%FKrdm+YJm=`+Vq&Gt7HAmb1NdyCN6bG-9>G?b#` z8;88-WpywJ}6^-68*IG&@HObcL(3%?Y=JIFf#|&P7eL| zxkH1_4?Cn^K}FwvGnZrjiF;j2D;;ImTIwD$?vj&t{eIqdQb7366 z{a&|6;<@!?`<8DxOd`dkz$D2UwF4F9TbWv)Gt(C1eR*YlSSI4{im>ais=d3c(EOJ41IariayMH<;` z^d>5znNkiNB4JMoz|Vif9SBxc6!i7000h$A1%onJoaFY}9v%5;WO#^4z6e>X>C$Bs z0>64K=YegJ)29%9$Z`2WozAdqLtQOdhN9P1*P1v(KqSTybI>)7@NX!BI}a6V zYHJMy?$9nh@$%XaM(u)UUA$=gX7t?QLSPc|55N%cQj20U;*2>-H}Vqww4TrRgGqwT z3$QzRxRsyNq4*?WhbPT^2XXB$=*0|2^FDE0J-v+sCw{IyzZ@avnb-G+P0r49cQv@iyd3UaygYM&PggaCZpvaF8xWDcys`J5`2zzJ`P#zoccVpXXThj5RnquwJ>;BKnB& z8u_^r{V8vfmTY-5 z|24={|E+_vmaw`$OUElArJEh$mq0}n7@~m_Kj&uusqmBaJI}z|Q)C}jIT4gW$7Bp4{2)6?x-? zNqY$1e*TXpO@C|3*V_&7?CenK+i!x`iqBbHt65LXsAUw%X7<$^jupU|u%+rP{|vUq zYwfgc@=AOEH_LRd=(4ZJ|LJjgCfBCnU@HiT_hmf@xjRk)eII#@2Gbn0-_R9!(+>S7 z06j5lAU+3m1pFtkPtyfT}qEPqLau&N`|roS`C&KPovAGLM<>K7bEvdY_mC zaL|l;yj*aVc_whDH{~J4sJX9DQO&Br#cPtER%mL!qrr@h8jm$mQPFoFW$f{C72YY< zs7$`g?-pw7^m5}ZyjaN$=d47-v<>2JRF?3 zI0szNw6ij}-N_w0+f2sM)*M8Zy5aRwI{&G;6dhTy?HEsssCEPKfL}!15h9nfV+0)7 zXE9O=24Ph?HSdKu4VT%bOKq^UHWiG%Os8UGd|n2cDU=J0(JJavcrb`A#=FY6dwS0I zN?=rdedXAFmbv~;)k;Ij!2Ub(>;7J)90u^N%KR=a^J@*8Sj7`th~6m`3^L zy*Z*!JUq!!X^-~1*C(br|1C)aSulphE!K#Pz}%=v{vr3QsO$NdE}TizT5)bYH0=H{ z9f>yz>Em8#L@jP^UL;B1+0Zhm4xc;KT{IbqDv%H+9qbOC!L$x^h!tY6n{_c-)u~CI z$?QilVeQAfm>;3q964$%fiFkZzUnJ!X;It=xeS0S_GR&?!H;245a=61X53q#7-}Wr zYz*~ip17n}?8oy%h;Sx+EOVY#@#I0FBf$auvd*u%H%HRC-J`&cAX2zF;PEP(rnV?` z=a`c`-kQ4t2C;81Q%2<^7lYqgEfepRmbOQI9XI&Ls zW*z@0?L*(X$;nTFfK2;8hfB2&!YRPQxq_ zKg)Uu2-hs%HFIgc`lr-}!l@ch|8}C1ssd8T{}x+Pt&NAy9)853hR6=ekQi&S>C3n5Q2wiV+C0`IWemaN}#a+j#p5G zQM1{Xa@ojj`zva4kL8-h&dKtfiqJ>#A$#l`9o2yF*3{JW4-bc2rJ$eHarU7FxVJ2i zg1O$>XffIVo;M4~#8|~MQ03dP5B|q{Uw{2#Xl-q^BIrQ{=x%I*X{ybH<9Yxo zZ=bl7{TJt-^y_6evMzQtu4QRGay53Qr*&c5;piqZN<7_=x@$}F<>ww|;jjh9l!uF* z4SYDPJ8M2m4qkIr_@t3X#XI2J+nnfZOdb2fF(KmPm9I5K|3*!xZjkj0h(CdFS1xub z7R^7%6^F|%Pz=a0>Z=pBJ^|N@$IvP4ihR0?HNXCW1bDb_qia^!B7De#@UG>mUWys^ zBM#hre5C4b@f-C-%MFs8w~|K~k9d<=W1TXcyTV!O>`?QWp4wT^It#{@rYI42D#m8%U375^kgs{b)}N^3Ecnhj-vqDfJ8aCFq+834}RWpB*ZY6Y8P z#VV_Ob2fq()wKR=1_g4rb6L7ZBmKC#xphrNU$o7PERsqUy(~l=*WDwm~F{7LC^oqwe%5lKbX?om=(1M^u_7vY3;0Z$`?#hc)gDH zL{%qXU~?s8{Gw4X(122Y_|lb+KK`}n68|{)OJXghR{Wi3o^@}%1H1#jfXeq;iQk43 zb9bJmW+{BBFivKlMm)3{pIE_otexvu4~$PFSGXoArzspD16gZcR9@z+f{iuYu+Mz-CzT*_Kzx6bYn zm3LL*4S@7J9p69AjR-VXmrUyM>(+cBBm~|l@U!#yGF)81L1ltCIeZ|mIxR90SKymW zw(@Rt{9DpyImpK6&@0*Vuy!PDMcN!=R;0w-E{yuC!?=ow7$toQR)_JC2M&DJb1YN*Y z4iz3)m-Nc5*bSL4Crc)Gr~62%8*+5xT{TZ8_xKZ^*g>Jn8X9D8`qCl*q_i9>wE-Rf zEu&>I;*PvaNkfx0VE5|uX!k|E&%?d-2_z^zG%SpE3Djk1f|8uRsDfR$ly|w3hN+9L zQHpvtoM`)voAXje3K`Bdx|T%O%&iqvxdJ8-hoG__G$eb%QfyN@(jjTDG8vH*f&n5t^AF1Iiz`|&A~*oLYW!Rd0g<|sj${Vf7Qyd z@;#M(g2H`|Tg z0-EC_g1q;uOWMfXinP0GW_Qs&R3wB$aAf;kU`Q%7Qpp;4hl?(-&Pu=S=;-)a%8{A= z!HajqJ~P&i0ID%YemEzr$1Oma03B14Id_+CC5C91D zQ4!nsyn;J5Uz_txLhmN(r!aD`6! zh_DF7*6G-*r_%o_pfy24*t1_3;jz?Xc_JTrkfO*5X6ND)=Vf4i72J#5J;wCxvy({3THzq*Xw|qNQ zu5fVSqZH5M^spYu>HX?H71@`p=m_rj$ZARzQ%bHlXhNwJ0>^`XZZtE9$}7#@MtR1U zmzQ%=wpzQUEh+aj8ij(*rZ*nS>o~0WZBwq_oA*}<)r7%OVUNB73zyjDX60u;o_ip@ zlE6a?Rz@@Un&c7c!vz;QwdM77H9bAOLC_qW9mt0#Ik)FQx<+|V{robYM5)LotSHK8 z!OgunhE}iGdA4oMCvfm-35Oq?Iy!V=n21(;pbEM^u9EWq=^TQ%{SHzerlN!yHk)B!nL}Y7|+vs@Q2qXAy>t2&TcdxWj#iV z9r=jkq0!odeKBeL{Mf&H3;#m#R{hhYl3ocU8T4>o+$xv>_qx>zClddC_xu5zv&SR=8FjZqWid>_VK>D{*aX%^(5nrb$FIy=CFfeX zdZ*-AMIJp*@#}Zj6Y@hzt@}Vut#^-&NddJz8W$|}zAL1ru48lVa*&|@_^VV85r(vC zGwP5>mtxeplfjC92cp-mU3<3KC?&%iVl%$#bXO;w@ZK!f^eHnRtN0&*#2XL@MAT#T zSuaXn4)zS@xj7xf;#76%V%P$9Im#^)jQ@B6I^H%8ck3tR^s*RBVtI_L*|vSW(y~G& zEHueE#{$d*5?!#Gyq3)$uD)pSlQAkXix?}jjg1hbRAB|VkR0!CqLB?d_b(#n@9(d( zg1si5U)P<;oej3@U}JJa;J%m_^ZuCT(`|Td;C8nYSAMV{AM)F{Hcm`{4eU3ZP#}Ra z5)bH%Q<;0h`_3Jk!>?bOzE#ONA+s6C{7m=Iuc0eHt3AKsNBP#fl0I^sh(#Oq!`a;y zs;AQ!ct)b&fc4np5af9Wv3U^98&kftAdm|}qzryehY`1ZUvoN z+3!Ck1(=}fs0YVCYyUFZ6vtq<@NnF&5Sm_RE@`Eo@>#Nox$r%TgEDcE@otGiRvQKD z7vln8Cg+jQTBT9e+!Zq8?f0n6X1{3=vS()d!_57d)owPNi0jM@y|P;;zAVsyvx1- z9}-5g;3&IR$p~_Zip8lBpoKC*duw9Nx1lwlB?AG?A zMk2X4-3+Pi=eA4Z5Mtw(IIbwaW^t)kqKHSvk9d8H-6}Cl%6RLL5}&X!C%6SS+o^vh z(7b=TK(4)7W+;_2Tn^ zjolHIQSVexlCn|A(ECebu3kF1%rw6KC{O((ZC-u7yiA|tNP!9H{DfFyH*mK?A)GI= ze`+dbdfI%_e}Ae9hmiZ}wK<(VrJEvoeSLkM1i|jelP>$rVjRS?iNi@3Td;>pt@Pk; zu8`Ns6I`y_HQyWOZpI>vk8@zcD)VW`a#T(Te4fvw;)p za@dwcHuI!@A5(8iXIp56#Zabpme!Vi6o&-KC0n!L;XNtm@z9aK!i4}Go%22%`24Lw zYT6$vn^31Q7zUS*50VvfGJjKAP(|GuIJhGTPv`CtaIj3&X7C>&G^HCAU-_>>zGD0d zo1g}z(`=2S`AJ~ry5la>rT!tLPw4)oK|9Hx&NB+YtP?ADkWJN@@<@DIi8Ev1iYQGG z@)DDRHMw@O_*LMrtc()lvT*Oo*p&hU&p&gAXTKYvdw9m;w-fe7b8@t9HstUGvEBPyO>Q7lO?&sET=_=Kt#~|kEMtTn z4#5@;RPpgvm6uF;#BKz~;y`0;EyZqAPgoeNtMyOn(j=L58le=|t!26iON~zzOd*hd zEcP;*$)rj}S4!d9Hh5b>X}1M8t1${a3eL57T%9d5Qe_prBZKA6d8#36Xv5TVG&Ek} zUa&<#;>swEh3~~77>;_Dh!HXBM_>_)X@qx*CRv`^l{#}Qftx7cA>JLE;4F!XV^i4_ z?Ki3*O3lH|GjW3@*q1L~UTjU@{7wmh4(3{(ogBXS`KtNzQwEUo%`bpf21NBjaSb@Z zaags6QvLbm%;DqXb365328I{b<2Bp{19$MFC(?&Z;fFV&eQ*IX0l9{cF?!dCiZ?9Q z7~IqIj2rag<|A>7Q!qnMJMpkEu8D}ZXz&98VL&vR~xIJ;$+H39!TM7$A`rj>_x=pB0cTHO)s`EZV z%du~r4BjCVv@s`nVdcg(Cxu&&)=8xsC1q|lYfOUiqB6UYz(6-~-3mRv4hh7awKn>8vmn zJE0wZNZuSoWI_s)Kv(cEQYB&$+jqr=%=G9@KpfHry6n?D-FASXiNOihbT_W<05Vtq zR~7G#>ZPCl$DV&@8Wl}E_$QLyihv6jzI=He>z9L+nza{vi|y9d4S2&pk#boH>dtE0 z+cUJnE=*xvV|`-CrI)&uIM*$kxrL8=A5j>_ie{e?#s_G(xj$wkE zeby$;VElyVGiG<_$mPL#Ph(dNt?HKW@}*NSZk6u4XEHi_1eXeT`$#@#+a0-zOFARn z-qYu6A({Kzn;D#+91XO>3TTr(g&l0n z53)Hd{L}6qKa^KZa)bExkN+|&%ox75EVDixv6qUBDyX^CQ8b&ld-NLXS4TK`k}#_E z)l8TdFew=tB?T>3b=q6tDwfJ&4;(1xF|hh_Kp%ba;4b;)A^V3O=s0&2kX78r!n?L- zC#u%Jl5CTWkF+d+vTQ^z?(fal@-89U7Sa z>l8rJdyzP6HfB*#(qAqY=@jm25i3L+;k* z9Hpo-9{q>iK-om2rK}nS#5NWc7 zg@s+zlzjjncG;}of4#dpyu7iYOXr88(YZC+9lJ^WDL%MP8{4f?^l0|R^9zaW5`YD{ zdKm~Ax5e2>H%vPL-y>$*mnH@sFSDib+?b4T4m_TC@ym&gnnPjIeNjrp_V?qDH-ZWr zpxJJ%=^OWP(UfnTe(KBNW}q!WXHVrG0BWg&Ln~1EKY_uiH$#!5?9J~MU^~%2HkLfJ z*3?8Ij&n!=NAqH@t=5zNDlID&B|( zibv*t%wd8-4m)c`62>HPB7!=QLu>vdXstwf6@GUcE06k65F>%*!*%2PYrb+5e_O&?BTQi?seCN9itaqULxI}LY}Ead1jw=$9@4634kG)NOJFL zMsgP-%C}VqZM*{pyCYb+0b1FKcV%Q{)poZQVk-rgT2ta9Jo!3Lphvg#0#k(hT63O~ zTU+$E#9IZs|Fv^{qL7tnnS^NF)hU`FR@uNmHOveQygwu^;pU@6I)G8ir{G1&BO%*N zK*X-~+U$5wO7;^@eDij?jtQVe8eU$~--iVNd90N7f&(2%6tg_B7#|39WnF~p4kk)2 z2W%`ajV>!DvaD-=jLO9x*`^fC!ib)#uAxgvk){P)tDAdNfQzs)IOsRM95_^bQ?ag?FMq!5Ou5zu?`H>CHcs8@Wu7LEtf=WTH#i!#b zh8=H)tys}kNBpDQ)jCH{Rz5rnC_f0sszC?F^;0PCXS22Ttb2os&4oJ8G>@(*%BEXr zQK%eimzr1V=^(!-LKyR8epR1jglmJ7#6NdB-_|Mq%;$NMV#&%|P7OjCs&ppy88&5m zIGs@%--QxDlqwfzaB(CXQ?;-e|NZ>Up#i!~Nm8W__yZem;(f1kmz;OeNY!{bU4ofW>>wmo2t&vA{RS^;UC6Uzf&FpNV)mBizYwKpw5*O-$;72%5wO~sK{>6 zH<{$#kNIT(Ky!GbCc!y;MtqQbj`$?f1)lH+Na4x z!*4o-I`DKsd6_FfALl5n1*SyD-{8=bFb>dE-vYF%l(gVk_#n0=kVUVfYi-Abouw0} z{q#?{>~PUw8RUFq+;wEX-1XzWZrc_s4O3+T2BO$`Lq)4hecU@Sx2{Lh4n|-LKMB8c zCNGp$?w7l3lgtp%n8YhY1C&=@|NIcPO;HQZhbET$*{y3cSCj^rYhtbEesDP!tNG2K zx3*kL*FaQb4U%k3{cN%XCZ?j3w1-aHYX}_RF#-gFPuGtCrFU*_PAux7H{*%)3SAs@ z=*WKjAWq6DR~|k1_gLW~vn5g%n1mi>P7wh87+??@mT|NpdVD=r%L}i0zq9;?V*)Xs zLfq4L_+=X$?Ck7%#U4Ut@EH$H3Rn0|Yzn6Gy1-*RD^rH$f+0n5?0p%yqqI=UK(PNK zU-N0S*E_6}ZwkP)AI|I#jE_gg>nSif`{7th0R70!WB7SKEYvbQh>Yg-QeV3FVzTW| z&vnSfUTWC>A=J2hEtDQQ(Cy#wDylnr^Iqn0c92dI1CkfQ)Ok$K?+h|CdTe`Rn7f!a zKvA?(#~wP{Nc29mt?AG+n8kF8LDphTtbQgmLZNYUT{G5@@~y#zchMPZ$0n}&gZ>rn zIb9|?^w}{o;_FaHf%UV9Wp6+lsuZ=T>h2K`bkad59DW?-$z(8?8Cs3Ue#5V*s#r01 zJ*wu6%G$jo)7L4LDm4vb2NO=Gr zDGki`?9qacq{)WDSmUnQrfkhx!wJ01ywX?fTJp_=xe-=iKsCR>n@Y!t&_dH+2zVai z*-p6wSY*5{DoIg?D-LGEl!1EDn3qL|9CSO&kLjqGhA-egT1ZOC`}erOf?q z?0K1;(yOh-63gqThEu)cETf*Y+rHhw%w(MMx(|KdN0D(#PdsHNHTR2c7c*1Fn^z9v z>J%yx(d7r_4flHP3b7}v>+slo4arJu7gRG+gjZy5SEvF4PX(lXYfF@5YWwnXshUHS z>)U}A&G<0L3$W8s%*@)c0-)ISkBo#SCDA`Ht)v7Fs)dMAj0OA+^z!oZR@2BlyhB~3 z3MRL3W8~veAw6$Q)THjWVf%yI9?-{O zmImx3KTVmtbNsTww#=29COMCL9SLcn6CA@QEUg{3t{Nxg0qeX$Jw-NW--!vALp<_F z)USDvx}F}*#ZU^A<~%UEb{y@lZMRT}+}l*i`Kif}(*;rx;)dnXhz+pahT1f5 z;&+91J0#_U6f;Id;E?wv=#m~;mSTTWeG63#@#7nc?j4)BT!y?A)`W)b4n2Mb>nQ`q z6gN&CG~V)YSeX$b1(ljhlg*|{zN{-~5@_Oo(!R{>uDHu3oRxio-_NTc)nORs8R5OL z`}9oVfq60Qn2ty0EWtK2d+e_G=+xYOvi*9BxCe#@^-gJ zrYvNn?7!8Va5@3#Wx3x?S5jgryKnD7KHuB1yU)e+>H_Le^1h!KYV2>w(`Y=kK0Jk9 z+wndeLB*})VNU9=x=)hIFrxejnv;IS-+vnXeLwM5uZn5C%cEj9RMyjyGX`5%Yvx4s zSvUi;U~jTSeENelVA6j(UVhzc8qNzyYeDI9UOY>wLK>athBbh z!GyP_8+i9b<4zllNI~A^vH;KBQ$esqj>6Iwn8a_}G2CHOd6xf76tDw4Fsr)h?A^)& zqzUDP9p{3hc9)nJTa6aI{8M5@M$IN09L5m<68n3Nj4YK>T!$aoeQ#5)T%{1m2E5R3 zxInA!)69y>-!b-uLR-GygtjDxDvs|Ps%JAj_G`y@Ke<|LyRkD%Eh|9L;Ap}Q5Emt6cS^5wBd|vQfg)1^tW5g-_K`ZFTi8Tm31MMhyE0@9=2eS^z3F*lIf*Pdo z`)B-|4I5K)oU2#nwR}J&_B`~3FlF--#YG70fS%;9t)PK6q>pOPed%;ENhlDXKTO!y zRi(GXji^$onCJTCHc?;$z$!0q*_4ypGWs-eY>h2X!xY_$`1x;ZGf0 z;$qhaWDwv6Vu%G3$blVd*!%bI+tlZx!mX#!u*rq~xqX;#2>p;gOMKK#n}(d}PdPO9 zHJamp)<7Bz_1h7z#`>%?a*uF_gF7-P>SRTBsbUoY8ii2U5^FpE+Pgd<9p@42vLy3q zC-}_Aqb=`Jun-1PZD-l}l)wB;(8F5iS3G>qhJP^GC>9z$s>l1um_77OUISe{K4;k< ztOIznY9w-Ej}UKa>y7%yn^ZTBJw9-7{EjWo5_@Laq~WO42X(1`k4lW@4J@C67E7WB z7sUXhYn}E973~|d{=Z(VlOUgsGjCc&hz5t=m^&*kj5Y1#hXvPz#Gm`U5`dvn%5gk_ zmF6qIC=`a>%%D{1z3h^)Hoteh=y4w@NFvh3hH?HLiC3*~z#N>B(LeX{>|ef?J2BTF zmnN5v4{U_P?1sYm?nE`6oraGVyeD>YgFqev0ndKST_~}D?S_%tM8Gsp?UpQ#kwu>7 zw1pf?r>fJ{W4PyS=I1NHrm3z=0~zZA_{c=1V=J52)V0&*EXf87i|OX4I#_w%>M zt;-R_;67(wwY;n>()9H7t}A|~fr_~gnZ29$w5 zr$VNcuK@G~d~^(e`>uZ>O-s-g!8!?jXeo?z@Odww=$0x-3-KMLd@z=KAW>IuhXy~k z`H&`iqJ8whI^&7yddpzPpwL9|+rg7#0L=i@jwgJQJ7+~}vWAamNWsN!Rl)AB@i~47 z`ZZWin1wIsauu4D@kp10ZQ7ZxD9;}Zb>4`zzz8Vv<0RFLfHldRk%!eE5G+$B>mLJ0 zv5EA>X3EJ@@Vi8$RC6Yv2UtcVDGE=l#A17A#5!<{B0?ujhcY^fpF1~AXgLYBMjR%v z7_=&7VuWr>9b|SrhQsnTD@(&BFNMC{>!qHzailKgjvpJ+9?IO$h+F6Xaq4m;7LB3Q>M1m_>e-gr-{93HI_YM|~d2>oto3{-gqpMIId?ev=x0kBl0TeZ zpmn4m7`ZjQgi<-|=i2c#Cp73kl65#Zcu3onDcbhcjM`K^{Z7KQhC!88s+5glHn#X& z<4;aXatHF5*8YC|`JpezaC0s!&ri@eHP)@pg?4%NeF|{;`uf36qSws{g4#syl8y2BWg&^RbUU zStHpZxoEqC%pQ~CCRI3N?{C;GG@V=CE&!$?l+jy^)R%&JzAMHsEJmpA`6>+Po#(8- zsoR^~RKWSi_K-ee=_waO_Jm2wJ&Q-5>>F#P%A!_8fo8zUoBf)I5^cNirm>MpOEDj~ zD8z!_i2!*vG$8AiGB1Vtg4@Rv;eZiUJ7D%wxtS-^c%KYe(c1jsQU*GXTjSI5!z{z7 zsDnh@Y&2g>vO)0kNNoGyH4-6`Gd^+`2rF*H;Qf)QW%zxAU=}wSIubM5&;!-1_Zf?> z2O*nQHaBMp5UN0Fn;WvSvOl+)F7=)VDJsp#%|uK`3AZ#m2eNGX{}ns=l5=%eo!f)# z8vpaW4zV|(Tqw7fJC+44sE5suBd-N&gg%hY7ahFk4XoDE?j}C5(f$MAiTBQc#&#CR zDY?UFQTtbwFc^Sy@@IHppj_p( zw>KlOb_LQJ=J%0{pNJtU$-!7{t#3;M$zD-$2hhAe%ee8-3qgYK2pWAUEToF()$8ET zOB2r(3bqUf=8XBTVeBm(F)ZHvJS|WHy%cTT(ZLmDdSf1w~@w5VkJ^OYZ7IRj>j0wmxR*IsTBInA&VF-}!4&IDa zdZni{9qZ-zH8epClDZ)4PN!DINh!8a<1N){pb_=5d>`!T?k?HB{dsMEN3;#dnBi{3 za5)TSNjEnx+UA397Wo6hGN~OXG0uPIYiaah_hBP54&f4xyz2)>s*ukHS%&Y2ay85! zFT+^P*wqfubC!N}`bvrTF%Jzy&-Z5nU5_$EDPiAnvk9WAfD+u-ID7fR_6#`rNVaes z=ZvXRj!)bl>manUwQ(MI(E$o`sYb<)B<7=2G29i*)HF1CDAgujx5vNI=|e%%Zj~w3!mN)vtt+%j36IXZCZMgR*Q{(T-c>AVB|tM<lCm~P1H4wRO4Q4aYikCudEoJ-Z4z}XGOgK_>Wz9jQ89lz{ zJvC&=#FPdhFGD6;-0-(}d!P3SYp%VldPT0a@eM?&Hbn=ko*#wL2nOEX{Ia6~jREug z*#bCGpWT0ZPf)YaNNf7#z}Q%XNZ?^lvHPcJT+?*D@AhzUz#Wd`KWIRb&0N@zVUeB> zQ#|291)jkln3P_*u(JcJv_$eyKzE zRT}FZz=qbO%m8Q{z&ZgV`Rmo8{N?54$L43rJ@_qvwaxM>9$pXFE6cD1_JYf6YbuPP ze-_{eFN_&j(aL}9NV4XRUmIRH_Nb`tZ*Gzx8i=6@E;UF>R-bcfJQ8_*CQ&)C{L@Fo zHqoC0Fs%XJ;0u*axPHeFm`=zfZ2MS=uMarMfq(T8F0g21zwjdiLdMpG+z+g)tSFr~ zdcV#bY?GAA6LyF-cwI8crN{eNw;kam$)J0`_2bpkp7B*Zx;w$DCsA*g#8Zyt5yJMj zj8IA(p*-J4^rpV)-SWEJ8Sn_NLwj$ivh(JGM!5lKa^S0D9@0N)NpG!q$Y~i=TYjB7 zIjo=*FYcV#U6O#O74xhBVJVfEkiE8$DFViI7w-+TgMYM)f2y}=niTfd0z3m_m9F3V z)FZ01tt;`iY}{+yAG&Yf@#`dJT-1LF+9z8X+~aI=E{>42X8G--9`9^|(aw&IMs}3r zG^|0;^|@j4M2cdoLh6_ZWjU3DNFOXRuLG7T!Z3d;4>3fA?Ras<@^yvM)$B`&Vdkz5 z1pJ7?8f04eR@vFv87sx^@-l6+#zh=Zs?ULh@NK!-cuVaC#@vOPqzuRChGRTmIIgmJ zR#JznJgCEogyZ_bT#n))@V z`jXZHHzDN78*G0L~JCR z<1|ho+tpZDSdseS3(AwL!qPi7$W!j$2wSePtmk21ZbZ6ftK`d-_Q(d${)DYpyFqO7 z*;JuTy7ZX6q(ErF-Wu}kHAfH(!6ByTs1~?FZ7avZUrwFFq6QPTM;$=lEz4d~=WqNWNozehkL1k?c{=Mz)a|H#o!&vXD8KntN)XP|087TJa zXzRbOP`F51@9*!VzD6`_g|WCL146{&#JCV?j<^g}{r{pMr%n8gF?5ZfFp$n+DnPDOTan3frPXn!^*;DYH);<%{HmHf zF6K)(z3$8K=<;GkiL7I3GFWzRH)OLVT?+O=KLqmr1@KUuUdVdqNMPc+CMf zc0c|9u^C)mjJufredCO<2GIYnH}`r;nW~?os(l$ccGt8)t3_3kB2YD5>+M2{gXo@n z@??vSaiB02e?RjH{j}cwQm91mZotW-ln_X7T*z*tQ-4D$zEiF!QM@ znbY^0=VX0C#I5{JLmP*V%ZP*pcoC_WmLboB6g75@97)eUh|GcX_bf31A6Zh)IBU?! zaT@nGJ1&SqW#HnjuZJ3Hw`tAnCM}-ndlZwYkA`wZWyaO#3#W|fq}ywC!>m>J=O-z- zwzKomWpF^!wQCqZ{wq=x#1dQeWeDRY<3K(cQSdq$Z*s5@p2U{Hp^rYEWEo)4G)YXm zHspC*FJnXNaK3)>G%g>8Zekw)rX>WzMz2aM6HY3PUzaX(vRf|I4}YA~I5x7EvmRr` zNwQv8MiOI|W;%@l(S1f2t7yK2xx%3Pf!#Gmq&ixA-7TF8;q6Sb_SrS2noAz5YcDrE z3m8b1cVAmVkzT=&G-Wb*2)!w_wh!a}@CLbG^n3t&oU1X-+ORTKz)K#>%FTimaqoZt z+3MB<8ILDdf>EWp`0$(KuHjTj;NHSF4_ zc(_z)k_m!_YSmhy$A~BW6Nb za*w624y?#_?I*|rcXvGDwPq^nP-Fyh<(3j3ecxT}dUTw0sR5*6kT4CnM^jn8{2aEr zYT4%+)6h#wuRjt>Q^NWGW^P>zggvV@^airXW0u+-SlyTg@lu zaaD#{ePRV(t1YZ{O{I#4k*58V&!=O`BY?57Eq7!C_#fzE z!!D}%b44?}_?C??o@Q$Gc0Km z&s1-0e3Exp`jH9WZDw`av{&FChX0V$4I0rUY+42?g-1XCngh)O?Kv)0blttIdY{>t zH=X?;rqCtldfLQ{qHd!;H#Lvb%GzP82X>9ns#yWg?B8hwKb9MSXW6+1uzu_CTGZd=m zRX6L=aR@5jbpK_)7ZXzlpP!m#YbgM4|(~nJ5!saUI zHg|&|Gn;O+>n-VI2z2L(Z^_CE)*4n1 ztA}Ws=NDSW-;9g-pI;kG)ZxqC-r1k?Q8iy0fq2KXyFZ{(cyIZQvx-i+g_^U#(y#fb zljA=CPJ@iBX^0b_>PC56o)$LkV$#*(#@1QR2j>8 zYk%OFj}P4mrqLGdaoUX15s!U+T>^}#bN@-hE%!~@3R>yM{v5xU`V}_oN-D`#39*~m zZEE~R-TBs`x72P7*MvF;3oG3nEr@xxo7K~PU`}WO#U#+ z1ILQ!v`85q^E3s%uXXA7``$?VgzbE|D>8QmD?iV?TGL|KFuguzNLOB}Wh+8{@4MgU zw;K;5-tjq3hHV;|ZH^^n1MYOlRbX9^jg#|9;ohI@t$kw0H5K5cTjC&pHLn|vJ)QP9 zoO7Pbx0vYX7va1Jj5k~3x|)mS$J=lj*DVO!1|tL=bHEnI3g=4ey;O;3%-Ru0R~;aI zW|aK@EnxK2!!n0^avO@J6V}Mv48}<$@n2M>x0K7r%vT zv}`h(T=x*5HHw3YEF-pcKLnIbuh_<5!DA$#O6X4qNL56)O3Ho2CKS)hhw(=6o{JCV z>OJLm2a9_xprJ~qPme-H(|CCL%Xbj>G|W63ob@aD7>VdA;&U8wqp9Q`^|&fR)e0WGfLoO z0~SEeLgdx%r+cO0EYD;8WhJ7QGnS&)=j3mD8IH&2g1*G40B%$*UU6*H&Zs~-opC8RtX+Te=6C6tW^GHi-r{3kqo@EgljbIJ=`HGbx z#jT+n#z?-{5NWMF?LUtl#oD0+T(L!uB;uyNVCjrJ(oXvu@Snd;#<*R_vGix?`tg5D zu$+kf#Fo?&hoRc0>H*HaW+%Q8L)H^##(+$H%}UN2<0+p8sS$?B2!_5W!6JAa;U z#3jN^Rc=bQJ?w2qMnv`)KgT+Z#guxrB}q=zb=eYLmtNsM9sd%jA%mBG!|qdjvJokq z*m2_4huR%=b>D&h-RnQOy{Kur-7Z~i=6CCef0V}8yII|gy9ZAEDcZ_ZG_K)y2ksHRW$1}Xc$M&s^ZE;x5G;E^yY%H$zhm#>}R z=w7A)0ID6XCu^^jWI4$Li!WeFfN~gYSoz!%*qYG|vX_rNJUlD_l7as9tt0fMbNd6} zD+F_CVwv+HZL9O64MZi+&CB}tXHJVQy+lp7HU1ISnLf!^G3@X@hQj~Nk7VAV#t$A z<`he{*L)Q?xV|Zq6e!hNHo8xv5-gFY9Z=D-^#1JkdvIOkUTbNrG#DDv2&}3<;H$P* z!s@ioytgAMUrwo2%L})9OL%qxZ<3`^>_G-C!|HgmleKPya=P`%_P_C?Wz5ZE_*7FkkB__&hB#iHSag7LGWIsPT;qqFF>L;Ff^2~+f2|e1%~>sU%w`QnwSCO^^@J1Lf}5X zyDgPC4L*u)LL zV&t(?870h(l)KjF4##5~tn_!+zhYl%5*|yXFdhx55h{P-h8OI(5XX{ho|XsCnOrQ7 zA+GTJkyq$Y^yTRNZ?&Sb6ybAX`|)bU_fW4SDg$GSqgMLQiN}H2I6T>x*Zx1Jr&*|? zB~Erl96P6Crmp(>K3I#d?S_O5r+3?jBTYVk$D}KEsf-8 z!+)qlTPGfvCd1`#bUV>Z0=KNFO=YPgzeyc-B8n?1XZ=&-$%ZR_SLT`23V}B5RP;q2 zR_gqf1CO2CK05oz^ZZ+xT!-N}?8oX;o7!@NDAgHH&feC!Mlf~@(J~DuVmAFW!oM)U zZyHXVuQru{a~M-yh$BbYu z3Nuk!h4JjkO|Nzg6bp5+dn~sIsC#a{+vQ*XwX4;ZysyvXgS}i{*?XEu1|aso6EJBf znn0^qSCjGd<#Erppf%$Z9c=y&Z|V0whE|nWHdM12PGZbMurXpF-exndwleX%?Pgn$ zS1+h!UU12&_&{)MtuEm*eMnb`94}RG_W7~Uw-VeN$A$dsb{=1a*1~Xue7EPzt~%83*MW8p)xHkqQ=6L<7Mbda{^?vh(k%uTB+`ZW9Y`N?zisC zdn|}PY%oTDwQ8I;Ges;-`uClsV9^Gicc`9iwd@bh0H&fyB&7Xo;JFu@zZ!QWuLsm`-G29e{!Vfm ziyZoq@$gdK{oy6YW&+_)VdnnNragJXC?tnU*{NrTSoyk7uv&e2%4OLT{*WP==RG2b z2PfLqEHa&NUZ{;uhMKG^eIETFs!R=K_zCZvdtv>eH0$c(mA`Cy9Ru;vy;6IA6?flF zJG`mKSI75Ku*@mKDWDl+3RvOa%a5D0oO%`;MX#=o^TKBY6TaIVwtjV31)&Bc0Em7} z#ox!&abfsy(jLARMt`^u;#|~J@EB*C$iB&*Ka^?n;J&$xHt+N13Eg$-Wa#t;K{gk; zXZaS!vvV`yGp((4t_WhAW1qKkUkNUil}Sm%4W9>tU<~5Ct94G)%~>bY*poA8;C0r_ z&U7WJ()=3#Y&k#{q=UI0{}3w#GqY_EI=MQNt_c;Uy==tf!a{TneB)8mX6}2J?cy}n ztRGg(9e(IOPMM(8M@Cj7ANkOODl)-oX1@2YudivCm=I$DH|{YpF)QE`;6UyWyQV*x z4u^LyQUjux`c)TnP3aQ=Qx>`!VQX&$zljOXvt(~6v7lbv0BvP0q zDpP`E^@pwGeiU1f7BxSIZ;l@JN-9B`n60)L@?9xCd>DSt;BE8gh1)MQO~C4?1GQ%o z8+kpz{g*OUh}(6hN%5Ef$Kd3Q?Y>3RH)?BZ>u0gCmVc^Ey>Gi9H_luieq{bp^i(T& zFl)}A-`GfX(#^c|doEHtHfF`AhB}Ltj1n%RcL>`MA#VrVQhQ+R&;I#|f{EUdxUJ1k7c)HJq5u8TG= zL#t4Vvgd{1y}U6aUj3AzuJ5lb?S#2%%iwx0&xRU!3EI1voy0UvLm;U%z=HZ)(cWvnn`0KhHrMfrpEGcsH@RBj$kUIkB*?t4NpB z!}*w-_+jnQfeB0MHtI;qNPLTs8KPz1pcX7KL1?tI_^S#Uk|ivFqqRTC+@F4?UHn@0 zs)_cMZJy1o!6<%pHpb;hcQd#7zqaAQE>styi^#*|ehTtoNRY=-nQ##L_-9F$t46Vf zUMo3M1!}Nv#Gy@=C$kJD02PmYcB2}GAIBNT4wD5<80o{1B~Yi0a#wy4jX{PygsG9~7|fx+tYufKl(k~J5| zHj6~)bvBblBE!#~Dlzf&Qs6z1O>!^k34i&XN2W|TW$5b=krF(X3BRllc{AU&t-fZg zgj8ASN*LQrWv4RSY=CTBeOR|uKb%#Dq-`9Ff1~V6!qstJ@cwV6fF4(#Yq-(x;^wiF zD8{UYG8;r_q-U8LKiz2oO)}Ld>W@nl2#%f`zcEJiK@-+=zy*bLi7}x|rVInb0(fd3 zkw2x{NW5yvXKB7+e|8?cwflOc$37IZ!zOc!$J80;Fi{@k5ifz4JzWP9wUP;Eq@S{n zai9wmA?ieV*JkH9su<7tcP`(D3WBTLZnQ5Ohkz74l^2+IP3V2r8Z@Pa#Y(p5yZgE6 za=#UoSSJLR&gffq?QmXr_J(f%$XBRrclOh6dd3(sT^_^u^NUwL?K9EduJs(K^%PS= zD=E=5g+g1F&-OHegtIYuPNIb0zf`gEf4$zEB)wJRNWPpYthNrfwD{ujN=H+ZXh)in zH?H4hDbm$b3)_nK2f z!S($w#GkmeY`hoW_Dd{m+_jb~{M3hwe=;$WDjje@Z5oVixuxjxOhVu}Ekj{WM`dkV^$^+C z6shjTbuCpDp1EBMImw>}ZZQk~=Gy^Fc-2Nnf0@K265_Ro|NEDN_e~Z4Y{kz=Vs-JN z22+CC3H{DtVUIDDB6gSK>UYJdfpq^~t{PGT8d$?HsT+8G6_MtAc}pts_0k8yX}BQBULV z-`e8RE2j*!QXX_gFodfx`B8%BFK4bd>z$L~t!VWAzSCW{SEfVtQ%6TW$p7p{zz+n- zKKH)zW2#l^PBcyhsF%SEUaRHL@wv+Yt=$U9X?bdG%?2_TCT3>BTMs(uL7d*;<}rBW z+zXYTt+m9u>!I2X{0@5U!Q^hisr5(XMIvS`eo+@I&SRQD+s6OT0$|eC2^H865_GFh z!Aw5>=pk51l7pDC2mQ5fhQ{$o7$#+gVFv1Ogs?2U!>%&n$D4vhe+^YpNo?Sib_Yoh zrv>4)i}fzr<=4TENFq~2YDr|N+CYPFH-VgNAg*RF|3X+lP3`E#P;6|H#LJJN$_oPz zLNO~~L}DLPR*v7&XQ}Ufn-`tOFxfq3A!1%$j_>GxT2)@DuvuX!?z<$dDCXD`F6Pu{ zw7XNwp4Csg4U>oLKcW@hzW$QoBh82%@)QPx<%>cG{(XMwI+86RUQ&v8ix8}RH9+WH zs;L0N(n_4?f+r}npc;xzOyI`QU7_lOLwU&^&DW@=BQI-{tD@rDclC!6WWU1FDb# zgN+l+p@-jf?iqG7!!#9`Gd@IK2S;t6_5M32CB`L-RJ7QVeDj#LDCB9(j^sNBx*N}V z*ozFp|Bifk!7xeX@^Zo=)4QUb;pF5*e5b6?1q9Vuq1O7xVMItI5;)Zc9*;?f0FOQ3 zKP}Jpf8YJh;9!LQpO_S`a$q^fE~Q8n=91kw7vXstD5WuI&#J#>IEQPJzP?xa>2l+- zn@MWQOW!yt&-%Hl!idS14e>Qc^-??|z2e9Ewu>9V9e>$YwLEodhJ}92h#Qe_%arrF zEvgrX`4?6ZMoLXfCnRZ%Rn$Y#aJLXkb`$8cxuhsQ#JBHB3D$|$&$)fc$Kd`3$M^I9 z{(U4oIV4e_{Yk9)U**>iuKCH+pTN8j|pw~jj^PVypn>KGnQ$GumXD;h|bHT ziL)(9neCGvMIq}UOc$SmK+c%!O^cnDeH+{48`z51LTQvoj`Gd);^i z*Qei_YT6k(jlbdpUXZ5IanULhojMl2KiSZhQsuZXTe3S_yekd>A7WFLcH7lXwQddg zRi6qR@`jH9t0nH~=k!F%TF3P{f06$B@xtA}#?B%xl!fLL)OQj_#8^X(GZIXTUjUde zzy$Kji26yg{{DUV>lf8ycQr>~SO9q7zHvLnLg~sdC}am>M%>=*L;+< zu(aOL3__2E0UoL?59Yb2`vMQo68F1ig0tWAYd>R1ks?Nm zYR?nL!0rxcDRxq>!CC8Py9Ym}4tUJEmJ574v1LT3{oMYB7eeJdRXHmnPobSN|zs)i*;2$nSrD{YHL#v$rHiN|%DT@N*-T z05I9GkUxFzcU?e-3t0hGpQ1Q4w=d=lFxpJFXoNQ~=|BsbfEoe%2KReOgwX~9X?pjA z)+G4unvh(-Q{z%i;WvH&0uV2TE1^v-Q$V}L`b?zngZ z-*YhUJ?p&nYrDNZ2(R9~hmF~^^(i_*t9143GEsx$4isWee0DdLdQoSE1H$73B_*Te zm|b*;8S)pmcw>1za`H7^li||&j)qtntiIS@$|z1EwWnm8IL&{dw;R$7^|z*}CBkCJ zAdF*VP^wN5nQ+MT9v5^uh+|0KMy)UnAQJ!iqDTX?tC3pqc;=%Uhb<+RgMuq~E|Jq`Ve!KJv!3fD&Eq< zzaX&uV<>+Ob$dx<_+#4HOk8c|z~_+7qN&%T8!qaaL~ne3YhkH9Z6LIaL{jqbt(REL zTPi*XD|?&nPkO)1l5LxuJ2TSb%F2n&6IRgxnU-sRUh}W`V7|iUH^hDje#l$V0-xSY z^UON8VO;l76ySt(Wr}nS-UI%8IWBCC49xF21bZb}fgLil?wgp7j+dOWshFb9xPUIL zb+kYbuRFIAk?@&BpbXWM&xTN@MR#8@)#|a7Vku()4*E>nIA*rq@p5X z){0Xu9_CD1TV}9K3<@29H&!olvd$J$-IUC$&6}|C)mgB%iH%=r4*hK8*WKDO&^>OG%O%g|^gj9WT(7(-CDQ=3;%V4m>6-jDN(Ds&o zhz8DYI4YQmrLh4k@*?HiaBEgo#z_rII@CPoBEtL zUYDG^YHZW!i2S92JHo*csEA3!H~@UQY1~_|z{~VIi$Ob#q{!4&$qaK~d6^S)h zpI@>+G5BPtDtlmK8}n#5J3N`}Wj{e&R}f3ySX!#;+EH-PQ!R(}f4UR-cycu*mQ^qk zcSu`}jvO6?5UW+kz+0e}_eyUj5vO*xQD~;V_W8^No<)4gDoZ?`HXZJOCWZN+O~N#+ z3gw$v=U8=mi7M}qsZuYEhO_11`X5oOe19Bd9p68q!VpT3=YyN&$#4mQ+AfGU>U2>x zRvTUfuH%Wej;->w#IYY}9)#}~E7kLcMdC~o;XxeAfjj^~RJ@49IaQKAU zuKtt9U?RaCad`u9PF1_Tt*x%hr861tZ*PPAQ2kv|4{FCG@Or7uBK~$k1`vq5+rFwA z*<(UnYTNL_HuKqnsFnaFX&rCXW6cUbCTP%AIDVI6ou^+w zqa;pfzm*UWcrC50Fahg&C$s>mG#NF#ut~e{@PK?TF{Gz)PZh(2+~6qTP5j!7;cn3J zjC=v4S1{Yl{mEQ;wMAy!#Pea{q|#>$J)aNUn2Nn7-78{TzqNNxnsNIuZ#riW6hVP4 z=AgtU`N)AiGgY_%E<5yUQTL&(^?g09KYOloFHiNS&Hdw3v{kF6X*dH@Qr9!}V~fdu zv~FWMH5u+XA7%E1z|U6son3N5>y?LmG}?0TDjA|sjQis5SVLpP;jWB{86;1j!lhd7 zykX0J+vOEvJZ7ObH9Q%M-a5-h0O&Oe`%CLz>S2 zWKI13{bbv0I*gPM_kSK+kbm;x%j*f2z2jx!MW902-gW{IMSLSg|E|-3aN&>Lk!Ky( zd(Lc(@obd%s~`rDDDKJW3p5a{fBsxaRAKBE>p&4@yN^m7dQ0Eg%UBcd(b3Tnw=hk< z{sh`+bFP(;P)w`FSiTIxo8P_ns4KjKhyEpHs7J(vSGbz|gzdNKrn17z+k z6%)4-72%fT1&rvLeSW^u{)J)7W)jM^NQB5Z9*+bj!t#K)x1QI=UE&`|m7Ce(I)#9m z-X!%0EAnK`RkK&S-RuL#TeVVfQM0{T@a_{ljIxw#aJ*VXb{if0RE@q$RIH1c4=k}H zh-NI*%%EiOU$Iju2y8g=`8h8-%5{I8BhZKlOB)w+);6;V$h33bP=~N^O9#4Fb`9P< zA;WunH%NjoNH!fS*SmQUD2Q&Q4*cHaE_^$RR%IZqdHpaQ*k7;uaI z+@Htkw9MbAYS1aG34eDqRCaqYlL)Azq8k)bqInA?4rB><0OsTU4XUPo&*NVbm_sTm zbm+JQof&nE@ZQd0*1BgwAQ^;TL>vMQE2FgXJ?L`5951^tJ`8NNc_&~JaS?DS2EUAx z8s9uF5K8Py)-PFEJwLYm_~$sJ_1)?}0M{|bBc%k|KU@OvXranDEPz2}_pfZ9v$ zXxAgGJBZR(=6R%gs`Ur@AKSDe^&GZ{XW7T6X!z9aqM&wDVFM=2G2o*EGpS3;Z~!f| z&pt~mEp~e!sK@_|?N)yoH*owYUiX7*iC>dGafcrzNoJO;%8c~XYv4j^OR9-SaPfp3 zcMMATgsT%+qSHLraow9gqT!gAL@G%o#g9!!5kWD;;ZiPh%5+Y|D(n|~n2HT@&5Kv< z@TJ5w^PyL+?T8TbH1F#Q6Jo@is0M_IpYo7J9MzAKRBd2Hs+tNv>krfI*BGY^ z=qxr&Dr|5sisT4K>Jxyfrd7&`BH?y8ypB1rULP;3sE`Mu9ngz}oR_4tU3%_|-=L8> zry%sU4#XNP0)c4ui@m!uUCk^}*`wtTRjrcWW?SAqGOy7wEeD4yhcZbNeGF%OTlcQ` zt*)y7x^P;`oty0Lr6Bc=ee9a|`MeJ8mWxp_Uqd3F)b zG<;k{OZ|xUoWHqb+gK})M@2Bt{9EJVzN|?QREqMRv+?sepHE5q%iJzp2t~=DH@`a= zR&y%Eu0&Q7Bs_2YPTpjDtwoAgl-~y@RHl{CVzd8~Fis9)bXAGHxa%lXy46qWPvh6s z-|l~yv&N8TyT4dgjxC?76VQFqorRndkrZ-Mh0Gwk5Bsp+E+|{We9OXg$=v>zT&-(r zN|c{YR_}ZA1|}xP^z-;G4C{;i)ZxPN4b?J8@+XT`t^*LQ^y#cM$i^km(bqpt`+Flr z^-;jw?DUo-0IhImF7^P%iXbeh{JM`jh$^1a4u#ne${K*k{WI;;S>V2d6 ziPH4hfuIM2Kn91*OT*BJl5RVi!RLl7&tFC-tK)Kmz|_TBH+CnkC*KAR5K(&P{0#l> zzSSsS)Dy_b$51~=6?yXXo|Qy+z_ItC!h$kIpv;0Y6}z>sY7;UTpQ+W>_(hGqI5(6( z`YrM#uRSwt#*@K3N?Esf7j4WFIu{c1LQ)hLBJMxUgXeX$Ugf~SQ4547AcB>Zmv{Gs z64Y7szIn~HRIIFb=^_Mz8%c2nV{cnqzlXVc2jNI`h7+JA8fBnT>( zV5VNy1|JP(2W55%t!ST4}X2g})(rAEcXJWL(V>thdy@58$0kIjNMtv)@~g=C?W*K+Bd)~^@G6^QZ8D#mwDw1h2OY)zGpdF<|Y z4xCF%7qP344mSyI5nGU$%|Gomn>p;&)CiuMf}R{ew!cSQrV}+-Yz3w>}{=AMk&9Y7hkfE`&$}-`=dnNO`w#LAoFNXw zlz-c=+^WPcUTes1KQusC)q*(Y&8;Tb3b}-t4SoO zEsk*)-w9Tg^peQNxY%*Nac~fF+}6tm1S0rZULsCbNu(sZlfe|r9~EuBax!DC(z6)? za0ZDHc}xf|fvPFOb5*dqvO<2gp0v@Ca91+vVKT(lm~FC4!1ke2`nnc*&CJVpxP+VC zaM{w$*V={593YP=oAwJZjo&$dUbJ}&8R)!x84Z*JCb0S7ZcXAE3jHvn%lOg7%?cS$ z^!kZ!;*br8ZO^le$dSKt6HcsW^c^ZK+jtdnlu6%;7ZD-&4Rdd4^FCgtdk~{!P@aRA zECFftRo_qZWfH3&-5Ol4c_&`hr0hoSuls*rSj&SNxs4@V>kjcfv@7>uQ9Xki)R$x} z6(%ti@qW)so2z%@FPhT*%CXV9acTe84a#$FHk#JPVIR{Of42I0kUYHg>Zz6!etrGk zHHNj5R%h=6gD@rPOrm3_5K0efG^MTmaX(JXE4^|zhAgKw@y zlT^gU=lJp*g<{@pciz%B!x@J(a0yB^ds6|n9LKGnZ%_9|o&}7LEZ%Ux|71N(2^+Ao z?b!+XA2I1}%-9_NKfV@6y5TqRE;yIy2 zy?U`*g8z!3DGc$7qY?lC43DbHv+c~MU;wc*KQr!{Z$1u&1*iXI64bj98{hx^lE$W(v&(yCd`4rW` z+*}lL)Ql6n$4{&rcR#;Bg~F=u`@f-i(fpb$PWHz8?mbPFYKPlrf(~6pn$e38&tN}< z(4=h{$Y0XH4o^VokE?_VaVM`cKn!#=0aDa<`#kLb4o^K(ocgF`$& znf&$aRal`UL0{t;6Xn+NdA5*F5hd-5?OO}Mi1{#F5Qm;$UVgu&8sJ?sx*lL)c9&3` z?KaFku4uqP9T?Kh49wdmB#V{h*aP>+T^=Zi-}xmG5-#l1?^4ZhjM*`E#Igfra0eXhuH|K*FH-v%0 zA&D@V!T04qLda-}*EkvUO^lPqI9Iabbh5z9*?P}?f>(Fe9rO9)1>57kC zf`qnwewpfGSmiM*DaW6L^`0%duk4x}30#aW|3D3}J(u{cMwjSaC`_Dod4N9h<;`y-%EC~_oRHrI_)gB+4}IHd7#Nhmw*(L{ zcb7TXlmj07sVGw()81Gc9;}$*^rxNfzJHLbTIQ*iivEmRT|NfIUx$6R$i&3~kdpjn zLH)u7`P4)6RoXCX2V9E4w<>=8{jn=xCO=Afs9i5LyL0-34OVL? z1QVzjUQFoP8V_zs@pgGYF`K@2`|ReI zHu44l2?e^0DT=Tm#P@}S>qPIh3*60E;WEWW76zR*)5!PyBv_YNRa;)%3zhRpo#o!p z18Sz|H&rHM31>qqLe1d@_;B}RV}q;zY{7qDu}~PRV#dW<5xpP?p(IVO3*~w|(ZmGpX z^82%mdr&!T@azX$G%(>?3QRp)TV-tGoyG~o1pI`9n&$YLJYY((Bk`;tG5u5Z?&yH` zP41Hy@V&3qe(mi#UF=l@qSVA1Q;LE#id>XD`YuJTzy-~cp~1=+pT>~FQ~2u{_a9sn zx{w&bfCiU~5dk)@>yy`S-zs`~iqy~Xf|P$jVd1rV6LW7HHSRSyE=1lt^Ohd85e7rx z_hGND-XqH?XL|H*;rWzJcfou2Gp3HPYtIg|W?0*u6GeL{cT!GYV;hoeRQ zdMkb=t@zlu4BJ#3stia0@YUa)@dE?OXt)eGgjjO4q}YE}R8&kWdzt)y769_|V1#rR=LRC9a;g|C+!U#e-VRE1;aKA#)+FNa zDhO&)Qx4!V2jkR6{Dxta5+r)tEc2<#y5%}LOy{?4c{UoV#d>O-QSc?r0t0S0sBF?N z+kka<8}!DEAwJbt_EeARx8;;D39X?9gHgWf^a)Nc#c}5fccY^EinY!*$2i%ZaD2NX z+6Pb6vQ_ayvBioLV>Twc2YtA_)CSvwXLL*NyZ>qYQKiWY}d zkZbCh%kCc+#OK{IudJ!_cR!{V1zlo6b@ix(OV(&Rb2ycf)R9jru5xOD0$roH?4RS_ z8CJ2z!)5f9TF3A*yZz>v?xDdL)7vb!-<9i<_VB{xb?^83^q=6zbU3SjF^Hp|P zLuK>kkH5Dx`YR3IgThRKnKaPW_-^}M?)&}!ZQxQ+P_Q*7guiu?PV+~eO}=1fVo$(e zsSrZFJLkM*Bn}6F0W?=D;m0e~taZHQ#&9ZVaRl5u%GW6)8?4;!aa)z z9b`W4g#|rT%IdST5yTIm{t*IL@bKPyxFKL%cvlF5Gt%X|5F$mwT$H5oh>=r1 zehQRE1~{BS(R26U1D3aeIlH{r*D%S*4#(E?*c7#5unR8YtHaFNorFA^BgLRXHMGVv zUvR$i{_~<3J5#Cb5cT<0#i{gz+#=|TGTy_fKYnu91fQYd{!mqBE;osbkC%!g!{krFy2R1oUw7H)hiP89 z*sSv*pHM}Edz%d?yR>XWHg0;##H&#$!g{ZIR|SE7!kX9x;+%j0m2+$imtk_b*sj%< zZFl4BK=((b5%u0}F`QUji~&8d>iG)Ux!yK&cUWGtJTYzOa{Oyp6p*s-)B-*}zBq-X z`A9`pTRT2T*X(S%f*3e~B*au^JOK-~2{F|QaZG-{t- zqr~sgvKj`}$SjfABq1|B^!Z$rUv}92K!*E!GxrC*h!VRdi~embTe(d&1|vG3+cH^? z*sb`^HO=vNBPR`Thedbh^Ez=&O#m+G9rKh+3+wJ>5pwcv@=6J2(0uWZqhRt?! z(pU~=Mpqd12Ys==Y+o(Tl<_^e+i<35)l z$$Ty?Cq+Z}siXuKa7h}y5cR>=7yUo>ZrQer22ca(%5nH$KCW} zxPKmf(^t+;_qh+JZ$^#K^PlVtHASbeanKM9{(!Z2xqj+`$4_LqOQ!s|`5X$PZC&I%?bwSw9H8asJ z;xQ_lKYG_~uH4dP{92}n@5=+YaMgvT?#1_^wH11SlW4-9z<2;IJWxv{Q>x5qkAC4B z;TfquJeb4!yLevWy5x?G1?xcEKK%tMboAy{3ikUYFGeCId64asSM*yG_{{S;B z=y|&i&N{dKRRsyLK(TyR3JeSkfT+5^*_(1vR7!7Ani+r6{-h7Afx0(RG23?ws3~!U zFJ?SJPg*o(Z+GL3&CT85!6n|FM+sfvSH1w{h01xpe`5DI5olvEixphy>FCD6^XJ*a zV9(uOt6&|WJCrW_V-Tw&1)ojBoUj7XX9}kxcBC4NP6=Su!QITPiT{VEw+@T?`=W&r z5D-ZbkX8|pp}Pn8QWDZgmvnazWq?XaOE*JzH_{-3fOL0v_j~5|-g}>izjzdena|m0 z@3q!m>l>Hm>f!PU+hd7Xb{1TpRR!AVj04WhhW2DAE-k zwj3Qm7&rqV^NO9+Y~kav&E_oT+;%cmm9YZ z8j)+qSZQiw-WfKrerm;Zcv10x9qg;xal3Ct0BZ`)aYF++*gI&?lnO~cM>+##6c#=u zA|i^eI9aLes2t} zd@k#lihamzX>ltcWMPLgbhXyj*1+hS(+Y8Oef>W@JlHe*4VE1!Ezr|!u;)jrJ~~F* zkunMV6|gyFeLtGatQggymj4`upG*Q!BKhjr;FSPOfsF~RJ8+%?`zulfDEH_M%{2_V zK{=4G2G0arUp}SIC_NI1sJ8)Vq%lM}smzu4$)| zKW(UUhRuGSv;5Mk^l3LDMm`(X^;w%4xIH`NMm=8B+EOzp{3jDm!J6fq+HN+kK(7{; z@NOq!V5p%)i1;;D@GQtb6lpp*Zp7XcOru~_D)hwYA@WH4%hPfpo2)T?qkgdHyVfe3 zASalPcgpA=eV`epOZ+l7%8);0lnc^aIN~`cCb-D7_chj1eC;JnD6sR@S@f#o{v`Zn zp~OT06%*gyd6Mw*WQl6+p8%@NV(AlggOD#q)I2P>@|@KvGKA5UpV2>jbbq6D!mVLX znezZpj}MezKCg-#ctu1{D;?DCEo-CxE9qHr8Y!$dl3J-Oy2Dg+Hc6)pv5QZG|5vS= zqBGbK?)Gpy#D5pcHUAvJ1q7%&JD^JhCE|B)FV^yrXTs+%@cQV*HrzAycp*@`qx<;# zUz^<^d%R)G(;)~E=JVKAq`A7ODSD7Gk_En`lX%Ve@aB)&oTI8B&wB|l@*suF^Yh_g z903vnev?;^KPBsN!@2z+y5e#Ws>%L=Q{~l{qQc4h@fcHbMlUeH_JrfK6}-JBWQ_&j zHTy4~Uc!E|E1b3w)0KSt`v8g_nBV~p&;hJds4PgrzE=bV95d4xwYDkjgeU8rGSA7M zQbqJ|fEg>M>ZMe2|C%fOv74Y*Mr>gF`d9x8b z8kY3mUJa|d-QhyEcu@D{U?MqKgoAmEGbgvpHTs?YeoDnqfe6)(y2txRdd+$uqB#+% z`mqwL{@!o*?Gd2?;%n$yXJaqff3Wu@PWOFQDr>uHWD4phXhtImI#EOKf`7{8XIa$a zbf#$>;R{eVJQzKf@uo3kdP6h(YxU~GETeQ?yh-fklCLt^#REwICNF`yPU&gujKRB; zU6P!FWv5$_+r-t+Z(P*=ssn-rtccJ?^tofz(aM-%t==s!2q-NN$!(PD3OO@F^nheX z1_5W@1EfKbZY>_Z$m!1&%D5rf4ndkmYqk|_DM-r>FN1ySsPJFCUIp6pU*#1p8;Z!4 z31s0w&IEd_8>T!!G~3k||JbYYXYzR3sMJGqbE?Ol^4zH?k@UO12elQw69tLv+4 zV0DNaLc;PpicY@FwC|Z&P9z9CLIDoRilpn0rcNYT{@OA2drpc2t zEPZn&=(mmycM>p!K-bNa-I9E2eg6ypE|l_CUT%yvjf*%Q3Xh@yvkq(8a|vfA%EOgPUtrbyId}3U3X-y6VHyWH-u-Ya~1I@nf0uPjJTgz+xeg{>ypB3n33j(j1+?rAXE@>ZyMV`|y z9`-@OdB?Q3iE3%3+B$U%lvw^(@3qh(G5p66V;~bjyqa)$oG9csL_| zmM5Ys+q-5xd{2mE-#EGI|021?{VFi>X;3F6A2*M&_*W;}=4}XoN@E0Yv0U{%lF?Up zGtMigm;;W{Oc`lEJ4Yw0qniS3+$2IT>SZSk9;PP_wR}ao zfdR~!H_#D=_G~!I0qM&z|#59r+r7kvg)}z+jXBPi}PIb4EYx6JWXX69w-xaK7Rc8n=ItHa6M;R<=eM~Ve68_b6v!^jE8y8E$)T*vj6f- zu_@9(K1YW>S0f8}Qda??f}G;{(P+x83T3xPZ%({Vi2F@bN~-jOLvzwIjZSgXBeq@K zO_Xn1b}fGBbJDQnS*zTzCSzAa$;zKp>hxMtxZN~53jd=v(T7pdSTievq1v#4eYmo$E0!_5O;?J}TnOD?BIW`}`X2yLE^j;O4T9 zV!-CwN~3vtzU&d%n|T)@% zirsGoX!5J@$?(31S56g06AxTGs(t7Aowko=?Y37yZE4Fas0|4d* zdlQp&PPE8i%fTc*A(!7~D5=emfuVJ00nnWS^lwvY)pN#}p zX3V#uZ2v8%mK2(@FAF^{lCFc_z3ZP%b~xmD#|hy}Jn?hs!E2Q^iKWw8gR)wskLWe_ z?K!M_wP-dRiH=dq-WHfj*qbcz;6Ms`N^=x0$w8v~rdvtKM@7k_^>VBOtp2oG*KW5HCS+1>usVnsx) zTZJ_SEa4Qv$}aV2XO#mCjqR>ObaB1_g41$N4t@tthnS&ZTC})0Dq}SZZ8BE;sezzY zBJYd-)QlP%8=DlIpL|K>zuO-=iLm&1QBg={J+n@3G)o(>@kK7vM;>)OJ^*7T0I>Kw zz)yn2I?J6$E`5Klzs*3F!TsLla0PHnQ6k(jAcQqvy`Q7uMbJ?k;^B3&n&c*M#bD>) zKzg|Yc{Q+a;=gcu6obyYb$WVpha{^&)-`}yGl$=9@9coMC`y2{3Piq3%te}JDCR$d zILQQ&IY&8V(G0@-zqJFH#sm}`fJAqMQwjag4D&0g0Z4yrjc)I-3PPM@5JH;c%KT8O$ zh<*N^FJoj-jCL!wR-^APScqtfUK^L57BKr^|S9y-=)b<1}2=L$$VCe%8V0WIY&eQnkphW(W0WcafrtW2`X=8 zezBJ_QeXJ{E38)iufRepH)VIJjdl9f-Q`4spq>c#7ysho$6Dvi)o@imI?8XRU9uUUo6z)XneE`V%N69xZv8;1mh+2FQQ{U5>3S4p@YG zM<1;yK-0fWM?Ew&p6*<*x(Ijc#uZ7XuRD_I61wEq0F)NKY)@>ePa_JS7}{FJ>%iHk zbLa1BoeFV0?1MO|g{4lVc0`_I3vf!lc_t2aF`ff+@9&bCyD-*kb+hn-^`0gk-)2V~17$uoY z*Yog&h{Po_+TqjVr^wib^>uU5g$V4Nw`0F~Z_eTi&M~?39?| zfEGoxSJ}-l+DJR|#+t3%8tyacnWtN0w;K_F9pYa|pC}gHAdrcK)G7@wD=fPThKcx` zBLf|kMDMtfH1Y0C?T{1ik*Ytprs{Z<@Vie*P5<4|%b-3^I`YxDX_!fU`I&mwQbEdr z@(q>B3`8VCRKoM8GrhkiUCVB_;U)R1Pn7P@;2$2c$-M^!=^Rl@SJx}Pi{i0Wyk^}A zIC;wlvEHn$GJd6Rbo18Lt0&~4J^mgxGG9f<{Cd|k6_Zp+vLFN*%Dux=o{mf&Bc_~W zp%D?Zk?;6919u~`8Hw+)CX&t7eS`v6FA99aB7&jc4d2Q9%Rn8w)o6%c57dM&xk6I( z3*3C_0%LITHp-hc7I*MHZ~F6tX(<_7-O6_S(C5P zgR~?C3)!x$Wz6qKq?BH#PlpbdKDC6t9(AKqioxOF+2S_;^DEF*{wX-d)VD(qodB5T zDEB~i1Ie4(en0d3f4-*8tyAujXFe?VZZ<%=xB;hq&baUdn%YSR|zF`#KOVBeZINlKWSE#z(Pk&1t>qqR1P z!l>(d7=<>_xB+|v{8|9Waky>&t8g~Qd`kHM=A5UbtdgL|23T$gTg$h|$jAzwwpcFx z1;bom82%9%aRrckWV9f7XgWV~FxUjkoF5)hzZ>?f1V3wdWMugtf10R26qz>yU>0ML zT!6Q4#!agkDti=<+M-T!#d96=DS|t9U?KZsd#lUWpZl7OI_UPk%LrVkfnS<>DwvCI z0*@tzHG%}aTG7Yqm<0A_V_5L)yYUcQ*~`pZhho1Q)dioB&ISN}won2SC2rQ8;)DMR z1){R5^k=y?WcS&|h^Kh#u-gydDpnwuALq&#t7z}Kcp38}XZR2$HIMLq zKe_AP2)vfUc(bhC=~A!uZL}=3Al4UNesu97D6n*5>=gl)7@DJIEg&yAG zigO2J57omQ?m_{_p-9m5N*aXrr#0SHv+(C=;5;BYOt;s39FYutenTBKG@yuMDFWPOl&0E#VEoD&aGH)^5r&r zi>O;Xju-GvdzaD*s!!b?8SE4PVvcso>x>py&^U66&4?OJy$w6TxyOTw!WP~Dk{nQ$ zD&*&${&*j#moDlBzI(OelYp&Je#&l8HjwBhikPM*DRO23RR^fdl#l3t;~r^Zf63%B zzMPkeoNyh-5$VD80L1~RnXOQF)$h5ya&Av7so}`z*oCG#hujPD~ zF8Z;FZw2})&2;tf(tW(z7@8yY*Z9{Sv2h;0o2R{5p;vOc?SmG0=35sPh{&S0YMu|- zg};H$tx9{x*^*EO!**AD8Cp6&Kh5FltzbshAOJoH|2X$-(B#3ZZ8?IzGimKiqi9*Z z?cMms`c__<_}gjgBj=_jSGvbbN7iVur^9?Fh}Ie$$xF=sH8;kS=27uuv9Si=ggdr` zEt4!Lvxr6c+7q}}4ZP;AM+=TYyHDaaMP2)^j2ZVO714;7WSZVm1@luH^8=RMIbHf} zCvhoql1;Uo=kJUQqfiSut*PJj(Ho0U;+Y_Yq?~5hfR+ZI9@rrOpB@Jk8V(vr8U9y+ zsolTZ2aR4IM0Upj1U)j65c$#NTD>L-$;ilPcWM~+1wt-TCRIY3dt@dtK0U{B^1P~*qS1ym|vTuJ?x%YH;Q=$p5ZS>x3@CH+g3adtXrf1X4=Rz9P$zRu1rlqm;P&GG2*ke4J zKCvu5;%N_Kj_sDYTXY>bfHx=i|3|Qpy{k1dZwS>O$9h6jK?4(py?+Mv{29>yopu6$ zFv7aXnfVqPZqWi=gC3awOotLVWt#$r|0R*u}O<=8ZYDy=)U4nhxgG z?~=bcmQmkwam!?>00Fbm#wI~4{b$y*U>pMQ`GPbs&-<$l5L2`k<4;9FApyV+L~Yit zrt|4fleEq6p-jSA;RCJ^LDfBC)!fx4O&$+_maYVu+rrn;W(%`1ezCXtQ4AXC&IEGW zAQOT%K|#>RgZ+hTMFOKd8j69}8Zo@6X!UDyMBQGNs`=u?nwC1<+64ap)dH-j?p@hm zj5K8JMg#1`cAyodRVj8J{s|~;r-FGJg!It8mUmR#Ow~LtNM&jjV+{N+W zY4^Q3H+FS>4xV<<1i}(597mH!dA6Az6!%8%#rfB6o)r5uC<$KHtvn4N;wJ^{H}+Q~ zF$x$1z%_fFtjBI)0DKr(=K%Q{gygW2fYICH;>)N$Q|)vTI1#a^dY`>2!gaLg%>jdf z4D4s^je;%Ir_3 z3$ts)XXbZt(Z}DmwPpRA4q_eCr-QGcStEsWi(;JB*%HKcOXGG6LVvwqCinkw`0i3V zu@kehZqYQN_xC|~vC|GufLi0i5mr}BNA_IeK)t%ps^FRak%wc0^JlbTU9X7Fz!}f) z2mN9k)Vp0*hq{jxZDLDk{=C5F>2`yZo;?0t;GpQLhnv@A+iV zeB=A0n`F*HZx#Qmvq~(pYh=EWrfVChVPYJFWyN7T<=|@8v^#aotX_;t9{>bpa`GGa zxBxZ=wsw$^ZB|y+|558b$4!0p>anyH!4iMgP2HiCFVHudnQ4K&LZmkA-J9hX8(G6| z6-Jr4I-earv&2M0dMTmsS9j>jP099|j&RVQU0i@RunqWvQAY^%gKb4i?R;pu-pf@N z`mq0CpXuO=pvGuu5OXHrfIjChxLfL7HsS?sa&cHByt>jljj=I#2V(A41c#|Fj~bKoGLfGyeE(L$e*oMhM2BFk**J#A&twhjc_7u|X|H7Oqal95tV#%7**K z6@TN%HEsK+);x7Y=bJ?Y{c=e5AB#$DAX%yq=r`pIH+lI22jbLzvu?ioDp{>cs92>1 zivLE*@o@qL_pImlRf&<8*@+Y_7LLLN>+Wx%fj3In8ltq4x`mCi|%+y4C$p?9G768@(nNtSp0nq8UNdUj-xkiupzUgC;V_#J~_aq@N{py8= zW(hY3a6y4)i^KmOhIH}E!SMP3Jqx3lK;d8W)CK8@v$J~A8|tb2puUus5BFK;wl*{f z_6*Zb5CwwU4bYV!wqtFv5e~-$E?me(2VlF5@_Y?}oSFdj10Kz#W>@;x@lWbph<@pP z3S0TksoMM9LOX7S{iTe^o-U9wL>_nrU`i!MGmFtt&&BC^ zL`V-okn!|o!qA@zDbd;BalVq_>498}{_??k!xHsJJn(U6i289TdOe?-PeD5ReW)C( z+TG9vhI6kxJQ{r-uV*RnGDU7(`AC(TyX(SftmV&)BSjXsd%^sm8D@j@iIh$Jh0?KH zt%!Jdntwc*&@)p}jiwKuD5JLpWSJ_I?2lhzmN?Y)C3Qbo9L!~{HuMV(FXWf(d$%?e zj#=mH;>-KJi!%!~qd56tXY82#<>?cGL(Y|-%%wO#%Z%ur+6&A6!bznNL*Hg4dEOQ>F3Zxf z!Un~Z${|14&5hrJiGQQT9wm=ZI5gDKjZj`KEi6fqLzwVQt*Ps3Lph<*Kmp$sviOVj`v_L@enCgn%0&)@4l!5-ZnLXjE}oGWAiMs8qYGQ6+Mp}hr z=S!8eYBSp(Mj{ei^DxFHOS{m~1_>!CNNVQb z;zAnY0IktKYaVWLTnopX41NGOFho!#0he~2;vn!=1C$R4gaH-AO&-R&@$^WN0G;(t zl_1%<4ly|BM&+rvLEv!-{_{oaeLiz}cpCdghW<{AjT}u}jX~(gA>7$bs&kzeX`)2) z=Y6URjj`cH5&>1}#UGA7)7+wfkCWed6$=@pnUIiB5>s0PHGJUJaf!R{@T|udovAK3 zZLO$Sc8!gVCHA0Br_#i2S~N5?r1{bH+WlZY4A|}e+i|Nc^l@|~==wOE!wPwhy&n;% zG*k;ZcH5a6TriWPIa&u#9If;mMW@}O=cx8Qrg92aCqUnE=e>4CUcX(tdJF#;U$9FR z*`&-RJ0S2UsBe-K;eg}(q}jAg4Cc&sK&k%)o=WBA9N>0e6k52#1BwmD&A+cGMZBL^ zR#t)(N&ELZg621F;iq%ctTgt@)K*jxltfI8uF0N35iHQ#%n9vQ2bQ3%PWShh^F7s; z9?z!SY6%yXg?Oi{J?Qo45nuO(C-Yb=$nk|VuWzL9j;jZcUnWsc&Z8A6)#e5=W=E8H z!|WRkja6DKp#%xSZm{yRMnHlglSNmMO-xcbmNpC!4hOdKP#` zw6)*}!ijo}p-p>3K!|7;?;Q)qae?q-S9_)*sKWh&&p^mbBp?UVtqM6cyhNl9p%K&E zJv*yM3lmBSmp4&mjZfhU9xn3Mdi$u5IEqAUy2hFBE947z+h{MRfWY^!UmtsXTLzLl z5O=ihwr=UfIEhCs2{uI9&L)EA<>}}E1`N7gA@}4T+f4BTKr)Qv&4BQ-e~nW$KSr&W z>`9TuzfC;yG*vN2ILOD)*3)yvV4~Ynb`=~$AAlUlT)>%sHkp3x0nQ+ zk>M@Z*(v@uMl_r4d7ns8-~C{ghb3B?_Pd39UH~jvSL?(_%FSG0=Ot3)E6j>HH$R;59u6y$%QX2?|^6Z7CO9@Y@bT{r39-0rJEVd?(_ zIYEF{gPs5Hm=|}Z#{N^9JX&ur*Qbve8I0wc?c&3~zCSY#A(xy|Y^1h3A|w1qM)6(p zrz~8hc&usYf!xDU9kTOWz_&Dl^m_Hjf%mW5@(THlPQLJ_p700+Ttjcq&F|W?IaR!y z<8bgO0f((&1yRDY=5IV40IJAXc#i*$>zG@S?`gA)+7m1NQ1aT9LPbv+-!Dr9GkiAB zkIwX4ZEif@@2Hv(E;!)MG_Bhtjl@JeI0?s)aIb0StN&hIeY3v4&d$rbuKKzABZozd za#l*}Xyl;z9BVPCA(q_Rs#K^p!7L|wxT(<-;Ql})nqZ6W(=Q{ab1!uD^dyTvNL1@c zH5(jwml%{b#yH@(4{v(&s7I$3Wr?8~GE1KoSCi^g;bsekV8((};_3?r*EuW6UJjqkTlOUD1ChWPdXA8u<; zAVX=p19Fzz)o6bA>8s0nYvL4;R3Q330%bPbA4Ah_zKIOz{JKFJEHaD228q)O< zC_r4SE&_P&UkLejGo+LYOGKXJ-sXb5(s+G$GGqiT2$2U}ky{Q!YD!Ai_BI5M1{#W- z>+D5b^e;neEvDBpyBK<4oRcHrWHRl5vOD!w7);SJ=4B3Tw{FTF6;3qEfu+DO~H&+itN=Xi}(EyQZr!@PU5g0jo0zb9S8O+Xu{WpU>tLXbcT)Q{q}>P`6{mKuB#xGj7fp!WVs3~bMI+~#5Bgj zb=BR(#i7tv2UKaECaCnx;5}XGnazx?H}`yxsGuLvB~gADNx7^_0064q%~!UfB)+)T z+dmeEEem&ZB?34rE*6;_R8RZUbedcCFKA^VmNO{q+em91JnC$WjUVNxJ^^2#HF>=G zQ*@??9Xby;qt*HF=j=o|#{Y|PIw_jTeN){3D?a$b*J5?Vp&ufjs-6Ch(MS^?xL~D0 zsePIBpVorOLXO*JGs)kp=e9RR__ivqO!2lsSwRNEBUHrAeh_-2j6X88QLf%A!~O!H zDOhA?VX6N%KQ^WTx}4L~5=2Y01qyBzu>*_@L_P+w21W^82!?!Q7P)}3lskpeg zzkslt#&50Q+U)C-1sBjp=OaY{*;c$KHA0T!T zT)rMH?;Gdb@%W6wa=rE?>7%!P%x?*N{^WneHDt6NTiQ9fb&~drNhI=}tCZw5jtKg^ zLQ?y|Zt%K{d5hb+^1YQD;98Vq zOClUv+DI30Ch)MQHEmO4crK#HU~D5dlXt8mdNxbl+#_8dT>Mmj1!k}@a*=G8b*J|E z3pt_h3H)r+CkEQE&Bzzo&iJy5Ux!&c~w$efJD8jsxQ-48+Hy3r7p^>tgM+j#SKbxeI4pLuBb<$ zG=e^-$uxo?u9}=?gbpuP z3^b&5zzF6rKJ6;B5vo@F@#HT7Am%~AQD!D_0w~ss8JiE;`TiULFkgWOZ1v=-WR4J$ zM4Yx2-bb1RzOy@9PXzGp>KS919yrgF}wl)Z3qLOWnje!5HnzM$?vp` zPNFzqRO0sWqOi1uJl@c+o`QjeK{45}(F>V>4dBw#)6?`}%f-thkl9S(Vi7b_K2XWP z5;P(3A&Zm1{$Guhm6TPu@aVq5aq~<|&vF`j2mB!MyrWiHU53tqes62aqDXThRB0bG z(7)$9Rb|*}dUO1(!c`uXgOEM+-u$ZcK%Zie&0j6}i!as%4bd}F>+rzSn*T1>GIbmEq`4ZAt zgXj)|CZxmd_VoHBWy57nU0~y%fF>BJ^1lf1+de^CqX?uK&tK3kaxTJ9X`CDXM5fz% zK%ItyZ4)wXwP1V$4|umgg$~awa;c{Tn@e$VagN8UvOq-PF)}SzIx*2@H|m^_}T0~8=gPD>s*(eebJsP{tpM1X^QpI zjxl|vWo82;@p$wpijD6Ca?LV{g8K~$$D9?Z9%Jp&ia+j|wqUPP`Ez}Hd)p+hf~;Pk z8pgLK`%;4Kf58;@0A`>j$NE&F{|fALmviwen;TroF|)B{eJFf|g^Fx^Qxq}5)W*1= zzBnl@C_l308lMpz4hcJ4cTjKw2M%PY4uhr{+-a_Y&Biyp5U?Lu>UUPCF9$41@P&*9 zYBoza<)c4jRJ9>U>EJeDt!j_TFSN39KfQ115R8KbvFfHtM^5pA%n-NBGIDts-rJf1 zNaVDCj~RmuhFRZ^ShX_CwbWD2CroWD0t@hHdFg#Ul(%f@6_HF&)ExU4^nY8_2hP;H+Urdl-7#KwOfJ< z@{zs!*=Gv+3BCRrSHU^67f(L5353)U@q&&P3^l+v!(PU=Ue8^~B=Afz9RyN?q@$}V zFH$c#3;fZk?GhTd>%7X~Doc;cO>Y4Tv)O(z{ZZ>#RqvV#X{$DdO6IhaB}I8Qs5YF@ zZ25>Ee3b~hVv+jp*`Ne`9<$ce0nrBt*iU?nfmki z{=*?nlM9ys&sTqHs;(Z7z2Cs@F0inq0ed6O9|~Gv!IbbBLX4s%Ruuh>CtzbiU?XQ= z*^5IC+(*cN3B-$k5Qt@vpW$Nn_u}UCZ5Z{0o0V0fmR?wG*GEF&uS^Zr3c)}Mx<|^A zB}5~jZYcR3Q2^ll3N-GuceBG2z%Cwq7sUo4AgEtB2BBwQKyo}QJrOI&mC|yP9=!&$ z_dQl-IXNy&Oe{f_t>q%zrfS_**$uHAg54xNd7%^4d3$4imNR=E15bNrtZdJWMTK}t zbg$hBv}e0FVuvP=Djw8WC+q(@mBRwsEsGdznVG{!ylwm0Z9*sNAC0@Kd>sxoxLDF& zNVfYjwEN=Hv9ff*_|$lVZr4Em1Umn;jj1rU6e3-v_##Ki$T!izrm)<^s65|6`|643ZxsTUguZFwO5P4iYyVY- z|DL8+|5HUDEB6>EN)VGEwT21{8RXrRK1GEf>`&tG=Cwc3z*Er=KMGF-sqMW6ugj6#ltQM)=XC~qJE0x(4YvY)JV zpaBp%FFJ{Ew6T$q(VPS57D|2QcGyKk_7HMLiBxk>9=m=vOUpz&t2uYwv*vCfZ-7;$ z@4U2S2zi{>)P2z4BI%DdE<>bE{So)Whw^bjU+E{!r7SkVRZD2&#!VVw-=G%J_yOBI zH>s6Z`-O%xk}W{PqF*Jd)-`$K+ud5`HOjFn{5Ius8_Oq7SZYgd=trjb+XRJ%Q_PyQ zehaq}4cVi?q>-=`dGag`+2wHI5{W&DUxA;~2F)vNJYL}Xg+l-7Q^w`Wrn%d?rFNJ` zLZ&Fy7Q$cYxAu?j2^D?BDx$jG&oZN-QT-g5n>C^o=1hk_UX`0@u6hISZ-o32t6llJ zQd%c_V;UsCS>Fb2+3cJNLSnIz^CG~X z^79$v_hW@V{Tc~te65bRb2(M@Movvov!%M&q(G(b{Gx2(cZ;rp9j?9HPCuzv#E1ug zwQ+mGmokU^saqOBw-#-2&RZ7A z-jkA{w>O-cH{@PY_AHFllx(plXDryweF%5nuOni9_T6)6wA|N1MgMQh&;&J!4FP_~ zST@7`RExH4m!N=qqPxn*pYZ0P_Tsa{#PO9;%w3qyl&x9XNFa;*{Ao%Yn~rxyJN&%a z9SS?O=P1DUnX;%Fa@{7V+zxjrRyso$VvC#Kn?BsaCE2;!99JIFEG^4>k9K z*CaK*EH;sMd%wo>gYZ{>l=q+hEn8{|Vz&w+H7!948ie|%myYL&T(MUsJ%_ti^ZNPf z4XQTQ5GVzTkw@$a*?=zZvaiK&_L|l>64<1HXsqVfxk8uCm7ViM{f*n%yp(Meb=~J2 z1=Rw{gOq7Zb8B$-ZP;lRO&2Y&V0`L*UP@2zH$9QYw9zkLa4CjGfCu#)^xi5)&6Fam zdb}SX8Y}fn`GP}n#{RJh3A>fA&h8zQz&0!r7Svt)p>Pd{7#wtf08;7nztyN=AqlB> z%0A9e`3)7%xiiUEhv0>ly;sM6qE$y5gcqKlpI-vI85kJY7rJSqyg(;&adAO1dX-bV zsA>wM(saLuE5RIrAZ&MWwQb-b=N`*5C6=>k(=<~IjKQ7)r4Jye01v1&DHyf{IhL*| zzNVuJmc~>}OibVIRz!mY-Tjl;Hch@zqjzf_iCj@c9@q$pk@XSnk~ko+fH*j zCI!c$J0QPnb=ESbIy`u7so$r#Vq5pA@mb!-beH0n6S=+Eg`+Y|$rKckvY+EezDDeG zW6wg+b>K=)DriZizD+V4fB0mk4Ozog3^Qd*O-og2{&dX#M7N)(A~RPvfT4 z+7Cq9TBW#53VVjf@24_X?T7qnpDy3^Vvaam>jLEf2iiK zIu8tiQ>n*l0$7N>?ffxoOK$QV_w&4R?JdO(l`y^Au-o@rdK)@nkKBu=1kdzIbZ;EX zbI^QAH-6o&D43bMlg!lG>GHJzND#0da)Q=B|F0GRz>AKGd~U~#DWKTUKKq{jp-{lP zCS0l6(5zzr8k%$-6l-Y9%}y4QVNhyfZjJ$0qTg8Nd*fb7?e(zOmuT;JW>1s&;yzd)(}h& zE==)7cYjVtaW6WK6e@?VAe|~-N{T}KnfuGba2Df(;d)$Mi4USGb1Ic0TA}6(7E~?d zml89W9#OhF>Vjh_hsI5M0||cq85j3Ou`XK^|387&k99?bg~>;voVPUi$&R8u^Gt`m z+xvH05vQZsHT19mC$(G2pms=Gd7sGs+Aqx+>~`w)rviM*Bi$18K$TOHIjZ7~bJ9S` z8sr<6ZbW4|4edxEmZL0uiItp@1BdrWbv>KpxFc)l45SXDP=^Q@s#`um-9Bq@`Hy{D zbshQ%2+0dG^mcG6lf+m;OgxUd>RnX{?_3_7=1#EKef;gA-{wU~xx~sxPE_a`+ zJVlDUL?S4B-weFyJ`MTeCEf3}>U%86HHZ6yJUHKLD)yAVI3 zKt++wC(XiSM8^-F9ed5e+go9|oM&KCK0jDE*wX|`a7+j%=V%-dRlY#RdH|`pbu~Hk z;%aCm(D3qcQLZY8(i~2)6Z`xkE8*Wu^Q_xTD`L?k&Nj$@*niw)B63-l;NuxpMl+cQ z!!_49UU3LmdjBVFUvT&)%8q5oXX@#9g*2wj^|ya2cj<|`?E=!TaBN$L>jPPhT!IF( z73D`CR|XyMa0?M=sGL?y^~m(7^mI&+4v=aDs!`{xm|qD`5aC+F7^o&{4ll}Fy`Yad z6b$lT4V6&rWevS8;5JX8(W6n<^S#>JYdZ8z+#c*7P=v39s>JaX68;+6oK&7N_K{_{ zP8z9)C_&eLNui-m;t7$2w!IlDUooPpzivgOlyJCR{uH%JWn?R=?l$%3h^h4?uaxnTz6=(AADkP|&;b7INYTW9#Jd#ZFYvD4m#1gX}Xku^gI z<{C_f5`SE*{FXmhCu>-&UQfDm$`z3ckVb%ZC5wPUvF1Ewoao)WpXnAK7e{%==*fUP$fA1*g3_42S>|Wd3yBsLa&XRL0x!#^pEf!F5>;(^~9IBBq37q-UIz= z^FwXvK(b(6y}hYS8`mfFJZYyvRp-iGINZ>4x16hHD$e5kK&DWy`}mj>RLwc<_c3m( ze84nim~l-DwBX>A27t-mEmz=y0<1KUCR;4JHBE0fc9rLu4vc2L5fjtST$xc>H(`HL z3;zcIQxjkpiQIt(afZ*nf6>LyHkmJFWUtSCSNo4N?~QZ#*=67Md+1dDP;~e1mDjb;i}NubZg#Pq zYCGkto(*PE_4<;7RX9G;1vaYIJ&584 z&s>HBnjDfmAjH5qUDUEND#7^dd@HLvu1HMJ#JsSO_hlIIfVY;cwxK7WX^{Ofp>F7J z`UPaOtZf)oZ0C9TC*7~fz7hC`GlF(WMdA|Tfh`@V48Dr7k3k4q7b->^;Cf!C3#H%{ zj1~C!gH7w*-6F04HDGp5g}FV}X7M<{x3nhm;;%6gdZ4^-rf$rXKeiyYDz^Ej-#{Q2 zUzyryZP_+aWmUum95|8&Ut^&H00Brgmzqux5?RA-E<+;0Yinj;jlCp!9U^IG`uXvl zd(jwS<_QhD4dWjFzAG;~c|4*N;3PoIra)hbxDvM@@zCec^n{PL&!&ph0e9!J1EGcX z9JpEnGwdkDvu^D7kqotykgZ%!l-l$p#!eG`>ZhQCe=UCss;pZN+m`oiJTp zEJ&!#Y(sL0@3-398d|vVxi=DhRiz^Q$-hhJXqI8L<-Dqr!|54KO>0+r{L8kL{OeVc z#>cVr5*OPC29~$QHaFUrkBP|b$OV5H4KL4y&2#EGIR0Hq%ubbzs?lNh5wYo^i$Bxt9b*_gOx^RZ zgyTM!&~5yc>6XUOy9yhL85=5zA|dAOB)gNn7^4M^$n0nt+(_=*9m=AjB3H6i*)-c8 z;G(HH=dQR%J}maEpD+BeS9z*vdkYa;lfN}~+Cn+n0W`&cI0f(Cd6Zrztp+z6?R|WY zz8WP>BiHAZK8b^beo*`V$It>c9+-gxKtTUmb^q=96cnIHfTWWqNXDKw64VySvH-LZ zX!G`V!Mz4(IS?HW#?Cx-NQpg_1P?0UoHGF7hMWVtNDYxs2r@|ux!nrxQHmb0h`Fxi z@vLxkft;HEV4NU>uwPFt2Hxqgy}DAen#x6ae%q1c(5-v1=khE3%!&1sl66f!X2bTW zS3bFK9f@|t{`?yeNcW?FNDx$L5TIt^?M>d6@AAsR!a}8VqR|~Is{5?zk)WHmxA!co zIR;yfDkBoHF9moUD3uM051y~gz!t=0tG_7VFxjEd{qFCI&r$SmC69`afjDy+(K!Wb zC31B;*%MiHecm`j+CHUG`m70T!xY~nW4sm_`L`DbV4`3XoD?{_kfle#M`Y z>ylivCe^9-pjYqYXCi|ZLWfK+> zrLD=I4wr|qR1~pyKk)m~intV8b!~?}rr@7@EO_1=2JEG^%s>lY%+!dxWtWvd425Bo z02g-{TZ;4>>Yn&ohl40$_s}si>piSEl1b_`<2iWzQNsw+728!36;0Q+pi+yIL+y+r zMxjCaitU+A&ZC;XWzjJP-}Ax`g8H$jzk276F4fJ+RI1n&d5$3aB}TmicHUo)+&r8e?*fqRH)zOt4{9^~X2 z1{zHjaxmZmsf3e|>}3fsCbH$-5qm~#0|BtJFE}}PIC)1ZE}ncz?~!;vm_?9c7;y84 z(};$Hqk?CxVfJ4ND;Q`?41_j5T&Z}gyljIlikG=7zlr5oUpCaza%_YHrZdGPxVr)r z?F;77f5We2$~<8+ys$I;2XKthN)aF^w{$4QO+unRcTpuhzds1Ijy<4srt`@^;!Dez z#{Ig?M`oU$bvw2MBMi7?;06CmNDv2I5Pftza3EGSynTJ1=Ds<3-2ZSSdYHCw#(H{j zku_$Wp~WnShQATHb^ps<3D=>Z%H=MvoF5C-B4%;cxn*oi;&b$n*kIKwO3Zy`RrZ{2 z^v6d9k~8jCmyi54?=w$rvR0nCZz^BMkm^#7)RK2>@DETsAVW6O-1XT7&Yr%c$5}{P7>fw^6T(8u`@BgFetD~C!zyCo5RLTMs2^HTW zsVKP-Dhf&~of6U=18EQu5y2o8M~EN8Db| z*L~jmxQ__n%E`$|NJ>(GT?>hy+Wr=i-IvwNE&seA?A?r%5`mX723EEA3iYIO#6x4@ z;#kEaS#*tDX#>_LAC(vg?Uh03$jtQPp;C*m24$7~CeDs;|Cz7AN906$Qm!salRLg# zUWx6Rp$z^9Xr*)x+<)qq6ej(a0y)nmW=MQeaVoDI)_rm54rIt5?C%=e{S4fW51jef z7Kb%xK#R5Tb5bshzCs${<=?sT!DVq`04)EF-C|3Ai#?L(mYY~EZ}>e~o2SD-;gBZ< z?AQWdt=#k);`{5so|HVlgk%mc_Hv=PE-|Zh`_>$xD9sD`7MT;RK7tE9>*TI?rD{2e zSscZEVHV~h$v9(I?(N=|7A3;>o3nZZ@#(GWaT#1ccD1&Lcl)Zr zNm>sE4grunNy%UJ1iubDRm%I>nzmRK z>lql_t2XhqzmpMbD7*^zMb!{Gy9rbYPQ{Sbz~ z0i1o&)IY0oXZ_5+-HcUag9i6Jhg<*$Y;%C#Zdm37l=gC(8PR~wQOoAu7pGWt5WGjd zD;Pqe1Q7Q!saC7u70%NkYavRzUcCzrrpC0xOO8UvYXI!_Aqn-Ev6lOA!J`ChXH`Y`PrVMeW%%DdihFY|->K7k?$%q;!c& z=PG+~E_p}()Ra%_{9K)1lG;Sgc>{6*$};#$PL%OyivBB-gS%RI2OUMtsctV>DEd?E z?k5M4k5RiA5D~`LuCVs4%I7FUTdhJT{y)C(aF`SqFNLfycCkX)7Y#jJ$Kqyuz?>1gMQB^ci zHLPvTC|V%D{HuT}hl>&pHgfSkb9KQqQ4-PEOpYrX$uHGz#Z0*(L(7TLpVlPMy z*oYdLp0wm6rwzeM==mh)VqI|U{vgVIi_%#W33k(!hXIPZA0B=an7(8CNz|N%KL*o> zQu?0W#5*GYS!d+WvTx(=2)zfQZ*xX{qPcd{_x0M^XnQbC`AVON!(n?E6;)W^rq^=Y zC&rd}@wh1N=FZO3l-IVt!w56m{&?tT>0K_BZLXui$afeMY??uyxrev4U@LP4)ta?X0noC&blnqIV%8AOGN*kav9z@Wy5&C_E778{qA3xds zDjjTrZ8Glpt1WxRxoA4!WO9i?UjC}85L>sa1=4?WT2GH8MjA2qlx@ZtI#{6Ya3~$VFO> zk|;G0s>?+RP2L{hRVG}lCLHJwbbF7A<*?`vVK+{r@BQ}cC9!zH?> z2(8-T$Bc5963+E<(!^u1_xs(lmMAEb7e-q zPWVfAtX=#UE{AJu!XmEB&?Jq#oUTKu-K3W9D^G6lzb$n*`?ya1mM-m)Dxxfg%PTnu zcPWTas+Q~;fifITO>(YLWHrfCr%kquF$jx_U_F4|0XX2W&_3d#6#gA@zY5_9km^bO z!W}l<>8~`#eyTGl*&Nfcyvy?e&{VYB5Kv%oFS(GOj35V8dr0L%cW#~loizYloiioM zGMx_Mm5jVRym37slmtOzvR$-Eb;E z#{Cy`W8%c#46&Q`^V&aK>R^xLQ3Cs5Zxj65nke9MgQq!;QiFWrl#b0wh8LPm&yvS5 zIe9?AXzz}RShzZjdN8ozK`QP!yl^=?>}1)XTCv~N?!e0m*rzch>~_@+}~g6m2hia&Ha(TUoi3e>#g7T%5({2*sP28e|pP7 zVwdzD43XB%5*@zfE>VLt|q!? ziGHi+{>d8S<&oK*^>xkK%cLL8TH!P}k0YcuxD9uojZ;+MFlpb`)W5^42<)>%?VME3 z(|0yz>A9#(_U-%vnxjx9DNWBKSb|4jPUriFzbM50o`^yJ#awDFWjS*q8psD(Z5yAG9y6kbg7 zLD$T6RRHVuEL`|C_;xnR(!6}wfgQmEbHKl)o1I?6q0kXwl6+3YVv-dA-(r4ikcSi2 zxQ8x@3+PjDq_GVl-;7lnn}PoeLJc@GXp8!&hW?m33(2EFgsP3wa#G-dI&{osyDHx2 zY_ZVIpr27086pJI~jTZ3dPjf z%F2pDmjlGY3``KwV@b*Ej;b7SY8Z;kD)@M?#GCl=DJUptTt5piGsBc#{D&-xI0c#n?zQ9@tKz&=MBoaP+FPowas@q!l zD!GJYJIN058LC=Czs4J^-=KmPR$t8R_1oi^_*bQB{BA5CTP)i-J(a=|QXKG<|FQkE zvLb@St2Y9u+~??$zv9tO`ngeN&02%078WG6ZKtcJmk}N%Hg!x>G*f4G$GQx2gGUI? zOjo-^Hv4t9Y7uUNuewBV>pKoerHBD>Dq-@gng;W_0#5-UfmgcdNCJ$1Uz{EWG~7A1 zVwZlgQENk!5HYSloSHL{xtcyvG^4HLT!WgeBz6YPY9lf{=lgbkv&72fOc<`8 zh{Dct?|f0$ov0M@cO3!Ho-#`Uu|`Ezb!_r?G^|J|#}B#cNW!B>0`xe;{!4C~c)=j- z!sqv?NtdQfS63G}IYY&aSIpXRyxMQQ2uN2>Wg3R>hKG*`)p2uT|f^ zAYggE^-EFqMHqKLAKxj0u@~nEL?v8~{$0LXvzC5itY&vXzS^WYQexz_SJeb39R6t! z#Pg+kdRL%`jsNCNz7J=K;$L4i@95k>NekSYx{+protSqHMAq!|V7~%URU&XzVwvS| ziA7IOug>{!!#TMyQdwDfYy4d8YpmatfQ@+Kc@B=Bpv-WpT0mjlH>G!`)3#c4YhJ)+ z9YBK#@ONaPq<{cf9k?rgGs;hY5NbBWVp=Wlr(u{U0>BnObbogfd#0S!(xz7U;|VK2 z>kmO$5(D}1m@`u{Tb)heJ=F_YxCVOW;PqF(B7>ftm&c{()W`bwMtu^qp}!jhuTGlc zJH&%3EVgaFGj-+nW>$*MRLH!=2`W|lua7_5eX~fMF&)RVqMEL^Tfkn6ABu0pwUjHk zs;ar8XF@MWo^rUs!vkw;O7aqj*no5byiF<$BQ1z0ZOR7Wqq|%Rp>w2NJTWJRsPAN+ z`N5xtU_YfXxsFG~qan5-S9K#EL$4*aMV)t`Z z*~Y^5bu&^=3oqN>`1wS7N9Tkmt?E<5HAECwZc*AiNv2A{GR99a(qQPjMf2msGCxHo zO!j2fau55H613-AZ!CK;YA)u`jwpE`I3$I^KbczWo&HKzZ#LRaWixK`d!@h>6@eFl z8l7E~?YQ~C$*}QDk-XRYY%?Nz>RMp0eDihEPX(%+kUOLw;}^8!wE23ArKZ;kw;nW; zyqcR`GrsPr52hm7W1CCZnT*^Az9$!6x%U6L04JZMp1W-)ikU+4vs_OGHI^}Fb8zql zD6|wbTRai9TIcS4J#9;viei*ed8JnDc?hALAr`NxFm8YL21&K>opzNFcbb`^t-@~3 zU8oV?E{nZ5U|)Wi8q`~8G0h<}ux`R>LG+o#;3LI;@yUe!W)-0Sv2a-k6Y!oZ-o_8e<`idsxyJOEEt=b91mZ_O|GfsgT_8IBdy&A*Avrov6Dh3n zDAQ3gF@W1|n7owA65xWCR=O4~Tx}|zNJ~X}Xz9}3+4-^cyatwFyc?_2M|Y8S2zU$C zboE)QSjpby=N#a;ZF!`i>2W$!BVCNW&ti}6Q%c>3eU0zJcX|rpA@{6$7Dp@WK0#4s z8E^cGjIHGY#C~|mC^;~%2$JZA+**Ys7pqoXppcBw%WVY@mNtl7dwSJb8xys{GWAZj z+Q72fSTn9hFhg60V|qkrbkOnZV%H&S*YxgL2}6XgMQ#gyY?+e!tTZmcK;)~rxPMvW zu+bp@VyWI-)&zFGWFqg@lji6O7SvhQ>TeI2)@#1&@TNHCm@o*`t^rR1tEgDnDJ$|` z3*As*g5sd|=)WvDvNER5Dc5kg%X5As+XLTtL=t)?ogpNx}^}H7pEQE-$|ePDNws2uoY3e#Xu>v zvzp02;%nCagUY{nr*gO{{0uKel}8C2)YI3mk5-or2Rc@<5(%o{+cvOKrhowl3yTNL z+kRY>;uQctn;ZD(AR?Ecq6iks*Lw|JmqzabfnkD%dy9%fe6HRw81g2e6TW=;*(`V9 zYUEN+3rvYd8W!nM=2(Po0FHq+@dPa^+eIOloS_*p`-F`i3+iZ=@|i=N!&=ow8%{Gc zfu(BJi&YxOY!cBt0gOj{aNTW>W3%1m_0ssaN7Ao6qE+x3f*q4o;~V1f6QBQPtj-e1 zC;}Uj>qKUET?5g3w3;8MwQ#=Fj+UCry2N@Iuyd%`@R=20Lj#y8Ag6+C?xPsE9;UwZ zY|L^G=G@a~dfTgEYWwjO5J5OnGEV<)cz=OfIqb-;s`X)>$KR2I z5AQ}<4yWJUTdWpgr~UapZS~Gcx)id8!-iroSFC@hOmoEkgqLb%Q^3h%A|K;Cm{Z8o zJp65bwe0JUczd7cO{ib`jl2EeIB|;RGv|eiWQ`}5g9rLy;qN3|BMn0JV$BEDW$m{M z*cS!2{`t2^I1GBoZpmrlZX!$~e`Y`IU+z3a`P z{O#bq?o|_V=u5~KMrayzls*bjF>%_a^1AI3kZ?dT5(5@LsE$DB3?dqNpv6y5UpL5O zgH`WDJxS`of<|!NF*z5hFsv^Nk_@1kQ1yCdfUCrsQcHco3N%!Md6(&4G6B;N zsOT_>MAe>d`$&YSaM1cgD@6LKW0d{;p*Qbt?yalGj>J2?=c6wJFCu_8fRTZ^AOwou z24CqgYo4m_&``h|XaNSofMcNc0rMaI(ndiTDWPpN^vt70t-|twfrqb9hxYN%|AW^| z?{X?-B@5*!YH^miN6mWvkH8eGppNiB={KT&^7tjT2)+`vU35|V__bXVHgd{i#g-8aL;bd9I@=@9ys`Q(e3*eB+?y(&hws?_F;L5&|tAW9pU)l{&vRE(R{9? z#XqZW!@XwCjwjOzb9_$3Vr#bj_5DN$28M)UHqR~MmN zEUwhbLMjnH%YAz)zS39(&TH9_8^gg4_K;m&cKa%*?I|n2X6`@^*e$>v9>&700CgIQ z4Zg1iCy;LWz!!1dE~BOZm>Ppnu)^P1TQVnqxKPG-~@1gCA)kwfzy2>jTcu+x$Mq!|=hbs3EMtdi0`KD-Kyr6FPNBtrD>XGTX~ zAW)+04}&pLWiO6{)z)gd`@Or>K=1}u6t1Q->zkTHCuf?6SZxivxt=q0Q6PSvT}ME> z1Q-;&e}(Wz0k_`#EnBD;D$hXP$h)Y0tl#qhpXsLX{C1fH$rg}tfPDb?A~U8^8I`mE zMP@LLLucW`*_(6ka9xl3Xiu!0(S?{l+wxp0+vU5e6a4wkXtEdq@> z#LH0vM!`y=u%cqtlgFJaF4f-$r?AjGRw^uDkwPZJfJqZ0+* zCZ6p#$-m%q0rCg*kb!mSW;D2$6iBIIy2_`&Ml6LjG}vrxj88q?Gbb#T?Ii|=Je=(Q zltN**(4I320$-roNe+Y{ys+5kjRHgcSrnoR$YR=UL@TzC1vqBV)^O;Q6%8p??g$?0 zem}7lqAMt;F_PcLe{Fs2wh+Gn-?>=Kb*s{q$Gcx2Eb0be50k?KGaa-P*#lQEEH~V& zFlJ!eb=x}|Mn2?s&*~~>sX>dg$-AokdMb%iQZ}1P(mEmOeOl4Vny_qxtB$1 zJK06#bs;=rum(owbdu9AA`f)}+bbj&U`FNCbGGg3{kteTl(K?;KuGZ~Q$N@4m2F~6 z?x-_Voyu<;Kt0$gCfKAEdP*ak>wKES_e&!Woh7K*t$8i@O*5QTF&#!JIT8Bew(x02{`2fI)s{t1 zvP@yY4Ym0B-f}a90#X)rAd5`X6HJQLw6?Npa^$p_0S^nX9)VW)Lp#ZHVJMs;pQH*( zbgDS+HRMX~R5>pWXpI?Vb^hgc*P}ZN7g%@ul{-QBuWb`_5O(OoQZr?4Wi; z&vmod@S9U2xhC8;T4T<;W@IK!^ESGm?7B;5tPy9}e;v1)_Q#lxn=MY#0BSAbOBE$` zm^?AD)z$Hsw5K7Tone=%VHV>DT;)^^m#`FZ@QXPgb^nUfW*b-)fP@w2&`+s*aH7A$ z3j>h2unYtG$)7W=%h1HTKBkv`9rNKOhckbPhv-ZcEA8d%p}s=hij+E>XtS^OmfPlg zZKE~)g^iSz^iv`pA6*zK5kuhTNZ}d)F&}XLv%paeh_q&RRg6vIoHTsuiS8?<_E7v8 z9cAM%m2fkinbRHimoSM?RXJor<8C}1sWlSK+T3Mgpti3UCTEXk4C?( zDJW)YXXthJTTth}K-H+D%N&|XEtXZc*-^;)ht3!Im_4f=(fGZ4p`G)3=U-EEm(asi zKFK&MZChN^aoSG1lVy8G4CD@!6RTz(QGz~~aKt+Wc}tr#!hZev4Px4fSDo=<@AX2b z)LSi$cGtQV`gb?x>T3nge)*B_o@!0Dv7;H(tsMNA?1MJ|0*?|f#ywlmsA5WKw1p7B(z*vai@wKaw_QYvFOx^r~=nWrC(Sa`<74#aO1DVjT<^Tl zISr#U2qr(ho@Q%_CvFW(8OHK^#4y9yHoK>JG=eI!GyWUs9TVaXLj$QMpdV#V)=kPQ zSKD?43Mojoj8n9LzWF2Hs{Hqh$~9M*L@7s)9RZ&r{oCXI`vK2F&fvHaFNcy3zk4wr znA#kZ3uqJo!Q-?CbisvDuS}HwOZ+?DbkUjeFL$MY6o7BKi?)2VkEIih?YGnVPl)`P zwl_I6(_V`>(V)ksJnNTpkiNcKfMIVc4Ty*qTr6_yK|IXGr=YgBqBa@^M1IU_zBNM& zu+{2=rPe%Sd(8~~PK%^t1e%`sWv063dvVmN!?h5l(h4VOXzZ4(aQgqQI8>F??l_rN z)3hEe2(&bdiB-wiKRlF+&h1_<5}n$`72TsaUZB(BO866jqLJbrXsB|ujuww8RpP-s$W4&magKJa%#F=_;$cAMxR0KC{(! zLtWP$X`N()^1@VZwLJ$H9ZLHO&CN^E$h+UDhnb$)4)8n37Np;4I&iH4qXJ;w5A{C% z8?Aa7?=>C8eZnX5AAm;B)up38J?9V*4Ql0>_9<>;A3+VfF06YA)s*IT*r^mYh@a8u zNX<4(i*?%K!fz^6-8*#f5g)YPSFN8>@IO>ZKXR11Nj+(9)^~5MpJm|MZWT*=_PFh$ zjOODJ?4^B&7(rPqoyETK;5}O9;4;UssH}y5#i)L-K7?Pbt8P-P<4$g@P>uT3MFb1t zpoO^LAlfe8xA++jL5xDe z!N@9SqC_+=6;{X97GLLrKE)`ds+5_bl1}VS{Xu^wQq?O>6JD1 zlKphLDbRm&>z@XBb6DLWp>+zjVKryO?%vMQuv`?#c2UFfI{6A|sObCV45q6r~}(mpVGzU5tjXIroYOS55)t zm^A5FHu&q)+iM2GJAKXXch@k51=cM8NF>S-Md21{UQg~^fAHsyNmf5?$)aqPRV4n# zH$d3_N5%up3@(LXFXFrlKT+AF(HNnV(RV5NlHTnTWNH2H>EhSs!#29uQ&5{=lajK& z)hjiai8R&kzG?3olJDQ+dNyo;C8PKJLGHIuAh^<&?)idZ=ZjIjj!%TA}V%A!|#{)BwX z-Ta#)e}~WbC9~XK_8Kq&S`TCY zCG@_)S+TNxB+ZPw?Lp9!!@ln1xs`QuiKt^67%2 ztqj1uQfbn>k$K>AW^o+8YXJWX3JOLY?!uOia(yEG%ZtPCTy#Q%Y1i;L%K9#FT{kdP zqH2t(uf`uK?l|xgG>BstiCeFbSN+mXAEg$q-E-TUR+NL7fXe^rQ32O1C+Al}gl!=( zI-$Trw@v9)0Sp848R3|uzFmvzrHMBvC!1N)=SOSaT7iywE_)izhZxRs`~4%wrIXYfR797Momc{wa+$ z%IEKaQ>gZN(}KE3fee~+es_j2CkK5UeEt2`hk>-~SgY+KW**E~Xe5kPCd#LN+rG=k zA+?dcwAb;65z*RO{;#hvU%X~xENt0;s&-GgcJjOj*aIp5mrhp%8#gdR%;!ksAC)|p z3tEu!`9wgXfrv#}zuBJ4N)Ss_-DJ+NE=Y-{;~1`aG{M~Nf9ytC$}J|nQiJ&;V_xFy zl6qOANe&xYlaH^y0K36Q#qOC+kN!>e78_(vyJNIqJ-`3dz`zaZIA>&Ea>7N)_S+Z+ zZpgK>qQZKL+_wGfirQmZ)@SdYDVxoB!spc+hWN9Ez9$>~+XG$yQ{-zwGCar`QiAzA ze~W6-pM_3jn`4?wf_k04xhvHleppfG<{8$X4?Z4A?^$i@5oc0%CvKum%+BkP-qItB zVCQD$!CbY|LIhQnI^CMWiZ>Fb)jUJZ@tIpidYHFDvIh>VFAFvek}$P7x6EvR;?2${ zmx-EE*UTp`dK0~rHSN~Qpzf&e;tyw}OB^q&j}^m#*uq9cNIu_@W_h|DNcy)F*M&ND zZ1>7^Zc%!r{C89`Re-JSaX1_xvi6F4K1eS>(w9Il@2D}Y6(IApybEm&*Yu4UK5slB zHR7XzxuMxf8|#zKov(`W(UVWhKa)Nmxx|7skxA%MI2oC;|!~ixCJ7u{e3@Ypf z1d8{(<{LNNH!Hrqj!fg8{w&GNN@I&18wN_}IRnM~^lOx9aZr%YnYd8P5^P2{-#pmc z9>4NJkCB0a!5A6ffVi)X-!|TzYe-O%o4sm4c{thIj9r>GF@-e*MIJN1zqp=e8plG9 z(vC_G$A0U%VzXOqEzcTXnTa~@nirN~hxdeXt8s@86a!1RNnyVV{uJ*#D}mDx>{&U_ zasKnaHtVJF!#bak^H_b8JD)9vRhoau0+v8}ICg>mXBjRxKi@O`FtuTN5+fTL4c5Oj zfxBgxrTLZ<6ay}w&kMT{UqE@`)F5fW1F>NG%-jIwR4CIDjbipIS5iKC)VOjvPsGvF zlMQ^G$+LlAy9d9=H~YG>Crc@5;`YXN%a9l$MZ(Q4UgPR%a8P{N#cJcibMUn|u5#u{ z)>$asU54G4M`k=KCONz&mj$&lJ_e+M5_yhT%f0AFLU!1QF0Eq&hoxwwHfQf&CU%!* z_O*;ZOSfJzpNiyf_S@1ae1PeyzTG>{v%fH5$d*{ZtSsj@Lg%r~vC$H^#>qyuT^=)x zeae<&TWt`wLZ^J_fSs?M%B%4t?{D~=U+mh+N_&jecIa~|TQ>ZpqU*2!E_bbZ(2E7T z-K4cha4oJ%!ducsX#_G||pp&&$=iyFU+wnEL+Q^eE{QQ)2vDZ%Z|##-&QK zYO9_2l<?B|@uDb!uKI?J>B9n1j_gfj*@rG;V>EOIv`17+`!vid4E z{;g(M#C)8g(_MHLAbWBFWQmetK=A}@%Z{QHL&|;(kcWjQSLgeS>B~lZ1ca-W?!lyU zeFp-%D(8nOPC9QI#}WT#1pw9!T%r#Q8g#DZBpA6fQJA@4&{MUZ=iDe%HZ;Bfq_U#{ z`-DJFC}uD+KOY<%c}1!E3!CbJJOA5X!0-=4G<3y_d-z3Q=E$@?hVJ*xgHN$6)4K~6 z$2F z$ag!gd^4lv8Tvd3oIX6dkZ)2e*c|Cb6Mppna{+$z#uz`XcqK^Hi?GQoy``R9T-QhM zDKtI4TJZ|yKW!GD8)9$7s+U}E=w(*Gr0!6V!Gbf`!aO_*-lt>S&NyeD|3u!_4w!ov zIp@zI*SuOQ{ZHghVa?vmeaa85CTnP_U9T?K^7P!gDcGu@R4Z2Za#@&I={KdaH&kh`3gIAq`Yl1R%*0{M{G zejaQ`JI>_NvOtSNksSe_7^u4%*Hd7Do9>XI`JgNHeMUcXXI@k|qFAuj*u-SPz+Q#O z_{Hrx9*;K%OHm3b32a4xL1ljn@uvlC>yLW!#X`H&De70;F!OyV+>=Hs6AGKU8t?~4oKj}XE zHhYk~YPPt#-X_7O#QjAXRS+8aiLEo6t|QYije)y$)r^_-qN%MVzeog5c_v}L!_**( zn?P6izDAyt&xpl`W$JAPlCWXV>A4q6zk4$^z@VaIqhOlZ0Zq?o82fj_I|A#7bTIDr z2i50uMr>hu#K}E^sQlYd)b0(GdE-dQptbIHe%HLL{og| zc2m|;-L1%u-~kb&?I_XvFEh|1*Q!|G+L|4{If##fU=U=#WUX{^;zltTOJfutb4jo> zl|@^FI0z&UAhKsI>_R(w|CU6-uE(i*U5663s%K>M6F9PPpI3a9mR(C_$@5+4HFQQD z!kHWLTmAcdcaRtb4WpNE=;;nsiQ$(3-~RRwgw1c4Hj!6$IUKe4S|P1`=?BB|4xyF{ zYR1-2UfE#aasc>YZex?#D!&QVvghmg6r?32!h(Z?h2OjFuM;MA$k=9J3ihTa`DbbPpYfuphk94dy zQOweE1KR=@_k~Zz#%b~0nJKUC+V^P|Or^;YD|ByK@$C93CAR7PF=uMXRZP|nx*znb z^rx?_pj8ahBFRXAswaSml;)_=BzdGY1m2#gKg@G0f4t21T=szx@k~ZtzmI>dVPhwO zUfU>_x&h4E4fQJL`fQ%gVMb~{2)0`bqO(qAbj?s%f4pd=s%O!7*gTR*_sG-O+ML+> z$H1*Ex4N>zho_hB&dDPW-k+p9+D`qp{Po1iQbT5?IKkgVna6#u>f@S{&MULq=3cT^ z_^cs$_044g1^bthA0^XLkBPH=yykg^s>6nAIC3Q0{&)6Jd`oWjpS5?{i@oufg&e1# zgb&XMk(rr);unX#7Qb&Mt)i!r>^V=$k|@40)`CkCD_n!>z0RCyyWBFjFZ(5{A#YwN z$j$bjP+~Dw+^NFdjpeQ;^8cFMBb+@m7rk=FlvnSbX5dVMU5luYtab3boSb2!@?dtQ z&77}RmM-a|*!4`6#~2px%o@!|ncU=(XEG}48EdIsFCCxlI-cP5m1V)|Tfc*!kbHpm zDrBZBUEY6VnDFXe+x(bybr>?Pl*p#}(In>68-_mKzv*~$aLU&{A9!N-FX?JkQrlk5 zIl9^r^KHGp%F=g)uH>6La}Rik)_866`{N0bkxXTYhMe?wPcr_okYP~Ve${wo$Eoo@ zSc8lqR#b<*@!Q!^=^&!oWJb;2bgLeA;$a&^yek}>H;38)qYaJ1Ez<~Vn8V`HX`s{s z zB!%|jgmVeapjwS1^+>h<8{W~ldG3se*g6K{4=f+ zcSfwYQv=G@3t9LH`jC5gFDyG>KiU1KL_YZ7(bRJpgw3Y!sa0HO($?+u3SCx43Y*pT z2TXgR4L3e-wDHQL4yKEJ&0KuB*&0UzMdi`lDF^;{Q$0v(*Ol)iC%2#B$Rp;~y z;48Bs0`r;N^_Hi?N!0YCeXI45E;!;lqTdW}IVr~%ct30Yv*JJaw3@rGBd}rVlWfl2 zFG}jDd_BPldzy$@?iPB%S4+#cR@|9{8D7-+lNPg~mF2CSJ;Q&|7Fq05h*Kq{t~?3Y zTztw4{aRc53|Ftwg1CigOB#oM0eKQjzuD$VIjbL8=h#C()G$0)uWv z295Vh-|&Dx>i`gbVDbd$sO*d-RLtAAZwtGMjnBf6)VWVU{52Z982QTmtAmph zI7*qrObK2LcMD?i5cvUE4x?lTWZVpH-w%R8cStQ0CJo-JtJ`})?o|NkXV$Ee+9n{` zy05PfI%zMdkF8Th5pO4{i?p12M4G(p-h@G?|9@gk=&ihNa(f-Tjfxr{tq*b1JyX_a zx6lnVHt`)k22*+)YIx{C*}qBDwr8sJ~`aoQmG|+ zHMz7hbRVC+jU%II_da)l_t(OF`**xKb;cCRCwcM0Zl$^_!TNbysm=66p#iq@FF}o1 zEa>|?y}(}Q)B0~#UuQkv+#d_kj$a7A>+-F?=RGuaqzX_2IB+NY(!E3tvB+U03KY`t1X6`!@BQWRSz;RaOq%2Xd7CTR${iphCRj zl~ZMj9f)`>tKBcB9B$jH7=&JM><-U)bt`AIe_6{iXI&Y0Oz) zikv;@3Rq;5Y@20s`-pxD7rAc~N{>Wktz3RunY%2Ts}~ZDYg=L1RU3@6@36*h7$960 zI@-}rRi$QfP{Fg_4w3ApkByo{QrTI0c;`{YsT+4UVN zmh}shea`m3N?yqlIkeJvyl=D_3qqtrtkS~V`N$?>j)pii@jqu#-|lsOK_8M1In@8T zO(!A41a$LF;iLofyoQe9ne^TdAf~hS*62;-;N@D5$RLBIzd>o%xIVgs3lNczI5&WS z2&Ld+4aaQ&F5f_hW>oe3RAOS{LuX72J2>)@ydImljm&)3khNt>ZXsT0(C*#-BKT%i zYf)=2&whv<+i>$L=}ik=x_81sUSMwuHo+j0h!ajO4x9OvXOc?&-%f5m%@mIrBAn&W zZh0A5-3%Az4ZPPvOT_&v_=KDy{TXG&1aqJH_-ZG|(;PIhG&?J?+v^C63POD*GAO$Y(<>0BsqGe87JGxh9ZP)iJ4xS%x>GJp>@opKbFu2B^w+3@PE2LTjw5l00v&mu+qGts#0FF zHSmzcO1Ab5Fc09`l-)?kSsa-^l-r__3j&U6Z=M#g9N2+f{-f>!%7@ESlpSR)<{qXF zw$jMm*cw=^O@lRE=ANPJEMsiFjYKW02Z>wi$3RosAUqkkE+_4%>hcJTF0}==fL2C6NtXjT5K&! zLe&zv`|{k2465@z;XZ#G8EFPieDo|_lqR3zC<~UQU~&3I_-s_2spzTLyBTIFFUo3a zqM%^~!gY|Fc;c{SRa(kK6sN*Hjg!|-AGdz?^`;S^G(9=Gt~+bCP|P5*27U#ec4fEc z+ZL6prx*S(E@aMZ?&43;m|l_@`1kJ`kVTYd#KAp_!s#ZXB-HWAa*J<|fA+i<{hPvX zmh{`Y3A;MuSs8X7kU4!ZZ@KMVF`VbO`c}aR+~1V!Ks5-M2{h|(8o!bS$Y~Rbk!O1E z{1VG+$0W5v!uhtuXXnBNF;|H(hw`|In3MdXvc zVZ`qkyupwB&@od1lHcASVWYsu-+zE1Ev&S4<+gv5?z{aqV?wnF3y|_?({4^NwJ~+Y z*njp>as9Az#XeIjsgC$vEurFN6sH)z&)R$B>h?$T00eK(v4?xcr0=Xc%w+cE>Sp|j3T19-fk!stLbq$Eyqu#%hqHwC)_m25`9*g>AS?Jg>uucD4rjn<5W)G zE1bXL?@_bma7~smzl8Bc-Ta@_;RoBPQI#!yH}~r>)?2-$`?-55#6_0TJ9!Q4LqZDQ zR$mo`t|&|~6Jp05k+L|nk|FX&pVJh^cZO<%3#p3|e#+21)7N?Gj={~pwF^PkhYocw zjSV*{I`xuQBh&U5(lB^lWghaL4*e^-|F%3ga^zpP8SZ7Tm8n@p49k5lFKx@5E< z^}%KN#ihR6u}8Wz+g~@YA?@w$ofH|EjE9y}Pw;XIzzx}B5xQzn!B!nLhpgXu zD9)61?cAIoY|10beFgZgWIfMW=_Wg(X*{M{SfOkoLrylor@N}4eJfs~J~&Dh@_#4^ zey#C0CdL~hK)VN(6~Jto$2Y0I98ulT&e0}mbZmH58kgB)2!k!d_%+b_waIkZh=NL} z5QlpON!%$$!aQKe%aM6@7VMR8)b8D)6k7m1z<~qm>g=RZa#B(g1wXN9j*<#yarnCq zbUEN(REBJoH-w$wk0pSe2hfS%R!Rq9wfHISKg}#?IZ^y6n_G^d+Ejvat9+q?ErtgT z;*N5sBT|QFMzuuWEUumZyryq|mVm-CUk_*_xn0-gAKCVrWjFn`ayF-Y=PZxEPOV}4 zOy$Bvm@KU>F|}kYa7EJoX0Pv-aqQ(m&q3i`JoJVp?`yZ3x^>^FpXxEUJX;H`9EY?E z6@!&m?}TF1Xc(?*`DhbWVf;|Z3DLvu{=1~x*ufe*V(#U}8nVHIwEoP=Tr8G{J(77c zShw+I@DWj`4jU!eoKxf-W>c>Ly5t{CUNhEWN=!^lW8w22^y(w1bFy2J&ZFG^a~39_ zw_`NK{Q4fc24r;nLSXXF{K?miWb7?DjacaAOW#u^rLf!EeEV8u`ciI+j>O1wTI{9* zAwSPB@+)rNA-VHU=bKvB{P&)-TE$32UTTnsmCR5fm^9Eao)dkTZJtd!dAil5jE`KP zrog>W#l`iF@MGyetp36HL@8ml2F$q^O6MO3xaFB|XK!eC$rvk-l}X2hP85It9uE2v zDr6X+{pis{2ZWwuNKJEDQZB~?YM50a;A^F)ARE|eJB3LSv$Dph%5es1O8?Wqc*2JF zQgR#MsE`9ly?>xKE2U6RX1?5cpYx_*g_V@75(6$3Kvn|T?D_M)JmYa`bISz>QiY=^ zJI#!d&HIeyEYO9nOts=K^!%}UyaQoF?e^HzGDp*jTVkQz%M*QDEAfEt(z&Ef(d=RU zUicsH+Kj<2%XU6;Rl*Y7=bc2^%ctTD{~t}~0ZsM)|8Ww^Y>{=TRQ9OMi>p#ZWn^ZC zWUp*pt3jD5QduE;XKxaUBJ<+fT-U{QjqLS*-QVy3JIDE+Z+*Wfx9fA?@7H)fA5X5X z$D{YwZd?06_2Qi<;56nv%?Lm{s35;Q$d;+PqYza4+M{Q?0DshWnI#~tz@j&pApgK8 z^#po$=d9vJZC%#3AHDCz26<+YHQvnCnqDaDc0#CVt z$=K@gapz&NuxF~gLKwdWETUaXBmppqbNlFqmL)aXx>m`F-e#gf*6ENgyDt$ICwNBP z3v5;h94JG9U>wOIYRRShU}xa9v(uo@9lnOh7d?rXDyf)_d7C1Sg#cEM6GI+NT_2?C zQQ7-9@SIpDFUq0fb9Jv(hMZ}#-v#iGI>xgoEm)7nUI6Z`LjAP{Kc0 zwb*<9=V=z+o^qx7pVl6mp^#_xaF=uTule?mW$_&>^(s3${#xjMSjf1+SGE(nCyG_iB zK}u$qfw}Fg(y`3QB=Orr1I1@g%nGZn}EOD?+JnU4Ej(2z9Cz>|o$NhJd~?(N6&ot=G@y4BSb>v@Vs@)01vdJLwjZ`Csa>^|oCm7++pE&p^F9U(<2 z1hP745+sin_`Y@fNcr_a_JqCJE(h6vTy1jg^E-yY&nmu`sqsQLE?{jU?Bp}~jvWDG zLfr7{?lWH%BOd<;oI?-C?rrwfO;|fYamTRociyr2)%}OpDN(T9g1PhAU&9Vkln&{< z=_g;Vlk;HaOrdkFNs^M5PNWKHZGkgx2Oi%dFa$qME{OnkgFrRP1yA+foNoH8l(g&9 z_*NouMP`V2L6A_4-upvq(VvyOxxA(+94xlsD~ZGr~y_Np++5sb)rYURv?{(w=7$_ZdmrNnIDH=~hfbqS@)!RH2DS#1tQ9G{RkiM$SCXTJgR5BvhZS&yV@y+-(bLqkN1|K-G; z{d%n9{cw$D7VLn76u5TDcPEg@K-)-;v>EwIvS_b_$0}F95N19t#9NR|x3vnYa2uOr z`US>Kf3-CxVSX|=G6F;qkDAZkW9cm(^`jZAZrkoxaYo3)xrC_^NPfO47z>=UTadE= zL<%`hK8}cL#Eu<50)g5?mW!+*H@PIO)rrmhGir@Wx)tn?5x61G9N`=E*Irt z=53ux&=h`zDZ@npOIHcq8sJDDhU?v_iDI@h%MJZpU=sc72Oan^&&+aHq7#t%t*c%-#Mc zItG303EaWd%k3bk~NFGaiv+X-t?TUI(f zx_5_2?zRW7wehjZ+w2MZ6SP-q5)}i`=sm<}@h#lTZdp)RLj}n}@p9x6j>^7K4>bst zA(^mOShvBE1n?2q!7$&_eqde}sKZFi`KdKY>vKqbK)2_V-3li?))03o%1Ff$b0k%gIMi%EpQjT17w?2M)uN1#poZ*q(aq306Rt<&wXLX|F)M*wxeHE8~lw@rib6|2mV>n03!<)w0n z9~Dh3cRzMFRxEj-vZq##1vbjGqtQBHf=o!2K68t0qmQZCBu!i^D^{9%dqyiKCZy~} zMU;`1=5AhSnue4K^Xv6r;sc1*1|q4xYxuA(oZhe!buhE#`s0}b`iaF6YdyWcqbM$H zk5XG>r$8rQ%@=9!d;ik{=;9a}14|}}tdbWzYK&~zBx)3xD$0tzP zv<>s8(mN^bZ#_|%XPDZ z7&BKA3c5ABdhGbXgj0tfAe!r$~~V;wrP>N2wr5Kw-fuW zs-^D5Q$uCklKJ!$XJsIO7y^(%tyJFGKh#PM-f?JkZzB_1wKWuQotL52r6PPT)5sCZ zZu%RN(p;o^@f5qu*COT_df;V%(*V9;WtrIQ0V%*0oNr3aVHOQK#m;E$-2Rb4Fm_2t z4xCs2Jg+Xk;697K$S5;D$izCX{=kGZgO~VuC1PZ5ZZ7aj(wg!DA41m|H;j8m$kU## zT1rh}==MlQ53+XDd{2=4!D9DChkK^C|Bg!R$#&_yD@cai>}WG=M(u4<$yU_5O=7iw z)r&B{5;tElWA0#WV$H+MmPa4-cimY!FzY3w)VP|qDVA|bqLG2iOA7==q+$uv0$Zx- zZ{O0057vSO<^k>sMf`^qEj_)REM0@^&xI8byrgE2#sMj-iHjQq9aQGt`IzHpcw#beyyj` zz5gAEv2`)`lHbmH_^BtJ)_YT(|uwtM2Isyvo*gU)gUQ!84GeS}dpt%m$Y) zUmhv=1m4pJycYWkfzog!L8+PFDG8m)g6&XJ_XJf zu*3i&O;#B~8|~jfjyD0JA@tKwBET1neqbL?M)oaP`1v8gIz#rXneaFRWe3(^?nneM znqYl2MLsp3;^+!Y>q4QUi+irl*ge>sO+|5-f@$`8b0NQlqw@P!Qe?Eo`C8V7(usuH z;I&4MtStsYf!Y`13&=qb+X_GDAXapmCEXsonWx;8d$qu$SiGMbYqhOti`TyF$fJ6? z1M4SIWcfwnv5`CXLd|zN3@yuzjNl9W*2P!vk2jUCXr!q)nxWO|+Sw9$%$sPP(+8z` zWwOtiF~0mt-MhWTKtw$(kSJOR+??Yo3blX(vq&Km5Og3d9$CA08Uus0CG8~Y^78W8 z2UGlAUnifps&hCvB562=`|f0i#`lEpnRGR#p!L)HJFPnkJ(#p+=O=URvK|$eR;Yck z;H$rj3+7OACua3_tnx?3wI~aFb}mP`Yc2k;h&A&Y;CSO0s%S6Yhq6s3`uMS(@2gG!2#H!z<>j|4Lcp9zkf*o*c`cWgZFrZg}nWV zLAt#Z%hzjRC+lF%$Iiva#}^G+|9m}@TZ?^tX8@{-y z%c>H#jWp~z(Bc(b*1e%sEI)2tNHEqKQ9%eDJCfNobnW(bczKt<9(#ucE^$NGH6*cZ zAi7z$*;*K}ZMyMh;dX;tok4;HF1X$dpIje?5soUV3|oEaSZpv>|9&l|Yhk2Y)_ONf z#>366SGJl(Y=`Sp{guAm*sdZG!@@{*tYw=Cz6fdKzPGN}7GC+#RWQIZxj#5_^~cnR z_`_cm%<07ix)d_8>eG+wn9O|8PE5(6E#iGnB;>*as}~uQBZGq!v-rC8U)L8ooD)mh z)3%t1xd#O;tEc7#ozoZPJT^M~eQ3j&!wrJEb`5mcw#(h@>gqQMbpvwFVJv@9=PX{O zkw#fx?~J8f@7g#$$oM7CrG(mB8GDp^NP53gfhmtopu2|WQ^V8=7zNbqkU zok@q<>c|41JHaQpQ7&@qxyeK*?vM2NkL@+QN#`mE4vg#3?7(J)IWbw#Gc)t`+VA4S zMIOdSI(7sHTd8;|XrJY@Ds=`vDTm$sbW$+-&d~-Lso;2SZwi24kO#+bAU(x)KmLs0 zC9-y!|A|(g?ws2&pZ%K7tw#`oxiiG`$hgfi)E}%DP6M6)2XH&VyG3OI&(KWU?8g&< z(Nf_()4QQ)iiHje?8b?Fy_1et^8MfmaCiVCS77=#hYo0aV(* zm^s#gyL{R($!S%Uj9ixO)O}=+ST34?6*A0h;a~)*5=Dn;e}*01$ZY5QfX{)H9<4JunOhsr0&2bE@~1(4y}pYrpL?p0NlMKwlFCd;c5 zvgmR+Gk=z)O_RY6K#GSq0Q4;w6j5UjAfpW=)W2OnsMDwa5qiBrZB`6$IK%we1kZac zzkCX7kdg{iyIFD!ed76~^7hQ78Ld~bOiVq|>b^biDCs2FPQJ)Gt%Hv=DdFPnRJ3Q) zv3%F%nu#yTHh(AoGo;X+i9$~KXvsJNkywJm!t3tm~EV^&WvP^)K^d z>s-p16|u-c9{aZ|Wl9TUVaY=~o4$pGJj2%h6;}h@+6N}>GXZ}TJ+tAo2#gGIWsq#; z_Hzv4?p37_rxLV;sU23BlT?3|{i_mf`mSFEef;K%Pk~=gjKHT#?T{J+GMErb!US2j*6zUC=aJXo6sk_N90?k_uXBBoBH-+F@m#)u;0KurC!B@#dP=b zEw#kn50Ukws@1`<8B#^}leM`s&`JnKHD==Ju8RXz=J>ZQZVA_FTet6Qrx0}=vOEaJ zD^_18WL!o4|hd?T`K1BL-NM&vqQsJ+b0vH+arck6MS(LC2Thm~H)D`WrQYSjd)nA-7aX z1&1533SsL3U*Iua5@s>Va^HTCT?Z@Xt<{aDui@>WFuV;5SqY97N9fMU{(TS@dlSnr zWHM{uW!qbpr&tUk`ZAtoD2oare)lpu5U*-cs@?drrVsjJa){EC5(2|Z*bPE!te@-v z)pF;j#^Ro0oG2gtsw}tp+DQsvw4e^RyU2YuC{;m02F`#Rzy@b}3nx5e@+9a}B%J8q z9$r{C{wfnBqYcZuoM71_bmfp&UtKM$Pq;o)N7nD0nE0FWA4Uv%`zrbL^+G4#@BUGK z#3huciMCfJ>q3Da?(<(s)#iHuts*nufC@yL_c2u?$Px^K0IPty8k;>p^mN@=dWRs+XtvXr^W!7R!sQ z3+=QoID|LJv{3pjKH2XJWvnF&Yq!OF8Xmji zJtFH#GrXZNPNmkxPEoPncKEtbVe4Fhan)1;AH~SS6E}*c8}TW4q9^B{CvJgp{K{V@ zuX04dN{U5!6|tesq7xxM!oXm-1|{B_%IwbvcYzu++H;ng*eN(qN0*H zh2*f%sjAR=HOwUG^!L-x?d-}>iSESDcBL}`>Df4;@?=&{!vn_%!iPhu7x>)e1`{g5 zyIUp^*9HQ=)bIyYe& zNQtVZ=We`CC-kVTva{sk`d`b{i;0_!=MH)|T>V!yB3AElst9MgY2h<^;Ha#4c8B>K zupc@NQcq$(-D@>xA84yDa*3Fi*>2S>eqJ6;(s`jsfGrZ_){idTUWGimtGA8v_1sSG z^&tjlO$+hQ6JQE6vTY9!DvUe}H00fSRweFN;NP!TC%K!t`oAOP8gp}V)9m=|y#U9r z2=KO_IoZ0*pIKgRW}|drXw;zaKG>~iCgQC2`lLh#)x)UrBWY1 z^iNCo&fUj$$o{TMv;ABdtSXkc;1FeTF{4|@zx_(ZR;;`h!fyVxCU;t^QdoAZnbE!x zCVwE^u}ImK@p}>aZkuM9#{eNgr!C)O2jqS2t|*oLJ`PgZ{m`ns=GKblA0dj4yNd?) zm_2G(X+eO+D@?Y-~+a1k&<&H}Y&fS|8_;+>3qIH;I0Qn6_`lHy25|C_f? z;*NpUMNG_;!h+5>89l_WP%9C~e*cVs9A2BZsr}bvKYXCIjhEmLTzw^VW*C))=hy4; zacI-=qSH{nH=!{w5a>U??}x_T=#9IURZ41q@1F3>i&VMqiC&A<|ANZ}O5Oo+ge$ll z|904AafvHeZedSz?AQ39*oF`Ehp}oOYXocmzXlCaW9uzZzLYDz^D%|RVb5edJy4}^ zrG)zafOyXHJD0 zs2-3^ATWOgUR5UDeKJET0Rc-Jn6JRL8u%zO;7M|-T~Wqw`4H0MmRrR9PvX0hRlpDh zv@;NSyKJvoL8A)B2(|R*<&CkSNN|v2K%!Z@r^a+Cd@Tk(GAA7k_kiy5Y%<#`~ z>xcr}WFhQf*nffB*|)Aq=`IjeL6b`+1`D$mc4VjF+m`*p5A^uxZ_p9)P6`;p_GRUj z7@E@Ta0g?e7P-Fe0fisvD`^|S77u95!070c)_*Mxk;wUDkB&)HzS3u8gpGz%96hO@ z$`HbV@WbM%k?msm!i;UWE-JlOQmMW>#AmSfASjNq*o|;QvJTiuVDBU@DftR|b67Q2 z7GuuX&9K<@4fN^AQ)NMJ2vB37ZU=W3Y<(Q}Gh8iU!-ae5bI#WV=KcAuNGdZQ97}~0 zj10tKnFKW|h%UJRG7e_hj)r~gYbIvPskVR-Ip_N2{qd+mDE*+PgxX$MM1;I-ZL#QP z*O^<^y8U7887zbM*;Mv0X0zT?QRf!-Ct6>HQLG78mL^ z_pzbT>*eZ_%XW$F&kApg=_2!rW4a!u<=_@RT&`c4_?VN>x2xNYlP^+6>mE2>Opc5e zY#ccDl{B#3wVtzS%b{8jUtttu8bf7w&MG-ppTKU$p=uw2Z~St;Df8chXkA>g`^4Y^ z*LDNQaL0=sj}_sB#t(>FX^K0%FsT3y5t;Eq)@XrhLEX6eWw$#=6K~X_ujoc})R(mu zF?c49fv%zR_~|#dU>@Q!9U;y1FB?mQ#EI#>?KP*ibIg4i%^{%|Y;z6N67hEOWy)82 zf~NBXl0V**xL4d?tmW{d{O@4fYoBz*1+9_vR$5bSuFT+5iJb0C^XT5!I`-m^IN9HR z3C)cR;<$wE`@Xas2YnzFFMf!VS-|e~J zHcYcHQ{H7XdLu%7K>U&IbZ(UV-QL<0)1b*od63P}XH6h|Ate}1bKK750rx%m)JQ}!(+sDah_M)a(qO_)?!71~N3S+^8tVPdrjeVn?1`CH z8vF3)3GD+F4Y<8IM%(oo>rW>SOH{YZ^;Oywzu5o1E8&|kz1f&s=!+Mi=tFJF3J1*a zI_ckmVjMoAH9Y>_m^#vai6Rxn-fW7}mea#b6qn7F2n)7k)7){t>a55shoDe1vc4CQ z+o{^4;dOq?ouUQZ$W*9n$x~>XK`F=dW5xaVDyp4>$G=Sejr~JBFFvH;S$ceauf?&0 z)+-MThp((mT8>|9C$UT~qfDfc1t0Wt<^Odn+x{-I$4B`OY-~B)*vWG?EjAc>+}7DH zML|_-y0Fr{xoISlARIg57p1szlw!i9Es7a(F^{e&aAc**-T2v1wRZm0&~d%59y65IQluDI7@fmBf;D-#Z;)U=no!z$+RG9Ol_RR3j2}W{e!@iANrZdByVQs%)ZT2 zF`A86)X0MYy895r`01K8grCFU6n5k;9U>JIAh_^`1A4@XAyP!US$_XtFCfI>{3bWd zFzzI0$R4F6kNi*bsRP4t5~hk2*oSngf(7@EgW!B*7mRt`c4hDx2C@LTz=T0Nh}6lWGd=)oX5DRLiE5+uOceja z@#;+1?w6_I603R<~=9g&u1FfP&MTe)$eNp9%RRa`Ogf~PB5JMs`yHp`B))@ z3-;T|1RTf%B{`Ukw}tf=obDGuXbP^uYsT=0l9irW+DDYj`4ZLT(hPI^pQ?)$q)$#x z2F3ZTN@W%XhtW(|Wwcy<|nu+?0FS?3yTlF8E_&e+z}{bY+vE{`Ya z;Peq7L9S0FhAXFS5ucpy?$<>-Sy)`Z(aWz~Ajhed9a_fGzOG@L^J?wQ>PvLozFyUC zKxgNaoV=e;SEAR2Z&k+=6iG`~5^gX^7wfaDB!NrVc7?fNO>SlJS{HaEQ^!d)fwW1o z=69jzfJ2|`NFxs{U|PL6^q*8D0QCWfTCO?7HUsYU&wpmGw_hlKzdbK`C>7x(%*n|q znp4_uCtG`SJLg|IdX}rC<{=wb69P5NEqQDhfedY?koole3a;dbq8)?z?v}qvnv|V3 zi*dxA^1X1!KH2n;zjmEZ>%(sQ&|%^{UJtJ426J!d+h&q9lfJ^_x6BdyPu709WRoA2 z-u!Fz9FB9CyDnq3eRZyGtF-0EUf1aNJs=2^@tflC>|L|&1nGJU`()+mV7BXRrQ;-C z?kL{(zaGKl#=O`pF}Y0%D?8V)TE97oX>FysP$@|i*@av(veu8>O@h1z)(Dlp>w?4B zD$=vMq-)2H7%{y8XptY8p-t$`L?jVFacyTS!Qqs@u$Rtt@rjAC@vUqf4wsL;m3NZV zkhX$X+8Jn69^!*oV=oyl`kqgGC{{Ebm@YgsGB7s_N_on(57B%S%qu8VB$!Xg zRyyc5iJn;MBjRopFKk|~mukc)c-9ZeIz|lGxrZrNJfJ&VaBO>EkZoG^e9l@i48K&{ zn?Jb;0MKWswZD7vZ~rXWX%8Zc?F|TBU5hVbxayhRz--VNA!>o(U7WL_PSRvgrGl*7MX)y9P&H-$&h zG9x{A5mfHzg&G#6w`TA}oqHUzxeZg$>|001ONeLseDhx1@!DCHp2`Gz?IWpMLsIiujNt!Y6HTdsG=qpThgg~Yd$VZ_ z-A82UFT_v^P0#LTeJslIG7GbsbBNO|XdWg~NeG_EKjjbqR|uY;qn_!Xu;U_>yZIHwcR!{DmNkL7H$Wh z%1^13gKr*@rK($7GT@~n2aQmLbOwU4DN{y>%~H8lI83Xxe4`Nr$f@lcR>tykL2c?RdSkVw`O&31K zp#I@u4uH&oS(w})K+}5$eShsSMxgE0Nq(tnwKRLP#m$om@^1nL94@f2H~9hPoNtQj zV8>&FK2B800s^4{zuBa;4*V9{`3KN?G z1WpSadw0dYCmOo9M}L_A{r4d2dGmJDowD~>S}CeVQj5jbFZbcH^Y^-^JnR?owNoFp zKk2uz(=%#}*g0Z54xwj()NvJja=o?(o{njhRooJm$4cg~!VqjS^YW1MQNd zRjE&3*1kroGPa-|U^n!fdw z!AeKc7I#fE+rn8p+jUW=wZy-GS%j5WkooTy-WCHL^;ogo;_E)=+ul6YTlpB_4df3@ zICGTUZuXv0cuum2XSuv;p{-GA#Eyx!|JFctJC(_c&{6c-KuEgZ$FYqj{VgWR@}fvs zJAmaBUM>SjdY5H9Uf#MOXRV)2sZwlTh-ucooH(!#X*&myd=gh-6@yf@VE|Y3_Xb$c zI(d~@s1^vJltM(W%)*23TgNSGTnTGI`M_*-p0&2^_jy`Ca_n7xQ%s zA5`ZusXa9JN$r~aBEKYEfk0BYJl(C$Ax08=TDHSmZaajOG4c~xUKoaFp?k~6d&bY+ znl2F=T=}+k3m=VqR4R(45lR;3?nAx599rUSvRm-2MS46BeeUq@239IZc+#)mUdC|U zRjNZV}}xh`bT90sJbe%w?lR z+!?P1P=bjv1?c2h=3!dDvsBMz$KC5Soi8y>j6C3DZM)|MAhhbWv3AXVFZVw?Ton|? z`y5}s`c1LDRk=pA2PqVMLByy1Ei2)oW-pt~G{=?v7{AO;{~I%M+7u zRCn_w0Uce}2j?11XwYYSPe3@1nX4@Zbg-=;novvsOK^ud2qc7f261vc=7^xND;o}U z6$Cg12=1?WORRoYqlj1?8NJ!s*T^WrHMI(D5XceF7!+CoB zMW|C|FX$P`(+%=52y{ita~X7(+b%&dOhu8%>T4s4g__u9_BVU&-f9QAb{32cJ^j?( z_+jQ*+nac87!~ao!U@~Yh0yu^=YE?3BqT7gDlq8rs=EKtoYZa6WlZN%q)<25-1P&m z6kh!9#Z#c$aH|O!ls7i@RKirFmoQNEj_6=eti z$v}i}30S5nh%xaf)xRAmuyF@VCffsK)O#)^#D!G1Y2oH}8Um*Pze5&JlC2WpeYLc* zvYJR>%!ruey5M)r_t3=;!50@dDa0%y#`_IHtu|)Gg6s)qVjY8Rpihk;Yx{yj9m+~C zqCZ1AE;xOW=rXgJW`x^lpq!n9;exq(2itRBLK`?*Vx5MU0%~f* zf6iXMfbX0<3&X8K4DG2wAyjtrFO1k-psfG2J?Be1>xR^)TTkrt_$zCJ~wn|A` zZR~C>!76tY2kdCLPWB1Z!huCaBCB2=UxiDBDx|}X>1pStZyidU&#fxK%|%=EDIec% zhwKl@TMvIBs%CQc4+fmnbiLWr+xlWS9L&9}PB&zIJHB}9rk$y4tSnj`BLP2K*LE>i z27I;PfnIdkUIKAuYh_WUld|W9yXE0FQ!Go)%&_7?flOzJs>p{jQW5$cFdDKKdMciX zY&@w$EfU?@2R#=OE+ktkpxPo^@O!^gH|?=`T;G&$<(pxURu_tMms&NsZ4;G{T@(|2 zmQlo1Y6|o+j2=7qG^!vL1 ztock{&JGST#?9xBAe>`wfG@Rri*p6s1h+-wsEXbL7HW=1Dqd#D=8;v+VdevYy$Me{ zYlQShw7RIj`sMdbil@C+xW0kcFf|~o92clvJC4VCB9(^&iX8fHSm-OJ>aHT2=|&jO-*@TK>vZ7;Hz!P#xBo*ATp z{w`-mF%hfb-$S_AJvZ<$N^I2QtP_);MeeeR=V-}WDK4sm&B=2u2;byL9umgmkCc($ zhxLb4S^3y0x|+41&D@h8t8Ex90{ivMCfPO@olSjFWf*=a#$MG_y2Imvumb_nVy=^Cc zbX-L)wQOkKtL18Kr)&2Y+5_uqJPfcGz2!Hfe2=!3W3Y7p{Bm(dp7Ug3KqiDx73 zn>Bf-FSEY?GFk5HmBIh$t7Z{JGvD5?zx_o&s{eiVi_^GcH1XZnkB*nL(w|Sqzo0|i z^Zb!fT={)$(@t}YM*fS|Thz09T9*@JTuUO(a68m+=&}=kD@smXTU7+oHRyH8iM!;L zJ~-#`$pPGFMU7oTFH#eCcB;eZF5d_F*nbixB|sQP!-R-zu>iS8D>-!y1YvPz{*XUq z-uUs0pH@m&;(3m3wWe$zRaH(p?op|Ge0p#jt=~#Bs%nekR+vvXWye3obR3z^7IFQH zIsV#sLuu(tV2x20HXI;fEDxwr3J2NS@ZG@2MV`5WSR7{b0S^kNrJu@rofD4Lqc%uL z{w)U!$posGoh9%XOT_=7Yze-^9aU3(?C~8pYKokfe;YHeKkvLK*tD>)0M9*4&O5~$ zOReEoPMo4`RD)O1E?&369w8TftnwJe@q(Y)b8`>UWP+F(BP3X1s$G?M4=mmMtYPF2 zjp$Q-W(p8%s7NdC+u8{)i0imy(49=C^zw`sTc&!7B69qjb_?+v$XM~onp;*)#p+pZG7MOu~sRNFz$`&Zd_E49OwudO<^+eSub*c92ysPanMX-4-I&mbSw zG(V`a)e@e5Rw$`Fm$33D8W3s1RGu;J8AZB2U%lf>i|8si{w*5zPE99!-k;xFUoo%4 z_+t(Su1_`>)|V0OD>(RKxDAs9f7LXu<9^i#!{iFDmD?!lfku8yz*<3?25SRDojL#=g1;Vaq>eX4(#+@A` zx9{9}0A0Wu2{t-VmY<=cHm-U~4SOapIg-w0xBTpAkTb#DsanECqS^%!rwUZuiq#u1gB!Pdn{;~L1tloamm3>Djp^|^AzKnes8wk30Oj7J6bRSBYg4# zJ^l|FCjq+*QNJZnv0l4J`2w$Zv}vHzrEXTJaDT6hH%YAuG0gCHHD5?XBS9wUjpLr9 zYb?jmnSgHwduhIT9Bf2i{raq(s)Ca^m2%OrH)o^;{4wj!iMa_%pNEH#?+s{ID%vj& z;M`iLIXmc5QL!J(=h`2$usDgz&uiL=XB?zUKK`A( zF&ZIYnk{6=_Xg|$1zD6&9OPVuZ5>`ryj~xY+PF*7{$22`?Ete)|7gO1Vj(;;2{3^P zCX3E3*=}ImNB>LX@iXf3U$o@Gk{ug|T`b9ei@*FhB2UMfJlP`n6jk&nD3Cg3L+!Dqz%9j*mD$^E6x*Ei+Sa)w)ZlA&8MmI_KQgHN&iaCe8UjXb&R zR^dU&cqavZrqR1=ebr`QoV1zfnn1#WT?eL_P&Uq7n6Ko0^-8u>U}WwOMt<0V?^R0D zZmRnE1N}>i03;$kA_px+ay5}vCY(-{lvT!^$NlMK@4L2G^F}AWzSHyRhZv^7*G{mztw*5}Z#DtwZPcA0cI!OVqls>89K6<~{ML)5t^*kI$ZZBv~B~5;5 zeS~|H0I$n_Yh8`{*pbc61`Q2M(4|7DMGkNqDzWY+dV;*Kdtsd{Z-xXRdYF$qrFlbj zPn5?Q{y*rGu+GN3)VK`rmT#BBtyfDt26LV}MIcdDpWRehv;?Q^7*bMZqL7G$JiWT< zUK^?Ck?>*fI=nW;98G|*=< zu$`xTK?KDc(!xHY!f^$!O;Z)zua)ubcEfv5h|)8w!gG_gw1c|berFN`mYKy}x37Xe zSB}W`OA3J6kFUOw9!H<kF;_~v&k zM-?3dvb1kI)4dqE>^ndO#Ea45CVW(lf9=hBq86 zGE|QR)9dtd848AU!o4)!O2N+34KF9w7Hutu5bG?8!cD|iT1j=Z~t#djkAZ~Pj-HI6;KHPS`Mh$%d_#$Q?U2~!h3l-hmTSA&QIXD}>|&TQu7BBoM`xYH!bL zG8Ad!Yo>hqLl&!hC7pa24~?2-Fz;6tV&hQtl#6*L_rr3D#olk-B5yGJCVT9>RdI=U z_$jaT$v{)7y*VysGHL*oa^r%bPKLq$csm78T?{RDMYA?FQr?kP(cVa;Yt|3L8-`|6 z!&-T$nPPTJlZSbBxp&pejFyqR&MUPjXT*l(w!GT2qh$m)!Dnc9&G5X{H;%fdzqauU znUV1sqNVP~gdCW?t}T2fyEi_4a`hEm4=6XI^8I9zrkBeo!~KupY_8DIVdy2toLe-E z;`|@}ZMF34!r(99p8C|;4<9Hfl9LhHBg>}lzm?Wc{UmB6b%D-$7J8Sw(kbmUW_d5(ds?5G+)0xjdsz+sK3y^ct zyfdB^Gq6$Mo*FCC&MuvPKC64^2jyF4<-yam>)Ff>ON)x4g_HWsZhIRo~L zt;d-!HvK2*Yi0*NVN9E!k?OJC(F9i+8i)58^%w3Rr-SMqOnhWhDA0^l=#LzuMka7d z7#pgXLxrqPACaTgd^H)@N#o%OYf~>7sqys2gzhJ27VlC0;MYLr&W*rTn_(WXe=H*1lN`d)IxGTvKhltca*shq%wg!Pel-r(yzm}Tzy79TrG z$t~mM^oVH>ePJ^7D#5{u%swlI&nm39Dqq~REM|jp%w_G5^faI%p+APE6oTmTzjBW+ zz4=y#gYe}jP9ez?{FV9#sdQBySvk#}f-QD3+HdnVpK?ESU~vg%N9&%qEMEU+p!D2N zJ%IVWEy~AYVd8U1s6d#YCzu!efXbmCAHP-jBRfw^b4NXQCOX6Oo{rD*FIC;vby<(j zI^3zFrb+?`WL`4yL0hRZ;URZAvCk)mNul#0jI{q%$b1*%;K0!`C|?z<+uFpcL@hm? z&+|K2V^i=s)l30t8!&JMUap%3Gc$9|nLD0I@1$}xvtQIb$R@{^^x4cv&X~j`&!`3} zs>QPfm1;rsZ-hYrq;v+if&#fGGOJswD;*$qiQCFP%KmxEeqq`=wwcB~ueFmOw4-u@ zx{wk&E3^Baok9fAl3&qN( zT8hlq?qY2jEm^y;sNJz&-(|lS>j6sx=^9%hB-X!i=sYBx#DK`pUyY7J9|dK+DBCNh zcg|(Nn*nCqz%vu(1b^})Nv6a`#{K^awNo?h&y$l;ZHa4JAdnG#_rY4_6#l7*-HDzC zBcqxpMuejCPavTe)-O-hXUX!CHJ><+*ObgZ*d@fl&T{L*NsxYqkRT=+G*}%&$z6C8 z@m`>byY&&6ZgJoNE%MA6mD~ouBbQkW!X_O-bD+ONxZwEStn|u=TNlK*u)t+CSq1wX zvJ}Qx)Y8%M&u#Y8m@6i{KJ*B!!|6;EPTa-XpZhdX3Z|ATz(Y;b5tL18fYpqR;HxV7 zvo8MzixH`)9scT3(F5!*Nd+tdgCDaCtETG=gvnGq5Favmz58&_{@#8VG8Q@Sc(lSf zBD+@iQzrUXNQ%SC`Kwzuyn{qY9Wq@#KfH4tq?C1zdn<&>7@tEL!=b;|oq_PbqPz?wx@o3`yk4Y)rHI=5t$OC$RZ(YL>>RnY@A zIKkktJg8X4nT4|4{)9xMYtVP-vDP&xohV)Z4lhm5Z#JJLQCJdb(D%Cwy{(n2C{}rN z_(_wdTwJGi%TCN$HN_U3LmXo&V@>O}tB$OUj;B^o8ID0Zt3tm?G`myJYh+(#{7Mj(X`4KBK-EM75 z!Nd2ntjj`;y`DK1Et@v=#*tU>9294}|H%IKEHf0rS3XWmxcj;DWh76}%QX!a1CPLW z!PSlr*G}w)DJLpn4l;>_B zT;B7QS_r2(>Q*Z7zKB zh^rtUPyEDo)Ss{R1KCUUCQZep{Tq23txz3%RSJ51K)-_B2-9yyGqa55T73^UEScpg zB9hWeAnWrxCvRJ;|A&n4l}-A`6=GT#Vwg|9^}RCgL$7$POa295LOlC>uZ#k>$?_q1 zphQ~{yi($Cwm!(@gS6t&SMU?U|1yhh2|EjwEF?l2&s$hjl5oT@G}}+ z8t{q!W1Zw0TnP&Kp`nNOoJq4w>z>aiVI%}Q9{PHFsd$*J!Cw^i;AG1|TDQwq@qaPs zu&+063j{$8c0z2*YCh+>Hw8l&=(f0p8Ynz7E$DLJWBQ70R?=hpXPBp+^l8fYY$AKzj-)55XE5j^hKd2TEhFV`d0SbfGQr}zGN^S1iF z8J2djQ~j%_#Hf$umD39;`8NpJYe|kJzLerW-~X%IkQR|T7Tm-eD%Pi$sm@)tK8R32 z((K4a|0!DdpB8|j>;Gu_%CIKi_wUh)l%gPwfvAW`cNw6dAkrl$-AGD}5)qO5QW7IX zlpIKhln5xX(LF-M(cL4SbHD%byz}4%$MD{LUFZ2p}J1J)aDY z!UDVoO>js=F>k2Xwda_+90Q7cqE zyj0z}?tZ$zn6?H)NY4WOqU7`^A5LU{; z{-Hj*$AE3RuI4dDfKt-JzK*xx9`-i9=0!oP(K2 zSbe(4^uB_Ygw{LK+AIwipws}A@>#88uAD?lmy8tH#Y(yMJ7boAG^&~Nu4eTbf+^pz z@*9B3FfOypBZ=x7va#s4wl-W-F|i@kR^B(_`YzSvYqExQv}d*8)LwL&2fI&QA^R+7 zalo<-@ej_@DSI;bPfDWs!FTaV)YcS1$%(obq@M`>)S9xcVItE-EXdJ#E6gu_js{%Sp?VcW2FVsk_N z=zQ9;N6dG((|{;fSx6soWgP{Zc0AICI3MV{0s%W{vB6IRl%kbHM(l5lYBrDO-B)UQ z0qv5%b_kd8@on4QvTgK0-*-Lu1MwE{yy(5?URA7`X&mQIjc=Gbd|j(0F~hmZC{|4=cBo{#poxmtndP!(3?W3nsj$34kA+!Rj7e~gj;kJqi%*pn`$ zBEr`o_>$Z4x7BthKj|<17qgWVBW_=P;^2K5xpSj-;c*FutzLB!s7btBTjy@lu3qz{ zaAVEd*P-|ZY}Mzz{x&}QZw+H&jFktY7V@FnExNZXch{?m7jLdgR=mGawmRx)+}6HI z9RI%BGo5VAX~+?0(r;67{oLD0`r!1{SzJIcq#|5q+MpKssV7I;i5G%TKu!)0 zEuyUFS02tW3+E^udiu=1Da?;eLdoF`LyKNl#>+p0`D^lInto<&x|xXhLKPLnj*N{K zo{vz9flz@iOPuJ+vlrx2SPyfBCx9#Hlf7H+zoQLY_w)~n?;GuWuct$ppWck8#E5ar zzX)L1W?c~c`LTu*f;?TDK+*(s1h5J~DX2Cnu_zYwEqmZ1GkSV7#F_fDUVghs9YTsp zlMUDWef1e0n>Ds9g?qmVSyD_ucppzcZr(Q2kp!Io-NRgBSm+(f*&V;3ENtA1_^| zW)qGtTcy z%zsilb)?B+?Rj*);-6EQ?g&mzYU1y`_xN~AkFNP)8!o+rBh>k(1c74Qi;rzm_1j17 z@=KBY2uCY=0=D#Df6`1A->Pm+-GC%^W4Aqb6E>G=Fi}^{e@QvkK}o@k0@5XQ`6ChJ z2Cu)1`d19fb0SRF#P0&ID(&@}_!G#ueb8|V>!UGySsl1tk+dYTqrwcKs$+nj>{w zY(@9#CkbAaw-EnBd!V0mt=QtH>9H-Tosb+gXA1QPrEAo}vQ+oR%px)ebMKOg(-zu} zf5~`J#x$AVLv4F!6;e#7zMq}SFMadlquCeCHPH&qj63h6BQyPVax*3!XVUH2Y#i!! zDb9kt3{Wn|L}H19GgfwY3jVQjmhCbHf-W46aKL8I)>5kb|A~~Q^!QjDQDYZgHtlqDtfRHHu~8E4 z_&4(X9kN&{@`nvbe>^)&oFYy)6?eJ_Yi{@EfNa|Ol{El-7Q&Y7yN+M zb%`MLsM(X zn{SuMe!rQuV#iCE|A{`$LM6mNb?zJ!ukfSPE_0qUj~dmkk?r%4Nxnk7pb`7_jo}4YTA5X!$$SNli2GfX zUo{GqxI90;qTBWo`#3)YD)El`enPRl{ei3ng-x^R5`+gM|ALV1WD9$;gxuW&5Tqzy zdn-*M5Zq5-(y7!THg~;frld-RbZaoR6qqz{0wG%+O9kq67?6pZc6rivfa}2N1$&02 z?T&>Pr*8)RxP|}RNIj$gGhYw$bL-5piD#z~Pn`w}cq8I;+D(>Im1*A^L^my5#(YH! zP@Ep{(mZPM!A*>WN*LZ1p}N|pom?q;qCs!bN2i#(=ZKVq14KwMJ+=;dEI4Yw2u_rquHHe%_Fi9W% zt?fh4C$C#eKa@G?dNeV%Kh0W(2+KybD;$|HYQ4sVdVAm5TF{+goELeyICLfT@nxR@ z?O}%SeM&dm@?^f4mQ8c}$&Ohea3XLBK!Ap45scl$YC~`DQ69=~e|2kHH}is;GNd&x zF`P1WbL)?9)Lskm5NOK{JY}3hc69XdW2!x2eDBMX*8};_L!jf*Gp##h&l_)7)}ZHD zU{DB0cqY`)HM#@@<1ZRi=kZ+Hg$|!0zhyheM7r*pnPeda#*5df9`cpT7kpn{S@9@A zNq@Ph2QnMAv^x*mp1FGeyE3V+rdF|bIl%Sx7MwT;#(~C01hL3f zGI#t*9EixF6iQfs|LQ2=&Y#B2Pk@c-okM7iQ?1vbt$Xdbbxzh8PIsAR zIjY=Z09!hYYc_$`4k8ZHpWj~tS$h>wxZ$-P7C4Ww!qVoGJzgiT) zAoz4=<;!H4@mDH`z$=U|SD9zioAS&ndmdW5v!}`DDl*VY=$)|YtsB~i+isjY(S-n# z_!=dLr=z{^#r0W6BC&_|&fB^LC%GFx&>DQDdo`nUT$reqt=E>R?f$Ct*}pp+h4mq~aMj-B7<7Ba}n?F8OLO28fhL_KUHEzmO623wXSp(2ogpG)- zU~C8+_@ExC`3s(EuxAGJ-G4UMCaPY=TW{@d_f9RFRpt=@%}RY}lG9pei;(59<(=lGbb=flSUcG}|CLn~A!~kPe{Y=;b9UTI+E|`yM6~i=^KC0B z(r=}=9tgHIB}f({)$-)hrNTsX(s-=zkC=JhUwfX=;E;7_b|VeKMkb$RugyD*8I7cR zf=p*JN=dNax-3q_T#_wFrN$L2HH3V^ajBg{z9z>kU&K7iw~s@Lbx*hY-o(IEYe;J8 z3lciC&4PJ7zT89hn}7i?N(#3?+HSn?A1E|Sgq6wuYZqp^_|;xR`H6!dg_`KpQd^>L znp7|A-%E`hyMO7+NkpewB}*(eZ=p!aBob&$HQOnt*8G|@veOOZ={uf zKDMO6N3x4l1YbM2TIstIGP=DZ>;Ls&Nxs)@`No}9W&h>S`04gO&@`rqIsC{ntjPHK zl?sQ$=`|EjVH*Ba|MxgKIVFWy&k8biFxf&C2w#M%9AFP~D=UuEUZx|h{xJOlt|efa zx&HyQCU6o$3X+v(h21#Ga8FMl^qg%~maAI}4C6com8b$Tn-o8Y(wA9|`41UOxODIX zeQ@!^efU;m#wyP^l<|p9_2O{LjhA=oP>=cJRfvHzKqtOABJ2Wh{JCZK4=cXr>+0B@;yRcXn2-4sceARmaDJ({|nS`uQIK zRmV2hFitM;Cghrx6F=R-lcS%dF_6?>x+t7P1MiLuwi$Y)1Vu$>mlA+WFd+4)t>zE8j@w4<%@+$0^Xivop?)Y{Bn-5j;~z9RpLP=&NE zr6MJ<;*GiX(;8-V)nV-dCHHT$qS8YN%=UkhXIo6~yqjcUx0h9J`wCac{VWa0d4i6t zid4~=G;Fm~n)FU@VdWo?x%cqT_l0TCd496_= z^*a776;*sxG;6d^@uc5ML;vOSQ)y*iN)z|TNLQMS7WLx89PFPFAF=Ak>x_hka+Bqi z!^FPl8j2|JF{}G6Xue*^{W^YmtkjAg)C-)%WL(@ms6cgsvkIQ#>qW!K_q*TmvhXYc zO?-X0-nKp!O#f%DCu?qL2`Y4OZ#^3bI4ERnls{~ihrIEboiV32=K3`X0Pv=H{Wo~m zu_uSvk0?|NVPd!b%mUtT7Z<9`=|yfgSkQ!*+pTu3KiNoZ_#gG$3c*?j2M66aTtq&) zh8h8C>2)aTn^rYBI0qod-OO1sj!F16f8O(<^|ZN7?2DGZkUlU894yt?L*4eszq%}2 z;9N}imeu00lrq{xE2+zpp=xN~YYAnW&d2e~ycqqpO;$7T+;X^-wHCP+r3iu<%z$!o zD*=|4S~18&qxdXJK@r0wYQ+fV3%%qIa_n!Iie7KrZG0bNOUvBg)z>MHsTLi~m2qQc zDC)a)VF&dV-`3h%T>B&}jjG+kx9aQH78bMayrLp{!wUPRWKlbYu={tQM<7)(K?Ve) zE1vA3L2~VEGJHH2Y5x5E9Xs6MFRzA@nr-KpyC^CCnMXKV(lK(m!qBOu`DDk*!HYI+ z=+B#cVYCtj!70!dLqY%PpAYNScV03L4-Ny~Pf%+bsvGfww&0F)mQ_c03~gxhins`Q zRrmuAO1VnN>lU}P`bPM5R{5Oc@Wl4$&}D{GRov|JpBwPEdAjm?L_bGf9SUq`Fz!ph z54|+?Ar^`-Y?jguk^1Oi-%dE0z zHj3+E27*m^-tD>99K_wMW_pLD3%U~SvTetYGI;3bqs_3JC+1>`d&F1S^1Ml-cgrlyF}-51R>)-9RV9@lTvz3k@q_ zY%ah0!?{iv?$Hms&x-`1c)U*+*{kJIli*7H2B#M}piJ2l=Uz zYHE#Lv@XZ!x%2kyC!EQ_;Jl>D>!qCDk0~=0 zz34PVS$xZ1TdBt*Q>J&xcXXx6lmYk;fR*9q1R4X5u@xHWYg_%c9eCOc;SYwaQpzBP z9EUCtwHq{r#^$-jMb`~Zy$T$$907DDn60FbABpu@R-!sLFX&Q6Hua&TJ^#2D`EbCx z_5AfT1$e6&C6I?zW7|Jpy{aQSu9ZI=te}wFJ{b60GI{iy&3@3SqG90p;J5U$Ywb7d z(w&5X(@2lpm*mKqisO%R%|+^i6Pj#&$E!oUerek=1xq@tCJz;qi!%LwHeO-;e%NSk zHR#?*0 zt2*?Cw&I}t2-4i0{0U#_S zq_~del!=Xyz0fBj}~7yvrPoZ@5jn3WwpgTB%ti zHVXUBtD5{6o7fRMJYGGKgG?sQ*Ha`iTiy3wV|^xqz3Ucb3P9<`jDWy=KP^F5fjpqE_;l zu-e9xXcPpAbznv8wD2{um#^x=q*F_4Q;YHSDXkT*eV-a$jsBSTw3S{7qz7qy~jOXfY|J zP-jIkr#@Wo%F%OE4hqUjMz!ktJdY3^@4wiKCrIw)r5++kP_azT78hRlZ{})N$+Ne% zB`eUPn$YOm1;({Zc0=fv8u!K2Sc-yv5Krwq$qaDAl`J}b8S&vZR6vq zv03D9=kH&^&5v78y{%PD&*G=ue(257_6txY+yvZN7yduniG>Auv~iEv8G3L~#C{#bm| z%eSBiyPVOB;~O0QR(APL26u&2D7$oosqxI`?2Tf|tvwmE9p9#i^G|}W8Np*oEW3Fa zSy#(eZdvEvJKC>^wci7q(}~!fx>5%{y()^R8G0qw>pP zN71!>qd*sE$~sE^;Fr1z+w5sfu-~?8<8{M+=K(L+J@;mOIX%5OEnOttL{TKz&9!@J zR3c4&7w zwVc{=dd6n6m1uohm&M(;x&%@RwwiyP#IbzN zq;%JE>e=o2&vQ`cIqmDsQuk%|!TR1sT{6BSw@UY&ql135{PMw|qj!Z=9Ht? zccNwr2W-&=%>MT#uRtp;hzkKlGpvDzB~(3gZ~wn;R8ZNK^7BH)r1uwn93Z6u&T&_g z_s}%{2TlPAzk@P9S|;icqsIHfIq~v&1GXJ%uiCFg#$+eOnRxt4ozk+wa%gYsAI37p zfWgu*?URv=|0plH8Hr__YTVC4nw3dh^wUU*&M~Wsw%q0dDUpeYbAelN?K!W8Gv6qd ztdfiK15d|4*ouuP@kHVrfqXrDoQZEUM;jov(G1C}6}-M@B?Qdc{J3ZmyO=5SEoei%TK@ zyEC0urBIV7YXl4^)#hgx91f^HXSYj~i-yh4;ic4lk3;qX#JJHLO7c_~{_589jN!bU z5NYRr`Vu?cqxS<#9UjXUF7(@oBw*!Xx<)6=0}n9b@Ag;G?rNC@pyZ}Ae3#{(rqyma79hLjAv5ASHp&U+iA%6o@$ z>u(*O2L7!(-l2rCR5BFXzO*U{5d&&+EWxRcSj7P{QTjwN%$%1Ee zock@4jE@&|L5n&a^}c0x`RB8pmJPWJP&(dZCHiw)c;}Igx>fS(g(Yt1Cc+%M0jFM9 zw-wW433d;b_|E8DoqX5^-DNP__SlCt)lU?t5RP&lG%>Vn3^bI+VW&3IIHNo88!R^y zt2W@)fx&2c3+4;Zyq5$P}Bj_02J1SNlnf)k>y9$xJRAO+^;M3$B* zy4iQE-`k6pu$~j^bV~<+n8$X4Yh5M$X>Q$5#=FLx{Ngn>Hbx5^YNl1HeQlQ%eLe6| zH)~*1=FlcPNH!}A5m4HNynX9-%{^}~4#H3Oub4#ERd%)j*FCK!L^jvS;lle(b=32C zGh_fo`V;5JUT?p5lt|i+Ll;)!e5Wu8Nc4>Fq+xlAb9}8G$fVWTYrE36$vWMZ4mr|6 zxwKXrLh9&9Nr{;1;Vb&-RA{`&{x>p`j_M$$O=NAug>~qoWx8uu?9PJ7y0H77N8<7m z#Qp?|?X4P>QI`^qV?!qe%+rAsi=r~2rhIZ-W({rz=6#maiP4x-(KPalL zQ4l4xyNc|vOTEeGLhiATuCQ>lkRgukMBckp)0jSRx+AE}=yvgH-+%En()tcmE8ZD$ z>vl{98)Vsg4HR+x&j`c#U*{}7z3$2(K9MJ zomyNiz441mieh35Mer4XBw?!e?(Xi8)zd_xzBp8*?CDua_;7dx!3|Qi&-P36^Un}} zYGRV^qXS7ISy6KDVKVAnKGf6GbDpZkd#$9_flUu2Ixj${Ly^y9c#37 zzD?27+eBIKFR>e*gfi_KIA8@j5vvCe71PlZ; z_7YwjSD$;&^Q6jn^-`1ouYtP_X2!QLgOHO3CK!7d_1$a`aegAV;e)O3Q||7qH@G|; zv`k~^ECX{7ieAx2)lWoDnUGC#>@4vCSls%0xi`(kFeSKPnagg#QqDQTHLyG0L!8R< zSi0ruLhkMj_n&u^a-K?+Jj}-;nLLk&qpCO01~+j7#xU>_f39%}h>bdop8rIoh%SBSZEkp=d=5Aaj@|J*!Kr;Nb%tMpZAk1ZC6SlYmW=rHIg2B z^Qqfr)%TL$u2YxZpB*Yd{NhO)}(cBB* z_lNtPN)CRihmHzvN|zt8bZ?QhIFwe@QY!aTmY9{z^l+a)VxgVW!)?1HA0JoVyx^v$ zKI2qr|4J_)VdyG{+pPqhg9*&H$>frqtb;3J*2HUAcX24I-iki2n%&X%T7_JR1Djmx zW73cyg6#Zb=_Nj6-7bEy7GP~@)wG}qO9z%ipqg#nrEdWP6{4vVjMt=A-{h= z0=%jkCqt~h7|xm<8_?B44w&DL3_F_oXgy{pO4Ivzoeh&dx^qx>jUk8q>8&_di*MT7 zJj=cY$5X8MlP&zA??aU9Htx0h_WT$HQrE61Cj&#ox`@U`pWT%QP#kKJX#BRae!Fll zEPd~EmA1|zows41v#7#;_u^F^D-(=AdG4;2dN%NilQR&0D~O-M}4 zBXa%0*U%9=xBouIgPg{|L*;tTgG{vt*j35f{6*QbSNp4r{hUNt_uS;LicM!i)-uyL z@y-lxndf@EKiyo)y(8h|<~yRCGOOH#eoIZuH8F|F?VX@L-Yho|ZoYMq<`W=g#IZ4S zA(yN$<68V>k}Eq&Y9#o8$fhdJ}m0WjZ(PWags%ifg&HN(V-ZbZ+i(b;sb(Xoy3i@kP|1HFzTPZm9VMU#(Gop)kf zp3!c?xz61E&B3WIGL&ST$-2v^vaA3EtQwkfI-GbXEzU*RZEIN>WGm z%4>4btuz^n9)9iC99bBuwuk!#bi#y}vmt1~e5>>98v3?PK~JssAHRpJGn1s$`&kAp zj;H4k9ZgUtW`1o(LHjs?N|W(0LX=+9N{p~?ZUo*iAiqj^L|(N}u4!TBs-MEsvN(V9 zR|j|D0#km<0Lh@8NXq1~O}Bcmf7}b2xb6f9&)T!keZxf`x?cS+vXN_b#UoIb_Qx|W z#{1yc2YD_a&$sy?NR09(Q#h=EQw#KdIsAURA0jW8+a-3?Tuq-t^KX=oivRVb%w_rf znWNWxdh!?Am_A>)gvgOl_femWU!C){6LRO$za@4(!*xKHH0Z=E=4_9k2&jsH| zL}O!P0N-Tmf1Olx?4TBaEAa=MpE#0k-xV-4)o-F!xi8WX_nX338x%v-Z7n6v$-{RE z;nG9-1GcI`ELc>(u@ul1VfTM%Gi81-zmWtt1VrZXnpIU)F{)X_Q+Bu`bNQ-w^k3={ zmc2Ugx^jnW&9DC@S>1v3Y6vk{vZH)RY)FfiNO~;A7RS>RV4)DjGK?^AE8jRf%M#43 z!1vJJkCTFMULso#m6Fo@^XL6=x=*+Nt{`_FxL1w(QZsD$b`x$2#gOA|oQohFPM>c)i}_vF8P-(J1qM}VBqV{Xuya|? z!du%`ghHWK3R>Zp{we9WeXp?Md!H4s_{%j0dU^`~Q*)gM%lEiGsIJl3oiU^td8-mw z9XY~&QK~1U$Ca2<#~v?8)?_kz5UjL^iT~D5BTEvNeJAzn^02d`+8K~nRb{NLgPcG3 z90T7XB<70(+z(*YDX0T}yxD*JQeC%irA}ZaY-kc{P^k zX4#aTHz}EX{24A;_j)J}kXM#_IvDd-?9s=I)Ze($P@gZpKiDxqUJU5tPab}fRH(>- z_A0NFRN7G_d`e$DeC0Ri`|Ryze2H@K$Ai4B9{2mB2lLu|_~&Xq4=CIZ2!!=UGI|68 z28&mJf1N$VtRB*VW?g#q8dLbbl)w37Rx=|6I8|@3vL=Gig@~ke4-JL-9}W4puuZH{ z0(`VX5F(BvU@5U5uj&z}PJVoC{TM25SN%^2P=!c5c72aG)7vHwyC$c|xb_01O*dW= zn(TsugAv_-Xf&Gi9~2~Y>tyB!{rgnW`d$e=5cmhrRHn;tze$@?w0+h^HH?e;CgLGa z>_-cQ`=j;$b`2umH4NGN7NY9l_^vo6NEY1ePLgcGdZ8@q798P0u^!woq@YWe^kXfm zU6E3D3St<4k)`yJ`W3a4FcLYBP+XTd+}_f)V~5IP=+8y6q7e60cnBwGQw6h$?^%=mcHOm3 zVQf{WJgGb+0RJ}cWeI}@56M_+?$}6bm%NxcujgmF@s+ho`yod>>4F~>n>B_`c?F4d z?_UylRq$8e{jPi3aHvPS?tY>fVrr1RRK|Vj5H-j$c<%G^D3{Z4fPyRjG{{tV+&>Kr z>+tH+UfBpm3D@!3WX|60@0sD7&%u0T6`;NvOXqD`)J|4MWzz=#AFK`uiQAmi6@4C6 zJ-ivsJ2-H!*`ezO13z{)&h8;)d@yM(T!ki+fBwemdZp2ktwbo1 z!Lb|2)``$g<7vooB~1P6dX2)Cay9H*X53JfNTgQbbIQ@|@L?qHouag$_Pl2keJ}Rh zb!D4q*G@pyqEZmgYQIRk7hK7F;)U{iiX8ZI_-{AO*NWDu-C{x)b!s_yL#*kx9}|hx zf+=l{ZTGvWOAeH5AIiOh%f6ZQV3T6#GAz0l#tHN0D_75G-K<(4o7_R=gV2dC*mHc^ z?Ykwl=1NS(Eos+{zmMR%cNWO*ySJD&QDY#t2SsI~?~nCjC-xMylPOP5rzoc26(xIB z?0w-5NoFbDn}mxDy{M+a1QLTlZcGDOm|uPUw-Md;%d|&Ft+vd*a2eHe@*hZIAZ7 zm@W($G!$5pKA?G@Cg%sS+D9Di&)QETB2D7c%Sl78)khC?%$D%QJe0GXf3!lGX*64d znROw?!rqaWU&YXyb!*069i9^(`FY2$C}0qbw`yrJVUSw}wJp5|H-UTN8c4!owBrcB+3uQ1WLM2)~Us zNRHfm-ln%ds{cJ~_X@6msKSGJnLoeJtsp-_bN*{Z z;v{>8-O^$M$*|$|)Xk&xlNOUHKl!7+NaXvWXr)nsMXQ?*ZigO`1vm#k=5oWf>Mky`%A4UkT9l5ekbODC4^mYSWPN4%e} zwtVVl{&xp9|F5g=6DE$ti$ZQQ2|G0igmP;HThHWV6!2_^9Sw)!(gm-}|9Nqu>vjx$ z!Kc_#;V|ahB|2mZe!-KysFQcFbP^F-kj%kp0`|r^yEJ))OSrKyf*(sWk@kl~fbIzB zioS@IBi!;>8YV&PE$BA9hfTFZpn*N?J}KyNMd>(Yh~IgCb&cxq<@ml+I*3B*_oQ#q zOZC^NtSQ{%xe9{H8c8VPNV~sNQQW&z<#MNz^&WYy)|8!{m3>A}BY&6fn8=y+}NQ(9;n zhEdio6+Q$%B2=_2F#dz@h6IQQsCpHHeWaMVOlA-7R7_%K*E-0^Ft4=koN3G>;Xv#K zXI^^K?Y+Z5_*JcP^&H(t?uYj#th~-!p5$fbL009&2@=tW5~w3b?2R96^Uazii+sv_ zd`BhtPn`B&T2aetOVMBVl3kDYe2lSiG3>R5;a!i%Jsffk9_VU{50|e{nHyv@ik-P8 zafh_9*4@4_fez7h`N`*QON%s0&VcxH^_@@ghqiBJ+M4!fJ!>pQy9=>4iD5-{tx`&H ziiarlqlGgQmBtF8%VYyLk8j4lntB(h%qT@H5b*Y9I7JSLM{5u-{eO}CBNqE1%`ZUD z1Xw(~obN?qVhbYwzyz-_uNaEjc^8C|k$)d}&Xnhd^1K7;(MB{*G{@U;|L%6g2DAH; zKMPy)cl-LpL<3&{tm z{34Knr1@2iXvu|q;t?_g=EhO;hV}Nr2AYi0gXr;w%aZwnY3?)HXLI917t!@B!o4i# zv$=k3|1hVHzX2`Bj`;A=3pCWF7aHu5=} zTAMkCh8EB;lko5W{0pbeRDK5m(1fd2I_;vQYdwza1t@R>%G#p~esL>1&u#m<#jP%1 z03fyadm`txBC*02vjRtr2Bl?dQ=V53Q`&v~EHw2C%BF5piZvi}`MFM!-w~3cK6Sf9 zAn7N4io(YO-i3R)6H}wv>Yv5R(^qtktQDQI(>H#E>@^;IC^Gd*^sn8qO5gvm8BSrs$;@llGv+op{Qml>KA-%D5x6(0yhqv0Dgmu6s;0Pga9_G(khKec#<9i zz)IvOzN(>qK!$;VibY<8%7@5WjaX;}dZH???#H;m|3|Fm`3QZl4r7DJX+^)MY5Yn{ zL3SEPp1t=4)ke!|YA+~+pWGj5$Co{4D7*76&eM#rv%L0wcC;2Y z0=-H{4umQE09~;ZQW52UIP-dMI+RGS%lhn0S^4i+tz$gv84=Dz>ZLFJSY+koGC>Ype% zMuaRl>D>7h+rtt3xyQu)k4j2<-QLdASzQR~X# zqu49bcOvw~<}kWw33EeCl&)aokE``-zF|v}QypX8 z{-SOYiCV{Q?4tJ!Y|x9rTckSd0+_HMj?XL&rFK#8joTh6q#SA&>YN200$Kt(X2LsxXjH_z{{6Mf)v_JgD43GB>5_c;MH*50 zcAuT%K+@!M_KG94sPucN?aA;rXPWXUa@)C$n6l#k+xqlkH|GAI?^f@QDj$-^Sl;06 zjZA7!4abGjS02?#J!ijn=i+@J+2OLBF=QUOufy{F0yZ>b48gSoJmD86N7w%eVq8Hfn>ibX1 zd#ZJwXe z3fiV$Px-YwI5LFt^fp=iSY{U(Ne99wDSVHVZ))uJ;?T@Oeo^b_KS`OJ{#A028W?WY z770q(=Z&sd*-)5=rKX;dMcmZv_qyVL^G>!^{=Bcv9ktmrDQM9kPqzgAcQ#&uF8KgG z*e_X&)YuDu?t6`EIPAz1DOV(&H4#Jc`RJI|ZfEk3bsk(*c%tx>L>xpoMC`26M0_PY*ey) zFXLYe$O>r9=be5HpMx00O0+rwAn|>xR~3X;a8Uq$2e&HlvqaXf$!%pp(<@_(VoD|A zmG~WZF`H&`#&(PX_f*gn_)sI_y%Xe;4zk%3DLeLPNCV2`hogYufw}mrGVqouRNKan zoVM*)uJ>ORTcB7l>)O)E7#s};gs#KlONzzlXt}r?xWab969f||s7T_aOMi1MNuTJB zpetzIGsH0Z@Wrh*l2b;za#pGScL# zz?$dg=I~KG9gRR9!|Aq@Wbu$12_J3iMvvq~zHLc&N0a@nW+gnn-_hQv^ zH;4UO+TyM$@L}4v?fnGn(XH|-%DsB>yis~50TQj!$Svjd!1Z<4*uwe)?OQlE#+M_v z;Ni3XyXP+imkMW8WnA;nf1{~nk%4wZjUcYZ-4S)uPwVac#cK4vt%F!cQH`MrBk#Pw z2AY)bHMeSeu5ppn+r|5W54JTVzNV^gQ(4RRC_Oz<_fuFn18vveC_lMRhz`47lGCZ( zd4GBV94JKAyb3rFXbdIBJU+hG_e^MN!e><$?+K}zm4pT$=sYL9cpV##JgoY=xlL;! zuFkoQ!?S8vT!1i8A4TurrlbN7<{WIcxyax;Ylk-qnncP$K(Rz2A{I5_q~O!g?i zA}9-PuDec7PO9hk5)2)i_(A0cvO$2ibjJpZw8mO?f(H)cP}(^)(bew?`;?{!G10|z z`8O{)a#S4k;)e}R@QmEHZx;8@F!x^n=|-gr+5S{tZ1>3q6Y&+Q%L4JTf#S5!tXpF( z-&J+~*+jhUgfJOpRf!Qv(}q3C3#@@o^1&hPKcyJ8rl|kZJgrd$N=yKWE6+4<$}H8- zU;Do7;M5F+``WJm$!-pp%sbfn>_^K^6Za%B$MLx!)kCxBtL${r3NZoah0j*s3--HY zEetp>5vPKe**;evjlhALi>-+E>diZO7>>zJP9$XznqF#x`g*MLZ@avo)eaxG%yon# zBxjxKiqNz{OEsu;wG8wN(Et&)Hv zX9C^=@v#f%*M(=E&b@ z)l7Sj`Dx7p$!QDLSqZi_&F+Ppg?8PWGP;8wXAJf9s<;i^k@hqKB4h>{wC48t^A_@EIT{u6t6Pu_xBX%WG(ZWj8>`s z;Y&t6Q)h!<3Rd&k@tgt;xxsT@sR9(iZYT{*4u*Stc>nM2(6?Fh%2%)3$zv{6U^?i_b72CnE3r z*NO{64HP&V&jmHra;iP{0p+;xxU=Muh_d0g-$>|9KR%s~Rq)ekKbyN`Myd@Kaf{ZnTV)4Jtj<}>V<6p_Tw3_S z)>Ciea=}K?q<2$?)D0;2^~?p%1?PPKUj*{>qcsHX_l#G^>>zY?`bDo;@e2@CeKe0QSguI%dA{}|#ps3MXzSzYj4EvMsQ~B8q zqe+1Z2>%K%;h>)D-=CgZFEm_VsBGXEu4TRiaeeJ01#zY0^D4DtQLPL3Xr+D=_Tb6Y z(GiD1re|FJqqxr`Z3QllP?!{U|5J+z*d{M>ae3D2 z>738)uN5GrnQ z(p18umhZE}8FI`%N(!PkhUs@S6uWLpAvZUdDdcq7hSdB| z?5)P1Uqt@+Y>4eoP+HHuvyIR^)`|b@nDX!9FE;Y?12!3#zDP&fcRxh6S|sQTx}3J< z>&|*h65*Pr|A6z^@h3*3q9J2idr^i9#RvOensCF_t`8_5R>;z77*A6FU8~zkI_k#> zv0o|DbZ)U++pPZUDwk-NdZ=>DL(li*p}$-@f}Hkhb`j;EM8m?nZ&8CUw5*b`Gs9k3 z?Mn%aS_f};DG{kvow)X~;YJmMEe>D^tt z(tY}D`q9;t*u7Nd3IV9KQ{^E~DM>fGDtl3@kC4lVK5SpSCC`VjwXsC0p;gZe=b>%B zdR~v(s>8%faU7Z`-YY-Tzy4Q3q%p&+WGa6r$wG0&iQ?R_xRgxizxrufr$)1=$}`5K z{@-4ZF(p$y!-BwL!vth67unhGLrmHkf$sr8VE)Pdng*Q^ji9ffq@wzUJn|+|5|H8n zc!Y932nfl@$Y7F1KV}gAmOHcOIr-PTgB96a@3(UDCz1m#a?U1S@zUZi!}{VdPG9w} zNkR(loI{chOlixF8`ibSJm+-nbUgU1voPO|i=@hXtfzJ&>BtWVf`XD^em&QB5;}$x zA0oQU-@U9$mTn99paC@JAwbWLn<*m-ipdznvF2S05jO&auJMMH1GUwN7xYvzt7dRPP8r9^U0U#BNS#sf_Tae3TJQ0 zm&Xn;ks7GR<;Xq7HBaU)%_f=UW!dPu7P?poVV@g;Cc+Noaosbx_zm|mKPA(^j%7OJ zWSn_jygK*=kjjrKDRz%oX~{_)l_`VUR8{%#>Mlp4Uelg57l~K_QD}KV*C?>5NinhW z!I;TV;OOUe!_Op)#l(gRqGJ#s4B*&6Ej(gB_&Xii(>w&XcXnz@q-6ddPj4C5g!{$| zgOn&CKSVlI6zPtQ76m~Cq#FdKyGMtL2n>{NkgfsJj0Wkh(I7RtM(1<$KhHUD^@Sfd zxbExvrts^}cgU;Wyd^f62)zOB2Fk-l5n%rVG7I2B;FXk||FvJ(C51~;F+;sxeA%8U zxWS`O$)PGIK0q%QFj#3@gG#o|*g zfRV2u=T_KL|0lkC#Yg9A(y_+vPsLNS$58f*F;m+dw@&27{k-J9O-}q*wYlCkIu|MxKdKT{Ca3H~@hi9~ zrd51jt^Yn$zR~ZzaBmvDESa;5rA{nbUqehMi4M3z`&`P!)M-N$-u_1Ud)z~*HClt z*jv(=xh};!gRb(pydpYEww5g5q_py(A>2kU)lYL!sihW4K%0 z(v1rxS0&@1tPzO_O3Os`SuXthJtv`i_wd9l=rEoD75GWvRk>edd8);euRlWcmOX+y zb105LqmmTEV~7O~P9VufXfz1^7{yj!u`7c(Uvf=vc=;D>bVG#eb{7|o@AD|hso`*P zbfqD`tc4Eo83OapsrWBw^C7*j9=>cEb zM70Bu&_RFE4CaA<##D%Z4=f6*@RX{$M9@YE7Jjjdtupt;U>2a$*f8&f3|re>CH?q$ zsG1R^@BzmOe1aN-QL>1b$0d`P@zb3Btd)f*yRpt^^ruAX?U_i^Cv1j;urhxRm+wW7 z`!~%6B8sa?s%6(Qhx`Ux?bi3$uzJie!gP&zIFqB_<$=pKi{0FMkAbK~2Q7>KezWP7 zTZV@PJOYp$a2a=^F}8h?EQQUv+KadZ6lv*6%TV=*8GHqbk|*CY%7LGbQGwb1Ci}e< z&-X;7B>Tf!mPqXe1G;y_d{!|^fb#P}HqP%`zIf2YNJPZM+o`{aM6!fpjF6(?;3@PnL>qx%PucexPjapmwP!~kqoY1m%cHF>-J6#W)2LZPkvHG;QikLI8mVZ2e_WA~t-qn1(V!L50WI!=cX*UnI zbU8D!*)WPRP8;#Su$f)cNjT!h)@=X<+&y@eHX>eoi^f_rF;HMk3Vugr`Exf_KZP5c zs_c2(v^E$25ekz|MeRBx)E-63b>7B;d-q{p(*jXq&>5^wluow3 zQU#TC`AV)vjV&Gg#(rH*Zw1B5;^9WmY_K<6Tq48=MA0)8D}ws1+tylR={_V471&WH zS6GyiO)bTS$8*QN6(2bLMr=8z7$qS#k~xy;l}MrJlXJ=997HC`V@}o}wba~qW#@7i z+3|b0wG-wY`GzKLIv@;1)AX&|<6l0wGpwmvjj8^)Qwuavt7cK`Gk9;3sqf;_#l5fT zo)vBSQ{T}Vudc~Q_yby5woBTy8mX-aRTOl`F*WR zatsU=-vNaeNoUShmXb_O*ZjkfzcI|Dc&Hjv0jjri6EV~lF_ zxR%LNbCf_%m6QusUqm3I&0{%1H$`T0d&`}T6+Y#n#kmxQF9}zrj_+(Jve?glY`)xn zo`U%=ykoYX^(aeV#K28v!$U>qr_%Z+TUws`YmoPHc<9_yo3rBsBvyJ&72pm5djR-G zlItr!J3kz9${bNZUZQ;&8XHXr{!DV*lKg-$25i(jB_$*V4(eoPX+Eb?kTcCkNSf2; zg{IFeLN({mCsE-bL;~PnHu4@H&!mpf?n>PX?37nqd}FUIO$xYF8UA?}N~q}@*|=Nv ztcy=g`l4-Y?9;~%ql{ILVNiqP)C0NC{HXE`{fc^PK7YgexOe&o+Vp_Xh1^9Vx!bIo3Q?lwcCi>vVQYkjUHS4JowS3J#IZ954 zJf|+fmVL_z=?!>dyKYoxjqjqJMu0bjnVx(`ki9c>kX7 zyP;+_yRm5XNI@$Uk&mb(w>Vh%6#`WB3sE#)LXzBt436UYoRX~G8>ALy(-=9?p!A+U zK+R8E+O(`Tk6F!Km0G#e0vGu7?h%6gLc%-h=S@GF>L0w$n{T9(mU&&2M&;H3%G)aF z<}^Ui5lN8l!!LM>qdb3PBjBo%H|ypPQ>p3NQUIcLeiD`}I?F{sBfXKP`>Y862b3m> z9B)2~QAF}GMfbIOgldh&@i#%+QTtCu)_|4JLb`Ga*-S0}Io1C4jrzrg7@rBeJ0XjW zDtDnC+>XHY`R%rN5ST!`-r9KewPR~wF`2SQ*sU`;T*qlQLubaZ7ThP@uI;d?@I=l1 za%bmu=>nsqmF6C%lIo!r*vg^#LX_~}6{un) z5l}DDO#Vb45-{Rp1VKx=HJLxpLKFd+gL?`(B~R)By(`{V^QgT^T!K;ek%|^HIS=cj z5XIx6y>x4)@Uq>y80z>sN)%HvgpN&WqVy=diCQ2$a@zn}CM1 z1*sjE4AfO^u&jv3P(B_Qsxjh$ujp@ipC-=7CI1z6-D=u-D!11OqILR)UR+z%guWV? zM7?8)4sw1qVeQwAcsf>^kX{J?8IT$^i5pSKpO3Lj+#nUwm($7r>g^W)O$(b^P0~S8 zUTz0IQc;BUi*c{dMe59ip95Au7ye8LcExGu5xEp-n3B-qO;5iTm*h;Ku}P(U{1tfy zZV!-Xh;t1HzS{~OFynRY>M86zMiK!%eA|I@y7%$+xdkoWw`LV66iT-+4y10xv_c}@ zK*zQh3VebCzSl`LMi=kQSbVZz+0WKHLmd&q-FDEHN`b%t_6@CkhJQ)Q1~0z9gZ-76 z_I*y(mWnV8PaH^skz^v-b2qu6d3UeFu%G3i=-wIH2j>8X72T!Hed5zh^?DK$fk z!HqAupLbAiARvlYQCl;4Vw!1zm`7ohBXp#de=x=9uHJ|Si7MRb zBr||=R8_%bF33A=W{6|lv1aQN6Td_JmsTeD)Rd)6{!O|(Zd9olbMn9)jV+cj^vs9e z`41<2+G#*)eY>Fp15^pPam={M%r(!sxVWCsgh63V|3x(&^n=(VTP!dF1#Z(M0m=dH z*9;Joj`Hw^G=W&eTN7eZqyd)RLXL(mS6~M&TlagsL+t9B&u3x-x|4Vyf)B8Epy!Ux z#wCas7G<_;en5);B2;oGIrH&K4t~!V!bmFEkN&LZTu&ohrD3>V(;#j3Z_U3tN8zxY zlz$KbqI-9mSd4j{Ge-b%+*6Lx=x1RTcL}<4VP)}KwE0aquvo>q%Qcwn1#SZIII#G( zT*aJhgV2v_LYpOE$jNbf=rx85Md<5aY&6$Nyi?$jsa6XCj!_4OrJQ3Ohup~8TAk%I3Dxy1X=Bkx2PXeV z??30&_3X4;v(cmfl%f9I(hHzWRm|Ib^51=bV3*!3Lqd8cB!E$lo91EpwI8}DsiweW z2%;|e4cpmAu?A!<1H~uG)z-#$Y;`Q{yKx+mW!`qj@TVy1I$;~Ro$jn{rK{g#R^_`J zX66q@xxZ&SQfTd0bj@!GcVr&ZrpiO!PbX~#LK9qr@iA5v36U%@+&3j^EkPIO_P#Yl z&dv+I0{ibbgy&K{6v+wB^2eUO$T74TAS`p-{80GWf_7|Py_mh52GtD)R zzu%CPE))2^Y^6L;3gbkjUX2*s{g(>?Jya>~ zi-e#_qm5My3aL$wIZ22t99; zLY~k;xeI=$Tl%0QA>B^Nzv{xr-I9swGE0F@RABw$E>LaWeW-`8;mYB-BarsjrNt~F z_2@+4T;OiE&qiEVN0et0`+XuuTbBm^XsNfNL4hc5fn-@KcI^AzItRIoyY}J}QXvPd zHz=dDl#z6J0nNlcH4Ch7e%}%FSe(yH9#(6f4QOVOCkEstL>NgMdaH}KYC><4R5?>! z4242w<-%W1_jQCXA+Zd6ua0gt7~d*)BFYyET(X_LF5g|`>&~AUxHXZDqR-$u&s8m& zW#iMoiJ=W~I39f}?@vFVK#^VKQNvTv6@F{AaL$P|uTMA{&RSy)gS%^=cv=%t_S>ML zX92{)S@!YUg3%5n;Ylfr&FdT)tqq`15Bwz)uqhcBawY!nZ3bPvAi1C;E7o8GD;6+< zn%8AOtDY>hVg9Fl$r8w%_7bSKiTHR2Nzs$Mk=N{w z^86)#xn61Wy-+vE3M5QpH8rdvs3b3X@tp-0(#8G}_)G}eq6p67|FprwYQrbT9^D;u z$*pVORZHDK*JfX~7kDdQrCr*fo=KK51;FP6c%VKA>a0lmoH2;2m;wP(;)ILCNW=B% z^Tez$=fZQ#v$qx&pYQuU(k&m->Q|r#Xu-2T?!;$&4|P~2)d6;AjOX_VCO^02EfDcr zo?}_={mUgP0j9o%#$(;>ua*@XO&>fZHy(D|CmZ5#Q@jEP$7L^sMVxx?;{%=TGcXH5 zSkEnibbD0Y0`1_A5xIChkdrrN$>s1o5*)V3=_1Mv`TFMdUf!ueXpSe$?Du>XmA^~v_;5`LJwe2k}0R?nM+v1$b1;-Cl zfyWudodMkeczAUb{8$^Ed;~#m9E|s$2eV1fo$Maap`{ho(z92%I(=^6zefgctC_0I(DiP@{)CI&)(97Ov|_W#^j2Dwj7rBYa<4f72v zkLs=q4F6s;-Z+Q}iQL`Y`v@|I3$@Ge!H26m%QR z_fAo<))DbeV##Z$fjN1t47lvjCi~&X|JlR>emEdiPqO^J2x(#5Z4TAy0RGzH0KUax zv@4E{QgqKU_6ot6=!V%|%CgJshu#L&%AcfN85fKDmFSHvtLMeJ1{KvI61phy!2dD> zpS$JyHn&&gs6RP1bE!Cg>~rw#Y^G$}r-)N&{wO)^HW#EPbVk$c7iky_947r|?5J)a}nsu@j2nP>VUpa0cYBl-tM&qOj6{?o#yBwRBWiZfKj%lq*SzkuzD zfn76}m4M2E7SE59k()egzZJ}%TbHqGC>jQiY=BAls=P?!l?<;hD?2@3V5$QV;d}z4 zDszF|uP6xUac$+$(s4jy1{i+qRZ*_`(P)S7^=ExOjm3zhvvk=YHp5{;b3C+j;l=|% zL7U-@P${2pAedbEIC7;J2*1A6Dl;VpLI@DbNOqTlpaB>I05`p^pcbJt8oyXi*v^Z5 zNvyl`9NQ1zhrm~r1a-NmB!2WT1-43!4pnJ(AhK3_3E<%+u!W>J9g|q(X)hF_l+ZlM zib$Y{GQfT$nE8gCHYxo8Rn#u903mhW0}mPgL{y`|^j$x8(ll??r{*A#2f(01eu^-V z1yZM!6IRy}3ZsDw=!}XyH~476B+O-iX(>HtXN)bz|EPYQWJ zjh2CR<0m@5^Fjp3KeA^YFxQBo>2aQW_%6e#&y!s_EiI$l9?vxDIFsDM)c?g8`$m(6 zq)pRT?`(dQxxhk^qy47cGUjybUAzA=k=8HDIPpAm0;^Fg48@ygpqikCWw4Tf(7pEg z_%S^zMskOv1umvDu#8%Gt+VsXxP|y=xv?mEWQ6YhE(jja{KB zF!74M%_^>s?k?`kB*#oTHAxV?ugZ0q60l?x4c!Xp-S_`el7-0v9sL>>1t(cv(>;2y zo}yx6C$7;8On1hj>2q)g)KKhkg?`?UhG)Vnp$*&|99Uua#|k__ z+l&S3bx1;ybv=h9jh$h}LCFdvL=NylliihiKQ;`eO4vrmWEaI>umGESu)tRMRD)gt z(S&{99?i}})B(dPI6%tCrW0GVW3y+>w+u0rs{yH- zXibA)TDv+jO#|37pp{IbZ*ftaa&RLFeAw+)-sK6>SAmc~j?w!eh{=!vC=QScU0&90 zqQQm?KnsUktIx&syzG;ow>^P?#!OQcp_2v9-v#Pz@`JnRP^aIA9}g(ENmd#Gp9y5D zHJI}9a*7qQ)O5#q*UIGk-FHmU1^NmJ{7g%*6j4-2nm*v$hv*1bw^^pXhTwPoswBIh}8Ktq+3N*(aRf@LM6udpkM8n)sqVwy{M`peoIkyTz zahH34jmZE`4+^LMjwnfnf$<3f;Hz{wL9hbQx!kU2N=o6IR)8LsmS}Kv!^5$%-2LOb zAv)Clq2{3f$^X*=WP>cKN&T!piHAvviNMRlOBg8diRZiYvm;1hgZfo^T@K%zP=&5K z0>trNs@=R8*oXQ49Kbn(`f$*-gYeW-Jtn{UGp`<}<7fZ5D``^JekLxMS@s^wQKgN% zEb{QbN}tVsmRAiQYgDD)Hbdr;nr&lk-0jvLyOs2w2K6O^MuO7MpgfjWqVuL*~mB8H_XCI=Rtos;0^s)0xr|x+@}|X&TY}s>J6>#Xp1c zPJGie%tc?C25Cn2VEADdMA+BAC4}fd;+%v~2BA}bL*14y|MrYcepMDv= zDp*Ccmw2y$};TKg^OQBNMEhauTaht=*kbsy6lguIEnE z`tGhAIP^f`9QdW+fB1-!66_{Pk+P4A+XbU3qIvm=AY3jH{!aXF*0*x`i~U53)mz){ z;A}e14V*;WHH(l2=>UD(nfmaHG6i#j~9{UX* z4`s&PqIhLIKiW0Y`{FIZohMK`J^qBRvf9c8oQyngn>3P{``TD``PicuN@LheB7&uB zfa8YF5qhhuCZPjdyZ3tT*D+=GV_FEB%gTU_r+N0K);_Wtp%!sj`Mc z-9J<6d=Tnm3~0B{6*%lz&(?ddt-k4k@4U+3#$%?sy9Ua(>q2+WpxQ43Ra@{ydr42G zH))m8U&QFMFl#gGP5?+PRcv?aNRSAbT%&0khwS6{AM(%1q1(dot(~JF;l0mInTD0z z$kj~FSPm4yY%E;wWV5LdLUsqcniw^zt?C#&y@C}*OS^hosa|!|00Px2pR)j}d||bc zaI6&gD#ph%F__)Q#x5)1Ci&f>St3D(YU6Z+E_Jri0~7|-h1}N1m6R-C5#5p0ORc?z z;Nx3ynrGE&Y@0^Ym+PwKls1k|m*crJ-p5r5KgV9^Ccx73i*kLmUdY6a;#q$K(JL-a z3giRw_gnlU%EX3wn46Ad3FzQkiG^qUKr~$~e>RxnK(BvW-8nQ=>V*KwMtDnf76A`R zyky5f^3wiZE9ufgb0Epqb6+P3_iHBX<^BErM~ShAA6tmgkw#=_eYcdoaOa_SpDVJ= zeKpylo$hQ#p{?)X>+Fr;8=mPMWzdAJEHj;VMODqPzDK5hR_S6a_a2=$Z4|&d+>fW; zl5l^3wYR3O`7aw-6^?CU}2I^Z&@WMX~#K>RisRKPa^bfTENv6$g4w_#N`lQPzAf$wsYTE*PE zD!10Zlc!hi_+)R})*&Bt0>TgEt^{o~vJ1A0#4J$%?Pdwx(`9}Qk2 zL<@YKe+Q^J{%I@T!WkfA9?AbgsfJ;+qojeOM5X!VwlzKSytDQ?x+8C?b9y<%*LRUn z%wr{b4+>oXzJ*p|+N5Hsn_snUQ`wd{dgf2Vf4S0hW|5?CDNntyO?Q$yYqNSmFg9P| zPn|_3nbDZhRS*NupMD|AYLe>7S(q&5w8%v4b4_z)y$4+w%^(K9r}sU@TLjJ z#sZ1H`E#;56m75)zv~3nTj$J-r_pLO`Q7R(2g+38Mxv%X6Y5+{ANOk6rQVd8w-84Z z@_cF{#CCe0Ktlh`HizFCI%w}tFz-H1# z(BZU4gJx>CtMT}TGs@uY+hNFj32>VIg9X)}>@Vf(xoT&>2&H#w*ZePkhhUid$Lt;? zRZ%o?6f)gkX_iYCx`(BoQCgeBt-#Rw#xE$1`2?0##coxcAmi^LxQ3!7-q!vA4~h9# zgrGa5D!UP5TzPI0_93hbU)cUIL{{=NX_rR>w}k%1dnKjKr#VViC;m9yR^j5;)#t*t zYU#>vNJhZ@`wIt+KTNFZ++Me9@S)AAZh-gAYFglcyJDfnUXvy+zrgAcagH$QL%w#P z+xZm5!v~zI3jHLz_}|Z^|L#Q%gl8_}mI{;?7c1G=*mxWc$yI=~LV5`=5mlGPB`0W$ zBnb}|jv_&5*#Lo}RjJlH!UuOg4*zL=C5Xc`>91qG^J$o|c=^i?$(-2tO(zmgY)Sxl zs>4!!JItsY7z+k0^3)Wjm#{}8NMnwF#bw<28+c`Kw(H@a#)rYHSv7p?FNk7H&(bSy2UBwX>C$MfgL?j#e>x{3d69*z4b+`u3AOVWGkMe0o)9;#_4Z zFVHi@vGnF}TR8iFVqM?fW2Dj>r*RII#`S#aC~O#(Twwl;H~SJFb4r|GwSzd~`w-jK z8R?*QFEpO|{KhWo=wuGL6ZaOKlwoEw6&24P5YzdUK%=hdZzQil7Py?prl%9v6jMve zB;??BB|k$at9m|O!in7_#NJ>iu*ih>r?>AxN2_d{z0i_~#&{O5g7359Z`$-?6`lbO zEKjE>yG$m{t*oZbGFw?|?#Z_HfJY3Xdhs3zIfHGiugl}9T8p!?uG`7Szao)#JuR%L zPzUR@$69)j^V;C!u+Y#<&e10ZM}GW-4CjhjqLoiJggR&#yxbDu^#OB(qxYNB+*0~o zt$SgD6IohETXm~mTUWpD23zGev1n`Lsi`RcS0mH-t7#wYy>RMKk1Sw+=FGf)9?iCi z+^v!0u05VwPIM~1usdZcuhvQ47v*k24Yf0o!kvaBeUdkQQIZUuXoi#h1;VOnTnN4B z>FI9{5WbU(M2b?FfHt(n~9~fv$Hl|r3!!5 zf7EDpM#ky~3=8xVYzPdqh~xY8JPenQXE~k&JR_XYcTln_1Q>zKq8-zf2UFj@Tl@A@ z&e>B*i7j)o&O-IM;y1;|bJG9r2d4mbEAy375$H63DY@Gr>7#Of9jhXLgQyZ-XF|(& zsO?P;53Brek)W`q1D?44N!LnonJ}gr0@XT|&~N|kvwhdPdJyPt`zF)6i8Qd5g>K<> zVm`{HKZcVvZc|;{oz0#%v`Jp}J#=WsD6J89)&!llZ$Yx%dP!$NyXdCGrc1YKYIv=`#z#@JfiXV8b9zDjzyBs!krwH9vI%|E4TOW>fZysN&)`{ z62BXBYYuvM?~d`JUzvvblPvSef+@Sx`77A6zLL$Br1lqj)lMxjuP*D$%cDrB+gTrD zEx_Xl)E8Bpckc(Y=fw9=pBGPBXJa9Xg*x9lGsz$%#Xqh)zHv%;4f~fo$4&4f^yg-h z(v#x9sUngh!+oawOUv%5^}ZkGhZ#}w2vv7{fA(1KwKb1t_L|9IvqX)PoR>#o`*}eXiP&(e--<8u`S8Hhpx{M zF^=A7PN+-oV?xRfLgt^j%12*_gox*!OiCNYFo_-RkBM{P;5IK%Br&64J6@+r7ne1W zTt$e&)=5|ErAm>5q+-+6OVak0!{_ebW!|O@RuwWmKCF4mHRL;8t8Pb2{h?HCn9-%lwKrjm{T?O{(M>7F@Uf>Om!?Op;_ZlDRlIGK+qSoZO)&<_55s0x;0f(9`Qj zj&?;hiZvWvUmRU-JJF)4z3;x)Q{sW=BCBsdKu*|?zl#aKajLe5T#@1fw23$LF!txV zdNE=TR+?XQSbL>_Nb~TP*k9v=e%> zSS50=udhS7lH%e9!Dc%G^X;YQ`#1eZq)6Nd-OPE4HTmO`XkJuli1EjVw6GECLyF%WnP22JnMhgcO2(n^_V;P{Q9Js9mZB zs>;;bvunbeJ!!+*6L2c&H>KsO5`lQiOgBc+ z%4{vP?f?vKYrv`|Es+#+I8cfUO;gFs9OD`E_VF+4Ze%<>}q z{EfWPH?EfC2*t)9W&^tq_0C?P&x zUjFXo^LxVwGT4km|(78EK`BD(Z)|CL4u|v-79_ zkiY(u2>b>{pS+UztgBF-Q)RNvfU*-7M-kM|cII@3p8RH}StNCTnnK5G{4nzF4RFY+ zFq#}G&I1WRgIb)?HV_uA`mz@It??^N(HlRkA(-Jgrpf^%`?iGpp2f(Nzly+v7skTI zJGcllcix9XLk<~j$eGfUSN@v4?tV-(@&pTHqp}f-H}}5=fKQ?v6wc^_!kKvHCnsdg zzZ0~&ZGG_vn?IZw^`y%Lm4hu*{B$93-AIq^!Bf9OHbSfhf>pX1sCV*ia*9MTIGfbx zoYFE0Ft7$uF_Qin)&n%Ah5&KpllruH54YTjegIs}ggnwAq{$MTf;6n@Pg$?@YZrg? zBE`*D8}phzzw;A`eebqf1GlkXkV!Ih|MiJP{kxy0+c)|&en}C#{vfUsUJ=UAQRuUK z_3lNYI53JvE@6i945dp~?ZdW$K%o@c3o7aCo+l@;5^@@a0{QoMSR|^rSVWqEFC^IR zcjT&HwA+OX>x+rr=arY@LzUJ13>~!eoTP&_;utAbe_ga$PF|1NXw}fr#Q+YD$Io%Q z`TFbgcWIPnchAWW5BRrFNwk^nE(J@vJrRe5?Ht>L#<{um+v|Z~riKzn3H(syLSF{g=VOlzyt=db4W z7R-w@R1FOcbyl1~iYqZGX)&QPfKIoeE|z_IpH@G+Yjr$-KE9?NkZ6r3P_Lq2UsB>_ z1kqjPyQX@>WU)c`!3%qpq9Nq9cxU4YL9HKqI_1@`C_=63o2A2JtdQvs9eK>h-Yzi% zudU~VX}&^i%OLzkIz^WD_R8o~-v%(9%<-Ufu*0?wjYbo9GL)s8!4l{n|M z;&2JtrPsD`lx*$s!prbdkz%A`2(SizKy#7A-C{nXBX4!j)^ne#-S@CcpB|g3@ zwAF!6Xe?6faHOg(IVov$Ys-2#WR3ddv0l|j=TpY=Lz%JF7MebJNd zv39GDrl!wT7gqV+615$@do**3L5^(<8K^}M}AS!dtqYIREL!7RV%|0 z(Yfp6FLGiA(vAPF0BFAs-1{S-G6#rWvpIDubE~R^TQmCEL86_48UMuu{nAB}KY1F? zZqEKqZ|}R`{O&VXX3NC-$&}NXyz>kpY215w9zp8a;M9$$P?|e_r?_#toQbb_nQhME zB}V4tu|Kh?v6x|InG*N-pI(s$Iq^T;dyksh0cI*6E}neMt++u4b$$avCvIXTR;@*+ zuhq+g7=5&MJy1x;Mj36G@?>%s7#77Jg3sNC&(&#t`r@a23&#$9Nr^3tji0FZVib?l z+Fls>T}8-7F~AvQi86MAe^9OMEd-0UV~yC65NGi_A53MZKc;Z}CCvNa-uraPc3QLX zT^F-xyz=8J|M%VsvS()|HVWl ziHDkJ40T$=qzvQ2!T$d63sasOP@2(09GSOe6mDi%UC|sgiy}V1-VP3*P0~x5Klwbs zXXJ@D-#WRD#&o%<`SB?-A~lt39-sKUl3HD$$ob38D_)IhR(L&Mw*(gx8Yey38N(oI zo{RUO8FkJbE${qc_>$(!P<}`2HB%o(+hN6w8-N!%HZPwv-YKcy7+HVin}Jzh5agCx z^&dD5rJ7lhaP!lL>q$@}8#|Ku6MFnHiJ~v&d>b$ec!y3b6X*vX7Z+YfcO`#vU31+8 zD>|3s@EY|9l2LiCRI(&uR=Fi&+s(v!(30HlbT<-_edp`3_3wP$rfq&~BT@P}lCyQ% zUwIhX*GV8jVjVvgMbNkPCdm`_})A1F**D@V^35Rf3?^ZquCwTGT zXSpm_V&BTkpz(2y_wV0-&i|;dXdKbx5;oF%v4i<{g=u#pB=Jncp02B|jwAWByS+UI zK_^ApCzzDHK<%@TGD4CwlJ&zS&*lQ-^){;qa6%+l9DLS-2;g`5PV@QEUys_cz(2gY zy8yKo`LlK9qWf?D%$qBc!QAn@qb6;l>$9JYftVkzp^JJ!f&lH-_HoRkdM^w4J__yQ zlfHq0O%O9eIM4g2U)T}ZCno3h&%OVM@#J91-{i(&=AS_I+2(|7JP*&){Q;4j3Jj?2}vVTZPvY6Q(&M!^6M8-2dMa30iJhSxaFUQ=6IU z4*>7~6=g33O=O+`4uyQUY$a{j7-w#YC~#ELP*V@ximrS8_w`V-vqivg5D;mkBOl); zCR79>*Su=X_wghG}kd0vMVE`WIyM@_A;FnlCdTw#VN%~fQEHQ zxfnH4Y1|-~U`Md*zwmOs_i=H|j%{?$iU6sEDfelB>7d94SwJyjBu%xP)mD;zpf+?* zVs+Z0&8Zq6W+|k3|Bs%VuJAU=?}!h|bDgC4uP%I3xMLT7NKXJ0+HIY06;OG7{WdI}7jYXu~wO^eY|4-k3N%xN=FssjBVkYek;6 zN+^+uDo26;m+F6lQ}?TI7^?o!Gn5@HNG!p9GB>rV97-4d!f+(soIBB9zPV`Tz6`j1 zm^7R_$}~#EzrK_P=Dk6Xo=^c6D;HPS{7Gv|XJ>)rq3^`0$;o4&v+uTYgkHp+iGuRX zJ(-ctkhjs`?hYpQq>+Vug8llBTtT@`s8M`iZ2fTY4%qkit6U0q=k`Y!0HnhpV>|zLu!oBsyiqv+yNwGAXSv}CXkbPKj&c;V zLppIa}j+pikMNeM~TC)#(r|;v{0|lI$?qXI}mfBzWXHfOZU&D~(&d5|b z8H`Vwu)f*pq<$~?m7DH~p%a_D8>2|txK(lAdu7k2sVV|f60!X+No`MPcKK5S`So{Z zp7U@?V2U&rcmuu_rqEIY+(K&^e)lM!`cv*AU2^ z;rZ+B`3*2`scUR)Y`|}{{U4d65t$aQ=M4JAaY0&U=L^@>Fl5062pbNYf?8^ic%alYsc?@ z9Q58Rzo2BcOwS<*PDaz2peytx&womIHRE~QEEwTy1{$VunqfSV-zfTC0-gBZw30uO1MY_&!5HEJ9xUH1P2O#+mzPZ!C)=1!^N;E^zb#PcBEHw%6$l+7BjBiha_DwS zdNMONlrC*&}s;Ds6RF#Es0H{Pe_U zgfUfB*!D1N6C5fP;J&<_pXBBry}+Gop=6U{n5Q;;vCiM_YHBJA)(5s|1*qflcTg#_ zyPo2?GnA*A!v}Xxj}XU-?Up8W7WH1r$8~F=i-X)iwGO4A(qzY0cxkUX`qx*Zhp^rj ze>pypYNTTN;j}*X80(jDXXL}xY&RT#jb;RQirGB!0uYz zp4TTfXq|%r#$9l#JomosY`MHmU-tE8cf&DW(d-AmY5$AN%UaZJd;hlZ!KNd@R~wBVKo&FLb|}_=qVVQ!vu&Vo(-O9Otp}ylz+W z*KoX1-ALr!HHJI7bKJ#zGNjy`MYbQl(q)MLwuK*b#fed^MPCi)k0evp?coZYRMVx~ zogs>fI3v~WZ0^~*aoqp<@?HRJFVW32bun(CBX>Y=pr$VbJ@$$oJ+Rk^ac}K-g!AQt z>m}wz&Nau{BpAigh=)P$2Ym%j^>J-B%M%k?wJ8G`4Sg5E=Uh{iDB_f}v#d7TjYg%2m&GeQ6~&IOn0n5DXkE0VSWy?b^B zn{}9j)#&>8ZvJ4;%wv6D*oo-j_vmwoD6h5rA!{#i&U^a%v^7b1xw2_}OA9*%b0T}$ zG0$A(9&>>-`U1kn-tE6)=wH&GljLS{)ilZLdhh!alD)>K z#j+CL2XiPhvZO)+sAf3snjrqF5 z2(fzS$xM%bo}CInFuxvupi<)Ct1BblaY~u?$%+({S1_d4ixDe{PG6~6>UK- z2l#myvlcqaV7z*BGVj|6XAn;~A2H|P-k&Y`DC4-Zo@3|ol$HEJ+6^e9$CJb6a+t$} z=G`1i0U<*OV5-Q?_qMqXn$)7i&&k)9)MG;V@&8_(0IdtS>qfAXBe;zxWirJv}|A@NpQvG%)Dl>v=x7AJGGp>*^Ic?nYE=(cxyVll$hyI@S}=94nBh zp}gr1u4Y!(_HLCM+GICUja*6kYgRCSH>SlM;@2hNu;S&6e?A!Qxnng3p4#IL+p zf~PG$ePMGdzJ9K??k`I!>!3(^*rz+YNT`MyVd!;%{qSfazr$edBJnJ}Uu6AhB?^b1 z*M5sVh>)g3N|DI4#@pX_;aMy}Ea}=7W{s*BJzf>plIO(Wd@f6U;D*$bek5k)i+cIfRsj zM{?~qIC}tk8LAH?fgsI#V{2=4a4;g}Vg|j@&0eeqfX-|Y{4o0s~cqUal4&NXG z(AjEi>mZf87M_t=?1{ zhcI@mD&izxdNFoV=L-cv2iCB*Y_SlSm5`?Q zN2P_DtwJkuV#-y^_mF(#7@Y6l$#G>QJkJ4E$|AkJo?jUz1 z^d0yA%I`k*?fh-xY}mYu3A=VK+!gVM9J$lGgZfFfWYJ#N9!6V>q4$)Ah5Dpo5!2{t zBoejvt4hpzWB0_9hFzX+2Y@ZV_J2;BBR(dzwa;kCTa})u+L%Q`&88=hi3EwL{y(DL zJRZvTed8v}*dj^DR)|7m%Qj{xOG+d{_EMJYS;p9xN?AjZFhfKU@=^9R%Oo+@Mz+CV zhQZjEu|3y(pV#ks{_Ry_-1l{z=W!m#`#eED|C1i}8y_Ru&+U6^rlnQ*PP8PW_r9vv z&=;Sn(dDqPU@-H%CDUElC~Z4%j$t-Rj*?Yi+d+u?O|Mt^&nS~rR#x^{;$v$^3&683 z+>yCe(LdQ_6uW8*F);QsbdUTrIEZ166uZiD=~)q6(l#h*r!`H|t0C;&O~zWrr#`zu zFLzoQ_~~AOyT{I_l}Uq`?RW3)>)dop$yD9e5%tD#H`i-f3sVCCo8WqUbV$3cz<3r6 z<_7lxe#z`Qb5WWEoqq!7dF6-jyNIA^ONd!7d}ZpCalYEd?xt;Iqx%wT;7*{Xa0_)Jksc%u~M_qyJfEHJa(Ncckij7+twRD z6Ikc(laMp^+-)_XNx%a%D5O~U^hYuHF20a5-loDC5uepM)Su%E=AMi*&c=5ilI#n20XNe;rl~R{Z^7NY9ix-)}L>2*>lCUwLgRU6o>% z&444oI=8aTG9Dbuj&g|_G~i-Xe$j0riiXgOas*p99RM^&9j5Bp7Bso~>f=qcf* z2A3MGgrwTBA0&^xk-j?>@9Cw+kP|!=;23{8`j3(P1I((2yixHRY==<#0asbeesC-l zEgLtS)3B%}$Rghe*VULUm#E}~gJs2;kQ~SH^n7M}QehK7;6-vVQ^$@}ae?COpDZhNA z#WnV?d(Zr{3ydZCPQ%A$ZgTjJnf3H9*=@S(%oAMld~7ewOR@VmhuSNJLZ8H!FRjhI z-m=cK`ZIzssnSnaY}HLQ48NAM^Ug)>+KC&!tLkc;M}D@+lK?q%+h(6y3kMI=Xj51{ z0L|yc%QvY#d=$!e+J344Xc!h9mDVDS9Lpp3*48khpjgu?08xI~QW2kQ@-vZ&*zeW} z40ye<3?f7!(1fKm!fRjab8q7>u_mVVWX@!mKI+a6QEy+bnG~{==H#7v+asT~aUAk^ z%z2*OT367gV=lubbXq_E!oR)CN#0W(TUYt8dM^*o;oKWyqop$BaqbEK4!v<&zfz>+ z`-FEh5AMJpWM&XUYHfG%#_UJQ8u+zOPD{>}Ux;>oi7QP+luEFUwVZMyls}E70l%M0 zl<|@8a05@Nn_i6f15ypk*BL^9NPq`9l;_F7p(I9Ta;k$ALJb@h$%rf*F_Y)tdVd=G z@~p>$g*t&cyMrYcTA4`ge$9F)T3R}=^!59r{E6c=F#%jf8TwH5fb`v0lr^l^;z6iB zJ_l8nF9z?xr^F)5oTMT$3T6qKr8&mN4$YnM!P%nOCeW(WbHfXQ6)ZJT!;cX5p%rYU zrFG#H`>_4Rk^pkyo$f>XHHKG36~!?jCMf6^00acjlw=e7!-oOTs4A?b9OfR&on>tJ!;#VqD+eSGcmwx~b< zQOw4JS@Fk1gipUz^jufUL11HI=x?Fu?B>pPqTtrc^s_1nQX8v3s(&Gn5ttA_QEKK3 z6I;=n591{c{{P3SC6w_N-ICYaPs1_S{z;ixpKRey=xp(EFh3)=%0H4A7S`2r(6RLO z$kV+fPA1Ip@>dyd%Ws=m2u;U4?|XsRW0u)<*XxALm4l5o&5wiAj&j&8gdU~YZBkx! zh}%*72G`3yH39LLv4<2^W*xrr_Ghd5gsUbFp3zRkI8+lbFoXNWb*##BK{g2}Uf-)L zEF%f+X2_)|8`LtS3I$vup8ks0Py~(t}bFT$u0s^6xy`s#&*!l!G9&&4c2Tf z`Ted1Y~I>v$g?0C3z60(z~Sg16^(84Lh#Xm*VEinKqqoTs-d$%sl4yKqYX&3fDk8G z|MBJ1r#VkG{%WbboN|tp7)~9QV?*i_UQG&jpl~r@%TZWy~LJSNXo>6t}Mi) zprvvR2XTULZcKRg{qqgo6Uysn({3C!G+@UCk`9*Wr8902?-T7zJO(mI5_=(gLbXZ8 zwxQu7+Sp1JiCga(ma3&7so8R6&E5w&d=9b#Kr}&x*G>5U(+>ncJGd6&I)>jRH9c(+ z_QAdLJs_)pgEAa~_}Wl^e+qS`)vk!E>IM04ns~Xc1Sui$I<}^_Ej`a{W?bFGcjaYr ze~b;VajBQf`Hct&8E2aiA0BrRGU2-Ft~}V z+2Y#iOhhJq)njll%W|}@&1Bb?%buhK!-MHn$Ce>Yo%oTx9LWfiTyZdRUTbLT2c~jS*w8%0Hl}RQcu7*cg&I*(@5)L+g z?57yaE+;LIZMhE@2bD+}W?Kp?)p90<1>_`$hWs3|Z1F*Rm-8Y~Fm;M<6Co_c<a8xtaekw-R=R zaDui3^o9JUAE;#UN5MGHBlVu;wC;F^?)n_5^#dvVb&il&`Iqvii0ah&2KgBS%ts+) z3$!`niRKT0+UTa(wt4}{78Lk5Su?=H{Cd-J&$; z>Fh#hcIAeI41> zO_Fjsglb`)cvae!*Ii*EHc#zgaizk-(mPvj;g5BjfqVew|AtlU+VdO6dF zbKb|}!1QEE-U^o7+wlLt{{4ohhli}0Ta=g|A<9(p>Jl9;O6KT;UTX!&;o z50n+&EaYZ7vV`>N6SGAv6}__aO%wEU5Zdu99}i(%oBQ>`yH`26Jc8cvGMvisEy~d} zU_^}+o{;LP4vn+`US5G-P{E;*v)mKNu8RweUVnh4$-HD(u}hiLWAkF!!O4lnpI`rZ z6ql69lyan4R1dE|KlO4%SjDwtD?E@*8AK{>jjf(ClCT;CFZF!ldGY(NxWB7MJj$M_ zx)^>fN{S_u&y|H#xL6OyctBXiB#T;tvg;gQ_oCB@q>x8%dSdR=-6>-4iU;AD;(xZ2 zMFF9q(EEP(=+$7brp_*3_2Vs|HuNV658OH)wz7{S69Nr->GR8L9D1?w|AXmxIPn9s}=yEY7*<|DA7rkjX%{05~1UX0Ua5 z@Y)xaGFD7{Ne*rozHITMmOx6ni&}|eW%V|7sBHto;g4Jii3>4dVeXR#7t=K<%82J5 zl`rnGZ<0Af=S5Yxros_D!az7to9us35#F@O;n(uniq!fOMUu1UwZuVEJ zp@?FfV9}W4=@;hwVuD9yT$?*3$cX^3QL{NGGfNYF=wUd}Od+Q&{p0?#k7rce71cBp zYl-<*=HAyWlH0-UXTxv9F{zOhnQ=(>7a;Y$y)6w43<_O47&sY?`q@PoS92pF%)mP_ zG(7w+#RPTZZu*+|ja7*8`R~42+CC=tIs^N${8t0(IvBao``aH!)VNZ$`Ih!T@Dxy4 z(#kx&y-oa{^Yj+y(1fqah6h0Z0P9z~qKc^R-WMtFo8U7T; z=LH4iRvxeV0|77mLOxn%;n|c<>edN4)0c$tzFictG~@G)$%A0bS4P%}BV>HlEA<^- zR~I(suRG&K17efRS%07Y_@4UwzIsB8??5$FcHU{jJxngpJ}56d+br~gA-?Wl{rhm% z_c$GK5ya8Ew~qxm=<&+u5{=&Ap2*Aq6ww=tD~b@uug;a37NVHPKfVh=2@Qs*o+>$D zig6oOWOa((1$B949cS3Uy#4noSo=T znWQV3JUI7W)gw(xFlJ=(8+_`4eA%i(jmKOUZ|LnlHRgU{zM1{nau#^UYzr93ND2sS zT_ObLP!t8WblN{76DykPiwt^X%7;qL%%tCTQ%UMXS@H`ome&m2)eIfyt_NA{{faA1 z*6QWC-2rd*f0Isdz1cuytBU$D63rP?P-Gc(>uu**jO$b}nME z7xT_-xotjauwvCvQ0+&oli%>*7y!YtEg;1Cs$xQP|hR{T=u2^ec4$fEOV~**)56E(Z+n37@u;UxG;%cJa(|te1fp;jDjJuK4?x4DCC#F73Z3@zni&z&8n){gv{)Sr#%g zb3SM)*@YpRPQ?C&x$N11+m@EhtJkvb@MgJNj`cxJx#`^*g-lIq#%I;H<;tP?RU$@#Au74p+y2|*T^LiBaw;G;nJYMyye%cTKTGo>uwIvTzGCGrOKg2lx_hH-qM)pwk9<^#)^ayw#P1(e(iI+wiR_0 z{)4%8RY5O2zBg)v*H{RRJax@GO935HR04Sg)~S>y3}f^i#G9vX1}jE3sbrNznfXgN z#X%SNe_{7;RNw3##sU*iCS8R$zO!;%=W*H1d;1orKxqNyIfl(0S9G*m3G|Zl^hfy- z_V-y%f>Zh443oxRa=@KZkC^$5#fF41aZ-PE>UriO(;x<~DGbA~fR<(OGrnX`gZ$7s z)cIF;W#!6~m{gIGH|~9`-f6Wg*R@^HfHXZ9we!lmfZu4wOO>9r3_338P{L>$vFg;0nL0~q*|;pXt~Dj!Fm*yJ zbV_^v$lETw7B+$}|7a1wiw(#+@0NJv=H_O2s3#ir54zW)BsRHvT?2EYsi$I$5o71r z1J-kcR`H2+8<2N?@-a#ynOntEZ<0>>cK~>7>l^Uo*{hVo_)<}hOEujv^Y7XBiTtNlbx-tFO7|M@$vB= zKr0I@{ELu{m7X*~ZmyYn<#Qz^%lXER_N=!QDUempyZ`3}uq6j|EASr)2Foq775%_g z47S7!RJ>xOPBkMpa_iwrlJ4JdFgUk^#>!TOUXH*aJ4V*@8h&iB(t}_b=;X8aI1AhG z=!(gCZ3wR4%VeZ6dVf7mWPS5LIHWn_BkEFoQ#3zv12jk`n>`02lo)cen)ktS*sCUn zjX2}gSP}t!>Ik=OKHg)yj7=h&cz= zDP^o00l84`Ws~CAS|-+H^8(a@H{fG89Zs>l7i)?gw8SXDs_hvUSVdQ*G~d3Na(ux7 zCp}ul&CV8VFOL<)K)4EL1&Am7L_|0EdGgEmYte(6q9I1O(#o8VasM8Fkvcq#t&JZ^ z*o#gd@jcc&`v@?5J}u{54*j`u+F>| zY)TasjOz_^jtxgaq9XvTmI713vfbAg16G=k!-4BcTRwD}9V;0Se&UKnwx)J`t3+f3 z#|Pcj*;_wjYPsnKKRR7@OH{~P+Z!LZ)o|@;wNHLbP%3z$sXD-$I^la=@Y z)>6AUI%2ivSmR9MbiqBC|^jqMG2Duhc)n1(XJ@+3oGxNZ<2tXDWC4ghKsLj5A7u{y(g__hEQ^OhHHs(TM{6I# zS4Nv1fD5Yr@G$erzx7n*m78kE7`hWXA$P&1ccQM;STo{WO_KlQy0(G+)o7Th?iA%U z1=F8IH-cFq{2I*af4zZkkROF3-tYZ!TMW!>nlDv*C1dmr=>ESg8^pv#uUJoDL~@AF zX8dM#co5;C2@2=Ag{5%3DO~RbF+u~y;l9~ZI<;1LC$F%a54!udR0Irz!F@4m&n~Ff z$A#h0qI7YbkZw{rM_7B@3}FgAMid*nxVWUP#6<-!X_Y(*T{49oY*>ZGg-Q6%LZ`8t zlm@N@T#N$kumB09-Q6H-;RkXVgT*M2nz1fT?~Dw08oP(ToijBfU;SetWo=F6Kizt# z{lFjmSUvTvMJ#9&?qps2G@JoE@WxRdRFm`Xh8sm3eL|y?0<#5>Cq)vv&g_a=$kxMr zCIPbFNluHO*cHCp5o6Q;AXa`)IEK&EI~f1h-BdLwzHS)*`T(4aU%)h@3sugt=k4Tl zFE97{mxAjySx4nPSv=uR_G*>SbI(y6nS}2TH{JIEW~n(4qJ@9RxnEIfCMs~w`Y)Qi z%RFfdN3Jplr&!@`_lGM93lX znqq5!`A*2ih8_09_Ij<=S7Dji*+$T*y5C{OJGig|({ypvpUT0eoU1*D54dKifn6fs zoWCmkn-4}+)EKSS?hkPz^wgig@;TpHF#Py+v(X;=)z~Nak$g(Yu5rf0<6gI=_ZJ_L zN#1M5$%5K4DB(S^PM&em4VR4v1rOWvVP|n<7-y58?BX+eY*1(*JpWnZQL?b13Wt}2`3JZIr8`%;I0A1?YoR_n5t&!T z2myb%7eqYS!k8%P$-(0tVY28D%!5^CLL4;%rYqW$W-6hSZIJSWWVH76_+((9JpcqB zTtER5ez^(4|Eu952qDYg&9}$JLYV(6_g>Nz5c)4J@S-TGz4+a^xgoK zceLMdZm-{}{YrIEhNihP*T;2ERmLX7#h1b{v3YqKs!iQl5OLGH_LpbrPRC5^xRuBG z`%LM07NtP!B}(ac$xJNygUi~jttFa|#w*=(Jf$SQj0}7X3)ykj7Vi8dLxp~067|W^ zoK1j?-pB_^)gPUje&hynYDyCYMyiUjk3#5PX#Hd5M?R5kI9)Q$GPPG9W>^zrPNxg{ z(9wCY5zz`{Wreqi=iAZ}=_K(<#N9OlErqWXSq#F^$uO#`bI4VpI4}wUu5!1>k9EP# z;&5xk@os#_M}T{Lt?Ui532x;9r+t12w{j8{@aZpyudkkgGP1-@GMc|paWG!y9qF(2 z(ITKVSrBi2QbboK>gA4CCaO(nwhCvP3z016Q}(uy0ovI`5hTGD=A*T#7BhMU#&>=B zBCAvCWl|&v1yMBYM%<|zjJH*g3sPD@YAVT8+3n!V@e_@j8}^jsW^C)H9UJRX>hIee zH7Ni3R=m0DPke$nvsz7Z6Y^AhPS$5L;Y|&$V8>28abrGsoG3P`i{J=7f~t|LqzB@{ z`$$fVTYaNCu;5oae#sE)pd!sPU&9^I3k?+t<;LRZkY>z&_wG~}mu&D2+%D7y&iUBr zRPc#5WY=62Vl6y%8uTKmZy$s$=sj-h`@B$@+@nyJ#El^b_wG_p8 z*`CVElJW&r3#HA4LP)?$u$R!QXBe(tBmgPQO@*bZKgRsbbI@m-n{wR&rK=*n zd6l$t({upZ?^sS_)V^_nh;Y;_8Gbri_r`axVGZ>jO2;4%Qd_pC0iY^-WQ{ zb4+b~5WKuJ)@<6$eXBz96cTU-8!^;aR986G4YRlaC5{->XNYlKYt$p#De@^Vc7omLcf9NognE^PuCW| zj}v~){fBzQ%d5)G0-{i3-YW9oO;rp>lIfnH)<;qOgy$!$y46dV z8tgSV5UK}1Ah8>oP6?g9O3#*$zLOY*#qP*R>H^=)eVZlj}~|5^T4HwMla)$Hmw ztZbHHdR)q_oq6nPC5qIPzRnnOMNm6tRwn38EVQ}j(2(fK##n=i=g&5=lR|YhN5S8- z%m2rOsd&UHa-kN3IM82#nr^47Ha`GUGvK=jo`_Gs5i}?Qw);IPhW=fYVu}Bw$=*--Wwc*Fmkfy8EjG z<;ZMk7&Wv8Ymc5R8tjz}KwYojo6ibZ{(*Z+nQWvEWHc3ke_GwNRT|uFGnrbpx1Q1b zH92g_Nh4@A7mUWYs;V3B(1>+_i0t2erJB_3aP;3b@5!$_z}HFbRBg&D51o^tx$sfGJ`{3Bm9CgY~Hw9g&1Y z)y3*?ay8IQH$06au*3roukiG?iuK_TpDE!iF4 z6b6i2eS(v#%#C0_P9Jcqh(sLthRyJx`)Gwe1z!#Zc#Z4t%7?(ean1=@sfAx2I4*HF zRS(G(_p7=VF)h_oPNP4dCu?_{RzCN=$o0| z7n&SRE{eA%bs&T%g7oF*{DP^qjNpjY@SS-s60)R_qvk7izx0%U!L!bsbDh)lR`aj5 z1t>c$g3x$zjz~uHKRrDQAibXX&t9l+nS8^rux^AxkWCf&L( zkVH0xiqnN2t63!+uFrDxAV-m`43juq5h$O*PN1j22?E@TAQN)aktRDuO1M|`-q7j zUii?G%aB&izE3~aMRG26a;F)Jv=d?T@8?^^Uo68P?dMEC40Cn8#6TMVl3*Mql_K`0 z2;P4ovGp{rwF3Xgz+X2k8-NF<&=8}EG9(_E1Q)HV1=;=?KY_F>M}KZI;L%#l=lKyL z@F4AZQxg7LBlz4$gZ4|Dat3wr)eQpD)VFI!ePvDPBY7_ zS_HMG@xMM`^_L#`(Cu~|9~NK==r~C=8~J=nvpGFybG$Q(xXQoY3`!}5H5d=bIIOV& zzf3_zKIW1KUH+>5={1t%iF3UnBX@)xFg#wOYKXQpxX9+(6g+gM0f0B&R(ZV8XH*zr z<`qeM+xZWu+aP4wczCd})fofXif-PoPY{|w_Ulo5Zs~b~Ovw@S>J9XJ1e*j+!f+T* z557BA-5Apg;wFY=AhLN{ODtTEqIRso75z@4RNZxQVI`Jje@CRfz3QG2PdP%sN;~6G z^;eeP#NLwJL7lclk30*G^{dw+$_G2r`2WO`d84g<>9W~YS3TXSaEe=Q5l?o_ZH8-Q zE&JttAp~$0_BF_F=17S4u$zX4a(n9u&Kb^scF5r@Q*xriZ9ONLls$YG3eFFJ(gmAB z%0P@#0tGPrtS&u0J)d&bpr;uoNk71F1N30SPgM>{2JiuzBLO^9l1A~po5hd)RSj7m zbHN!O#I7`mTJQc={FXp~>}FrNVAt$-r=YgrjE_HF0(%_QY1>xAa!I2HnM^o`DHE{$ z@eB*Ne;OG*Pna8*yRMn!8q||Yyc;gjqubbJX${Q@8*94Yy6ri+FUY);@pkdB2eWgR zxcbUKH3-xxHTl9OY|NBr?x$K6ts?Z2|yd`2f@XBzNXa|!G~lA(4eW70JRf)e1P5B zDvz+EjbrV%iY=co9(IiaxqI?(1wjU&x4|O#p&Otlfh&&0?y!6P*=EzhoIKeKO?^wV z5#SGc@Ix<83Z|}Q6nKXc1gW!9@Gt1&Jv0t|_z%5Mfe{((QN_y|29J$R7J`ZL;VuUL z*W`E;kg-JfUV*o26BBWOp@Ki9T|aY|J+n5NgZ-{b%*peHOMZY$oqNac@#)8pA5S8e zz_d$)5f%9(x$UH8X9w?F!Dp8Rhql;Gax@EG;+px7Dq#Vwy%68);~ymawx+TrK!LQv z%z0Gt}Y92KM7&;BPQS!%ElId=twVN09P1 zZFjXSN-feV=QpEJ=Fj(|{=wuyy3kF1A7t?Wvw3TmkW5Z75Hak&pDD8$1#!y#Bq)aF z5;|EGke}C_?NEbZSl|@%&8EM%vfCn$iF*mrv z`%PwH(Ry6Jc9jGK*H3WqJhv*ZlijNPc1||n!&)=8qWWgDD-Xa3EK*QxJ^KEK~Akk9|Q~z$=D@cauYdPvL)$-Zw#=)y8 zUJSOxx+XtCGGW!FGtL=NQ;TOf-W+}+5E^Coq7y}0jpjUVuCKQlShTP~DaY}?6%`S- zvpn0p4L^!4+xvpHPV@K&tkW~qppo-mIT^;>=7^XHpK3bCj(QfpC4F-#3(JIV6Q_yT zxdq*4p)tnmO2OY+vjcR+Ue9(CjE8eTZPoQ|Z_k%H4LyGjt+x^RZg65wY&}ED=TUC*4yIk(zNK@k?z?SD z69B2(1x>%`ioF;`ODIR**rodwML3HZ`}?;LSbTu58i;pBG+m^P3!aUd))C2YA(?Q~ zInAh!q%|XxHeO4Ogt@EEJ_hF6i;3gL^+~=VGyE}+tH!h_F$6hLQS^m0dtHK!gsClw zKB5{Ep?obJcD#i`sp!dj?PqGv((eN+>?6?#M}U^dXP;6Die1({?x{n(052BDutRpEds67e@tTG0IbgYUDn(qJK4G)5sjvnhp59m+lJ@M$b2p1x(*# zs>(F;(P;(_L|)tlWAOU{Y z)!HP>KGcS=IT?q3pgqw3%lp#2cK-c(!5dllum9^K1O?M1>_XQ%>Zpq) zW~bIv%8`jpo1f$tK=W8P70rHBTX5)5TpRuD>Ux^1>Fb)P__%%UPZZx4MR+RIMo38@-TJhlB>W#vV>M7q!0n~GG$2ZpRhsY`1ykLmAoM*7?X3I4Ka z`bgoVb2tsxeY>r%iz7j)qSO4sAU!CWTZJ){xkwGW3GAiW{i zd#a&r^Fg_i%nJNjl;hrd);?n+qk`u*WzR->d3>7fILRpe*<(i`8h0EzD9OurcGFTb z@UxX{anV0>6B83jZH)9ZxW>W3(_WN1P<(z~nwhCZPUL&*+RF%EYr~`V`;cBIZUYU@ zmQKAxjFOmhfJo7rG0y2vErcv(dD?~i1M4}GyHo!4I}@>G2jt0t0PXOzYL&|c@Kyai zW)BgEv9LB{ZA+8B!dW*pBdw}2&oL|1ax3@lxesk2tD=6C-T267vZU8_XqWx$R?Uu? z#ozyGE-LmAHJSUyC2MkCAM}lm7K75A^bZ?e1-3dXRyl@;!#umda_E%K7rk#Sxb7Q3 z#0CwLg!)1FidOcygNSYAql9pF)!}CwBjaDWkYbZ8HpxN03_E z6ImN61^&#RyPtQz!V}fn=R_a8tiBxhXXDe%L2X05!)z7zWTdw(Y>hV?mSo5WT=U4X zB$tVu7%!Lw=Jz;3d7Y69rf*v@zdaH&+=umim3-ei(Nt|^E4+^D^zk;Y<4T0)-}aBc%r%U?UPzC7i!vml5*&+e2&W1);6l5{^bGD)9}g* zB}h#U<)C{1wHMdN#`BZ2U02v_b9wN{ndF}Wz4ypu^6ia3KMt7lJ8JbEg7P>uAShy} z-qFtRb@Iin=_jPAU6yld_K4#a9&KfZex^WQRN(%?`|f?n#QHpz*uNEw5+#&bq5lBNk0R4N8e7kVyP-?NYXxVJ7iVv*>iE$0B<2~%L%N;9w+OZEh zxnhvY4WoHJE*fHyy?&dcxF(C{&D+gyWwa}V;o-LE;{)Q>e)I8urozzEAGUNC3<1ys zBziNoN{bz+=JRHE zIc7CjMVo`OHjU>bBX0_Hj6vn7_ogT!RhT3A{EHAfH@t5v(`eX~_KI!j&Zv6;sV`60 z#ZVwpl-}B3cVc>Dkq__8K;;AeVB|cfE)61UU|w<`G$FJW;?A9gkMVK?fI$Mv=(LT$ z9%UlZ8Za2j@N>|U7|k;ZK_ed5?t`(<6QNCiM|zV9+j8=#Cgo3`=T4a&E5|oP#1HHH zKrN-=8pp;;K#2huQ!di>2T&m*oG5_ceDv;|U(b$+S~P+_kWrb=#QwhC-Iuiw>jfgD zc&~HHE>HlEKr+P;&7%CDgizf*q+#SG=BAr7zFLP?Cg{N?MBB+aQp1MC6?B;PJ#^e} z{rnWpet(TR=mn|Uw@ZeXfmTh6m3Jlznhm&ta;N_#U8&~z<_TQU&(6f|4VNehx=)%) zrDk|>@-Wp&D0lD3w&DMI z0p=;wc5;>qEVIW>?$Glc_#@#RdzYhHFZs<#?WpN7+U;^UAmSN(PwYQm_2LQ@To!QCq&O^{dOu&MO;n z7%};}wD9M!jD9TylIVNd2b}EYH%l)3u2qp( zgR0NS+{*6_ux+yfcID3A^;(F|u5T!-{LkB)$v@dPH%TPdffrv%Zrbs1@oG?YVD9NFFV?-K=5tFR}2T2X{>)l!??S$<~8zYID|Yv}a{U2q*`B0IH2)H`NVfr50>@1ykRyp`rcVVZT(Urw?a#e=~e_Gd^c>&)h<` zte@*w2#0y35;*V%Ebfm46p0=Xb!2c|4e>8Iw{lNYoVyipP6{kBN$UmmQfHz3vw@#z z_f3%jpF?N`pjoA}l9Y~WYis?j6x9APl$zhKuC6Y*d+D=vDX{jsg1HZbO9Z4OiWH$> zh3n}~NtQT#8^2+19p}!XC$8C1hijy^r^D+_=&I+|L5{IgwO>+fkcgE!^QV?mBna+B ziu|-w^#$V{-~ix4!L9`OyW)-x-A4i`O<{G^;u6I=F={%=Je1MUO_f1j$lrG6eaG@e zzaj7%l?)I3GrMx7o2X_4utu{TZntL=DcP9u?du`c@ny|Ilpy?pQtBO{^GT>cBa$MW zw{No)PvgVne>#yAVYIFXnci$yOCC1m|FL}aErE;3z3D`Yj!LS8i-w)(oG0u|H7B<% zkYOHxq1$RevqQGJI zg~Q$B-}c>;oU@GIFc=Ju7;~0pNGjp)9h1L*>m{4mU6}4J%IIB< zR<=Co?+?JV@|GTBl@6L3IBLJw5#@X6>AH9=8;ozmHXP~nF_wP2TKqCXW|Ite=tMZv zL!r$RgZU9G-)ZRWFMXrMHv7~eTPrPDkiGog(K0X|)lwm)HjCGc^nXEN6+@sDNWkZj znx0loD_;P1vbav-;XUBG1D6Ej>dZCOzIJ5SUX=91V!`_QdL?GCzLj)?K#-P`C5=W< zi&PqdF*%4uJ)C{kc8t_}@O%u{-n)P6YTR!NF3H_%(VYJ^Vw>xqMOLvf0mD|kNa)@A zvS!#8{T>+{L$qg88XJRR6twc}*!TGy#0kCWcye+h&Kpw0xeaa6QdP|;F3-VCPxI4l zJbr8WUOl&dY2bDM{&1%}Cx(XC!(cvzQ0`z~h>k4w?BuvCCD2b?KjjY8ctE!PQVxO$ zgTNq!W9%Mx^Uc+37XGHtM2f7l^Xua;c|IP+EJSrd(fLix=y(?)^ZWa9u)%*nl%iJ} zHt+Gq>4mxa+`ZD7Y`;K!tqt3Ve8muS?mV=&J~;*32Pw<2Gf?}sgM6g{mAv4#GNb|5 zxQh@L-e=KzbXAGjZRR*Z{KQ;GM~AM7C|Bt0fsk#yNu1y(`Ko(^Pt>J8&)cvmcmEIt^usG!hWCmB05gQVe817&RAYTfhH&+MrwiX=U3qt&SN`Xqndu-5uI$lxqIC;%C1#zumd4 z``rw=4D`d>HtK6$L9W10)Klt2SEc35(busi!YVw=Ys9?F;!&5>>TLxMZyTU=K+Q0q z@VFE`uGu)nR)(=XD*gUW5P3P;}zD@{!y=Q83ZZp_fx72;k2gDF%-EBp2Pq! z3tEh3m;2>$`{mdFN)tAq!SU*171w}11MD(xAWlWI+W_&8Q&^(_$Z|z331cB_Z$h&S zOw#)dxXL~{k=ShrYFb)8lp~IfDcCzm-MYt>RvRMweB`h`>P?D8*fq?V)!6QPpdKP# z$h{4$gsCauNVmfut_VC?5j|c&`!BOQyl<836_gMQ5w+OOz zF3FQIhl@Y0yI@}+N&aI)9d^v4%qz3qw)RNs(o#){x%I^2IR|bn?Tsen)Ch*C5c7V@ z7xm267%jdM2t(kb5czygGn!m3NO8H=_m5iLHoGR~^@D@N{#A#>ZJ!M0P(S>qB*IrxoYx zhSCmE*^dsIdSt_Vvk6@y7WXo`=gyGl9*nSB%(j2b`z5m*Pm&IX%sSt{ZZUzC49fqh9JSFz#1pn){F9e1!nlJGw z$T2vnh3^!4HHj11Y2Lr~%y|44NDh(;cQPCBv*Glx;Ao8^e0{ zS>zd=*cf%UAE!T-l-vf5fchRdOS`ktV2jt=D)vkNgYN$Ys!3<&*2WtW+EPIQ*2y4x zMOK!UW2AlZU`5{Mh*NT@gU=V=y+oQn zDL6!(;ggp-Y58~yzq54(YoJu$!G)diMmVRaBP8;VHnk1?)h3v08)nS+Z%Kgc!?jX$ zc=;GzQ1bbgcrv|sQHG|C$X7o*QsijNl|Ns`(rbKkde>4ML?aA!qkQ;Rd_)4uW_Zz73bs;$f|EiKu; z0`JUQTf)-S^4aaCX@1q?i0w(}&GnMHjYDVWFc0$%3or7rK(IGx;SxW8{&R2`j!*}0Op{CPj^$E=Wh-ng<-GCQBM1syI;wh2;r3HI=$t_Dr_RQ4NPe|h4A}`I{#68T>+2c*_AX~tO zU2nR(TgNDMZWut$#OM}Y!HLdY6|R`))yST)H4_asYQNF`Q=KRy-2OGIu46lK%>UzG zBr&H5xNi$o9)C#=&NiOu#X>7P`Gqjfv&v;k4wh zL913rN3Gck#^ko;WH-8h|BeFyg|w4r74&D_XH;j-;su`wE_hPSTuzl&d^3(v4KMN} z{_FUjSX6@tIqU-s% z8$zmMOU_um@mrc{PK9)>jTM{=^}%Y3`Jc0rWf%#VlrS4L(3${0VM zsYmyk7xUSFz73WK9bn9qWh=!_Hk`G+B>u5HzABYrgp&h_OTO-N#!dS$wG-40n__ePXNw1%~V5|Tu zY!Hhuh3HSp#ECte07o()wmc5mecuCSc

    cV`Ukw4X!R`BG2qBqHl z)3F1~lIzH2^+5jFe5u-?gTRMXd(})c|L;-*BhHnkeXpb$T#9%I*sEK> zg=9jzIRF0r>p%C-a`B{hP>f_%&bQ;Cc%~2W!dP0jOry4f0fiJQ=sFGKsS)_=XDN8} z2m}HRL<0kpJHF2)Qvj~`T{8rctV1gDlp2RL)aXf$=Dm21_j!-kPkx!3+kId6dHxbQG}|SrYx^%z z*sw~bQYOah6Hl1Hx2CdzSKtD9?beMplg|pqsL#yL)C_UcqXb^AFStqPX^(Y1CwjH) zc^d&z3M7T;{QRSWF(>si@6aGUMUapkvuvaq*`I~-J)%#Jg)wp77CX11KPO3DYlzz( zYZDk;`Sb`|eTO{Fwa7@AARItx=;K?|L#$~MKl@#TcDC)Z82fIQ)1$qwx^Xo0EiGJu_OZq28Px3NBmBQ z-R~-o+;{qNT;4oelukNUmCQVQXyWXsq=?~!7>y{$e-?tWNV)oT2r9FD^`%68bLUQ; zNent9fOV8$TQHqw^(!9vsr!(q+{-AQcwVhs`NO;LG{QXhHB8s?@(9W5Jb272uOsfsefGiDh%(B1LeeXU2@LVRt&Fu8rix?rquu zssTi}=Wk4k)W&&;@5TDV+}voG-aiZ!+ougQ{TC%;%jBT0H#;-Po8Hi1Ta{(|LDEBN ze8ZjNK(>BEQtv!bYW-oA?BLD!Z8QTNPfZjV`sV>~KST=Hp7;%qf%fLWwVWcCyP>Xu z#5$?$00f(!NK;YDhGH+of$hvH*%i@AEJ~Lt`H^sd(oL#gJzn089PK1JpNT4pp0wdd zoiLArwYl9UW4L*BskhvQ%j&JBS-iG(M@OXy9aT4+$eoy`5BMc7Py%GB7n1 z{#otLswyn{uh@8omB&>w+Pw~iSlp|3aCF=p%)@K%2Scs3E+m+QqYYW+qgO|UK)9(2 zxP$*;lP{7{eSPcQ)?3h$`@BF$%B)J10^9>`V&-h$2oA(TJi|L_#QG;n!2Vjh5B_G2 z1EY7t(O>2>vndxe#Cy$P=D(`?MJ@niC4*jxi}6Gut7I)nxaqL(Xwl@%vap~a+u=78 zpxt-qPj@xXFWA_^mX;Q`g{YniobgYO#vN4c!CW|~TNxUlKDPYX-!I_F0JO}YCfN=2 zF6YeyF!e1ot6|K3H9s#+<*N;_)dQ~v2z0sddO*)7C+c$`?Us0DfyUbV4AQ`Uz>0ry zyose;@Bc2J_0{x|ad?ME_WkSmad$31CcB)v#_urKgP%M9QO)u%YiQgeXFmR63~p56 znzfsoYskH|$Li}hwnd5JzgxR|gD7#z(rO{k_^*Ol7k;#B>j$K;Ljc;+uD=SpKQ0QT z{``4^0=X(P$J0a=bg<{-!quI-ho9%4eSM6Y!XECPC_ycR_K+v|^8&^6y@L1OFjy>G za<$|R4w%vZ`%_ppps1iQ2tOm@11e696CD?ueCMc-^4~Q)yDpddX#ROU$c63eQwMMH zY%c^OO#_|ujZ`e>g+(NB32om{(lfahQ#2uN`U?QQR3c9rsvj)Bf*Eo127mSiQT~D| zlC12m$8H+^D?M3?B?g z#4L|AsBuMF?{}lOp}bahZ@ZGtHi_i}d`xM_Uer5fAH?S`X5_m4y2Md)=j0@XY?y%i z3T(Nh*$4|N4KKM4qhaLkrP6aU19lOBuCG+bN4lB z&Gk&x=bOS1*Vsij*Zv@B{ACZXf9uX9ytM<-h~#D6s?F{dcsEY~mQKe$g+jInem>>1 zuIs(jF^}F$N^w*fo0(j>yI6`g9dkm>*X*ihM%K8Z%@b)L2d2MTj~c+tz%oH0wCz;* zcA8^Vvcojct4+b2d|PDHk`0`u&1~K8#mGa&mS2Q;m9g$ftpp7MS--J2JEbl3%S5km^*kR3Hz-TmJRM%h_WwTc%JR6^N34l6 zPURM@LSqH_eyW1vJ#_TYyS7Ub5)vN-0Bb})2-NGZUVwvWA zlw?uKaA%z#Qs>spchKUmgYB3xTJGN#?7oLv6RP1%X?Z}xe`*irtPAvM2P;g<1OhI6D&XD z`z$IP%<=Tc-7b@`DL9AOqjz679zKO%chE0(z_OGCqU9Mv&@+jZxj7J5@YXr+KWpU0 zAT+lT3d*)@h~Pl?5wDZUEpxV9TdjQijZI(%gu+)}uUbz+WPMU;F%Hg!^#Sg06`6fs zHNh9-phwMDq5cb@(*jU^6`@QCddpm#ZLE$KQ`;qVx056Ot74*too8~-=}TDGb`dWE zkkyfPPld6@1~tbye3CKlh}tI(B91%v@gbgWJZc;pl^zFU;mFxa!W=mfoFejFcz1F(dwQ>SBhc*aKM$OhAb`l7 zaL`Hpv4cMjl&36^^EH-{k+sjSmTE1vj@L1@Q(N5%HpLi?2t4ipjT}3k3W-Gv# z#CR!skWy`v(~|3Onj~D!=Em4qPsA%M zrKOsHmHIJbpN(&liB~$r>4eMr8(Q@HN#8)=9@-1p!3?=e{_L9vjD!WQq`?z~S2Mw= z79A3tOVT<3JS|khG~A8HweBLXnK3)09<^7E5W(FIPPAuVxk7%HNhEREN-)g~ z#gOgmYS0ss8mDjDjx9)$z%p6Vcjng(#N=pSnDtLmfFx;gY+6d^c^eI-wfwr$X^Wa_ zH}fEuIdykTXZqB*TSM{c#v5$V)kVR32+qorjI!aARunV&v&EyoRF>INL(1lPVu#tl zb;;=5Ga$SLH1*1- zFCQvuISrC_CTC{SQ?&-;(|%29;2#F-x(m@Gl~wHCXhWG?!EOxZFyFVPYf_ zCn+1(i8vYRCK_|FB?8s3zOL@8tbtcxwgLWd6;QEwv9j6C?3hC9{hVJ-O&7VGZ1?Pq zD98$$UY)zvos+00?elzd^Qll+B?>>(!chg34k^>0wE&&#;=3eDL?1K&7ca}lQ6?NO zHN|re2Z&lo_y1}E2ptex?qMQ@XJdfBu_742+^_?rOy8bBd=AW3j@GCVm@ey~Pz}eO zL@(_AeLPZ^$J}r~hN!ASp*I*I(kc?}{<`gEJ(Hzho6Runtf$MA#2a!F;mSKAOW*H~ zxxVmN2-8=Xp4a<6n%XOc_NlcK-k!%Fd4ybJ^~cwmy^O`(DM?4$OvIzF4Eopajq;wh zZ_R&QY!k%&p!#P|{z2aRt~L1Tsz8Xy6kII>MCP+fuxvc(mP@DG5Zk6(q1w1D^$t)Z zXm6@4-ayL5mu+{*-Q?)3q`vIsUu7<5vG_;<|8e+fzrbTvmx5l3!O4>)*yRVh_hGnK zj94%`=e!ua{wLb+@8-Y0zQRvtgv5yYryGoPD_OIVe}UK*4kB;ww__-hz=Z5;`Sa&b z@UwCBw+1G9?^C2qLL~|t0oc_?wum~n2lhcV8#f>H3gBOX!J!KWt8Cl2 zo&t(D?od#y4yy9>ZJv$s7_`@=*xxv~P5=_@n=cg!T$e&ZLf~VT39Kx`zj3CRq*uUx z9PLj24J4<4ad;UB0`S9%r19nofv+*i6~D@~zwZQ6@X+U+MA8)qe0kos;T(z(J=aSd zb1p6Wt1Mh1O&zxSouf6+z zV%hm2+Tzz^K@@A;(opx91D_p+xMf)ke(>?2Nc1EuKxYf!d$(@ zl0Q?v1lsnkM}S$g!4l+l!TSWEN5TPR;li4ReifVRYdR&6jBwM5%cRILSnI|FKnZ|& zUY(>UGHM2-B&6TuDdnl~>l4gJZn)Pi`2O1I6c+~#juEyWAAU5xvT=5pi*lWK`4hNd7ZHT8%ulzyIMf>$0#-scg~E*f^B=w)saM68m1&YpJ<$9{gi^ zbKYJ8U&$c6*-|KNfs;cvW#SY_&NlJRM@W?JcrV{EaZh@EuNF3;_u=rbOX53qDV+M% zuM}5FR&{R}uH17r!hrEq5nqM7f$prC3rJwM@YQtFAGGa&N{lSu?dnn?CdoXek!;=P zz`+olRvjHeqC)W^=UM?uVs#7VGp>74PYuibF{L~>((N1YcH?v-n^^Qw0dr2F;1+fb zE>Wxa3g19Y{hxggVv_dMfZTJS#PllGPTY#B)+E&$^AirDrztt*^nPbtU3?HJR{UoB zDmo@bschha@_$R6pmxqbF1K+V|wUZ|xoPuH3LZc4ODZmNpF+a~oHYQ`Ds! z&bUm9)~pq+?y_bJ>ED6_k`;x3{jb8}x8)vid>98S8noVX)~TlXxp=pWb>MmT=JKBHy zzCfns1Ew8F^V^+GeQ6khpIBQ@?Ok6@ZvW8wXJ=-a1*|&5wk?` zB<(&n8j}hTno%rJZ$x1KN#Zn<7hiB5-(OiIke|6Cel*SLXGzXtOskHgX_|Bc_VEEl z)S#Oi;lE*L;PCe6QS*1%)tmb&sXZb{Moq@68&b*~EqwbayA~5m*Jl_U#7HdW%F+Uk zK0k|t7)%}v?({W(+<0&9IDd&m%#*wnSGbi5FAo;%NJ`UL4Z!{7rMs$MT*^?A0K?btYS@HMl;!QbTrbl@5#g~b3?|&?YVsI z*cN55&fweoT&i}rAINt+@@9Na zBDv(m>}1iZ9Iaspf5QRes)R&7u5xHza7pP9pzSp9A1Swpx4=XJJ6Yn0RM1IBheEff z8-oj;3?eBIedAukrg=ZQys{NJ-+9?Uk_Mu6f~|05az9>jVQ4g*pG?zi%+*pqdnkRf zQ6mbGa(&N9M!7gz)mX9jcihe+@^cFX#zUZdk_4jDIP-b;yNtXyol?i1Ep$i(sh}PE zlebln9uX_N8G|#|u$DXOs39I?UPeo{9ho;wb@c8r609dg{bcFU6?i*t@`rNxt1Aln zQI(<=yohwZpk3td0{xQ6!Prp^`z?ui@DnzmnP=pQ2@ShBgO$E3ZpNiL_E%B`bv8D+7D;z%%Kb{U`Z?yIpCQi~a||E5aH#smud&HVwL1Rl z9`V%|+qS}EifKq_$IS3_OQDIK+FjG zB~T&;mbRe*JjJs1Te>07KCi;DFSBAco@#eISnj?{W{ST`ju|VFJu&O8EG^9huXT%b z<=L)tc~>_za*=ov6%|!ZojQ;RVb`rVv;|37a$2 zGyH-TT8Pn%w@(ExdjGDrDUD`TdOjz`vA(3O_*U3eV==YWEXm&MK2s0ix8T0QMi2J7 zJ378h^YiPJaym-5KktGLb)`G38C2EX$wk7i<9X*aar5ti2~O_Nc^8&GWV{%xs_Km! zeyyB7mb82*6cB?M{^S3}TO?!vrUCb_Lj3si!5g<;;8=6+uRNIUWD?L7ZesYmocD*B zS7NKp0!QWA`O9R8!Q0Y&QI(5CRZ@?F}*?^WK;LURUX%^ZMES+fF_IO_u0pE7}K#-CCd? z>^g^uQ}SAEF zVQjDS-@ef^(6M$wS z!wh_%lpY3dh=jG4jwj}@e|2+>n{m1L1=Fh+sQl)T=bkjoj7{r&rz!zW-c=sv$!ygr zUzOiDqSsRL+_r3XU>q|ZukhbPmUZ`i5-N=lo z1rk{v-xe~Ja^Lgy0)IcZ*W;4MDYw!{XxH%K|JWZ?{cSv2{_O!2;c05G@NIw!M1lMu z=il2>WzPyT8YIn0o&}ZL&YvAKVd=`|Ipa_k6gJI6f#tG@I`wRnwDGmS;ux5vr6o?> zxo-#C{AEX@A5(*;wS72Ly;I>{$7PEi>#%^_5W0EAmeEzx*Qr83&f5pR9&m;=g7uUn zYYaHUe9}lU62)Wx_TcnIZnQ3tGVH*Qt$-p{=zbom_lY%P%JTtI$n$c1T9v&fmzy}3qXHJCj`&w4m4m1i)>&FcIVwbQZHah}@h znJ#6}@oI^AT*#SVZ1N87sY_^B=i8g}2KeiA>QJz2yv29^=^aJ=Xu>Hf=y}miM4Y(GOZx6PCHj?da7U=jl3K_L7{k90~2|`(2Sb^tJh^_SxrIfO>=;px~bClEtV4_Bpcr)F;$vrWH!GY(0SCRl_KK z%yJq1rg$pRD5atySg#=d(4j&?0k#w1;Nu&WV9mO9iEiS>!E(jYq5Bs;kDnLE zn9!3Iuq<6rtry2vE=vZ@g9qgRb{Tn{QySAY2Uo7&gm{6b9ge&5A$KivElE9&M*VFB z=vRT&gYff_`*!M)F}BzvN(n^k#e!}QCcoVQfesKU_W>yC#!Nr~(M6TJMg<_}FMMnl z1oOqos>tm3dc)lSKv4Q%Oa-2M(Al>_E0SI`+iSyi2OQrYH4SMr6c&;nVInZ^pK{3I z&9m)>>tY#BPYcd|#Vy|z$uX*&sEXRAgv?i*iMU`T#%j;kvFC|LqepEpif^}au;N|ggj3~2ja*dc;zcXi&FnMHtoXWiEyW_W{HHh$zI!HM9)9xL9 zSy{@$PbK1ROslT-dhp`Y!#LWW7L%t*-iAy+Ps!|mg8Lhl!wNa=5LPKa>F+T~qq?#@ z<6@A;U&&CCNC=k^oG0tKar7>t2^`Ei+m|;iNRq;&%wO~#;2JwYhHYA2p;N){dEHaT z-KL{0X57yCf+m&vriAxvX7C%dI7|`bUd($S|Lk4(^A`fTFRz9-C7_@l(_VR-^*fmV zdnyjlkUea4cHm(VJk!V;?2bU(H|hBU7h=7_c%?9Ltj)#;)9(v)*f}4Q%b4G9wXv_2 zWMDjFLaAthu1#hm{pb&Zep{+0D!3xAkunuDQSQ3>V!IRxWK@&>^|h31m)<_P#_ql< zACkBB*O6og;;~2Tc0s@w$YF&c+5i>>gco;%NuYw`LR{h>y?gS|+>Y5#r&%m)q|NGC zRgsbTH%!O7#rIi0aw)H{(|lxal(q)ChOtSpUG_kK z+YyGWz+pK$UTfyXuRoClF5IZ`308{!AeRQ+=l?3f^&~ZXG@w|Nh|&-piqf#|xreEl z5X6dJYTf!}OusKaJ-k;(m{z7=q~1%j{54U+xD|D$2ut`>cDb{xzGkRd;1{n-glX&0 zWm-c2B7ebzpIbno-4C7oV)JhydY|1E?&7{lVnTOMv!xcHs)nSoISW!&nH_Ub;_otz z=vmL|Axj=ndYtQULYs$s>~^*IP=_}Z(dy7K19^`eZ6+E7Q19@zd~%IIGrGebAC65X z&O=|2L*1WN!;l&~9%7ANYTpl2YDdFF zqgCp{6FD{>M&OPCXZgVg?2|J<R8@Y=ZXN_uv8F z1v#POt+24Lg@<6t%9kK4&2n60%9|0hoqTuiGYD+VOh7JeQSxfM26VxSe%{akScCyC zeNokbVA#D040G`%{w)=Y%$n@ZR(1Fs?J+Om#KR=`VcA;#pKe7aJt7wV`9;q%h(j$nDp1sjQ&FYq%2^-s^@PY5sM{^&3L3ibBN5)a$W#39_3l7xh)0)a z5C7Bfmbv*J%1nNR1jo?kZ4{+Mtb=2JKw_lH(MW=o8IPrXuW3*FB|`xaTAA5?&m z&Ofl-^ovGpD*uyb{#VqYCwe!kT|3s2Zbho+`zi=eWWnZED)&xff9zs%7cR*PlLkHU zv$s{QvYJ-h6*f6eE^6AWr4k9IfnC1}2D$IT5{J5-XIYD^q^^zH&Cv8!{(v0NiB z%frd~No_;gFYd?A?gk_rOvp(0tM|6;C=7?Ha|Tw*1{|89c2SBe-;m4Axzr=g2r+x{ zDnqnT=b_{crY_lFsqOFR2f^e5+F6(7NUtN=GPBsX@1WYAM-coohV3^E?T{4^$}FL^r8;Em7Nn<+dh7O5=dDYl`SG=S z-dXdpySNYb>F~kMFa`B%d$FV?CX4~(nR3A|pv)HE*!Eer3-F0aUQyHQF#*W!iM6=x zPdm|MyKUYUGv-oLOtv&J*M10RYGAtvj7^IXdKi}l_%t($yC9*7GW?ryg+A8`U&3VV z~(d`*ur-j9^+jbEX{fM~Y6vYP;%gJ{$1W13h z3dxViPQXCfe3+V>65nc&GBg;GAMVPHvb|scxNp#p=Uzq@y;rbY;NAXi+k5!kxO>aA zsuU-fu>2#FJS?4qp-(pL>QI7Sd5Qn_+oCBE$yHT0^Lz4I-KI;rky{6wPe@3no?g9e zC}mi;K)TJd$cWN$@p#$Bv6K&jvDXx`+Ut+`>IY?uQ~N0{ZWX#5>D%{9!15$7PL&b)xZ zQ~zr~f;(wKK}c8?EFk`!+5^7Iu*(TVF7DN(4I*#NSepUOUuqL}*h2<>U`G-G~yvDjCht*B8yZrXUt_52j-^5;!- zwnqe#aK$XuM2tJ}jrEaMsDZL>vzS=qY30Yq>37={nZC;`zr0QtR8A=S*e9xWZ>%g$5o0`jtmBueowy}QDGC`z08$iTpjTIWsI_OEFqe3uys;Uorz zI75QF5^W*~nTyT0c_p1p>D*y~OO%;fS+}Rj+wlOH;>BzZxHS->5t!Z7B(k{mXDo|xV9c(uD0SYpzR7lPCmkY?Gw|qX`tMxS0?qiD_)M8Sz z=arZg`Hv}db-az7^K(PREo1uIQU0P?NO7g4fTtOW{JJpAZDbT(XbDd}&wemPIqj$A zw=`>}Gp-%%w#$|5{1y@e{n>xj@Kl6w%%{J@$W1(LQ-9Vg4(!^h`hBm+M;u>2m3aLxTdW2<$$P12%FWJW7Wj?=qNj+EwbS}Q(p&F1eW>2}|YB_2~{*6*C8IMwV#b~)Rp zD5|Tdz$!0Naa6Y;@xwLN&o1;O7Cb(B-qS6fL+x%>QoSLJ{I(OfiHTAYPQHjmaG0o0 z*l{xjKPdTl_{p^knvPLQV5bhnamcz_EW1IUVIGoh*6fcPiNsVxSFNiOT6JP&+W53` z55n=wPef}M_W7P>_u3SgawEg58QWwJ%;F?a^w2ssF4OcF0FTLB)FO z9l+@Tq_te{A))IvsJjM4eV~#kJ|Uq3xG+jLCwZPtdUCs6qj3Krq7yV5p+JA1DgcR) zhEm$p*DzB~9@lgZ4Przy7H}f(2H5#L_pKTFql7I?vMfF-J_WUuajT)yBNqRhu4x#u z2-W*|dk^}KAGijHQqV8hx9%PJdO>@DYFvdbTR>^f8(;7B-2I`wqhrHAVWvg%!@oZ3 zrXb2Z$3uIo^8s?c$0v=Y~C$`;lKT5S)lB%QV7{%?nEKT*O?eilq~iY^&gP0 zW1JdT9_x{@(;uRIi55Up9xEj;ma5GkD07maYU$_}EE(j6ACcsXM?V9G`$zcW$9yks3Kc`2xqm(PdnGS&@>x&Sh`UyNa8!cn-S0bEdQ4t6TJgg@`6%~AC9%tH4B;J=BR%4qEn#=b zcdG*$Lw2iV2#sJRe`@Wkwa%E(t|ki=)NO(TM4J0L9qr^-!ezJbh$nq>$w<3%r!qM& z4V0qzOaDBIMNDpJohvkA{;{SD%H{MQifh<*q;=TVja(mB$Ay#0`*_^UGOR|u`V_Zf zXW#0XNPurc-Cybe*bXx*?!5pIX51Fj^PQ?-{*<2(87+ZQPe8_5~mJ9XCe z`_(BCd|9A%$=Uhhsc_*`0V4Z7;2g^#_IPTX(BP}U5f&-c{jpQnZNZsaH_!6Y3KK|e zEK(Y;*mSLH6KR?hy@v}1S})l%!D6|P%#|1eT*1&ui`3lpVvZ)wj-9TE4`Sp=hntt! z9WIlk05O!UU$imhPPOI~!Weeg!{Dg2Tb3#ispdn1OL}k0=+rPv%;gfwd)F|B z4)9IzlRX-okxs_{Gi&=)&*P7f`9XULd-!6qkx<4MTI~OjOY{z-YTGXmPTEd)1*gdD zDUJ1P=XBpFHM^3Jo|~IWrVQXav^F(;*ihGTvg~0k=F)l;z1AznTvb2nAD#{!i zP672xJRP)uyaR835!d@9uAom>#-FihVa^)&;>8RnEj*<>%OI2iQ?X78-|z81y!_yn zft3TEv3tNYi)9F2Ew{Mkrt(_oUj02QN_%RhQ-|18Eze2^IIR1y4y}B3kr*GJ_EyU2 zY^`ZzX&{UBx{d7buaP@!8$xZTeDCOMfVHaDm4fV}4mRcX`|Zz>M}{O7D`w+c>>Pu! zmp+dLFWiA%9aSK=>OXA3*Y=eV=Ih=b)KyWV@f(w0XG1lnMJR^a&a+r}==0yMUn^il z@?Yz7a(nz@`ESX9OS8Lcc^FZCKBdE5fGLyL;?=^8SGlslQkEG3U$cKBZROIAmS@@> z>z1OzLRP3kYyTcY20eQ;$z;%iS1q_ac8l?N`1-`m$d)Qk+}D>)mAA<`pY=2;rKnhP za-t`28=tmBIMT;Rhr&M2lTj>i0rmGwp@ARev?XUbZzmFk=0`?p94 z>$eb;+R$&ST2{4R)E!q**cqi*3IQ)N~u zi9OFVq)YCa4#gNo{-?favrKMa)zk|OL$A;zl`pu4hRqa#j=y=YgKXy8 z@>h~>EYm8vDA3-&WJ@>~x9YLj-v47r^6<9lw#hY5N?ke9Cn!EQA-S|Y&zqRh0PN*s zn@hic`yUm+tX}~bB%^=h*Ez`{iKqb6j~8`x0;0j_J^E`064&2$yZ>@o`<2dX`ft*? zz|cax6pbAaRm^&d81oZ&^_2vgz6BfjzT$--D(cCO4~@e8P#Sq|3bjFrmqldWXx&>G zjh~)2zR0mNGy5J3UlKHRz8~ZPE@p$LY&l(BkjA%qZ(X=v^mm}#z!OMIZk?^gJC;9n zCRL`n;wAn%{xgCM!yEMcc9^4vJg#fTbvqD7dx*l>vO8~d7*Q{fVMJFnYAomnR;Uht zrWj{@Un5XnL+`_&T>E0Uw-mbg)W?oP8wz;TT6b3xJ8}#`2%~LjQe=tR%?TDQGFk2E zBrTDgp{ACynf#Z$mUl8QBJyrQ@XRVLC#X%Z=a{2T0EwQ zUAwEK>o{xOY^I(m>CJkHNDNlI?YXN|k97TF3_sa?ofl)X%ayN?#5VRN8ZocJ@UNLl zG6z61l09!H=bZ6P_A`a`q&OLcr^ub`26W+Wketr@0LvtYemZ5oDX{6XrvBddmntJK&Qv^CZs zgd>q_RpBquOn&9Vz`%|d)h^6MlHbmEKicIcrP-i`o^Ko!ysmUl6SV>LeH#`9Ek@AT zV)3O>5jQ_SBM|1rVdv@PCCcjTNprm{ToVP2`*5`QmwRh?gf4A+3qVeOjuX_qp9s5~+GBpf)hKPOp3D)tiE=4R( zFyr}#DE~&sIufN`ac8 z-9rWCbiXduT~e&C6+Me(TcduYK(Zc`XV3+#ERXSIhb=dvxCzD{p;C3NHv&Fq@qDLk5v{`6id?|-Q6RCpOT!3p>%rAw!Ovl?)}^e%YDfC<57gP@Sxs! z*9RoYOAK%G!`E(-V#h5Sv?L4QBi`)9dp;#i^IEuZ4Dn(oeIRNKbs&FxP^xE@{_h7v z5&vM=*nFDQc?Z`RfEMW)7&tAnlivZ>*fzotyWn&6+7*kTF26h%i*a-oS=N>*Teb|N z*MC)2!q= zfq{V1<2$3gZCU=yfy-7m%H)E@>1zgF%)!7H+L>j)9e}aaC{}0{u1tt&pGpfSN%fjO z4MluRJ?R+;x9dDD?cEVsCO0$T>Jc^0UoW?+hC~CDT6@YCR3hLr^DU3-I zP5Ny&(k0p&ae~dFw77ERw)`Cb_E!{Ygu^K{?QM?!o1Ch5ar)}aAcK)ELtH;n43hbM zL&!I_0J;30FBmN`bFw~`Xg@0R~;(VKK_1e&&XC?zz^)#(>_H!%KuN!(!_+2aTmecOjUPq=t zYAbn=vFWv62Ji7B=8sMeAA`n-I=}3A2#e#yLHt3I-5726F0!^u{AKS;{|WGvrfo~w z0KReETXzTOEbtn2Q*VJUbbH%XUu@}S5k8eW+t~f?-U;wR19`rcwemHc1_N5fKV=Ox*F1d5hZYRR15Itp{@56LclBk2XqT+XnX+K3Ik6!o%3$%? zO_>=E`&l$N;N-7E^xa9R1#`{bSuiQJP?>CnaWNRkO!mARb}S7cd`b$7&y>6E-4 ztp{|$W)YwCPX?+m*<;P(4oerc8Wh1m9O@mtACKH$;}7sWVdPX@zjMfDouDPWai2YN zLuq_RZ@jAH+*oxtDhi3oy{B6?U^TDN)){h!Y3AC<{c-%xo zAn73JG)#=^^bl`+?tL0^e!#4{d)TWktQ_rl)NAcNu=zP)-}-C-#bF5zL@XID-OgZKqvBpK;1L;J&)Wx2kCAZK4si=wh1e2nu@81VqT++yF6^jNa zcpV;}?NvvZg)TlODNWtC#)>*n5ZmqAZ<79hxRSt+>?w4ZT+4^Qs{JFt{ZJXDVA^b| zajno=hh4zt#+Lr;Bdsk3=i}3Rw=|y>mO)ez@dXJMTOOQ^nm|resgsAvZ$k6b6)dDC zxLaSNzI$jK@Kl#2!$QHeNK$g%$2Rboj`@*g@F2V`;>O^U!7$hyevWMZ@tqe+GO}MX zT1hI?zneYaj{@PW0yU?ulNX`lcL;q!2L439E%t)c)`;fhT~kzU18w``Axf~kqt70UZ{32WwT038DE;Y#n`Rktxv_mb_6JZL8aC&SB_Iiq_lvZ9T z*QSQqIjzk@qt3j|JTLA%Vb^(tINn?`gK`NQn-e8e(k4xEEPM5vUAUd_nMN&Tz$eQUu)?Trlge;`8-ob#piAZ-)PLGP7D@k1{3Gm)I}VN;+Ac`t6~2>!rfm4g-u^y?>#W#Z?HT`}GRCZ})m1B6wMtgB{>yG0hZ?xd-Tr33%8_BS+%=kT7^ zox@^~h#4!P40)erq^-={799gIloCojK0XGiagU5(z=hyE8wg}OT7G*!P2QA^#byr& zkd{GF8soe#Kr#ua(A^^v^R_xFv6U}GewCMJ198c+LSwdLL}JQztgnhOMidaFQGVTB z^i_Z7np0f9;Dw6BhGum8u^p1_H9G|39<4L6Z+neVlnsP`W5J#UHYDG>(XXa`*g z0+oJ-2H?~M|G4(-CxNF5p6BcKA6ggVfpnfL+W#Us3Z#$$aP*I3)deoTY(bhhLC?fA z0^FY<3xf)&P534mE4!HhvCIAG6~C{I8BmjG3w&j$8XvVJHTU7ED>$GUynGEoL^u_e zDx4Zy%{^yRwIZExY?H_2qCD)iG~`}qq;CRtPq6s{-Fp%Mok5^)w zQy;Gwo@&E2K0qZ8;H2&QcwHi4654M8c{k`&AcC;D>cZ%s)-n{jq9*%Pbt`nr~>lMdhcbeYJpk6dG$1{XO@bCLlUx%T9a++i19U2~i{3S-#g zICFYdgKLs3J)pwQ4xY0__INfZ((zeZCuk_j#Gb4?|8Mf zeApC#Q^{5h!e#@xB?D|4bR#*F5rgFu z+eNSLt=^<=B4qe*zpAOQ*y86xO>790w-Qh&;fWKUFEpDn_pYjvTAdi&8+{!y@YnA9 z64#P|{|#MNM0ME;bKI5NOwUXbQp;EoL4H0^5*Mv|%6ENwd)>q*%vl?8mGb+=?6*!& zW;2es>(rPhCSP0HD6P8fGEh?=^%@&!grj~)Le|pmSn)?GL>Y7UW_zGW;>7>!mhK6R zA|YAn3=D#ty-pP3Q(rsSyfidO^q8+p?4y&R4Mx63ko>uJH#__sjOpdSe*Gd#eQ}8z zU(L|`o>`QeA%W79QsnLn7fe>n;D!fOOwnpo1hHHArxNpjXnO0oCcOXsTLnQBG0-<9 zpi(L&-J6I=4*{hlR9d>5iKvKl=NL+fAV@c;#9+jvyJL(2gOLLU_u1!r|NP5`>fM z&MU6#dF4tOhB2_Sa&|NCNX}g#9?MtzFgCO~_^?`gNMH3BxN3d+O(dbqWtW*0Kz)4D z>l*>{V%48K&xq?hylWnZ8dVwiBA0FQO-z7wks2kkjrK%Al=IW@L!wDxPcV+bxU6jOG<-EIHwY_;b6IU)t9e4~=*q9Y_@?OB=*)^o_<< zgwq~t_Fj#s>s<(o8dR-bS<4s5?`s1lpJ)XsVVUgo)6R0&%gQWTB$e?^3J85a9;vQB|LinPSLh~zvC zdSe|X!>43)XM7#5968li61Q`Df?K^)ei0etg{>@rX{vrm;7m>U&g5T2`VWR02#AM;76 zH9W=0l?DsW8p+S+nG^8s(ez~`y`Mm+0p!a_Km}7J$W2{D|Zl(Kx05(0k!-955Qp9mo$Q86b&#t@tY6h z>xa?3d9^ncxXm0m$l!~@C#VHZp9jh$S(`1he|q__f_qidzE($H#6bn8Eu2O13)Q~| zuO8TKI(1)-SsYAaq0Khwurd~4j|U*tr%#{iZd!v^9vB#Se^$xp+OF0hmB$;ub^jpS zm(QZ~pogs5ik}Y?B+rz$W}9&*S()1j_i=P@xtJ^j3AwkfH(KBvQ$J(&M#BWkR*rXs|xo^m3$YC+#VHxbD8bhVA4HxbIU5b z1Zeg?_lz0r1$$Wew=bC0uOZjlm{spAhs~&kcSv26YxR@A0?IUhE(~J`iDQ~+Vy^Dh zJ21yK;uLw?yO*z3mV83AS&i-x+cN92-IJJBYDAU(!~Po>$nFC6yXxM}-kUGbdnK0~ zdC*)(dT-9r;@BMp&^e#kWrTI$&rVdAvS%Cf>tgM5fx=M zA{oNRksluju1Af%;^;YXq?qF0!$efFt6*_S34YiDwZnvp*3k9S9--92^+$)#jSQc` z;qbU{h84Nbi{3LeW*a6_+O^sM$IavMuw%j3_4ZV=Ol|PC_H^>|el3}9pFCn9t!LB8 zZV7&G!WnLinFf>(N<&IKO@H(3@n*97n^B*F=MQqbZ&*iOk9bHGhMw`vbaZ8V&T->p z@;%G>i#J`V)r$Eagp>>Fyvnp^*U@RCr-_2fGJsk-y&WYXFW+$f8<>PdaSUxS@_ALd zQw*?qPn8nsMa`oL^!>g5 z{udg)&vHGwO{V+Jy!Ox~dQ6`>xp&rG-&K5P65{QX>eS!s%93{<;l22RHEgSn)E6kO zaCzQgP31Q}S-xEo_u$no7b|=b z-sMSS=3^dZV4$zB&cL*XBtB%d%nN<`3#jeYQYBwDOF-%*_$OqZU7fy^a|fs`2(m zCh{+lXNpM94Fsng{M^$v%@b#u{)Tm(kO`MXjrZ%r|O;+GqiUINWQ zhZR9!FLarnKEdY$A@A26bkG&>^MkH1sp;6qb*}qS8qUrophFvSko1=MARXGupL5pJ z&4h|0d}$XbuNiJhX8~_MI1_-Q>cyprrvbnd4X|^<4KtIIgCN-mBoJ!&H~?7(Abx%3 z@Lh~8|NAY65n;3@ykxSd6EzmlJ%baUmv;$FPXY>0E;vfU4zgM5@6-&&E8rQyQJGuU z;NQklWkx7%lHQQ^ioTO?aMx)^Vl`sL#UgNcyZ4KPxf4)Yva7-JN;zIXK0|V$C>2Ox zIx)U9D{(xir_Iy-kRqJaC|y9L9*PV=dhaadlxGMs-V)~_?>zt=g@DZN7!8#%0L&O0 z8>kJ&Uo-F4?3^U=d1+SxP{w+k=e8HF-OFoS_x+#p?l%qgm#bDc*5UY?G(4ZeuXr+ zQyu-gLIVCobMZ|EL4+|~Spl`%1fDN3@h13x;YQU=aR2vt{f6?_nauQf?!cv{qyAki zfVJhGvF*L4&5p=M?%t)6%i(ur!%i*i*Ohf!H5)Zg*vuy!*_?!VbiLNyPVwY&WbRKt z6hbQyZPtYHw~R0!=*V1{U9m z{Gr$q|Ie%iwEw)wFe-%rPM$ztS6aIrT${9l zKZRJs*EGbl+Y?WD}PCp?Qg)Ii&f5F|gG#VnnIB)w|Hn z6z@y;(gj2A-0ddQlEl2ktV@?QiT8t}>~Q#vbQD{KWcWs>;gB+_x-3+*!OSizqcH0*HKLDsGNEfA^F0QNr2o%Ao!10Dofw) zu}K3adEWeUfNBXA#G0FBQW}0=FZn49r4wX!s_kNJcua_i&G|Vf_J&uBL<-!4{D;AN57uM z*3LGt@?WJ@X8#5D_~{U`-TI3M6NjU6A5B3$#&Ycn?{C_z_@P0z3)a_n5}0FbngZmSLvB;KAxaLieMndYAxL9r-_Y z(QY>${dg~e6Yt4ugx8_EI(BAY&hkY3Y53tJKC;&nt-i{MPWg_pMfyY?+cZU#^?8=U zFuop-jif-SPw>6F!DCHq1X?+YXYnk1Grx<41s?Iq%m9!Bbb#*_$jd36IK?V0a1-$c z(%VMP5sPE)*lzm}40M6^7z4wSpLV8JHibF;8_pK~(ca)}22N@q82i`J@p*V;L_$vP z<@_J9#A+xhXIf4oF)9rFZ5kLzQ=nzW|7ePU$uM5pE3+Sv=9I+J=WAD_01TEO|L=JT zk_}Xee?n*_Ku67o3=loPT2nZ(A193a7r{KnGw#~2|EjAZ5~NzbYnYW77Q~_JIeO{= zy=tG^7xl#o4c3AHGWTO3Oi6catmk&9)w?6oM0mLD-nug(ZKC;Pp2@Ri8;QKNmXNKJ z8E=!)ZQ)14l*LKE6McU?O8{-UOoj~2sdD|u$KE~L64#)48}y}xo$tu8|BjsGH%?L{ z=|7NI2HtrE?G*YHf6l%e#e;e3AKbS7kI;G;k=t>UfXxZ@{Zkg_6T7D!)!QUI{$VZj zNW*XK;}Tbu*Ab|(4@qC|yb!8WJq>czsdl6l=D}s!mkiNj5xsy|$3j*j>5JRp|9Q68k~yD+!Oj=lqW*d{(MzK8^xd}H85*6z%+;NH_ap9pPDHDG{`G_>mcQ>;p2df(JA9uP3`d2Iv{;G4vfg71 zk$G@%Kfqm=5`Rp2BTqK>;pPhFr*)uLP)A8T!+~+%cwg}K;A{A=W!6*rS9N{a8YV23 zt8U)7%pKh$Z~3tYY*BgRg-+HW&qyk>9A{Hd94PEetp%UWKT*RcE{~Lgdn;B1@=7gi z%%U~`lFP2k(Sx_BxOn576Ng;nqjQ@5Z4BbH@0mYr-5R|!Yh(MUh7;6|<#{0p8jl~N zxZj@aRF~G|*kf|a|EMsCGd_%WTAaGDp*G?4JAoMD=mJ}ibhUPiJvE^nxrbO!P-Kuz zi(2jk;)1!kx$Dy6rt7mi@<(ad0rzQK0%oAHbYx`20KMWyLXdo?4jT!%1Z3^j(}H{z z&Z(fWYE)ZkYH@-E$Aoc*e74COg(fKLCz%s5f^y78lZYY4H@`QVpVWu4*Ay{Yj8hWI;i&&KI=HQ)Y4at_S{5d`+H9s z1b3gzHTH|k*QPaSg-9LEa<7(WI+coM7CfP9HrB_n#q`72FL>@#Cnu*ouJXHZa#uW` z=fK{zBIHRdXJ3!`!F#ilvSc3FG_Sr#62hZrc+ACqwY8q7x%C6kB&B=r)sOLxNMS8X zbm_uGH=-jw(D2hS!(DfP3{jh@={Y$$sYplt`2u#5I}9~ob$Lz>a+1$h(nfJZAAw|~ z9bGWp&$Fa^b727V!O}xm?#K={9sOs>2|I10fINV%`1{|q$Zfl1y}$P3bX+~wV(Sha zGT2F#;!{)ii+sT&5xAa84Vgbv2CfGA6_t8m$xR7yNJ~q5(3AW;=(Y4n{qFqR4@><$oB%{Vps--z52cgS(^zyWGuSz)n$#WH+!G7uPV?w@TT&t2mOJ6KAaUR<~O z00BQCfr{f0q%h^7IQ$(9KKZu(*8DKKOMjB98;~u zw(73N;~#@br&WMWTdGtV>`=FHw)u2_O+IKj>81K{ zo9|cc&e8aVx#OqEIM+z3`=IGXxXmq0M9@a+3FbFUw4e1}y+@??76oO|BIA59$AZpL zcSg6R0JiRD_IC?;WV`f6Ir;n^ord}W$)pQfo7D@<&bzZAS62T4G%XR$U%n6iYgYKp zNnb$BqVozR01>d%PNV$C8U=)f@zX$Ybko4(Yq)Tev_A&8#hMP{pwYg2lr(}!AbXm()aJUfG@L=QN~b*}oR zHp(erChRg#2^A+m*`(Wyqh$DgdqEq@Lp~*roDp*k05h6Kj}s~H(pF9GfqxgLk8SH> zrEG7+!PU|aQswO-Zs}eTn=Db$0c_EpVGNrqw%;1={^Pxhm0c?LVC^rsiVgonfB9N( z*ePR5Y+he5VMdd%!oAf9!A~9A$(9L~2tqkS-t1iWp`zfz`-tppYg4v?c5eIF^4`rQ% zbFy(B+e}Tj)eaZoN6vNRC1K&7uXcZH7mOEE>{3MkwcFg|`*z2PGK@54Xxft~>EoOZ ztgcJ^rZ@dU-A`wq#L*0Ix2OzS5*qtH0(S2ASLS^y=2mYTn_O8_f$1OEMgW3?sdOUo zQ>U=UWZQM$XXCELh#nEWQi5x~B1PH*TVR%z`uQ>day%e74D|?5$qX~hhGE)U{^4;+#=tzpqj%T@i$8qSgQwb#LEeAnnaI$^5v#E zQh-iY+W58YukY;c;y?;@Zg$@xSkQFxB(JO%mgs}ZP)}PSmoojnqOcQ_*0U^BWK)aw z5zd02ChQ(+OX!=jGLmgE>wRX2h#rmd--p2xqr66AR)~tmym}wRfN;N4!2F z=U9}PnR&xD^3Z79XnXliSNTGGzM3f@W>VIAI;|dva#cVVI zD^j;l{ca_^*8Jc(wexk+c0+b5)Axhl6fvplhE*~CF7!J8lgZSU4w;E?pNBMK?y~Z4 zCJcpL&wv!e^Vko>8BF|4O2*^#iCwXd-&?<6H2OdFa*12VK~d|!1bffBUY}SHOHY5< z>FIonZ9vtAFYM#)zv_8Xq@w7&)jk&hW5|vR4%5Zy>e8bWk?h!e<2nh-6>Q&*qYwWP z|H!srd|;|Gk&&0lp*HeLZD93bb^!8`xpC7IP6Lr3t=sIh99qvaBI2F&q9WGTMn}cn zVMA`|qg9&gJu1nfk(93eD_5@M?<*VcyPzUVQ;xcJyG4AeBXO2RbBJ%?GvWwPcRjiA zaK7$`oe`ZQ{ZX8R|2q;vSI|UEETMc9HdqIZfb5WBp)U#AE%XB`JF@p=OQQxLmQaFK zKwq>nFQka5tdy7nfO^muj9ytiX8-RT#y02a*Oeo|ci+Cf;g+#Z=(8mW+uQ5rew)ae z{h{dFc0KY<^2)Ow85Izc*7V)s+w19{i?===Z^Ti_*%dwerejx*80Dn7a>2IfU!$YD zi_0&McKP5h_?*&5|J3rCBklX44{Xn!v9sAIm|XdA7o)tyev=Q!%8u_F4gXZF$QHSw z%6QI_ic{{Rt?I)LHNNa4LT$nGsxn7}=bQ|fPU{BBwX{2eq|&5bQvN{tZT@p37kV$e zJ-FL+AwyG&cn4t!X@R@AJhTc;iCR?bkAK>VMyuaHP(E?JlM=nHbybZ|(WI~_-Gk^X zvOVm1_1X1J_hJjgwM~ts2pKc)#*OBY2r=UWIrg_Y5SGy;(U#ifl}A~3V&d7Ab!>s^ zi+$>ii^+|bu&=;ccrY!$jOl$9O&mc9{rvfJ{o+c(#fT@pmqJ9uIgV5P!W!N@QakDG ze9annf{yWBSl!250^Txc0LaNb1P_D6N z%P*=lSlgPEQOe??qp)t<@Wa?o_b&&qx-DO^7H@BQc+e#&ui`QP?`+G7yP1PPsrfb9 zU&1+79+E0+*CK<4nXKN;Obp;W)XyRePj=#wgV1{No~dDES;SMH1eu%yl&YyJR$@tb z$zkxkj`x)R&UdHohAW%G&NYh7?tjj&svL1pd49mYgYj=i#b0p~P_^M?Brit%2 zcEsC;0roAF{ruo%VK4WmG5?)tb5zr3bG?&SGFC=d*Y-J852SVACY*TCX9mK`qU3I` zO!~+^JsR7|XA4S7$Y3^6l3~a03M7VroC+<|t@=xs>UKN%Jm-HD=D<{%%NoPw_u94> zNt+5@Z?AS;Eolq7HlPgHVk;Z@aIsTeDHR#?tJIlXu660?scI0bvATmB03{#=0M9(g z@b|mB0*$r5`{mdZj|<8s>#{RV?63IEHs1@XcwJy-&UY!w6s8rS^tNGZ{s49XI?;;} z%!Sh)3z3JKG4XuGHIJRyIP@>W{OoMB9$uOPc*u4}s`=wM6*&ZAYCB0dNhe7zJzY*E zh9ZbnSG+>=dX#C^V4$bB1ys@f{%ooAl3@iN)@_b?k9zBd4oTRE`lfTmP?V+kPa z$pD;gejo*#v_F+dCPo)MJ8NiYbjA?K)gHZmMN50W;G<+>@B|JxmmK-|51%`iP%Dn# z|Kjk9kM^y==5Z=^75iJ|#^dK}GF%4^5&9RcsuTHT{&hgMyr(t3vMFXj2ktESGk0VW zB?P~lm`Jg6FNWNT3=m{Z764Xc1OXQGxq*@!){aCyv3gQ>=>5R+{cZE`=4(Zz&H95L zsyCHmZ}Et~34r27n@Q)}H!uL_3kYoe!}?H-md>aA>~?FRiWi%YjNTVq$a05Sb68Y@ zu~dY5wc0qChf_|MN?cRFtLDO&^{byn7P{av?-n!-&t0>IGt#R(>c0I6|4R`^;HYK~ zh(%@JS$1`AOr1VGn#_m_#LC6xEHIf1c*@qf2Q)khy)bOM(*J1Ala(`}vG3io?55v* zTK1jZQ!wG7JMf&qf#J7d+!gUOk_|S({2Z9+fk;dFf=0B~{$%#)LO#5%B2(VRWFgPr zWLw8;AeAjLxJD9yf0$C;rj!F8TO?rmzuIB*Bd_&(OCkO=DN}`hf|5ez)moAr%Y-n^ z&%J_3a*;P?G?aw)66^kc0`rj9nQUB8z5UVqe`|AKbAf#;dAD2}^TH8tbn=ZqJxos~ zXMb&%;Gi<;>)<8NPrAVF_IBW63_C70!Bk>PjLdy$t)(Xa%va()oyT2A7%y*rR%$S- zfCibNHr^$;cm|ABJsN)?gDZ7k4 zG-m9?ollnz#{-S3%YE)P{}>9Z*xw8yD|R=L=H?d_WEeRx%Q5OClz2TWv#F zHUOw@PEYwhEtTfsc`Bd!YMg;;fk{6(JIGu7?kX>K3=H-&^`djdbk&s-311%4~kUj5pt{d zm=gHMuQS2KUEbeuO(*b}Wk)>|a{oJPxwPkw`N{LKAbPQOH-=Gt%Bgx@ip9zg^?{9>@?>N)x|p=HwZYIs2cqpO;DQ1YBh*@@!dU@aZW7P zP?FR=TAG8(aV4hhdel!Do6MHF+pyxgT>A)h3TUdM$3}NCr`s}E)fj^l5lJg@|Dk0u znbkAf!|k2O_e;AiGT*@{DveNey4U-%U8gk#bZ;P9&EG1&e#%MWERZTaTd#OcuVExE zh~O&IW?^Q227tqWR3h3Zx*FJV#9PnLw5VMMePP9@qm(UFO4-Xw!ym z*!o1ZHj}AGY;ohBF~WbNwvNzrwDZNF;W03HgA22cw4A=1kT0(+9Ej8KJfWMtuhzW# zvN^Y&(DV{yY?gx?RBHIpd%H&pU!WcM<9~bWDp2tPIRWJvDFU*%97=e$EH=Y^XA%pk zmaSUHfLmi|-OF>zb3`qUl5w$uIa$N(L^=n6hEu8TaJA5L=!JpZNU>@Dlk9Aj=v5G$ z5fg;<4pITihq~GKmv#!94-1ESvndcr@JU+rsy}SygM97l(`h_j5*`69{~a|yjQ?~t zpZpx%|6UPJ8*U8VnGqBBNbv6(UtQ9Bx%4O5L)`AShGKAd$rkyp5bWL72_EDhwSoLt zZd}>lt;@M#2;CXm4`O{Vi_|kY)RumxgcpV**0Z+d{esfhhqZrooC#M9d2W8*HbhoT zEF18ER((s}s|WRGB_FEH&YoDiMJn3%2V=L{xYh6~w4=V#%ySxhw<4_n_N#Ch7RxI> zzbI68N?m@R52o)gZ?Fb`{vumuZ$;mlt?*Ld~>RRQsm^=RIy`$ zl!}KvvevS%s+mVm9TJkcL_1vN*38kDsIsZoBHPE&UxA&>Q@i8HdTHor4@b5^{&cD? zG?;?JD@A7tciv`yjJhB2Ai&f@hzxwp*QSdqF>See zrQYF(xMt0C82xLw?YLg?aq8ZOuut~p#5i;&Y5L^%;|(bsjCEToDz-E0dX&}GOv%38 zn#I+(CotANZ5>F@gl6xOWtqnKx1HF@+*$j4-S6djYU5}3g5~H>Rgy!?BNyp*Pn)~D z2hC)A-1fn6(#G5))=A#)xv`Osx91DzjFfwans2zah1Rc-miKsuJQPGSD>DC;H|`OJ z#R#KaZEC|j79!?S&b7p<8zDaQ{dMf_#7}-IZ0$B;TZ^ZAADco;sT}KEzv5p94&qx2 zIJ&@bT{l%Z)!F)Zd4{kto~t;-L~ZprMntuG;^%c^q1p?D2?smmiqiJ?LepOt5CUMg z2ukLkB-XuH{=z^ESU^goQkLQ%L3=f5?==8cf-lJx`OQa_2cSC91esqqf6B8wZHRG8 z?}Wpv>D`k(+p~1Z(y!4GN1fRQrs{@yASSCk8h)Ht?>YS|u>J-l(<`_XvGh5my8)MI z!Us|3R6pF3s*3k;QA22^_p}*>sf|JVqjBybk0A;8ODIQ$n1$+;4^qBP#d9{tPW4(+lP)2d$BTUU**_tE+vzh!K$%L3mIgwE{+Uzq3_eUd;2R}0E;1@=b=?_W z-?Wn}jLUHE?X%$6W+rcOo|ZyD-rTbmHxP36?RvRWiwT5*s4{rv*Jw)O zwFjYbf0dH_MhQHf@+UMN?wX%^u20n)$a!xJQg(O{h#BL2OXwAYbN*P6`OL*h`dr*V zRBr?)_0Sdgff8U{I>&R9iNdGE`;E;uPEIfo20Fk=?&HL*m1Bnapd__MtOB90M{1^M zYs)ooC!2Ff1wy<=p{oy-1XXemRsAN+G@Dbh=7gG$-N+z`D3_u_F()OO_hl;hdu-HV zA*#iWH<@HpH7&2zEV)wSb}}M1%OT6{pMHSon2V_jiH~i%_n1Fh67L`dd2Hfn@{LC& zsUp^F3J`1dNt(pn2S%Y2Th|OdPEv1-(cfE?2783Uo5$b=c|jaip?T=yNv7h9Dt?7D z@uq3^nruS8RJr{4cwVB!&}FNUI@l>x{=vGL%Oexnpf=bq@F`wLMLGJM#bQidl@nEY zVyZy|?}+*JuAJ0~+uHOoKwMKO;v(O;SVwJ)ThybKU#1Q(P~v$8%hFdjDf?x|I-3AY!*#Ymr#epzI(~CHy$0h7G#yg zRqTUQqk6W>jT^14Q7D{<<(qLux}&vIdTEn`TZ;D#`13fJ4M{6dVn%~{>fNa+uW{!7 z?%#y8CP<>5h5gbtlX=mpPdiIL`ioh)Gcq#}#XjVmIY~;_4${R;)mK*?CW!vY>Xq#g z$qo4RFt$}BIY1pI|4aBp0WZ{-{Bf^y->}_{PYq4u`GD#tz4}3;Y%_ z8c~*N8u-xD<#Cp=!*H|jgSktmn^!6c=7}Dt0c3G?MD&OkR89uwzd;=(a-sBH^fMz< z(;>iH(vr;eT$@MuECYwRcNan==lRUd%qj%xN}8nIX+ukFnCL>lc!G;aIYcnBMZ*LnT(WYOvj>-tc`v?BbaToZ)?_qS*Fn3mZ8nc zeySnHFiIqGLer0LYDGz7OON+JC=;a{BpYU@Wxa%*a)ZEvA*3Omk53%OY_(`A{+rWQ}~bwzjTtoTys8 zrOPLy@lm*{tKYWhr%5fSJqsabE`QF~0aw@VH>Spw9E;J`N-aHdROj zUq&hUiT&xExe%wDEaNn+?DE7Vl`)3r8K#OHP%OJ_Sqc?<*Bg{(PAx^ZQNXtR^Uu>x z$yy(Jlg8D~mB#(4k?q>X8FDd=aD$7|)h7=Toxb~pPrT85DD9@25^9`T*n;~KP=z76 zJ||0Z5C#e#8orqU@uN;`EPYmdW)B;Ki~01KOyRS?^9ZL0-RsqO-(*w$N~?Eie%*B4 z6;?Tc=)4e({<|R~ac~#7v~`y)@8^E~J~`+X%MBMEZbP0ns4w-}C=@0+RIR&C<%Y4N(~jCKjfqnWYth`b zyYZqMe?^RiG#XTWg>lBboF+^m)^N;}^%&=T@ly-IvolWB{L{QM8Xqgf8;`L=WnqcO zCjDPO7^QlYDJ-B5^zN_4H;dUJAdMdsB<%~6i{wX%*$~X*#uM%B?V(cpD|u_Rc%jIK z+4Gf)H>2TuKZ2T}pM*oD;BtuFp?X-mp$g*OSNa4mS?OSc`-$oCEfMo^2ml>droU=($U7(iU9c|baNeF5e;hNAo$_SDz1sjQC5@fr* z?$3w%_^#s(|0yU+0d&P}OkZr~cRsPpla3-^P>Mm+2tGonZ)du;aR>BJ^03r7I&2 zDLnV!2)cR=rD2``NrFHfwcmK{ajjoK!A?^bw2$ZGe1aF2%6YnRUaHRH*B3Zejpv{3 ziICFbWrn*lo>@Wzqe-fP`zg|2)w?rgE+$o|ICNnQA^k8tLPvTd{xrA+lCUaCT>N|{u|wAip0Oe@(sHe~~S2@e=Hx`~Kj2O2Z}bi8t!ymcg;g=@=J z7au~N4H1Ou$IDW%q&tkzEyhZFVK}LaM~$NW0^ZGDgq%IYoNKgy2FRg%&T}3kN03JZ z9pZ)vKw1Gbu&*u$kniP!jK)-8gx+lgy4<6^b=eBK@4H?iY7~vEQ{%3F<0+X?5=8K- z2YDV-XPjV_5m8Zq#5}Lq_#F5ClF)a$?kILSkDZmi(7_XZBYtX8JIxCXjP#_SZRESV zR1S98!GRCS7XEAIdxL4^e{-@IQONvf2PUgSDp?qI=B9d{A%hz-!kc z^Sc50JH*D)rkU=X=-EdPZ9|-7YqXn^;`K7JSZ>`a>Sfp+1nmE~Qz;5fs%v+w2JH#mgOOleca+$yYql(uj2%yOIB zW$U&VLJ)r$TIhN2g#v~Yjd&o!W_p03zJ%rB!@d|d=h~NshTnVp*KfL5{fe#nMQyBC zC2giw=jCHadnsNP8TglRXE^rS z@IZwM$|4sz`MlL=lLob;A{F&`?`Xtd+i9^&x3l4Kyztu)PUr7gkB=YN&>Od1o%P2^ zD-mjl>SS}|!4t;@Zxf%_yJoDka~yhMGr66nQL$vACm+o~`=R^z53`fBhDGOq0-qAU z{^(TeWsQD0s}M-Zn8UFCU;k1TT>DAVL)SOrdm`~OYm7&+bYq&=b!b*za;Uq`M8H!n zpt)&5wRfAKKB8Tjut@ltl)yN#0T+9iMQ|ogS}$FmIjM3QZEBPyM#Kv(8wd%-q6vF; z;;cg&cr|~tJ-X>RG$<63isA0%f-}N%yOS(4OCPHVv>P4n2OIQ4A7_wY0|tu5 z0&6~BAYU%M?Py`EaxUr9M?`}6Rn9e+@3|HmUy-0n0j4N^LEO3Kl`zhhd&g zvmyUf6spnb3C06Ddm2Gs_LrRp@%?>BJ0{WC%!=&eM9ZIx*dDmuR358J8TT~*ob8Cp zY5KtfTw9ZMvpb(TU3yIQ4vB+l-8U>cOkoVVr%>YGFT>YHbdMV1@ytBDQy}STVcw#q z-TrJ$a%s|MOjiAb=RfU$-dpO`^+5?u`1u3*s6~;j8+P4(o#ndhGEI{`utq@zgCF@H zco3Z1PkIW2HbdtBc7``^p7#X7Q;mW98{@rinrQyiJ5Mr1J8Z*=u}$xSmcIV4i!H}M zUe16jtI)gUm%~KWPxT7jJCv3U0FW=*l2^bCVty^UGjqWr7 zLBx+}q5Wz95{}aYlt!G_#$%c z|Dip4@)G;lrhUlH?B?umTaXJkp?zi>mamsCaOb=BJJo;fKl9@x8yX@TxV}3}rVjy! zSt6(m?ZAsfMRSh){rgyOEV0v@>Qxj%Q7HQB9cH({TU?%90UEydf|;TesOZhH@R63P z>&%Q5BKOf%2PVb0Jvi-DzGJB0oS2!=p1FU$sm zB&@{7->@^^4zg3Y7V9?m;oYgbu7usfW7cagx!(zG$(O`OVdaUjtROs*7K_cb)+?E) zbzfI_$~TSOPMUi?)pVZ+FBzj|eUfx`#@a&bUk{;{^;i4$iuSk<1a+vTL?c%mS_Wh9 znJT`efmR$|s_KWjWi0aJ@A1%=U&+mqw|eiPF_8iJW;s#Dtq>SVj0qMyN|6-93-mo7 zw@p@;6j>4>KZ7LK+_MsjFB`NE@;)sSuHXS@%h$p6)w}`NKsp2GupBsfv<6jXG|5X& zHP=sdc?X)G=`;G1pvc@n?XfQVOp|+^-*MQZ(PaAW0jJ!cKIfyfK#7vvfCS6z9GisD zLDY_s9ZEDdx#>%1j@}=kF{zE-JNo%iOYR)nX8zLZ;|rX*+zf%zt4)A0@ErU15i??IGsn*NctzXF0hgzo{UMz$%OS#&Pst@es_iu$h?MQE1o*nlZn1I(3 zGf;eDsVXN@taxD`?>C8cXaN;p?YQl@zdvHM1a|_KtISPFg2o5(?1vyy_1@r zKJgDaE_(>wlUoQM^q$z)ZLA1AQHXZ@Chsm^99or$iD9a^xyW{e@Zs|89Z9WLJ6fO7 zfC#yIz%E*LRw)!G2ovw3X2OMAFYi>|3I$FzR~@?W9Ks@e`!*lvadHWJhjjLiOyHLF z=y#7>#&0g7wZb@^;z=~svB%Z{DCy5T_?t|Y>A68Z^kF|uZ0_@_zeMtg6d)@Vtk%+G z2W!2l&m}TitRyUKG~qB`eDy`@SAog5uj^9 zFIKnHui@DxSWQ_(ta^>;d%!mV0GWhEmViS=@9jdx08FoXVhDP=4Ydd6qnX3u>YWid zdF0B3P$KfM0NFp%v{#7^K3ShR`5ARfMwjj%#RW;(J%GWIK_%jN_@(oZWA&65TFjmD zT?HxX26X)jV4(>fQ$PNd;{H~F9`+p)DUtIl1Pjii6v_lmUch4V!P4JXT9n2$mEVA4t+6juyxJ<5beDw%J=!2d!9tI9kn*@de%K#(Te<|3&hWwGr<4C$i zk7CWTod@YMhBOOicZQv+!x`I}puXy|O9~q=izhYDq|)8k?p4eysi(kwKvY4o*>Ckn zYXlFoTs3jK1=q72@#bqug>7QKB64ztpd0Jy?R^XMgUTu-pP$bE-V^G2@?1OkCASKcRgg{*kEpJ zYV~GaV@8LDk>JhZ04|J%Xzz*W=9b}1g@uZ?ObuBlI<9WFmHjNz^PSC@Kc7~n*t!j! zlLpz9_z84$C>v6<$4^VDdt!r$Imt&0T*?jC*M=4r{MM@+UntPLbCz+*;$!E*m23O; ze>ze347_bR<~*M1v>7t89dyo`_roN|kTRyhh~V+VN^2|#^W6A+={sBPuMZ8S5pi%Hc!nG5x35^H z<*ebwjt(l0sm?=n^0tCAbX~lWOr05Ygv%evT*y(`LwZFAszSIGbUADb5B$}lj5q_0 zX!a@sZ+VAF@t8kTk4p$J!;#j)9aGIO)Tb70%2AmT>u#hZuSrkz*4+~x+bBr5MI|C` z)tG$6_t!c?{q_5F$@Q-Zt>m1sF&o5g%xVL^?2c^(g z9Y4DAS)~T_7(T!~@n80j?DKmamk`>3VNQ_~Ex?Bfs;H<`+K&hU;qgeOyJ?t8IcJ_8 z+UAgVz9N7(9uDAOezbo;4htZ$cpih$5;?D;FPwm$S*R8;`X4N1j{gB9GKK9DZYK_y+Kl(fN>LZb`D$|sUazeiWRwR zB}__f5-NQ~Oduke!`G7!hu4SsBJN+g#bzf& zu+Cd9ROg}Kl~&ExC_6o=mi)%{p-cYBmieuO!7Z~(YU;8{4PSfEDFxhOMz)Oo#e7k( zXQrB4f8^5TcC#!Ja>Fp!1t%q0Puc8IvbfQEMUP2QtPT5C-M+--fuw%1R9+oz-$1^QSAa@0jR#5r`cXv zvK?4-B%6Ara_oLrp$IDdmI1CQxpB=ZF6V!06A&h!pA3fYls`S!68b--WpWTM8B{Yc zb{V(D9LKfk#+S(^Zeb8GZeJyK36B61C1uc!@Lf(F0xaVNwq43lo|4_X6>eTcdDgnM zR?-e1Ka+_|Fl4tt8%Nm>0I^8sR)oz83&!WEXVT6R0JZ?OP~$d&FsLOpl>^Ex6lAZ| zugBg@?`M&;5hbn%{DMf}K?|oo9NtXX`Pw({*^gJ+C+AeEA#4=zMu&fynzFEv{o3(T zi%@UR@<04W*=xy}FSbX+u@cxt7hIT~fNE{w(3QPRZ?N%hB>k-QV_yF->+g1NWrT z@u*KZ+1d*P45IgNOCMH|^qzIZiguM+#AdEXNp>!W>MZ3H`U8Zg@$|w7Wc~xjTAj=*#)oFEU+`oXAm|hgb zWgf=ti7;NRs7#1-s;>Vdw0qIbmTGig*LDG0kBsJ#M}I#EYmCS5a5dVt>85=bQ}}!{#YAf=Kf;QwfsY)F zORkHv&@@{2l4^P>=$W{?||8p!f@ z*k)Etjq>$cBkiF>-t`)62IEOB7$uA^^uVNFe+hqrmy9^ zLQoQlT83mZ;l%cOY;L=8lXm?gh@a(Nwo*vlT*O9@4uWo@xxGtl(s|?*S$#@>9mUD< zu9#~%Z%E&sVT@kBdu}zHggbBB%Elv*FdAM@BcQ@#EUOQC09IDkA2=Vh4_Xw@Rh6~g zagvA8PEQ-<_C}TcDvmQNbIz5uWeRIffvU@Q%@ceh?l7^{1H}Aj?|BGr&o=kFJm=GFLG+%UeaTQxXWA$EM+q{KQ!_DB5_Aj-gdB57t)SA2r zz}*L&@~B3?CL?o`jV+hZYq(zaM!QQ>!os4vmVHXTj@{8iIWTi`WO4I}U*le7$I7kC{0riEmIUhLS8Pf(x*(BW9;bT!|0C+X1F8PwKi))2NbxP3gmaQ?*`tYb z97iZ4GkfpNF%nWnHW^1bNLKbHB{C1kcC0w|%CQ~ezWwg~{qFg%KT`O7-tX6VJ|E8- z!Z+8;7%Jju6(j=#w#AcA286XXuSC;eQ*^5*(vUTr)W`@!&bAGC# zs?9npc_`Ql{p$VQ@Ul-t<5?7B03M&(P?A8QhE9>-CvRALLRrmhEpkD9Z2K(T8&-!o zCZNWYJHPpuaE=rR|ASI?cAzUHJ9Kd6gObFQ_`eO+6$R}QCI3|{9^9SISI2P1)4~)L zv75zd5~=R0lV)ih&4VFEr*V57C?fK8XXS_8AgT|9;7!RB)c_%q3j4g&yR@hf-wqWB z7G4E@>BDh-bh#KOECr0uM{o9~>Uj8NeW@wLlH8y#Jg{*4jEViF-6C>*wDbx2D}Dce zmqFyO;2|zqV$hESRzb9LbH6WL!70hduWSwy<#Ba%YHQD!#RH3E4erhZ-ldcHFr&N0 zV~7`Jymr3vhF4R0?6HcE8gnm6ez*|(yKX5IHt}1{7gIEU5Mg*9ix9P>Sv4f&3fN#T z@qq6;xCt%v9wO8eqWL)HsJA9@o^Ixj<{>j zwcY4*#fKvW#*iJByo!eJ0Qq=)xWa{?1zKX>&4@{cf^DBJ+vR;tLjt!CLIJ8iaEggi z@iF0|6jZaEf0NegKv3S}YEE`G%b&t-XndB@!N=X-$m@HT?{(6+PN%FQ$;bOfQq?}GEoH7N&MYs4AW!94UP9Fkf3#@nZUXx_M+LrkBbhkwg?H-M|J4Fq zAqvuw>lUBh4Q`>=o!dlQEfr7~m;SyJYkhXQq_JL0+SqM5pS3J6j@8g_K!k6H)6=d9zDERMxkcJ-j$pz`nPq@FY1^7;jg*&oYS(j(-ppVglJg>2oLM=+m5t;_;Nc zQ$(iXR=}q?HDpj)(0B9gyIO>2IEB?Yf(A!RTPvlpuT8CQ3-+`y!0s%-LzaEA#w`5w z1k~T#d+Uj85-hAbU9UDYom9manWR6@XpBN`Km4h!jm(hp_8Y?LNjk5!uQFA(Ke+@^@44e`O{^Q)Z{E<bI(^U7wa>JY5{Ske zxst-dL8G0_dSSPT1)CM?y^Kv+z!n|-ca71ENdZeydtx_K=}_vA?&Mt#cH?!hp+?%z*1I&gF5 z(WIPcS&M{*r{=W*C5G+TOah;e>XHR3*-;Mi1q z<-(}bX_$Y;%aVA^G9SUPXkU=P&)2U=dW3+nq+fOH71{e4%{(m@{^W2Ld2IuJ@2~gp zBhaHaWQC%5+jyg_-A?@5=r9qgvoE5@nu7iBup89}20A=ej#Jo@49u1lta-RO+E_1< z-&R@&`i?}~&q3`oeyNvpXg^OwIk0RxrtZf3`)4P~0Wi+fKgw{^&*!)LF4QU`hwNYG z7M(@XY0HS~Uj{FmqgO|TS^|nhOz-Z9ami{)^Qm%?WkLGgb5Yj0B=)RiqfOiAT`2z_ zDoX3frSt<$5{0zpf&8J?-GVT z*W7ij-Utnp4k~PR1z51>D6;%L$JF-rYS)|5XN@w;)&K)CuDcuY%q+ybcx6r(4ht}r z{Qh_M{Ci^jKwhJmp8moN480B)B<*%aw-ZZL;v557sBL%tB#t#cgxDnQY&WJ?bSl1K zo(?2sbMVq$TM@8I*Wj%>x}behm{CJU9Y58CZD#)Ws%kR#@R?PIf(7ow%=-xb&S#F5 z79U^xn23r3o#v6z$nTfQgb#Iw>y4WVyZ5erp)agEOUNHoA4oBY6z>>{p;GE*=v2O_ z6e3T=2B!s6S2N`a9=(c=sZ(L`rb(j1{|XKc2G=qc6Mq(uUZb-Rf>OliVe~2K@}bvE z_*QG9GW}->F+K-V%8I@MWMws9tJfy-HzG3Z4*gf2ulV6YD)Q9b>Uq;%v4|c1{?Rr< zbQT>YcdA~6;eVdLQ|p%57%~xxW%;JZX(gKR*+r(RoSw=tfK0w!k9Ogi%5Gflbi@gX@F3J z(iox{khONN7hKm$ZcEX{Jay}A>u}~>20o=O%EV(>z7U%k(h{S-bd$5@TARs&PDEH* zf6s|;4>{e^tZY~K+s(rjon53oC9J8Q$8(>_U$I2PG9pKHF2^`&#fKW{ZcK_xUc$~1 z3S|Wwo^OIdQb^zGpfv9Ny2h<;enETF)1}XAxY&U1Xk+|6{rR)a-w(qgw2iCF=&!i$ zrAG*`lJ_dfQmrsLF^?7lE&waL4I`XIOalN(3Hw2EEZ(PB%>?!(bf($VOWmDy+(S;hgp zEPPa1_CE;AahkDzEwCqCk_DorSB675XG9^^r6pnq7`!*1rlRwu5tkd1w8+ybcoKRL zt{S)22#xyrpp62-21zP$n32uVQcv@Vh$EC^?do51IHamWa(_&GmnWEf3#?&_Hs(A7 z9o=|^R9$~ynibvJ!^x9@jQ)K%&Ba zxzzz->^)!jw@Zz+chI+?469A;$65B8LiEnWW{ZZ3_i++Y9+r1$T#-f~%=@`L0gJk+!JNeAk=86LfR<8ZK{Y@6EY|wU?MpiF}T|uRYK&ROt&j7#u}oLY7x4*CH*lBqRQ|piMM@hOcb)h05STUpKyj&4&a|GC zV6iUN?|#h0a%@05!ws;1AOAeJ+JqL*-N-W(Shj-97)Ty!mWgRj(&e#ZGX8i-h_GN0x_4D5VvdU?tio>|`* z7p(s$0)A1DVM|>FRYu6Nw0qeBiC<6|B3-*G};0q(w#9D5b#< zyJ{d75vMCJI#=n~`uuw3+(L{jIt{yZ4|^${&WxP0Zx?{@k*Y=Jkx)QBn)(UwA74M`)VC0QYt3|q5S9e zAOm9)Iy#AeJ4LrljPO>M3UL?!tDJ)rae}8}@8|T;(9qTYYS#}BeE=!75+*bhVzZKG z@vB)x#r(^=pfM!gL-qnBYvJkFWn1CD`vN}1n7KWsyFz)I4cl*L5|0SkN&-(16(03= z%8>`-z@p$Wku~2uWIOZ*IIZxnpR2K2r~NePnECC$w_=TF2{EL+C0M0HQI~#~73|6T zBIcN`aVi+_#@{WWnee&)p0v4Hp-wd}b{qTD85xQj9GmLKhF5b{Q83PjnR{2Ct5|J5%vH#eRH@qeu4_{9M>JXBAyy*nU}Q$Wp>0eVy~B7ZUnbloqZ9_=UHbw!)Nat)RV zPFW}U30Bhq^%Y(vQ(g5PTwc7A zjU=BLTez21&KYt{-Cvtn5_eBOdFx@P5VS)TmD{xNb9NA&pnj%g@MAOr3)P<4UVysY zAaHMGukuEzv?ts!>IyAi<6fP?FxX_e&k?NKNU5ZyA$3?KgA!38K)qJB{|Du#(zQck z^6peYiQqWva9T=~L@1N=mj1ZtEPdNqQ}f$PYB6y=5KdQDw0O1}U;oDw!hYPkRASkK z{PLGooxfh#BMvpySg&pPZc#)r;EZlsejKnC|JK1W!ta2PW3CW==zMVxytEH4JX?H} zWizvOJHg5nA1lM;3NuS4Qxk%AnO-=`M=B=^2*9K~i#%ozY6`{hdtPsf5KKwwcYS`( z49b-U@B8$DD<51dSKb*gF3)WicQx#}A!ibLcNe_ZpX&gxMU(JHM{$;wFO!L>4w?7qe)p(!lPg9l_Ge;jRNGOk|MJp+9wboS2KPS{ z^;dwhW()g0uqo z&Um$FhQUKfP;l6rQ0gbye|+puoBmuOXLsf{gK4d%NQ-&rrRBs3rva`DyI;215uxrRVt#Mq{Dr(yb>#uC-_GXk)K2l5{Es?#I*-P_Qw4M zc*|9qjdl>@rPtqD-F~F_ciM2#c64rH{bPhY4&4;g&;5H3dWR*FE6X>Uz?9lkycJ*VGy*t`=c*A{#_!+1uMWsK z&R?TG+Gpcl=k|IF7ABsv-Zpvfs3*?iQ0~UyS?qx%MpszM&76K07*Rdk3G6ZlLO40+ zYJEke$TPpFj-A`IHt}Ub>DLk6N&7ix{Ja(dLTjAR|4=bD9}h2#TkVbQTOKDJnKkL| zxxN8ob{(DblW1NTPK6lnp;xdIXQ^|aR*)aWMH${I@tq-)C+*>PLsf-_&cIri^;T3Y zl+R9+9jdt@6|BVZJm9XRJ-1gf#tG^FQ1+t)AL{<$&k?Tl&mDVft z&Vso{8w4XgpCIST4hq|x!X4uLRcZd4O?G{|zLCY#?z^b;Zs;xer;pVg+=}YVIZ@dN ztMrV6bg4Jqsp6i0b$tZzDn{}t|955p{}ONuzf7ZXx!z$C7xpPwg@v~GIudI4q$OJz zX!5?zmAL9CEi00fLnkt3s`}5Rufb6?_ZdbLF7_J*6Y^x(4Ydy(Tx?(=x(+(3!CfN$RCd>GL-qKI%gDT1{s~4KvL{Ti+fI{NX7#|j(|l(d{5E=D4unC_-ns3iD4S9F(xqo%yq?-VrjV7U#x0aP zO~+g;hUWo@FbWvW0+^GwJg(u0&SFi=Uw4jU&4oqY*R*a6x~ z>Q5;tef!O4D1c;`&WBXy>|)&cn6X*+$b81-a4kQ+Cpm zh!Q$^Z_{&%ae!rg@({bwc{7-AmFAA&R|c9YZ$fsU7aCrb=|0cN;7CZs=Wccc#rdYn zbc)1TC0vT;w~3w03)ms1TP9iuVsyCG%% z+(x>KyMgJ2-nBJqrj$AY&zDsJUaE2dV)Uu>{CEV}_~oi~yW!XPDU3R<;jNmrGA~h@+ZoxW0-zMqC_O-6F9Wr|3OC@&IFO9p96jEZJ3TsjC4d4{!M;Xb$QrhLT$D zG#|9wEag{Q;}JT^*c9fPLh7Tjc||k3J!{Gl0kyc37nx>gqFyIhz^JEg@mR25vifvWdCFM~dhQLdt}Fo#KamG^h?cJn!19zNVDN)7oU@TZEt zK%9m4r2X7iw7>TERrk~-bsHU+qNyBCI_595$+LH8S6I7RPFVTg(A-h0bk1Zt#tNC0 zQye=?$ltn+FB7_>;3NEht;qfR_s^w$m8q{NE0MPbez@{i&}u`}Y;N?jEe28PBx1l@#^ifB)z*&C^>S1LN*=YKCTx&1+y=bIZq%u=#Dk;m!f1Y)*&A1tL;k z+o3fkG~#x~pmL9F#dkP?qMVS? zF5xSxt{KG%(6E48G<34TX;Iv7y(F)yTDOCr)-E9?1Cub?zf((GS~?#T%`E?T?^gLI z5n@`*-@NGjt|<2Li^6rbxV&OT2ThK~Hi`(c+7O7bmB}-|?`$cOrg1I)m(6!tWAp*!6rzCH2 zp=G}~%L-s@g?!-|GB5tmTT4mH(=EMfH$kLI1O6lNB3pGTYz%Sz;1$*4sNk5+Sms_` zaPRyiCTH}w` zuc)>eQ1uSm#bgL}oaOHbIGlzs>x{Dt5(c)B(W z+2&6=j@-iNwF7G5IT#vlfs2C!Hit_Bn_IW1K;|L6-N9eTCKh178-l{@ieC;_Yd>+Xo zh(%C?HR^Q5Cstfa5U7Gps*E{^vy7Lb>Z3ViLBIjB?^wvGHfK@b%<(Ls(PN|-?qsOB zh>G%ucgMz~B4X}32@=RkC48o=#cen9%sv-eO!5Y*e1dALHUBOZZWGU} z11=`n*u5ZWx|p6r(U_jVHENgq)tpU;ycXl3LCHaAO~2@4n$DCs*LlBp(8vPo7?r@z zG#lNr(n$7!+vIYh&wZ4pjz0z#{lqaK2XR){12NUq81NrHw-W@Beq=(9qEpfQ)f)|I2I- zDZRx%aPz2o5%@YcD)xo(OS3tXx%!%#8m_NwOiX=1_6Oqn&fQEax{%~_9_K7e^4}EP zQPm`PIMNIu92lI?S90~p+PNb-EH%9-8-dEJOgBRO7P6GVa%O> zCx6}F-?wvd(Ew6jKt-v%`SSjP7mJBZ9+-8!*Eyd#RpW0uta-0b9NWJ!s(yKO@N7u^ z6mvT5w~@cQ>ITRtEUK!$zoOa4Z(P9bipH*GrI1ku-_ns!$)hl#xRF3cj;!i2`8g*_ zdqrU~jFdPNyv`%UJb2x@)R@wj0}EI!dl{p>Sb}}Q(6^$i=5e;x)+)gFHFUKO$X?EO zJihH&zh#mlyeVA=1&A|84)}Yij@5X(_{bj1-KqPEze>lorD`@;R|_B^RFFSt1Nqjs zcb4~~uV4fl_oph)rVqk0>%E*jFqma2fCvvRH{hD{1$i9b5-Y$c(Bt8)7I?ngzaQj7 zDSVv8)2Ppxyu#R-7C8j#E@!A5$5t$D*qqXV%-y&)w`R@cjICo6lV9 zdn3;DGG@uW^w%50e;7uEmW8D#R1b4fEKE_0F#MEAsAdP{)@pRNMTX ziT6Z{^As^Z740MFin_nf**cYkN`%4$v}eI%1d0WxfdTJ7(I$NxD_Q}xl6+2rk33?95QRJ`h#lru`t*Q7egh6dtK0`W7;N0tkk9Kv5#t?<~_bSn`}&!3x&ti zZ_qrRm&%_2E^g@77w57G2YhtSlV5pl|EmSq6bbYtSlig-?=`XDyV4Ux zHdENF$Kq|CUKrX6?3{eBQm2UaQhx(*m%% zqi+S@y!hd(R7Ie#g6l{*+6dgR8)t$>M@8iW)WJc7S7MDr=UoT*_@yIMTc8cy`Y)|L zEg{iZSa+Ovr@!i0PV^_8jc^ygBOS=++fV*H<)y}VJtN0>nNrV|f(al{X}(l`=k`;0oeQNT7>8K1)|*xk z`5Ys7UnMF`FbzH80DwQaLpaa}UgMC#7|k!N<9E}h&jPU1yvygR6n&5+NbKk3d{(>V z61L0=E062RQx_Vu1}anklI1pv8r6tiy~wokn1r!4+0rP+H|9oRN58Ca$>p^9r&B5` z{-#1JmDDabR!tgnYj@==dQsgG;xYW{o`8GI>dDOp>`}S0H4M+o&VLWbY(Y$0&b9@n6uOwMs_xRKU26ou`O%DM_vQM?(z0 zGe9`(Ga}&@^FNN5DE}Oel)zNHxI;#JrMz1Gs>^jRo>PI}v>cLN&lLXuo(x1BR-j0p z>l3x*n%>3ErnqAB8Qvj!OW;N_3x{3i^msbgzwCZ4paZ;)#)Qex=u}DwZRw-`px#pP zYC)ONp~yJ*jv!?>w>0F+#IWu1Qh#PLPo>XdX8g8@_fxdS_u`T6;_rr}n> zeiPS*N1<=7Y&(M*7rfXkOiW+jJjh&Xzb}oLVNr(HIjftxH zH)P{on)Q@dtiT=2ZbyhC<8D{ZSXx~jz(;c=9+4{d(Pz>_+HpInc&8DdL(6~2z%UES zsdLF7i2LHL2eYbIKJ_5>FDHi=T&f^~HJ?St7?EpPyWZ-;%gmNGMe|Y162^aqoq>kX zQ@&39TGcE3XkD@Mu0@@WEKQSJb@Zm2e#7+6!aYq~C~Ut_h+GZV8X+~TY`Eif(P=+q zFL(!O6dO(RAA)?3FMe_`&_-S_aqgo;(}aBdA|Wks&Q|gA1Mn^H|hcus<|Fto=8ZIkK-fS5AbK@Gz9hh)?su7(T0VO$#1TAZsx zxxmJ_{xmv%2gG~Q8KmsYy`k6^3o%{ca=Edb{|`%-TQenh5fH}{)6HPM&mr(V)AG}l z(^Px8p)GSxT=b#he0tS{t}VFX0O+N_xq_iVT3Q)Bd#a^a`=dwV=el>{uz*>NKbmVk zWbd(Ns49JPTtH5!^!-S370G=O5{%8{71P;^qw#fHruAn)Mj z{-O2jW<{tA)pB`5L*ZO|j1D!ue84``r)O)sk!x7}C`yyq6I#_ZttN|u0L{b~3^(7e zvCQ_l-~LU>A6OVlGy>k80KSU{xXn!);=LQ*j;OG9QjwPZ8ZPwhj8!@4KS%}XLB?sL zc}6ZR;d9F9S0={GUR*wiT%9(u3b(YIF=&yD_0Owr84=78yd6(g(n-72zkb=d%ep*< zO-CqXqK5U3{+{fQ9J!O!kKay}`BhUcE({7ZNEV4xnqJ7fW~xw%wGkT|L0UP)g?!*K zR6o)kr|Cp9-i~8zgd_{dMv}dw`|8K0Jd40_l~&CM)$>Q_F!&`m#Vhc#u1~r(`hQWS z>T)g|6d`_Wz!)XBZT^mBL!U5vEyrDMO=%s)B%86$Cbecq*bq}3x^!j@j(RG@A{LKR zi9ecnI5ECPeE38R0O+A6>BNV;t;(bJ)rqz|}j6gG$h&e67uWS2* zle7=mPQ*n-KDW^Ye7Esi88q%g-d5LdeHbQ(rMiTZWC*U1Mg&;C2{+3_uwKXA(wd?& zom8gutZ3Zfq^M80G4gj6L)E_SDXlc}t79--%7imtasxg8LG+JEs&|j2ndZs#AK9QiEt)XZwo6>600n3exto_)85pnRLWMjtEVm662qn9aP zH3=~YHLmPz(rC+TPj%f+A*0{Lq3)^m3a8AOhfs&OoLLct=DD`6&hs6jT}>MoMQRS$ zEInm?);w$CMdF3n7(S2>U{V?IaxA^O^BUm>u}EeMdQlff3mld584_*IBKB8B+7lL; ze$--@%EmXAM-WpKdreRPo5UrLq&%QwGRtm8NQtjhtijZjtpal>k!igHk~UDm*R&I*?8-&XJ9O>rH?JI6Bo zsHxVwC80DW#zA(qu>6};oAS2nogbm1$W+xpEY%%iyLXTHxjb@bry^kU2btkfk<-mX z2<*)HaDE(sC;rN&{a4}RF-U4?VZEO^Z2ViS9$hEh&qUJS zL4EOy%Iw%(WH&eIR*G;SIt5h;S>{;izx`sBa@J{=%d|dwI4y&yUoZZ@`%e7Zq zu}>@_3g5gZ6vG04;`kdP#ntD|7p$GRz7j$4#-Mm=tk%t{=RivL&yQg$N!BLNRd_zqkp5u&N%jfoU9n%K}lvu>u*k~~^ zv2#|B2VkCQ^Y0tbWq{B@h&j(o*?T-gM%Q82xoyauzq_RaTm(Ix0!up<+PA=SO(*sS zfgV$X{{JS|AQ>V|z0eoVtoGcL`Fo+*SSKNoy@>o-CueoTkr=r`iTAFQly-Ee19T}3 z$Rd6;;JCovLJotBw7 z{P{_EMOm4q+AWWILr@eig8+;FQCMt&9`zg54^W}q`{60<$kBVwP(3$H6v6iiQ7!Lv zWPMy+yuEAUVCr9Mr+|KiU@#P?~G`A%m=tD(f`SD_s;1#|LQ;@VyC%ckQ7^hZP;neGLDR4#E(gsf>DZ zmXL7iBus|Ge>y#7#sPvM9L8?)n7;tP-jk$nbeu7lcVeEA^VF7jC&c_zDb1S2nfONh z?$*zBM^F39pq$ zLlt>5`i~LxxVwQ+b}(~@{R1U_kon}1;4jX=gwdOoCK_rMDFjwKRApd#c=LDic#EHo3&1Yc;@e!;- z#P5p8CJ}&kP+4VIKosXHxV6^?Zkyh3Mlb(~$ld&Xf#j6caP25PrtT_s$YOKi}*VvOOJ35MP_s?(zmIRo*@#5eIIfolqcv` z!H-t90~e59D2x<7>xhplN_wIHZaHp0*H|nnA|w*~CmUR*%So%tIpGyx+h6f_EXJr* zg~;W?ekP`@@!s%{@rV`v&+(;Fn&migbNRv0xQxyYt~O;pMh?#Tu=O!T9wkuS#<<13 z@&A$;XUQSt^XwQVBb5Zt;1%H0uORWsa_IA26BJ08iI&4d_a`M%yg%q--4|pV2R5G% z`>92{k=+bbPZg6-)l$=+wZkNrUSxCxO3=`DyHr*Cu87yfyQS+PeERV+`W6Lph|sXw zG5cGO5>-3;ULDf19c)nNH~bC+lm{RdIEMy`j>XgEWk}WII(#n*at52sb-xwzVg@tb zAtSlot$%@#%O{E@{amL`DAcR>S*KM^3i){1;1&rz&XzbbGAIS^x#h`y1BW_*)8ss! zxjZB$-tGB9VJfHJ`UL|yW&Bj|-zHF3fza^=xV061|GN42Sr?x?bAUKuy8}BkgaFfc?a-V?k-D2q4%43+vPN zX!e4s5bmPJ@UHqme~xOXRo$fHuBk>>IW!yK@t^VA2#ocC6{)-vsT8ETr>3U9zr3({ z4h;2Kw5o}B^7XB|h(tb2Nup3~>^#|@Hol}C&_-N<<>QKZx`NK+{<^P?iWrK?7U)x6 z_F#@i)D)GdE3US}$-Z0OUi}e9obON?H|~s#-v<-5A>G1w1FA$%KJrIrd9;58X{MZ{ zH*WqT`i@WG4o@~%bqvZl0(-L}j#U5k5}rYL;qhF|_jywmM+X+ljbeuC(mVdfp=WB~ zFh=Ct@2GKw?MayExZZx+o~%xe1rfS_t393U?W(#@r%C@K&5kP2cO7;#ZFB5%SqS5E z&eR&e&{?AN=nj)zpI`NsqeRMJoZKD{5|OM=&#Y)#F_(25wQhaoq!~?RyKR_)P{~ZW z#hg-)B0>(^7nuk|*-~>@$vc6&vncj3(ni-uy+f z@n7Jr{QYQZJ-sGe_LH>FNAbLpZLfX2RQozqVXrY^m$eO~lQ|eQ0oJDtU<`x%bEx&> zI+~GRZv@2U-b-8DHy+D${hUbp^Omy|MRm3Vb|nm600&*UZ`bc-X=u}2j#-~WEmu!W ziSNisF*yqad(|5!db&}|9v0h^ufEO2`kCC%l295tFyL{cFUR?#! zTj-#tl*TPOI03Xr*tMvTuz_ zm44)%|D-VJkbEnmKj~j;VIE=IKuUY~<r!09NQF6CRs-4sA$u(I zOZ*Q<{PJ9@JGk!?K^h}nMzYQN&ER5m!3i7|?5?0t_8~e#dBFTlY?;cGaKsQ$60vif zW_Em~sA?GDkMQoMCYK6XH<&c>$u6IR(?U`VVsxVWM3U%@jq>Ls*cjEn^6KusT>=W4 z2l?PH+X{&}fO-T}JOl!!R|a_gKxPrR0l~RccXmoT4ibOlzyUdVaF+gFcsjKSgp)0bp!{XIt(2s6-0Z=%vhg zzaIp~cy$hoNJCG;JNP^}?c9$KwrI)xsM6z%H_D;ADc3zN&OQqXIa+npu@!fpr}{Uv zHcUQ-VVqC!?cIN@w{f?b0-L#0I#H`w!Jc!|g(@XJrowPg}|Mf>~4;rXsSmUjEi!7N0m2{JKvIo)3KT{t*vIuIgV2& z$glGAb{)3Q3Eo{yx6cXu90lo7Qyr)2B46!&>O;)%3>m%C{zpMeJts<;;+2ulu-EwC zLGs!Ex`N|>4vKWDj63azl6g>Z69b0R%1r7K%mw3Pc9t=Qlv@~So8OD}C2J%AqbM-U zGjNY{Rg&#rF5Hw8QP}r()p1?Xz~w&8*8FmxG*>myrWF8p`7kfF%55aR4sUuN2#DX` zCP9rp9vhkaxm1TZsp|v?(LkRq^S*nudtWmTF7e0n(`l#K-vG=E%C`$$4^;)`LE)zL zXvVAa*Yu7~3A`vd3$)yq$u5lFIFIq7dDH4YK@x#%(~9j$Q-9{du4Wm2B;|RI<5s58 z*+8Igq+a+u-XZqZvfGkfDk4Ymwt}&5IT%> zqp}BK+rzv)QSuDcykVZ`!wlE;GiF9_AOJe#-{(c$*me(4K!vFnsUXY`=R9WlXYZ{H z26!0z)`Mma&=H$2V^{-Ro4@41Ep@8|hq^#9#VW{^2N)N-v8 zhf~UIG}AV0?v@%0@&+kc{hUTFn4Ex^?}7O(4IVlqvOn&BcRhKJG_YP|*63ke9{tebLd^#tpNP#6?5R^Fc45 zahzxPktR27&rVMgr&4oid{bWBX2KrvCG$R9pN*K9pSJ+nmD;inG~&QyUSOzL!B^Z> z5Kdd+kNE>kDGzQa%@6{_^!A;?!d}Q+S+Cl1F=UKy%OTiN3NYVIVWjFi&sD38SKvyc z8nrRI%UxwfV}63nuV7DY=%)C7*z=U#LXPZiyDGb?{wIDBSONVK!SNf#rwwTQz*sVY z77S>ZBTF-Jy|;%`cU>c;xd@9Xg=&f_eTYwDy07tr`2@b@)h(Qmr7`n&%!x&iQs&W^ zKjehRCOMuimCZEksUiO*7tBo?6Per?HT_9dr6o6bgH;+IH4UM5I}G*3z`2m-y;v5{ z3170D=YR*{+pLj-(0rf7Z3eyjIjvTdVZ5BZtp+7=uD=6BYs}dr%naZX?`0k~-Z}Xy zwDUWM=LPOgd#vtPch1$^6LF=^OVX``Vs4SU4j0zHqUP7u3c>lQ&7S;fC2cb=eZWZf z3ic@ zUTD>YAl^wg{)3)`qUHgt2Bh117!=`sy9nkU6>IE_Mqj-$U6d@i<$`B;=*_5CY^gpR z`0j?M+J@2b@Ek)55|A<+cKpH&cX-4VoDRT<-izxp(-N2Mzrz z^><$3hNRZ8^ygMHcfK>}W&KYy+p|)PiocR`8Sv(_=?Yk)nS#%*IHLycG7qP!uM*p$ z?;3U~`B-r)qP_cQ`>-O_#!SvLI)^cdE6fZxvg^Fhgm-hXpCPe@cx#65NuLO}zj}53 z`TJ5sxcmND`d7F6X-9lToaNT3Hg}NAF9Xg-MH=UK1|)gL_3pY6{HXA}VceXm?n3hD zgV?HUo;=<$H$%;n6e&De`&0x}davi;*-38Cj8zqE&C;+UV=3_r?)S)-SH4`JQ+7G& zv_`z+iNPm@05KYapTjwq7*qMbICUKGuZOFSze!LR)P)}%c(qlZM){`8@vv*{qv)VU zFr7~4j%prx=6zkHt118PgVMYie{FSEF9}e^Z&} zY*Sm?Z@$5Gm{+DlRHqaQR8wm&a-#UhtRoGYX;~kA#=h`;eW5!@K1x7G(1kZ-5O0%o zmHq1r)nf`4KWO?ITYeLy*R4cGx0A9frDX_KZMBty00_=W`GSq?|@Ve5I!?V zAeir-egshwz-zj4aQ{t&_yoQm52SxSIx_slxo}?5+W++9w+xyhF^|m0JU|l@&bR> zzT+jse!i%b?P&NCztb~A(pXIAh8fwZN?U2pM%X|Dbu%o5w`52L{W0`_qcKGoA=F>S~bbHMqO$E(Jba6ujEmG`oRunZG)S=mN zl34XBKIQ};Ac)Dc?t1Jr9hmdEy4E>My~>m2OpSP&n2IsQfEYF9v_6BPaIk42pDGAKys zEHkLnD?dXltNoO6yFXw+Qkij+=T}8*)C0dCK?2*7F1Aab_Scsqw2QKyCH&6|&?Wpa zR94sG`x$4}NY~WGoltX$LfZAL83&;tUduZe;;y+_@KQzJza!@1l4Y6UlvTF~RZaLS zxCYDn)_5TYjy~ zS*yQ19e0+0ZSulXP2PTt6NlO8Pw`o4$nnT&Nok$PF2!0bsGr;aJpX+v`#<6O0x{P_ zflRhsfo<9v8`&G#wcv`~z*H?S>+WkRzU8L8rtx9+c08pfH&2L@bK5&b&Ml^>FyPPx4S=R&ORYxS~o0{jFP+uP7R2# z6PPd>8DL($9sEK4_3Kq6=)fvqy9RwS{w4sw$8dLBd}3~nUFz7P4?pRgv?Q(|hp6q$#vdQ}w^(f-HT(rD|K>ay9)2|w1oU37u4a&Moe2l#K6a7x zMrj{GB=#SPTHH5`i6Qr)khwC;4X<)?5G0{?iNC@1}NIrgG#EJm7LMZLht2=r^;@mXX|P0gB56VRiAj*br4BhLl6 zK7r%@ZpKrTn)a_YhyJF{i+70szGX?x{%M!9mcoqTsC!l9xD@UtKL<4B^vOlD1;2yb z$fSI;ZW_*BHpoLO>9!Ap^sa`6J~`Jkc{P5wdXV)_4E4qzIk%`l&#;KI6{bd=y&&XI ziieXvwK8A!GN2*0CAzhvHxRuhC_7;RpDAAFfpqHX#y(rJ+tOrdGezth`K_tKTPI2`clG7NJZ=%lpF zWgfXh z+VGRlvly+)r+8>5GJQ+f2LEcMZI5ywqSXbRqmKlSb+Q!qbg4`LU**>JcIUx?52P`~ zk@$tCw;Z5T2vg{0J}$jG&Co(giAs^%!J=jkFJPdkrpDtwu&^*SgdOs6c;+7adh-i$LPHK`XDk?&}R;~U3jTGLBDs!?Lwtjcz zyMK*9FH6$Cgoi~whoT-uo_BX;Io}qQE>S>t#TJ}E3Gxsv2{|_Cx;T%j&F4G}gDHb_v z?@^etGrC0(B-aJ@9Hx2?;(pK*D_d_)(=C9o7E!HqdI&1Je~_YHl6{Kn5?~;>gEdv^)(X_~w22 zNcb`fB4&Usq>Lg`)!7Kv>^qyFP!dLY75csWDZ!T9Z&STC;)e9lvwhabHOgFtS@&|L_l5*93+Ndb(L6CZ=_JXt zteHMzsAiGk5o9pFFX&Bmtmv-c_xn6MdRS_=wJ9Nv5ZjKbl$BbF50S^saGTn^`}4^~ zCT_KU7Z?YA(sB6UyGcXP;UO zD#4mr^5AXxiMG_rd6p)S}f0{u2yY#q#Hgy(K{@>i7EZ zo*SV56MLvQbFX?~hD#jldk22ZMUMQkfj$GCM9d*A4u>1ZYc-lp0v2O>$g+pZo~1<& zjB29baB4q=#K&qQwAOQa4XHp(*reFdlT&Z%ktZ;j!44GJ_yTl;Kgmc(<`md9jjWGS zvY^KTQIw>1nDSQD>SaA+u6zwvGO;hx&)v_$)}WroIUYpnQtNPJ7+UX8kPQ&$(hKBy zQWO;q5Nk2O624qh-7+pbD?L;s+-~Z6ZeLlG;2#Zpi$mL!#9%jn3=1Y@?hGg5&&?(8 zj*=sgV+T}2w-~fLvt4iVJm~N^m6zf*Z3VYo*0VplQ`d)ADy|_E^Mc+kEg9JA|w$hB6(tvu-&z=|$ zacBbnPE`Zw@yfG8&>Ov8!`DR{0;YfJ>zM$YAJe9yLLXPp#VPR1hRbI2rlnRlIr_C4 z@QDZ$^?l)odkPXcX}RP0!_D*cA2N_vDrp4IMkmQpA=EmtQM7Xl?!c+nhM4Y2tjf^4 z?k^Y7iCStpXLvaX(Bf4<|6Ue=ZK!Byn9Mem32=-?I`1a5Q$VGTc_)!=G^EWCCuVo% zgdBnUGVrywq4p)38}}Xf7_YN36&MBA-?cj2lMN)MTuDGyQ7<@CtFoAkZEQKt=8pNY zGYx9{uB6snFP_A%udn~8dxK03p-QnFU$5MPSCq4&`pCE-*NRFKPIo`u!Ip$d4lT@! zovqqnX|l;VYvrClADdvqE{qbBMzr3DPEjti)qAvx+%6EWl#jc}bRPs=>%uv%OO?)K z0-Cmo<~noP&I%KKpuH+8N{uhRn?iW`iQg|2jj`DAuK~`|3&h3;26J;d#NowY1L!$y zOKd&I>StAngQywrc23yY`?Czg6TS4!N@YtUBcs#(E;Wlr|C%9O%_iFB;7CKQCYTbz z;NRd${9qv&+&V-{8(k?xI|vGtC7b;1V8J2D*ZuMLG&-DMQz6@iaf!rB=}V26Py;k_#Rek{(74(4Uoks@$}h@}PZBKqYXbx$=~<(#!QOhdSQ5VB&n)(vd!Q z5AmJy;qY%CHiR^6j>4+(nG!z7rUx93ZYO@WSnQzjZ`c^&3pZ=W-d zM>l!ndN_X!Qhl2~Y74nDn!;M?H}aH*erh0GWF4HMY`^cq-i@QjxZl^m!k7$DT5@Xh(YY z(t1E9w|zEYAD6@kpHG5(eVLq{oxMM+ivGQB3>D$h^Qn*Ep#BIr7&mSD{djGGA+7J9 zGCk8X7}SH@MeYLR{F$p6x{wuBRP^4#A%7e;dX_e81hgV8_tiZ1lFfHcjIb(aY_TfW zlNO;=$vm$j66+5!9B$pJ9ykj?0__BX5o~{Eaxwy-^MR@H1qmwBpI`lY;m`k2vAF3t1DsMM4Em4|{i4?M?e zWVS`$rzvN@KujjFw*LwZsCl>`qoBYM+MeAyhd*Rd;&{j&oFD1918%g{yA50G+u4&J zd*DB*{`uK%4@m(zIg0J`Z6dfky!>YT?5U>WOP!~8>0+{b+$E!d*G5yQ3dLWG(oK9oj+k~Bk4$E$m*~Pzm@81& zR`ElKYFN?~D>d@w2|v~V(STe`ByXszWBj-H$KzQzx%lpj2-czBwPHJXML}}a)0Wbm zV{wYM%^i}cgQjd>8_(uWe7`~u4_540jXxS>(SE1wt&cxsCBTQ)Y1hZkGAk(qbL4cs z4(HcvnH5~y3e0P+?MLSbe88HW8Qt!*cHMHhy;dcEBlR_t`_6Eebqe`>gG5Afr67il zg@v$tv1@(bu(?IBy|2-7;F$!|HCvgJSwv{9oq8 zoDjMeTPnLskG*rx=!g8wb8iPFx!!}p5@nW6_skKLH`iCqozjCxf3lanzpB*akry1b zB+ynocD9^U*B>O%PDqfEp__G`ArRW4!g_RD}LM zK~Rj`q}FfN`Yo&R^F@gSD-8=s-DYN!_#P-1>v|_tRasNk)NS6=bjL4q#w6!c`wKR( zgr-|T;6ek+g%xSMjq6%mdT%3=vexhZ>1biEp-AtlZP~x+t?bQ=Ahm=kCEh8ghlZr!ZECZm_6pGXwx=6BiEiS&Jz7blneAn)8=*SG4 zvfrR7s4i~L1Tr}{2MrAkT{|QJ4(~&U!k}QcVy~;Q5P%d|dqZ4Pozl1T+v&TJ|&>4MA}>*2#9K6J2UEqzL_J^?|dZ)qhL`$ zam*#i08-i$NNxvrw8BgMD0y0Y`a^sF{3k~l>+WzN_7kK);&Wl>_T14oiP7p?VgCxm zB@lmTr(LQDiDDO7>&)k?2OZnI2``w-dduhyHE83piBxDQ`JfU*PlTiqODkx$%fC>c zX|MYPBRVWD6a<4{TI5?NeW}tLbo>=qW$b19x)2`Z2%gQl!{?;gb^G8MeedbE`P3s5 zNC&hi_6)TO%RKbum_9f_7WW|tSU>%5mZnp8dPb*DGyA7CZSbcH4pY=~#RnO`#Y>(S zX7G9I^*Z@Q-VAkOuFrk|V-OsFjtkmpOS?)s3sOiVR_SRJY z#1>Bn6+-9WOoU08b8yrWUB4-Sn;{o7oB~S0MkHmYcJbZRYKm zQMsAO0kp%|%Y#nYE(nlAnAy(FK>gl#oDy<1AP=!He9`-h3H|{meG3PFl|6&3G5zbs zUS79CYGjUq@ms=@5;Gpiwr7Yra<8qZx^|S2Q70|11;-p24&{&D`X2X_@UbQkqKUc+ zyN1v4VbFOSag$J~aGY?oEqs!5RN9-exmjL+I9JhVq408G#(0FxetI<2&aCS(dvIV0 zTQZ4zDTy9mUlTusv&kc6*vn%@5u8z14Oy+-tb-HXdai4)#?{kcQt6eSzQy`y?pdMi zXx^}J?8}56F~gDEPzCVYs9<^dQyeHNM0htskH`BbTB%7dNXyMVN#1We!sdr z?Z42YK6+^YL5!m@Eh8g@qK@C9rc0vhpo!_`#BR{+>f*coRV-q^X3C3YWnV?bMkxey zW%5x!y?&y1)2ykfsbjNPEF}Bf;7o`F?8>HfNIL^IY1&?Rxt(zaq#w8?e4cY2LkT;y zZe}8rD^?A#xU#ydk?HB`kn54RZ^Z9Y%QFhB9x9W+S1Rp*4!1=za#w! z$jmOJTJwuGW~F2sV-CKFB7+Qm2lfdFSErZoH-Yc?@bUe=wL^c^)X~9|5&PmBhoqhv z?A#1>92pSvmH%PoGI>_6em0%Vmn)yO}4(c9neO-W|yv&-1PSWU*-zYO#*e?IuOtsUk; zR_-_`)>>uowIZ?aps2N^+~oiYLH>DZzN<%!j}3}dNIwq#ae>RX_xwlFtV1=FuoJ+; ze~UE#mw1>K6!@vRvDAC;*9)dQ9D9C^Ha=eyxXEV7IoNks?rNT=XbRek0g_dfZgT^-0Ac%ptC6Xy1tXRae@B+i&^*JA|oF4;*E+1)8y!p5E~V z+!bXeJ?qgcK%KDK`^yUj6&4r=0F-6dkk$sA1Jj=5`C*>zKfVuBwSJ9@+=F(5U#=vC z+?N(w76wx~8BGB3`_@yxjvEMln-VN#_M`$YVgkL1E=LC*o@=T-OfQKIq*Gwqx#-^b z5C}5s62{@wSlPRr6|GqW2p&HJ8!K9k+P1R2;t42u2N&u3eytl`UUH!3z)air_Y|=u z=FQyM3Eb28L-W`ho^LllJ?qli=8yX4 zqfOu&Mov$KinW_bAFVp2kBppFXL;YcDVaCYbct=+tUjgU5!g4MaeRxfEJ z8!INr%U$Y>2U%e!3*{}-6Hc^9{>yhZ@v$OLTgeW zSsCSRk&#P6K8hi6yE5pySN`_?`NJ40_TxGA=cId zFc-4NhKF-BVxYdq2>E*nJ^yGGWNY1#$HI^f)oTN87kZ?Gce3(W-#GbbcQ6kE!9E&+UJ2qo8b?UV6~agJm3Lp0CbkT_r9l)OYXRQNPtb@8IX{ zV2}i?KbJBEK>ekOIowCE+#LC^vEi63ZF?PbS zv#MN3HWY|bvYu>6rR0h~RpDGv>|r~go}g3ldny1Dnvv>RhQX!IXmA-cZu4wkqG^{F zf%^vvhq{0i^rqJ_H8J!=zR)etQWfRr`MFU5^Ux0JS>W&-yTYIiy}oZDp0vE&8#1PL zFPrGR+|B_EO-EM)t(-5StoL(nz@PCAh^2(~`DMF~xz_cy=Rk#fMRPhs96THnZC3RX zdY#RYR~4Go+HgJsxiQiPh;s{hu#k{tlXygU>b)$eU2bW!vt+ac2M2srT-!_IhO7uy zlMMa%QN}-Z4O>oq7dz0b?6B5X!Ktr|Zj;WOz`Vh*bd~t9%CNCcAhPQPSH1-1`tif5>Z%l! zwi{3yfBO0fu<}n=jb=L+wD-^ko!njo}x3*1}Q6ODnnTwS(`Jw%Y>+=J87J zD>xcFxO1js*1U4oyp||X8BP-v+n!^feX77Rch@FCt*$hlS8^Q>{H@WfQ0KeQ#Pi{+ zGM(3e237Baf`W7ons;Wi%TN%S#;m{cufUr3OlJ=J?%cJ?-;496vo_>oP1*2UBCESQ zid7W}>U%%#fCv9BH#0dX!Tp-^X8m{m2XM98*3US_1!|AiR}EA7saU4Jli9d&fD|EH zQ3fSbE$`3k>k|BrvoM&-W&a-UUyQ>gr1j}P_zsxW%(s!UCf0gZd!{%qk07b-(akyV zE)318Kgcd4luI)r*8v-#j}gY^qv+7nX~DP(5q#91_ICIUq_k7|GGirFC-~2k!!XfC z)0AmG4oocp_WFP7haFJ-X4T$RmD#ZO`64Yl!tur)_YcKSk#RQ-m6XelzE?2Es1c)R zSH9SDMo==I-|f`g(W8t3x=B#%6X8z^`hA#QGYs~epaL|)PGAInXJM}UoMAm_H_=(3 z&>|ndYE!dh@A&MI^$wu0BSQ+rCuC87``_YIK+xaVo3|76ZLR!t@b+nVctL_vKtKS| z;H`z!#sHfVtDg!+3-gz-h`UDXRe1a9@DO+QP=La>fA0V_tOJ;>*s`RD>L%cb{xOQt z#>)i9;vq){78aHoL2Vqvnt{R?qwBUew;uDNwviDE_}5<2FyB38+D=CwajWyJ^O01+ z)2YRG%{PjJADS$60#(Uujzz$Ev_E*8-k1LNP#OkIVO_#c{@Eq_A9<@wCC;Ug2AtY$ z4RGE3@`ij;bq(6u5qijxnHh@=8L$u#<1l?`VgQqC#(%iR>2a8Qf>yo?eO$`MX`gNE z`G!H&hUlB#8rLknV9de1|5AY$rFBE#XCpwpT=KvQ3iFPJvPSNaA@B81yqac@b~w(4 zCXR{Lf&dg8be+z-=A^l$h0kT8Ho! zuItzA>?&k$k5I?(QG_C_lPytm;3`SE)gDQGm)70Er7F&3siG@_N{$Bv^!*G%zFh6w zU|!c8kgDDG+&qa3+#egy=xs*1;44~Q zRCKbk5!%iPJY^P4nW`8od5y%wpFom)7SzXqf8le?H;%Yr%!L@O8b6*su3Iov1};1*h^-e03}h7({@fE%@#S zU4-S7qn66b;Xmd%x=i{JOuPG+U_6#K6g!&MSU0jBeLPSUwUSj*`W%Xh3O{NWK3@tC zKgwqm9>=!=xamuDZ`z-XQ#yUM4W6sG`ow|#yiniAmOO!lCk>|VZf?SWIeJ5~txjRL zd*XC|Ng5HH+i&c#r3G7P{oy4A`4A%$HGO-^`y@02AXmYS1sLd2+*f%A5{)4=$OH0(O#ZX<#5E@7MPb#d7)uFZ&jyGiN(H9zO-Utsis^*hZdt!HHM-&Rz%78y4vh>aaDG~IA%9H0CfNpRb=>j+gKaJ! zWPbi8n>b*o@Hm_WBStb0s!c5{qGfRP+?NLf1R^(%Mq^Hhn`^$aY>(nV-brUJi?8d!$%+5Ie~T|6V2&QZ z_>K&Qh>+wyI^!&$q1$_4^uqTNViHdx?>N>b|9JBX4=7cVLn)jsAwx z-a6VW^S|hksPv=@yCC`Z;JQVX2%);*z&gFvEyH;YeO+DM&JkR*nEc)(3R(m4^ANe( z_`*9-IiFrcf#bqeQdVn$L3Kt#h6ToDeSCMwqHlrBhY)^X078*AX&#mz%VHo_q7+b? z|NPV%_KtP@k7Y=uOQ6gX-dr*5BKPOdTz;T+9md%_!S%DpAJePK;KfBBy1%Zy<&5{- zgg4}({A(O}nqsAq#4MZZ5cE~5I%QUhsR!_ZY@W~t)^u^Rkr{q{zY^ElbQPQK3+4es zQkvZO3x@5P#ip}?OgR=*&_R_A2vkM)79=Z3J!&i@EY$TYCMLY4WkN5$x0<`dX-ir9 zTO6uFyd6=r(khe=q_izU-{DWV>zhrld#MtN*c)u`=g+LT`W^+*J7@TRf!NgAx*YLSAhLeDb{hC&UU6~prH!#- zVw3%Ig&LVa5J=3&$0rBSuP62c%B^C`weH0>Z*g+~OCtD;*ZK}XU&eTty!s{Bt9IuN zW^R+X@iiGh2o*Io&kr(DIRYDpP^9`6(Z8nkdx@Ki%b00=(9e@>@%;RJ8yA-+=KyiWouE+s!7Q)6goptu^rn-{eYeJ~|`Xy{1dakd!UXf0k%m=+w+J$cO@o9*glxwZdY z50L?l2v4fK{vgqBoO?#eP3|Y8=a3No{ySZhj06LEIlKIY6sIer&Wrs!AR!|&ZTekBJ@Mw71hXE+ra)1LupZ;c z&o_~Kd!wTsW8skpO1M2<9cZKNNA{cuXH+NN0aQ) zc#>2MF2mnFk@D(QMoU8(0A^e!YyhtyE+K&dUZDrt65I(SZ}0v5qyQjy$uQSV#{jH7 zAPE5UwIQ5VQ}coAFUB^;vo}&3?JBJb5u8aOkEFXcWD?l4@(kt#XfqY}u0{H+18yi) z{897)ASd|OL4Dq^va@&LaIVp6xqv|r@F%w@cdw@c#XVGIcXUjQ#{PRs*m5ts z@gU1$j+?8tu8u|Bu{sGLqu)?`&hW8?ix#gjAahPgVI z2G0Au#<%oX)zA3d`y?7el~KwoQr~|lTxDd>GhR};P)%Xg*frc$f0=XK3uX(qLQ*EE zWIVq4Op8VZe)S+;gttq!qT7!%KOS1ms@_lDPgZ7sF`&*76CMuEP?$Fz(&F#;zDZ7FN zVYI3pjI9gTZ#gLO78e7E8T>@BLm}8c=-LoD%HQ}D<$zN2mOUR;ay=}7_f|$@74Uup zhv0K8J*iY)^j!*>UFjdYI8Lq&sUE_rMPL$8b8Ks}kV-uzl$hE=@ z<_k@paR{*FC6V0*SIe3%3{-V>dPMJwxLjQ^wn6i`od})%`%?9k(~b|shcvhTt_R6K zkCZR_>m|hrOMJfm21q{VBoOE4ATvdqNGJ0Y%WH1oBf?taxOT zH;*|$8USyPrF|UGjQu5Wz;RbnTKfER0U)9V&C_DL#4^wKeb*Ml{`CSuvtIW3U6K2p zWUKrYVk_K_UBe=C!cD-^giSgRXc^UDj29yCAqo8$y7QRsRgKHZr=! zq5=<-j+Qq`{sWrk^xMn*g*5CZgVJ3@@sILm@PCZmT@#NCx=xI~=ORM+I$1qxDe<+L zl@$~)m#1cB#R6{M%cTuuD?kBjjhj)jogiTG1J?XmYuY8686O|-+5rLE2{=~$q3rDJ zEn(VCt=?QO3>acCWevTmC&rMI#b3XUh>pU+BxR0Bu)zgE{^re=}ULQyVKTzZg1kbww@6rW$EF^>Ffo7IAE|8WQYghG$Hv6%Y zj9JB%*NejN=XdAsoGsO5dN+(YY^)1bprlmT)aLA@^(8~=>jisHQoW|chZEje4TOag zu8~nW?H>1Fy@ern5v=U!2Xd!^vL(`h<-(@<7Md}L)`OaO%W2tnt!bJE=wOq*<rQdsp6LC`Ju_l` ziIlzDKS;v=&zxycIzEqAG*XFXeyg_{?m-dJPVw3Qz7O*~DavaeuV2#90W0kLa<+jN zf|u*Q5_{<#u374v^&Y%yd7&%8fpb}gXKz-{Xp>Vg2*AvXx3FLZ`A$$gR2x^e`g8GY z_ap`(Q%EC>Q^aj=k0DBdnx-ybqBuQx&d=fU6@R5-1c(HA;QcOj#jqF{8CkUWKL^m` z=9rN*seVN2jUR7Z@gY|P&2@(~0k1zB^WNJWfV8FHKkY&|Lzi_b$OY8Wa2|gTeAagD z6DUp^sGRVbIbM(~(j!JF zab8F9C0))pe;{`4V+M!T>nFm(=;GVldIJ_ zLHYSEK|3T6D%M_g#66i1TGiTWb!h25;t{XYyy9E;SARYzAaFW2w(Ig6@~3oz5q#*c ztjbb>xP3<<-xsN(f1O9K&tG)V6O0h*NsuuS4l56QOHGF1xa`kOny|=C`<{Xkf-tb? zZMV8MK3uv2%hXR_-@e?8$>e2k#$=BdH__AAkLo3T8DQ-DSc@z#+d&xsFVqPMiLbM-=r zpsJ=O^YT+;nA>iWDWWmy@f)KVT;1YTw2arrFYKr=t!I_h*tTRS+B=VrjU5~>$(|P~ zt+XxLwyx^!K$CWogC9*uG~+OohIX*!z)~Ya?%eH{D{DQp4L>Q$rEi%x8yrC-c+smr zby|}3VkRiY%53FWo}ghiJ$~O}>N#H=s4EHG$aZo*El|gXq2!Qs37fd1s4{Bd;dU&f zT6pRDabD8?sSVprc{f+rag6Nc$u0%2t242w4=-?$#(wDnY=0e$skkUf=}bZm!bj*M zREndL)9N=lajQ6zE7GRqr>f#z-z9&9LO`2ZH9-O@<`TxCjNR3XZuk48D!;k8S#y@y zKLWK{G&=9*VMac&%!u zmf~8czEH*@>reKesZ*d= z6jEkvQEg)n`~pBH!(RIB zBxFTvuB-skOrY>RcUKpeP9R9a3YJ{^fV@M+<~_H0w^!BM;zO7xr`1k3*H}J}mH|UW zv?bcV*7@kuM1*9xtPcxk(?F-=sPoCdZ0wKeKt|q*+gJ*C6}%|LQ_IYUnJ_=fI7v0M za_FvSM{MfP*IQ_zj;Akfgbs9#lm03`b?UwPFWUNcc~k$vl}4NDaC%F9DdLx~USX0l zdm%n&$nVFy;Gh97L6Y7_OnvPwn?J(KS;CKg!sB9+Vt+

    5siN$FV#S;<(Xewj=g z?db|d)gi+-ugCt|F(O|kw^KTaNJXu4&V@U+N`I=L8=FrK|2P6`jZ=>rUQ1ZB5=#7) zG3sA6?UH0oe2|`1q%Jye#Or;O@GxH!HsbjvGv~#EoP-407ae*tSAjw7j^ zM}X7k2GpYE*W1c66C`9+iPdHJRRs0h+ppDB*nG#&01U|PxBMM|_OVU4 z#>bg^8Q2aWuq|DZUw{7G23|Q~!X{P~usj2ZOj?pN-%FBpT>U2CMgaJmfh+~TgLDj>DM-0hd#h(7o@2-&HDiKPhmeK{GuZ?qFcoQA3Jzrkki8?{7M{@F*}1^ zBkD%k4~AQBn3?Hnl-rXmfm=BN2p~X|LjAYq`!Y%KN0T1UG=No!bPpW>TDeltSzWgn z!Cx9^bQ~(t^3ZC(#9^%c{u!W!r@~+{Lyn`Sw=@xg=HC2s?m+@Ce>!wpvza{@{5KZ7 zArtGwsrZ&9GjOzuRc2Ou@_|c6{!Qr*uE4F%`!w&Z@WP4a>KC#2v&itHM&Q!GLCS)_ z7s7ueTzfZ1OUn=$8&6mEA>ZOoU<4W;yb$7*F@MoUPRLQc(5~Lhd=wZA=Dh}xFx~aplP&3Z2 zF6%+V{j>b>DR{s_V;?*3)?=ib6H&XyJ@G)uP1ox9@<7Jvyu{wCN)x^=DK>$$`$aG3rBQ{>KqG}qm*VBw4CJH#mt1?UXbC=f(h1~`fMC+7uuKj% z`41Q{vUrv5Kp%tI`=q41VJ&2_b9nZ2XPIhl;u{L`B-wy8s{7Y``IpauSn8uDp)~Z+ zfV_Pfsxq73@AsE53OJAUn`kvNx-R3l`m%}hnm-bcCT3=$)j1%~TxaSH@Yy*}=;r8W zJ1Fi8qw^b05H^Nk8_Y4e(6+JQS-`(dpMuJW(3Wtm9!Tn~s;Y>@*m>Xl2PE3Cw;(~S zlQgEqnPgc*d#4eBl+$vL6y3y+->oNEN4*hz`&nP7zpk%aZwBoe`~Nsm-hIFfqUH>K z-CAcOpJK8b9mS{;wi?m(quFP=R|N1jxWq>oz1p#7y&{dcG&*(d5F57k(!PZ~BIoME9%t=VyKdf5udSV{=BglU?=E4o_% zpI}ogx$G|T-#M0pWZHu<30xH$g3RsRhlZ|UJ)U?rJGIUH=n`zMU7{6wRL3?({b z%84M>7pS+Lt58l`DSBc}Y+t5Zi73u)nso)F&2gII3?)K5rwV?@3}7Y0x$~ijwg`0~ z^Mm_hWiWX7wo74#cR-83ku9L+H;e(dJ-4$EY5*kJQGhl7Vh(R!`{-)N7&Aa`lF4hRbK( zRA?%U(3bH7$SBNikCw#;KR4YPxHZKi*=`j``?9w;6~5S`X>s94Gbe3>%r}}MR`)3$ zLfQcBCXWKHb+hcKkVRriH!RG6jU%BN=nO&;o)Jr})-a+G1i+(6e}&MitvMrp#hWyv z++7K*URrCuLv+V!+uPxbPp#hJca9U(*$c_L8cn?2T}RfJ=<+{m?-}?jcEYTn0{ zYqMA14kp+*X}|4)&%yi>RDX8lCq2iNNgWOiEPYrJkvN$qBk#)F?c~$LvrC~{KXJWx zW_~c9#&{i71j_3r%Dq>*ffY#D3bn?50PRNV73?sId_GAhC{blH{AY}ezp*hgFrWvl zv@ECnwAwh)B@hxYPX^MFzSk`=iu~THgMRMW%9;D8Jhu+xTtb1%N>m)YYufcsXfq5G z?T8^~J5mKpHmhV;^DQYUpV%&b@3m;xlFjyK&KTihS&~k%p1OHs32<^R0jn|^gdOP2 zjg`M|Qf3hWShFs*SAc>Bj>%gVzid9L!cY3!V!gy&G-`WcK1%X8{T|J>UF4WIzt2%V z{Ey1><1DTL-)?)i;xXfYlJ~yL4+Xc7R8;q@o)zO0=?O}$)bziqIhLw?e@WMvTY&r> z9QbQ%YnK2%{1&7RD4@U&z>2rmF8@8?Ft!TpJ{e;t-^_`TPLo}p$%d@R=E@Dq=EJ7v z=VK*MeI1zZDZMZ~6~Ag{4T#azM_l)#WTa>#h-|?-V6e4MV=FxrOb)}wque({ur;+91;Q2VojO~;6 z%IB*};F^C@`sW+$gnz{6h!AOoe_D# zy_OHTBez^wCPJg=XCT)apmh)tB%!cpbzpw*V)sSsplhXDt1@E65|Se;nY9+RV;1Yw z_++GIIenvVpE)a`IbLGau(D;>SwJ{V$YVxTZk1}3;qhvYPiryZ|8air?t~14GO)2d zyKyh@>u2&}9VtrR!S?K*#@Q)1zueUSR@SdH3VswUaW!v9fj)3k>Z}DD&8fbY6P!naSQe&9^V!ccvPEp2pH;8_JQ#z^ge9hMh ztqG7xX{bQHGOL#RD8B*F60Qkf1}>f<4aIh)oc#4K3{@$L+%~ zT6fv~g+LGcVD5EKl@4!e9h<@dr{aEWO(elN@PQZ>7B#IameWh#ALoI}$g@_CA&(BHDLFxOU7342hK#O_iodN9cWI z=a^Ip`*I~tMo!WyXr^cW42lnT3tanow0qc6zS@h2^rJgaM1KR>b6>f+o38;>XZ<63 zHfnw^(-%EGC(dVbE$Bo~j`IiaKdHuD-L zFj=0IqVdUg1r2l$@I|Hs`+anCLjX>!%j}gbZ>lZXaWt4vjo$18>=zK7USQXkl$D9c zOOG0!G<(oXU+nzjfL_vgH6LFg8V7d%wyw!<)RHsBoG4+X^;tz(n0&`W3*TCC}eNVq`{-j3#CrkiKSDuyxiJ2CXq%tkY z3NE}B#3%+}enZ^nFZF7i6GAwb=+;e#3h>RbHY!q{{$g?}miY?OKXh8_U6%*UCUs*% zJ{MP46e+iRP2GO4J)pb9lQiwxR4Q+UoG(=*<=5_)SUm+=<=0D%bjP`a)fo@|lv zTJCkqo{W$H4ogy8teB^zaqDe&&Of!SCnxIx~*4Ji<4NJQmY#lH0S&ARmyMj@~+f zH#JQk>4Fl-eCB^;AB@#f6cZbOy5V<2efMa?{`r%Q0Y<7Ax|)}&yS#IkMZiR$z6lJj zvnp934$C{TM_3V^fr5gfq7Pfid96J=yb5A}1WtHRKlJMWKdu72=59)D?dO#-n4S(; zy5bY~!H0}7zE~Oh`D1I*6|xuat}F#i@eV+U3A;Szk7hAGsnma;|IZ6B<9&r#i(#*Q zBHdeALWIZvz7O~+4%cQ1783RVoG3WF{jdyt_|?H z)H>dl)6n4NU+K>I5*vgD`Ws3t1R9&;xqm>TS?-o~d1U|1PLmM@b|K(8>E|wsE#AYFfUGRwUobye-wHRjH_q^&-Km>=q{&2?mQj=)B^!>3qY*^`2$@n2mcF(qr{QIyTR8` zfK+{p^9ebY<{FzP#XSHD*2(T_G%uf%SRf>5U2Dy1UB)s%paf!?Pm&m$IfGWN3pmDEIzx&yQdp=%{g5EsYc{7nmn8D2a7R*rhG4y2hBUpbZ z>c49L!E@s%8I4J|4SrZ&rJ&8KY1aijCtO1B|6}UC1KI4u_V2cOQ+JiB)~MCmY89;+ zt5tioikfL_)n2iMwr(|R&l0g}?>&=Jq;~Bs2ttC0E!KN^e!u5^Uw`?-m1^WVuk(AH z$MHFJQSHR(t?jvZN#kF8Nd^y&7+#s#FU_w4IoENR_-_99qlJbjHdb#RUjadQRn7ZJo2aNzg9ab2@t34=#VhB2ff_DHOjkTgKxjl7FS1U8dc< zDB<2Wx7k+0TLd_AXy-W1qa_0_hH3X6i8I_;m&CmtDJ2NwN&Sm=+`^9xFw6DI&0+2T zk;9kH;#?rV%vE}Kxrkf4-Ax()m@=-=t$m!;`t$S=$Bdn+G5}oZkfVBk+-hB|c^)oh zETqP!S6=8}>+=;NcI!o`499YIC|mLAi%`Scyp1(4&PV+9uKaSf>r9i^H*b^C*H*Ep z5;IYA&2oCofHB~pAIH<213Hq4)<-Z0cP&?nfnm%*S5Rsu#-c zFzNVT!&|1|1!i}b_Y5)ZCwb;d8VeiqJiv=owYIVV+6$ZiW>q6_w1v&l-qAX=*+b55 zNkns6-j!TdM)zdCzO>)wyVm(xaMi>khLV9C_H1F~dtMxpj_ysSnz;9G2T+J@p!-2z03%d26ng@zA3)gbjXe$iGy8y2a}od-!t6*5HF8PUclV1meh zjj;vI0LP*8SH1=~u0C&MUX z?@U)Av0CG_x9OKm(Wo^IBh4QOHDZ5U@(A^B*lfEf#4e$Ag3+UeE zqand8R~gft_~ko@eO6sn^~VFO$bH-JS8ag*;Q3zqm&nY zJ#Jk1;g?N7?VFmP{|?Zor$%}o+@A6~sRo~qAAe^*YggG(-TkRd)qswm0BVybtBl9& zo%$%JPRgnMro~s)477JtADMp7L%Ia4#Q9WlLjcz)4t!qXgJE8{do}U9jO`9^H14<*@GW@K7CmHB9Oju zlN4}(rDve$*`7El@9N?ca#NIp5qWYagQ*8w>fM2v_mkU(RzpoSMGoa?MEzuBN4afl zbeIa<*n)}nqHndR$Y=HDwHXy}Q-x}RGk$%sp$`9Ep5vjXm6L|8IN!E=E-{ZRc0fdq zcX~gIX;t6pG-Kql{|kOjIi|#QGDNmuC6c5mn1y8=BTC~)!AjiZCs1nlZM6M z{D$iEjTxG0`H?jx=Lh6Yt?1?O^*8>TNc?qrEG^k=;B;@pUEl+lLPWx&V20N6eU#)31 zz(Y%&)FW`-t^5yJ>_hgY4B&JiD#Q5JQ>&;xAT*1V+a=4E`T)sC^TVU_YikVVCDZ+j zEHi7FS-3Y;O(x7dW9ZfEu}Ggr*^s^O`*xXEIOOWwR|;1{0W8d0rC>Cif<2%zn>lgE z+oVf(z;1(it8w?5xSKFiKSeZqwb}d~*yGEyFz;ynXU?TVWcKnBfNS(h6c)hC_k5*S zJNb8CYdgFu+^vg!tMrYlhLcC2CUs}(esER z-knKSe+PReFtN0&7TDtaR>3o7KXPOr1bbSvM)yeoH*LeH}m=~2jLx>IS- zJO?KRJR-2*6I{w~H~s1mO_&WjLKU8JM|QTbh@(7A_%^3Z&pt-!btOd32o0F8L?Po0 zAHWL+O^M>aEmm%y^L*z#DSBgIa2}0yWUC2`rtvI)n$G*&<>&vV6(e{!lgi1yh2?V` zMOE55vCiEM(B$8F_v8t>8f5aEd-cWB6^O@e&g&@=QAmoqxvUnq*XK7Kp6R(a-;zRF zKMm8>ohtG;IXe+W!O6cWj#6Nj_gx6JzO(ZbKqj?4$pc1OZE(_C z2jts@IwX6F{BB%WOaK>ROUNZ$z^Hso>``pF=U&|NXA~mdoEKuj2OXPtFj9V`M%czV;aDOf+|zL1Qh5_-ppWh&8U4Y zojwZmKzs5cu-|D3nbIpHEyVEwFui?{nG&_u2k0|E=cC#LfSWLcLwkHW#rZ)L@3uMx z9GNu2AJM450hrb`fdPSb0Uc5LbN|p!t9pXXk$>!=O&2P4D6WC(QR8o|(6GUV(Z^}n zC*tNW7NWb9Ncwoq5tlEA>+@XI*@r?;}2#h{9^1M^`>NN>V$)Z_Y#efp^PT(I25^k>&(Ba z8X;b9+?PnbP!>W89+V8YtOy(!pOFTye!csz&NI!oUwE}iQX*|@t62w6`j1ljiBdAc z&X&swGF_guPPa}<5hpFC`^M1xiXzLIyqBQ%T$!}ifyzlP^k?@x=|z&*Z_uV`dPZ32 zKC;OJwc5Xti{LTL8O%Q$kvM)ACyz2@q8}vn5FZc52KdZHc446=rD!Sy9lExwvQTqM zvNuqL4vuwM4$t)N@8b%?KU}U8eB9;sC}!IGqoA%@72006`sbxwn-=*W z=0R}py{aZeiuH6@jSQQ2)C#4+AOj(nU9L|wTg$ftcJUADh1ch)V2^J>5nEyGy7m8W zser=;y9$>nna_{jN08|}dCw1_$kXC`E$!i7v(0^+(gEyxX1;yD`JOHP`~%tR9LUks z(d>RIvc4MlLFuto{I#Zli+}+K3fIy;r7kXP%Cq4=(jwC?1Q(mmzTNe%Y?%lr;2eiI zjzsVUe)N344PA+=LKK;Gw1@_-*#=2)aBMf89~KtpCiwy5?JDm8Q0n?vF(0=`G49iI zGzIvm`N}byQ18*$#57s)KS{xs3iHT{vw3t`kbe*HvLOK9kS~@SC_bGND4?griE>-i zT)c%iNXMmkV0FIy`hB4ty?(kSauR>l>HyxP{~2goTIRa#>yT%#+$w~V&TUqMOpU{L zk8e?a{XxY?vaMS}HVpsuVn?3V1hV5-2$_vb8QkwpP0XSWF#p}`JB1(C9;*VrE=Kk_ z%8#c^Xx|`u(81}fpf#@Ee=^m^K_cE*5iFCuD-`6_bv9KL6B~)Mu|R(^-kT zm*(hO3CDER&%5ovw~(l>-pWZ=5+T1gFFY!3^M1J@kY)oWzQw@9T%4GUSCKSo3wAU`ZG^SmbVVxH{MsfSUn zM3I_da>qEuI7R=vLw?K@L%l9&Rp~uDU9X^ZUUBh{q2>hufubC?Q|l#7c^dE4)3$KX zfe@EcL95B%KggXmkVD-}BjAXgN&6vdw_;!%>`8a`-@Djco~QN!Wm>recNLsPxA4go zz-|Wy6z|`ijb+nE_U?YF^F*R67;f9g-A8+La{a)wqM8#a<%a&zO7xb;?7px#IiLcQ zwjUM@oIp#ui2u!wO8B+18^b-#53Dczl*cdwoN0EGEU5Z}QKuL6WI}s;=QT59{$9_z zSsWC)K8N2Pq(u%A9AoxUzu2AhX7c3r>#Qt4|ufQSY}^&U|+mHuE9}m>)%r$ z8DllhS$luojHB-;-xzZJ2t($neSbwnW zh7NG{B?9_%^fvUUD+Pf!xAY8L4LXY<20_m!QE302_TyfKv){Gz@be~kK)JI^OxsYQ67SbGL`X`57UF+qgo#4PTjAg9_5LHAteR$ll$>)nbjP+C9 z`uiFaA&ahi$@)|JkNLePRK23tJFw%nDW(_QkD>$nq7Qd`rF*1p?xnbQ%lMkb;w`3y zml+?(ROY3-E6=n#$>C*b#buR1Du@=UMojM_2p{ul`{F~8+^6=#mAo3@4KgKEykVUY z5?J`7W91RzzErOTXKEd5qY|X^x7(EBp*l=j?fIBd4U*{&6>$bAQ{ezW4?sNtPEY`- z_w2^P%zSR(226o%MFs>ajj45K(e^DVUK^~a@6`C_ko0-yAB||%d4(PbBi`d7G^uoy z>&(c2SGKY4^d+jA&n@@nk7!ZD4n_5GAO{~7Mtb*@RZ@$^1n7d<6mViRe>H4=!a;=` z85+!g=GPN_vHY{drd;fUv$ywDhQe*O<@MP2jn7j8a1B80xY>!-KtEYkHTS@;?HjV- zGt7rqnzn))1=>|LE$n~v@68Rm+p_xR zO821oHFL(D5@%APH-JGhCOzGaz$^cH^kSKzt#GNvkE8G4bD+cC^R)Ngr&?zDqB&qC z7L1r8T=aM0m}=CAzdY(-4H3ZR2K#4TUH{wlF5AiA5g{3b!P)!Sg~=a4h`cj_Y$4!m zTa=j5`e=)3D4;*AXn)?*Yz;+wX>)ehX+fTt=(C)f(t7yMQv~mSHqxSk9&^{PSai%9PXoGQZ$dOBL;%f z_obKleD&|YdK;`1yg=m>LH>|#;uV`;teE(^@wJM9ohl#pw<#INz#q#8zv<}nY5Tlk zp1uOeQA_}6x`nzLIy9n@5kOc48W-cfOHDgv)qG}PV8GxN_R^kZ=k6ZKpKtIHqccha zW<%xgqvaT%E!_TX@cf2N+7jgV%C9kBtb2#=5)%2rPiDd;e(E)Aj)7;D&d3@Zif9e= zlZi-6tMaZ5=+d-^{~D)dbF2R?C>!Sy6V0UbxLs31p<14}P>)EsWO5p8m}JLiZf`nL zIX*B}rsJx6;4SYXM213WWFFzgm6Aud2PwX|^Q5OOxP8VVTc|48jbrx>u_1Voiv@D~ znjuL67Ss@T`)r9(4>(3H(Jb~*zBRzH+h9UrlBxh zg?&8$x@chxBraSs(<3>mP%BC{ zFFHL+&HQjps5G-@-)|gun0V$P26wWWm-K-%*GDCa3PHq!o?AU+dij zJb;dX_mMI<5UD_a*XW)tFiLzJ*@^vk?6hxC+6bgqB;g|h&J@c0B)scC%jhP&YcY@d z?;*Aw02RzL3|Hh)p<*f38gyAi{?YY48wR4_{ey$uR~b}=AbIj&r9^8cQ&ZCej(i|) z{=<-{)g$(OXkozuFo#RhzgA~6W3WwCJp21DE@)L-6s0)6jCIIFG_^uCHz#;5%*S6d3 zxSfD@l;Hw!U{i(u2BKt+{R93A7sSOAvU800tGJ=^lCf`)V2W*?rD=7>3G0}5e-F}U zb0uWqON(0h)%C|($(uXP8D1m5;=8W>pS&0MmAjJf$L(j;&8(KEa?UAIwlm$`r^`oT z?|N^Nt?KPbn*Pz4<%4laCxYzQYy$T2Fdg2&0HA>eLf$CSPP@W!@bL)pViND&BQqo( zSPi2RsnRQGjQJ)1C%^cvx0U+sLCJCLxm-U38t)kUlwwFJMu@0n`QnW0^0!;s5bs36 zO<>s_@K&4$22t(p>`fXOoOQS|rU(YQ`3A~&c)bX-pdV3A-+Gtiqro_hlG5y7XG)=i z_ce!#3HdetRm5zDKmKSsL2&jf>r+HV>a(|Tw- zcVT^W>e*Y2drZB{1&hhvn`Kb8BC>9frHB$7zRkPT{l7<%`**<2ugGxJpd@elr@3M| zFFaorywKC)jI*w$d}^2I3#UqD_IU7cBmH`d>2t4}L}LZ%J_&}k>o-I5bw`Qh=!E{{6vcnL;>y$HljP=x@HlKicO4{wbc!aqom;RCo{b#aNjvXz5Xr#+sZkG(= z5s(~xOjRF?l6R@W!WeFT3#c$wQRTT^>hR`<)ahVVR>HDp-2m%XOJawetLtggeTspg zaZ;vMoVLBdk!mOR-%-1`BJ~5=_XQxp>ljpHl>w0sh9yKZ#tOfNrELv+pYvqS`J!0w zG)L0U&Pg=Ds4W~kl=uBRk0X4hxhC+GC0e0=%Un4p93}(WC;|I)&l)+L(M7kd56x+E z4+xd+OEehd?209wzKQ@F*fp`2s+-LJ9nIM@7BXfEgt?o&<&N4XE@#4 zQIM$Qm6xi=eA7$Oh_yIFoY*JO^XCQx$G9!d!(pQSG6gE#vc#*)7S60uFLk(fEWkK; zl)f%GUvil0v-D2jy~qMz<$z`N+kjOb>zD&l#@}-g2W>FjBNKvptHT*eP1W&n~( zf|N$Fdt5dtWow6yhD%&a(7n9KnN{=ndkiR^jR=~Xjhx0H^eoI&fjr~5Wrb)Gs4438 zpqj@7P2d`fjo!e)m(d>|Y*L`T4VILHOh_ZkbtfxC5pJK$S@~J?DF6j`19a|pCMFR; z9|L4dD!esEXsl0h3Nii59pp0)Q#>0qN$?L)msz?SttssR8y=)ajT@gRe#Rqaq`O1X z$6_o*u%5|(U;CnFOajnp;+A`@+G|sx^_;Bc$usehOyH8@hqBZ$POgsA^a<7^r=TDO zK)=Ds02HFDY%K8o#}6MK&p*fbDJ*x^k6s+hb%GPGFJOJjwY}dOJP2}l8uk&mW6J2g z+0dujdwZ{IZ+5c=kJ>a3J{DpzDj1mkBv6Yk*PU6@wXvLLtI9)&$ElI#C#)g1NAUXTrqnG3P?Z_9zthKrO%Z}b&2wt=SDT}V>l9CJnE9DOF=#a)l&_mG+oe;bV zD#+vKbIO~i&m{%Zh<_Aa3>(OvO>FhXA>E?HrqBA<3gVXg<02_Rxq86{?ot`;xZxyGS zY}Jz?GU!yF?cYQ)J^meRnionLAP1N3pFVC}c>5u~hgEbWll5h{#O(eLybF)TOl8=y zj_qIHMV-vq8@d+0VkTln_g`_wCHzy=qmPBEw2%n<2}WA~64m(s3D^fK`QR81(J&ma z50Qf4qm_hz&0SQ@+3OSZEqI)Ul^NAZjnW8USOZWH2Rad@u5l@Q`WP;g2Wm%{3A2fS zx&mG=h)B%HC^hpWz9YxEWIo?#p6ZsS!bzi4VD{WosTLrr01T!Mhzjr{UpND>*%g>< zF<#-i0hbX_07?_&{0j2o>4AeFaPP<5F)=rHTJLo%pz{>p@I1?bDJ>^h@=PkFwXLwM zc-OT6*=?Y)sH(2MXFHTxM)wU6E2-b%Z@p{_4Q~nMlGN~NqK+@Eb^*N*{w=&LbO7wR zc?(n=8K#ppUFZ{wGsMwPcXrw;S(fhifq{-^+zc}AF8?QGiCdII$0cs)r3m#FTXt_Y zOMX{!5DfJm$^4SgXj9 zb5eev7>#;D-_`T4{|6`T{Zz*>LMOe}#10#rrnak-eN3}d6|I{4`s`1VfE&RwhLyF) zBH7IjDmVDnU=zp>qrklsYdP2IwovmPn>Fr)U>cRC*10VBGvJ(wr=_Vod03i`^v&Vn zz%ewn^ou>(t~c-;`Gyyt{Tn?N7IwuTe8F4*JB(`_ih0BRJxA4PRD~9EFTpnO{?;xO zwU?b)Ar#39H3GH`9X08=FpGcxvVK6!cvc^cKa;Waj{c|Z4*TuHfz_T3cj;VVPI~>v zHv3k~1IN8G#wq*EMCJ|dJ7$H-%($&8^T9iZMq+r3j(K;Wt?1odu>?~n_T9fhjq};U z#DsUw|6i*R-MP%Q`kL!zZh2)Ps0j+51)Gbu+`~bl7qZ;}8=B8%73!mdLrHd4;SS|u zoA8sD{K=dB>hqY8Z(QP_XNnec>w4E)Mr=;s_CmgiD`pP&DN@ZsEUX~)p>amkwpOA=>PDu{l<%}G#2HTmAA{ynnq0Ey?qv>k>f4&32XulR*++j z+u_0^_x$etB4Rna+ttWZ+qNb9`;}S9PQV#IBG^G5JfvZW#C}F_omRdJ`PU3*nN;~0 zG3nm5>;}RvF531`_IgwbRg^8Vs@zeS1Z7fS;iA>DUJQ5x%}E-pR5Uk*%73$f#Nu8mN5BSV#Nr+lwN7aS9?HS zzae4H0JZw&2B2yH%omw_%Kq%qqKGYz68u&Pby~YSG)^3pg@0;np=oYPr4pG z!~^DtUVyo+^`|vrqGfTf!hwP6fivf>1*V(xPSV|;HFnS7nYUkcJak^EF1Z2P;>1?m zjGp=KXi{EA;+R#?v+lX;>KT266&NJX>)mnOmw4@Nc0Vbn_84xig>3n^L<|$Ri*qEX zvF~)__PPZRWGZuea%wlN0bt1-1>*E+-F6Z4VPVWAC2oiPX@0gNz<+-ARX8ioh^J|m z{!eAAC6K*uA9*vtOANmK7?h>Wx`@FvOYY5P1l59_(PwO^B4=dyb*Xx-weX|BXE~O# z^{@PURz4_44Rcz2YKRq~a&7Hz7T^3M0a0+uM0IdkIvsbNu2*liroTOtUl3t(J1e?$ zlx6nb@U$3OcM)hUxC54=_JV&2TA@Y7KC3(7>x4Z?{3nL?q|pa1b>VbGdrHe2d)W$C zXCEP)AJy;6?VXt0>UC#oNo(UWl1F#%Co$bjOf?w%CHjEnd#vI6x8uX2{~%0JNxq%o zAMgGdFnnLs_%Sypzq%)}vV5L>+7=SN4X!5u_|R{ zBAdu-Qg-@sH_#VU_}2Ilcn3bWY1vr20 zw|Sx`S1m*WR~H{44t;KWkq2_@e*S!!%w&drX~=V3_yP2C;^f4~L|NePV%tJ@UWbg> zV%MXovcs~i=HUA&UG=}(Mw7mXFQi<5c@Q!gU?xsFLANV-kFA?b1a_0v>!KnT6$Ap3 z(M6Ukg~t($lh8bAhk~+s2|X-C+Jzg;@$)Z5+0$s2kLv46i*@LG8cRi$@`n&6F!xOv16h8x65QWn57q{N z7Z3ZBmYEq1*iXoX^QmGH5(u||8sB1rtJn;HRbmHbj$f3@;*FlR@u5=`}ZfT>8CtiPkvXkv@d~Vp`9b7Ti+?#%FS4Snvuc!n})Dp922P_vV`{tkZ$mli*?P zyL-XCy%K*}=5?M(Mtni(gljrw^W(EP6F}Z$4>-qj7C*TdAige{J}yG zeF~rHJrWjCeLE1svB19j*0Q7P;Yv}r&XI>I_Hqc=5@p;BTZIx9e0I`ubQYB=YRstCe&psz`=zP3 z<1NQ`E=3ik4g-|4%{hIv=3vGL-{k;Jfh4a!1Q=fR`Vew4e(S@)> z8@^2*Z;m%*zwJh|+Fd{sP6NFW>!higrvFh#dGgQYABoyy#gL1PD)>R2E3c;#siHLn z>*V9qQ4!54y|lQSs#D;R00$8e3vP`lB-6ek%H&vb=}tHQKE^@Ub7AI5`s6UtTBG@ z{ZyYZYaa9h7H?uLT2#Xq>7LT7PLAFNu~=;kdwjh|v(L8J<}{w3Av4r8x}5cmI`sOt zVAsQ?yg}YOJ1}9IN)VxzHuV-4S1e9llp>R#Hume&4bLV&IOERgjYnkDFKOi8T^<9= z6KBvBn!rNKle_<&6&QHBHliUn=FVf&a6)H7&jjWor^pN&2*#{#ybCYOy-qkBQ8`!I=w{hWX76Xtz(yk}SJ3lS@t z;L{@bg~IUCXOa2eF0jePIZuW8*%3WYxZ1AA9P^K@=8B#6dnbxB ztGtcYrp0JWDc?Vx=`(xn;%){H|Lg`5Bz=<(yLpD%G84@(3E$cJrWjI$=swz2>L4~+ zbz7y{q6caZA_fbbOdC_AJ;NX+BArd)s$&Y^0DS|GgeRnmJuNoZoY4amCV`j#6#+1X zAAR+iDAQgnCA*~M-q^-;sU=tHu z<{VQD$`crpHTxadOWL`U_BWc37W^G#U=!O*5^b5v51b*=q7#TsD4`^Ub>y_Vm{bO2 zRs(TgD59s}M_?IQ7V4Ise~H@7*++&?g{ALg2*z5tFTV)4=YC%>YS*y(kXLSwy^?xd zHciVO3T*?%ZwM1pQ+z$wits%k0d!Ge3$V<0%e`5Lxs#3pw;flqNl}}&Wl>hk?sp=o=KNA zn?DNUyg}(t3j-?I_q=byY6W>b>8)RHe|-Fxh$?7$@|!h!8-wEuS^{gBJ#~F*+|_(; zF|xAw9eMs+=4AE@e1?dpd^Ykv?x-qHak*7*@hB-?{XZ5LU+p66@BaZN zfKCSEl4Yf1+m43f<&BiBhZlCPjkUFJfpA$7ip{_DD$QCmT?&)}bEFvCoiYTk zKpynlE?8tk3JXMnj+aPd1@Z=0R|L7?Cs+uqj(%XK!i4_#=;L$h(l>2o%hwi8G<^4D zCUsqSwZldh5~+6bKCp-FU8)mWweS4Wmm7OY@u^HAg9Zh2*f6Vhf!_RU(yE}|;yCJ5 z9@Cw?Mf%l=w`3KPmo?wEh4F^#mZu0IMpP3hHVb&SNM{oaZ*ILMs6bHJA|GgvMgQ*pprjyS!Q%n7vsz)m4 zg8WF-uJ7%1EOBW~4wsN)U1{#<`D`UnJX`hhwgcCkvYackn){;)A7Sm*Jb-Q;fu##Lv_@9Q=JrGoFySpJxIF z6E^on&H(1^#X$N&2blD;JX*8D=hfEcCIkcmh)U*-uGv893$V-ro@2mLyLOygP;(p| z3QRi`{4gqVXA4Jc*$37HfAAfP{TvcIyU*gECh;(8R`QLCb}m>F?s=ipzCXyst~(-rRx0&N&)=BB%50=^7Dvss_s~i#0UQ zB^@|(%-n5&+iz5&t~G!yID@uKON+i=;iia7Ryt2Ev8D@eD*RRjTKv{W&(!Jb214F8 ztGEH={Rx2aD5(yBmC$Dud>U5<~fEwlz)&bA& zM6Z2UR`^h&>o(CH#5TF=PbkyW1r3{foMieJlLwOyzkinjW{%Qe?|Y7d3X2GntrLC2 zQt|Jij5TK)j1N%X4ZIijQX$iD$Y0Uv7Wp4O2W2ebwo)Gk7*`VFR)RBoSzp$#%(_Zt zq~~FtTfAY>keb@Sytpsi;rhcs#I3;RuL+QR8ZDL7F0G~sw>cbeQWeW-s}^2Pfq=T~ zj+}}V?5JjpDij_I_>CSb2E0M8PD*`vfuK_rxTp<~;l0C6HXVhc!KQ77i1HI3^+b`D zn@2h>QAu5SgE@k|=7MZDKaD{U+qDp#UtzP%wJfc&9%ag$dOKdX!VEwgIOwpOjM`Qe z{@3s8i4=z5HcsrO=g)ZZ_Jx8KF4p6b_WWzT*I8K`Da?@QNLibsWx|*)FNjmAtpb-`Egg1^Y~Q3MaqOgCHF*?eol-<>!fN-^x>N zW(N#l+P9zX%CNi2w1LV=&(w50o57A7n!B7rJAMCwRx^J&-YDiLZq|=iS0q>1CtWJ= zdKTlVm$H#@&$UI{q3g`(vZ)(TO=7<=8^I@%bWFG;n%P!G`nwAHCPH`RhvUg zl2}I@OJNK273S1JK^S$al%$m8{&wlZNm8LtAbDsf9A~;P$x$2Knh-5A4unI`YULPdH!E9VD)KBbS(Q zLNp+~U>IyLd3@Ue7{U520FYJMzzbV;lHU1V0qAE!!shV7Lc_j6wt~jH1V4ZLMA^*z zd>KGCK<I$vP_@OnXy+h+ z!1eDepd<$e&k`UrKpGPeLOE+=kwO{5m!(_Sy7_4zko-My6HNI1+ikiA<3bvs@>=(Y zLeMxC3(1G$#|!>=Y(u>>xU$6*U0wA$p{#6>xAL+FCB1Dq+|k#*cqkhbfaf{)x~Oz! zM;|`u64hQH)$4>4Hq&|F`+*#=J(j5D+7-fyNVnKX=11OBTq6n-GP;FPK*898SeX50 z1Bzo9e-Z7*&-|0$Ds1eA-|tG9pmSQVoxoHjyc=-)C&u@ZW%h1KwcMo3OwH+IHae%W z9*vD?yqMi`qxK}u+`j*1KJg#ayG~>$|B4V4RP}`Tz<1`M!0}BQUKmS-Oubd<`Do(* z){-9SQK^l9eWbm7nrO$V<~qbUR2G2znl?C(TZt8=OS-U06S9CY`HeBVg5T=bzc|&1 zgzHFy$fq_l9_FtySCo(Vg(1a0<4loA(aV zgKtr|mNR6oxJ_3Msc)A~k_n#1ky1!&0q%EaDGHyvCJC~X)@ekl;IhH0zZ6Xx#ioXu zK&GUw%bOg7A`}P!WAYd0jW=_6zqH>(T?n@0e!OvXNGGS|GYaNn)q+$zKhR;TT}jZ0 z^eT|;QG>d%ZaWBQ7gs`wU!Ua#wxDIp8^LFzH~K|tcldvdtpPp8R&XwzYzjp%=|_83 z@v!P)L6`odH+$!<%mTK#2M>t~&MTIs6fj3Qxqc#O@%gs&c-NFAgIDF`?;h})PiL;H zg^)3J+jNswkmn5|JCC;P!4SV$mMGeWr#)$gh?6!Fj}S{#ca zI7VIbaMmq$FR>NkCzT4hTz7jHY|le81*W#}L`HAefi~oQ+j&29(zQ`odU|?pvpyWN z#4??9d34Tb-4pK~K}bzu6Ku+LS42d~=(vH;R48Je8Y=sOs2u{D17@7SN7?yj>ozyL zaEyv)Q5Ej|j)Q{%h4(^|viY*|J^a2oWd`p)`*yR-wz0c2vR7oYprgIVxzc+9FZmjkO+#cI)M+?B=p#<1gI|20d+B^x{8+yay0Me}F zx4w+v<<>>uc};=5=Qi|?fPldKN_1w}G;n(YzT76RML<)9$wQlKLZ=-k6F`QxkCGR6{h8g`v@asv&C^A(hPknhxWKRd*XbT6foo+J)+nMRQ0O-Fsc7Va^jhH5ZHyT7_E3Vv$EWhyuYxe| zetYJH%+dvoc&dj&%rO6=jP_X**)4@oj-wlp?VErll`8~ z90OG}@S6-B@@tN~kb7XL;iq#FAG#eJ7P68cb+Qa;7XGC4@`s>1i$;@_4%RC5)Mb}P zJA!C|tB-+7ovb9dtw@T3EGHRE=o4fjtNFZ(8utv|L$0kwkI|`YXBE$sSiKc7N)?UM zz;1kzzfMkJ&hJC&wHWRTTxY3x9lN}U5K(Nn5%4cZPQ$@1!42XyooT*L{*}4`mM|U8 z6V-wNkIYz20gkiTVCfikmO0-h`{lUNc@1Z=Uq?h4mzcO?=D2sJNXQdv(8Ev`5xjQ$88fV^}4ddSPm?yAXGi&V>JA-`{7^#|_-raN7hiT;>(>)n^46JvO z_EnbV0;w<&VNWhPY|#-YaF(#eMgKs$fx!SJtNBp;N3T8wUai!pCK~a7FNbVuw$H^! zH)?0w-vrh z6Al5o*AzjaxjvGd>MNGtjGLrF|6_{N?f>-xyrSW4oeG*XuHO*Vlb>hEuD*qLjnqa) zM@meA>(u=cbaSHk_ULtCDN)zAX+pZ@sly1Yrv*fECzYvw-u01psRz>32b8=YkU*9F zAhayk;Kqvi%Dnr0x~)%oqYvVD3jNxV4gO@Tg%j+}nftjMt|F6DeDa06J+|Dl5}R<{ zuCo8j=Ztulp7z60>90%$aI#O*Ol_YN-y?8`ie{(sH6ko#ev2LjMc0%wYd@>Hr*4Mw z&agKA4D_gk8NT$5)vPU8oTumpF(%}9iWdMol&({az-|=mM?;T17BV$*roSl1bDpfU zr*d<%w6R@(G=Wi^{o;N@6#72#*U&+FxbTRYzjvmL(?Ww)pB7ss4Rz_gp?3xN5HR+L z7ruv~&X{O(?}S+`D010ISMt%yO);N46iSsMa!qvwI_2VW-Z zq8kE+)c=JJ2dT+HLqNMn`gP?&Nj@^^p1SK?3O_y;iwM34)3HN;^)$YHe!2Y^9Izyl zNS>mxe8R;y`-vO$=1eUxb@FF>%A`8Hn_yV#j@}Ly(zR*W3=?y2S@Vp#6K?CAu${uR z7x1(@X7ty23lx38B{G5cQqI(L)*2(Nl+vs>eGYMQUGBB+7%86ht?(;S$b9#+KfwR- z{O?16JT8lRsiVwC`%6jkbkQxuClOV$?bw#Q42>5N%{X4xZI6xN4_`v45TsY=7DpcF z{wocoMDIu*s2+%Z`F#kuCZVV`8|YaoWn8ig(PNA(S|N4Obq+&GJHBxdiaZ#jp7lHa z&Az?$a(pYiBB-+VZ3%E!4Pgfdrc>8hzN>fwQ%m4jzjd}yq+fuWC^M}?BEdm>z>s1$ z0d6L;WoPTYWda4TNJW4avhlRxzJ|Q%zL1EBx7VY#l$a08k@A`{YqRf5pgerj;9gw_ zfN2|Vxafh88C{SnBu|g_kUO^zQV=KUEtGstWj{OVphr$mSAOu!Y> zONJ5Kwr0Z72WoHysJh?j3Le#phD!aOEs-IWi;cGXMf5RJ{ra25{C3LK^XW7|DOe;NLdK2-s`W!rMyUIM!FK{H&JlaySw znSu#SX~E^6g{gaH(y{G}ufVWpXXnq<(T&=r>uZvp!{^Mmp^+CJ?RR*+|9I~XFeJTZ z+Yb?Dj>bTuCL7%2@Boe%)N|pG20lj4Rdp=%bFjj`~B;I``jr#Y`~j(dffDnZ_N(zc!3_> zO|#V$#pkDLK*F?l{8Vv<+h_tl^D#R!j$+UjyfGbr+nV=6j5hwW^0KF9{$|h(Wp$gp zxBx9E$ERJzVh5OHUWkB4&*U>#^+}%~Xx0*)ab7$A)19{??;jKU4pg_ec2NFr%;TAq zns^6U|L_DhfyWwna5p>K20Mca;GV>yTilAHpNpQyK1KtVJlHLK#eRx;1g2D(bm)mB zdyG{oQ5bw#Q0J*z{QGoa+1x(;++)^dIK?sC$$uICX#V`oLn|Mu9hVcbBTD%XztBDG zB|`y7?Y_Y2dcd#E>5^fw8{Dc^4X6nfV-5R%Px~F3vi{Tk-8}R$;J{!_*p`QXtlUsR zjNUC42Q@mg-+)>2#{Ar@`Q#nQ-J(XOd}x3)m3UUnY40md*J`TCP7G z;-md;e1+iCX9Xh+yP>SP?Du)-6@V7H#rtz%MYTE)A{>@cUVOsq2;7@T3ruwb>Q8i= zE7=fv76%(J;m+St6ApLjb`}_i|aJJm``b!yY%gdYb_!D=D#t zdk@}V|3m;0rXsqWRCejN)LkH2BEy+F1$EWcZ-C{A6@@ebJHe`?U%LSNz)0@GXPj^u z*mklr6>|Fj5OwC!P`B~>uPAvGJrq5%7A6%^vJ8ewF}5i}*+!|5eHr`AByEy?D~yR~ zLe}iYSi)pyY}sXLn6b?;h8bgipU(MyzrX*S!{PXF-=F)w-mmMr)(U|e`e?C3;a>&# zhe&vifl5qCUBjJKz=YDHzR$P_f52Vp{+RAiZ~b}T>-5gYzI(^tFmh&gVt{~QG-01g zEu7x2VikIaT8@SVa-OpATRSQJNg!EK$xLeCh^xP1K5jeF zLCzj1_~6&rh7vg$RhbmVLKXWCZ878a=Q>dZ#5BWY-;~oom?c_$^Rc8kjz}qZ$M2;a zxS{#umqDG@AIk=UL+<7eYM{q;2&=ZW`tOQIXv)?Btv`UYS;=dwyPSTxcJDlBLK61( zw*b_N&yZZgu5X-}VtXaUG`O2vzh50-1!Z=dWgB8X~yKH7!gXRRNzTL?iM~I?XDvQCjPqZoDH(%}QF%dZlzE;j+ za3k1WJJpI$%t>y>&;Ea3(JjrN9fg+!&0-&1d=;MZe9f2G;=XiX;RFiEbgLb9R|%m- zlPN>3?+-LMk_>UCIP$@!WF{+pWoYPOQTy!;b#jln44EtZxcEDN5>7M_{*2VF%ipMR!vZ z5kn3*hl(%Ptq&314tz>HB92l%ZY?a-VM0%y*vM@)n6sQ~+!{`Lqzv2{1l-Q)A>%V$ zp?;pU6n%~37KMM9W#lAl=u^l?|s1FRR`q>-NfPn}bcI$%KeK zX4Ij9_L}*mw7S%2Yt7O}5~Cxa_Yb8k2VXv4V;)w@Nf6Op$PREo_%O65tk5T~B5##Y zvnG`J{z%yn=Y5O5eH#KE^I3fnfvvj~A>WLhA4)2_yr5;M`U34Ok448_ogjEVVc@oA zb}OWQ^|C?@>g^Hb^CaEG63S!Kg;v{VGstVpqtz()95iqipV;ov^XT%7MhIJm95Yq@ zP-k-H&$c@yaxi|bZssabX7itr?mcPFFCvAGWDd^`<)@qB80|eh>A1PrOi7V`vTDR{ z-}gFCTiVM6IOkTg7#kh&zyV%=nYO3|z?7_kuVMeRB9>-noxG?b4d_MY%*N}`wZ8q8 z1ePN`HfYGCfKpi!V%D&HP8t|Ya5?_uMvA95kn7^j-NI4PVf3Upk5P?`o;v34SESdq zFF{UAAKHE9B4gSAxS4OAP$BhEn0=Dp8KYhMJ&pN|%v{iLuud_6)r?P1#}d+14Fi01 zzN*8&ms>PyW(?q~KKp%04|l(l|6k(m_r9_2nas%> z7apD`pP|ZRnL9_moVbU@GPiXCE4SL*{L#zd52b^VIp=6Oh#2g=rB!Q#m0{3`Q}%J` z(bp&ukuq*99E0w?$oYb_Y!qp5)HwnceTtXmv{nwq6=>UKCp?`3p^R;82~n>gHxO69 zP^1Qi(vSIP2&Y=x!PfLs%{B3uKLIzdWFu8Inpd|1usfKoNksB`tjYeo-2YGoVgi`M zl5w!)pUYvh1?jL~{R!GlRvSBIg*Jtkj5t&PQ4D3Kq1=!&%Y##0r;zZuf?c`zey^7c+Ix~cl4#AvS`7Ro=^1m`#ac{$`BdQ0ff)jb>2*lZQ7aL zc8KP>?I)|Y-Nne)Cv`AlbJ}QJ6^ligeK$jpf4}sU^tL%;ZxKkRMdtjBe%#HQ_WaT9?(s7;aU@be$bp3CJzm-Ar@DWLJ-hOV}dtgVh+vkd3*TV&z;pz~XG{4a-z zyhmXF9Mg?3o3e(2iSx=`)@;Eggq{sj_+%J%N?k{GmM%P_+f1n#0H}#CtiTDs4BF=V zYo;qn3N!Q$=R=;wc|vOzd^4uoe^R%?IzXD({M%$**m&;*HW`zQ~o8*?MMfh+DHosno z=@FUF5f}u1ZaZTR18*>@t}IkCEt@j@&B6+ICKLiecKr-kfi0Qcpzzs$#uAkc>p zq`T^N?bolb(qJ^o)5ylpIZi2h?@cCoLJjyZ+vNNbwK&zKZYZ`G5QsVs8qYb@csf z7w<*(Hc_zJ)Dj&I5zdm6^zY8~X1XbfuRo>XD6xZgM>BG9C?#yx1`ettn!oYkkp$8k3ER(`mJs=pmZaReX0+!>=>ul>Y()PTbM<+<(ZbF1(wcs)ik-QBW4+L#ZFwK zHP5RfdfIaw(16jtnBG}?3 zA|75LH%z|5M#nQd@kk4 z*-ITRVUJ#flR}m=vSNM5gC!SpS>gR;s6brNN^~y}26!&aYx8iK{jrwQ%HsB7x&8|Y z?1PP2MCes&DgYeOc@MI0>vjM7Wy|;q!n--Yw_#xtZ_sr~ve<4}b0b*)<+}x^66a~b zYaJgJ^p-%0SP=KWoA+>4*%s1@mH=g9`2>s!6nPjsFL#xhFBRq{U4FMs)D!y!H!!C0 z=$b9hrE8*#)M78R68bX5bFOMYihza;0w*R(%eI){=wvYUs~-S)Z$?ROS)vBm@?MyFqZpMHhhQ-n4;MUtYI$z38FQhPTEqh{Rqh<`%P`SqdDKs25SO zNQIaWoXslGUfZ%lE0r7f^pXfRJ z2USiyOA?9OI#c1zxg+bVhs%Jbd?Xbx3j(Xy54T2>G=L$zm*20DK9>Ad zGflwW)4Tpm;KArY;E-rtuHU#^jqtkiaVS_PE9oNV_~La(>P}~8=VZ=5%AK;Jv(fV% z+5_^axZ9t>nwm>h6rX*+a>}d|>g?Un8+Kx5bMt>^TU!2K{;KJK@C}|T^4yy06E#VA%0NFoOGvWZHG94$n5n2>A_x;lHXjl00s! zLECQh@VpkndkC0s+cAEgiwjuqd#Ll*_ynBi{|?}QiJEvEkrA}bq&U?M}9-Po588}r&H|o z%1ZHLM=E1$3f;%x#F!|dBIn}K*k=2Zul0ChobM~mWd*`$ZR!*iKcV6Lo*4dz*WygC z5H7>H>1964H2^Jx{^qQxx{e>MghVaxyyMVW!S88Ji;EoDNk9+ILu9$SRHLA?nyl4!z# zYg|96pykGahdCJ-y}-AQnD7T$ILc6z?0=lU4dS?yk~fis>FDy#Wy=YEXX@3Drhl?d z{xRV3jUHEcO+zK1I&QpDt3z8)*-PN6K6vL&v39O=wxG9J2gdO%1N4GGXh0FGgSs5& z`ep^Rt0H}S>~av5Ss%9nTDtefc>Mb8|DC?0GZDtGeV;E+WXWBg7|*%R)1GvC?~H~< zp`gw0a@`V`r^tps{3*tzB^;<^91)Zj(bKH?F8##V@rtWo<*RY}rkAcwR`O6SEzRm7{{FryK!wG{yBK@Gp^WvR3cOO zL`4(gA9J_a*)1AG`d z@MxmgWse0aY;b)x%LyPPYn|s{=a8ptn*gp0kveJ-Tg+7Yxch0eB&fE|>?fc6f!^zU zRL1^*%9pB-&o^q8BgI))Nxyx&u@;`Yv#oIC2PYb;wrGHG@`o_YC{9Q`{LqWl1flW= zq%Y1M(TvbXGt2iJ2!|Reu}bI1%%}bg9{6UXR;nwFuRU&YJ0~Veku2#s!0~yfx>fis zT3Y%Wl!(lM;^!?1tPKR&%TOcrohg?PwcFvq8ht z^8Q6lV1V6vhi(Th1}C2u)}cfSgw%rCx6%Vj5gnFwI$U8U2CY;Op5eX|ES^ zJ7-#|nw>hA>wM@GjJ4ZPq}e@B?#(JHm{8vr_`7Cj(A?FR;vQ40i4_|YWokqRM?OSM zMQwxTAE;`dbM4@TFy^Mm#WwFLs=%>eWV!ZK+T%avXB80I7Aq-2{wseF-%+Hc`;iDO z??LaWn;)O;{RID7H;5)5(JX_G+naX?l`E4S%H=WsGm27$UKBjFh8agDX_B08y+b$( zd+pv3ScPuq1^3}TcWjP%s51=;;+~9whU&3YG^mcdLYUl>$+|FAedPDXTaKRpZ9eDFeQMR^?hkB1W`O%w#q9bxs;FM z+bnPapll#X{u#hWjD2?@Cx&JnFmD>Z{&jpCq;pixVTAYD-fG8HTE<1~%qrevj8*-q zUE($(MmQ1N?)eMvNxn;Y0~)-~I^b4*ij0Zeyw@1(+kal0bS<~>@RtS$?;ne@5R$bm z;wy@h&s02qBtR)?#0tTi86|ZnA$QQ+@WPt21=4Xz`sw!x9=Vy=SNer**r6;)rkc6a zB}N}2t?oB$JtV`e{B1>bcq-eIWrZUylIE@WZ$x7=i*%wJE(Eut!b)N};&>~PWb#LXc_q*{IWEfJAWM>vVA*4(MS!<(}i^@@(* z8bYp=k?Gq?PhWPm`Y)eLIwkdakn+G>!K%l*F$d~If@Dl(;f*3~=##6j1DOjTy%52; zXNB^T=U^PDT4xeDuW<`h@uV0$f-s)6=_#pL)OSGSwVqqdHaHp5BKLO5XeTM0^ajSd zESr+3BeibPVnM9=^p+FYSQu)bCam7C#kz_0F;y*ZJ2!=WWJnPKUBt38$wM>TNiyYB z9K_a9xuj@#FRbQUFz5o#O9wK)-NK&8XcljjJ0zpGKpdS!L!Huilqt6=}^tA zqPp;%;**uPCY2q(Yc}d+)pNacLq7OCEPdb3BqR$6V||tF2FBgI=2LyVMvInT9nv$&Z`ay6}JQAawyl1M-Ml! z9N@EtH`m98pVNC#y;&(AXMIMn>Z7TVjN(BUpJJ~7MJqz9gwa~DGVZo@FnMr}V@AIN zw@7@&WaUPpZC7*W>duOPSdl~P4lLqFRL9TR+^9ZM6(zVGxqpE+C4jw6J1EBj5#8AgMAGJ+IGOF5{_#QmEEj62r7+ zd(30*)M`S7d}9i0F)}UH)9=$~l%{0S!J~YF`BGJ%BeZA-pZwTQK(%YJE|ZIh8YB7J zYPEob9H(>3cs~g>lHCGKr4IOaS&w80rS5E|@QVO{>z}g||InL8+2)-e;RV}%_ z_1N9+SnOX`oVvOmOq|^9x_FTh^ZD+nCGlgiUNejL^M=vVu~!Y{v;4 z2VNx=r|4Z&_ko!U&rGzwbUY?C=-nfPU-=ji@*Ft93woE$C`o=H`12i#Q)2b7r=)g^ zsCnEqz58+0$gX(5E#ErUY%R86_f>Z849Iy8XtFso0fmfvCeyUr?l%U#lML43-nPrT z6i!l#q1x3M*=p{_ZZ5-8I z2asQazh@C;1GTEHJU;1`CnF<%a!)I%5da4O-O>Nx_1-I5mIIh0qu|~&e2DCZ`|*XN zZ#C4_{~T!w1?0OKo)T8NFj1+_NQlvdK^vcbH(l_#u&U!K-)TWVi!i15n~wPaMSxIo z+kW1$Ei6RR&5sd(f-#wBk>8I` zT}ZQ-yqmpWT5Nr&bv}A?Nsb4-ov{5|y)b20;zS7P)fHyqo;J;}PQlD+NnHAE%`to& zB&w;Q;0du+rB~YFq5~;cK;$f{VbkK(=sVQ$4{CQTraERU9EZe;-`&GP>se;-IYRU9 zEz?_sn&Z`p(@`M2dfR`n7uy4Q;A=lKd!9~Jod<4MCd4sA((?8qplCPjcRAXL$oEE% ztOGm0a`P?Br@j2oYo9ZxQ_X6X-|DR;S!9}R6-sp~FN4?32(n{h6M>T*ki6Cs>N#p& zO#L^DJ=fh}GSvOiXxUG|Lf#no#}vtGkC|BC;C0OS*p2VAt%Zok09;k!{sL@27ig8L zBRERMP)NVSt``<4!)xxK**?`Tz#iN_!pf7s*VZAxC_sfz)>+Mz;wNL8e>t|?TgcdK zpMTOK-Fp>PA1AXO9E0-zHZT{`QjecTTs>8}2sYaLjd%X$HWoXWGyl$H%Pv==js8+4 z7=P;A;D?eDug)z^+a--X+i}N4)zzxSB>aiSyTui3wX*rTpP{xD3R!X)2uU;ARR%Nw zclzh1z3VI<_9}E-ETdpt+ai~0x5^m!bh?*T%6_yO-gMtwx|b#F*(u-~KK`z&gIkNY z;;V+A`(j!}oX-r9b+CW_V+Rv(ZTBWF!LxQcF)sY9xhHGx#Q0|wHS_%!>gyt3%yDdF z=d_qXDUxMPjv}In*A`;tU%WIMl4`^-Szj7O^#)thDZ7B^hA76&gf@~%`r&F!N->~<)I6t6Wk1Sm7iY_Xj0v{H9YxVla?@7YYKk90aj{IZh z7o2$UV7v;qT%`~Vxa6*3Mm*4s(-j01+aC7F-rW9q`qkwN_OG%b%TivA*`Rn*7jjAq zbcfs=%hcB2a1VZe&}N-9@Hu5A=%33{v%)o7T=O@4*U2u@Q%Z!&U|)$7UJ>pbQE$@1 z8!>VevoFFTJv?U*VuX~q0EJnD8yMny3ETEFaDKlFHx218rE zfQ_MN3SNGyhD)%8pMTEaiO!$V5iFJa__Csm+Z%O5% zD)*kwEd#v?y4$~;5sRHEwaoj-AFlU)3=gOGJY`%2GGl--Z>aHSfR*%?h-=n>Lk z+Jje!FtmjZ4BVlvt6UfZL9dDAfjlP`ZzJ`3nTn|jdaYr5HC>K)e~(rw=C&TJw%-dG z5h>XfuJU?$BFfin^Q;b%GGE^i^`hwAj4 zvTk|`9*I1sb!T@&?J3k*va{hD|A@{1FwJE?GAT`^&(pP4P=g&TLh73S;cW!~fU|ic zq6I|pSow59!ny;8URPO}KzX$;Lzb^#rco|267!F*EFZxu$$&s9FH-p8t!3Pg-}w~_ zdoSNVZ6j8F>rMkvKFP?N^(O=_yMQ!`o!nh=TG#9+&%QihbVUbx0Q&qVPYry+29~o~ z<1hG0^Uk1L7f=>deM9k}e+gD+mB-@(Jvo$xu)P8CKslbJ;sfO$kW`%P76ItqNB1(j$yp%KbWXt|Ip&Ow9>; zMWLYsWvQL{*o@;kW-R_oE-M%c(cTrV9-iMpT3}4Miq0t4$ahhYv0ph@R2r?cQYoDp z1^St^{zpcxvc!9Mef`(c_jBYJHox>Gzl{->H1ql;VI_j3^~G3A4g0vAFfgXKf!hk| z88hr`6T|05JT!i!fT}y5cx1TwmY(AElCUX94!;~(Xu=83K`|ca#1jUEsvlkSvzwKmGsDlC?-dO9b-xa949f}oB^{njk^YQ67n}pgRGwin4uU))| z@KTS1+M-6eAie8ZnmtJ0k=^;x_%wb{ZBJ!z@?1hO;$s!7Z{bqOLsL`K%NfGa*_sdf z;&$_ya(vShbYFZsu^X?k>|2Pw(8_kB%MYM3B_wW^6AaE#H+ge6Nxl}*sYx4cAtaJn z9Mk^NKoAy4t;55;ZWblZ397zadTa;y%C*uA;qN~kFOyc9uGM8Rz9k`o8}WLI?Nuui zC6a<~`~|LBavjiLXCkjp3&(oytZ6Fkk^Ouoe39-Q6?w$;pENd$;`d*Y*CR&~@m2kb zH$AK%PUL)%?{_9NfPSuv>NtAx4Sc$Oh7IA=SEUT?q83kmOPkpvWeXkwP`%MkQNmT2#r6Odm@w7G`N>SA`zY*~)vbR5 zDwTF`F#px*i?Eyvx-eaxi&kn(4F*kbyh*)wR@E zcHYI>!NF4<3XBXt=5VN22D0p2(bi_@7Iwx%!_(x8H%zY9+xUJ2O6_J1(ic+vgsqH)a2RtOe{^$@_!srsPqNFdbeF9&bqX}#$NOOOofSoWK6Mi4;nJI?h_rGf*pn-WANOr--Y%_FI7Tj$i z%DZ(7VUsS^k3P-+TP=;th8?LRie0_(1t@omR#BY(8tiw)>@2Rv7O~|fy-(L>G+VQ)R*!mC7h1+n54HqgK%`h|P=U&_8(lU^PY1g|<~i@x)*Lp8(-tzi2`0DM z_%gsW@~crb%NoRbb`jSHI;MkSQ%Xk!-rJ$No)jrDCasf77CE_N zyGf|c42FU(JrJqiGXD)!DX%9pEzf><>0y{6w22VX4WoS^)-?UFdEw`@R2IV|0jjUY z^u8~xJ!u`0w)ppA}ZZvq$81c3$!0e&| z5ShlqUek+(yWIfA@aPaIH86F#Fi*w=d+Ar3+nq3omuFiOWQFtwA$(jhuxiO9X zb^nh4g)CeBZ)DlifPc6{M#DNCuV z^@M~s9es7(cC??Wk8{#K+(hJM!s(K^3DJI2#lO5vV9Sk3NUa7WDuw(ZdLXc2|1ldn zmng<^Ykx!=@V)!}KoDgDd&pR=Qo#VKvbdz$#&K}R572A>|NgI8>T8&uS;=RAd`ahy zoJ$EW2)>{JT=4*_U;8|5(q!GvJTl@z#opF-V8fh0R-06fhFih+DsYm%9|$C9?}$je zloL$&eCEi)R^ogk5OtE^oF;|FqqYfb%7h>Y_sc8sZVvIF_n|A_CYql~>z_LPb=znX)Q6$|BiSL|Z^-#!jxekPeR>E^Hi-r~ zvbKn9BgtnS@7rv!mBGv4<grhvMSQz9| zLv*{FytLiLOKu{{8Oc88_hmXV_uO_RnS)YSf1&rEqHQmpO)AcvsZ%yh8q@bi{O_xkFB`+S1QQ*VC!UIo2S92H%M z*|JtTc2_iww+rVLwE_}7e$C|{IvG9uH2tK>l{s%BQfa@QyI$Yhr+wQ5vDJ2Ey)mHqiLrRx=TYQo zbaiklMTX;O#K+Z6^_jMkluSF%Z7+IRd#BCwQyyQdh&gQ7bFZVwKSX&fjxe}myI-VI zT(v`vHWb!H3h*>2BiSv3LxJ?9g=OgUnOyeRQ};(|495Qrdrka~t{F|;^*=#$59p1s zN$=0ETa~!|dB9$B|B9s~leg>;I=x>OlN(v6HB1=nBFOb)g@+YSRP9iB=HMBo>04oN z5~YsUG>)eiIXlfqMm6%$A-V&qFJ!sML=>oL{nORsi7b6nlj(1tg(lgRNT*oOa`P8; z1-oeuU`$b!B^s*N=Wam+1qP6H8*$PMfS;BYL zw6Vc5G7A?kiI^!lh9ZkRS8TV3fcna5HK*B6k*ihDgNz01!)p%6m>tn{xL^v&qasTO z#Pz?(J)3hj(X+^q;$yEgwx#7}ctz)Gj8#%yOtOf_r}0=TEAO$fd=r2%T0R3b;8OHZ zBj01ctr#N|>Nz*YU9`-JTE5v--8B$C$Gzs%8Ji!K<0e&Ifk{&FgrSn$By$z^_`AmG z>fb*1^|p5VMxEU9_qTPK5;TSqM-&dgdt&n^`)GQg>|uo@+nm1TPssdL>l+bdq*Yn* zJnwPOyeAque|X#)+db8bz9K?{J<}JAeCuEFOnP&cQZ6z!-sss|Sv4Yqr@YZypBaf_ zjWwI|wg!3p;>cg1&Y{&QcH3!O4)f`|K*k{U_S5C>{>%teFBM9-J+Y9>L{(kB*9Bwj zmZVOK!~i0i@wzn@AH3($_VT2PRzmA5-DL0bvZ1v3HRu)hj?raUxDh0l&<6TutNK%{ zG(^XrOIh_TmtFqOBxS)D7ez?C_ctQdbve5$@^mxXf09cG zwGGdK`^|Jy?@vPP)W5pd>c^h`B0p$7g|cUE=0}TiIgY4bxR-bL?$6zvv%BcEO;c?% zAZNc@`3b7U2yy`afb-9hs*bWR6EDXZx8i%@RVk&m?-YAA;6u0eYu?|p6*0;AA*Pw2 z;K00A5^BYn@kX=n{=PR{=(yX-0s{3MfzY7&Grn$J*nT1u@(ji@p4bXnj@K(X{I!>z zWPYdYe~n4d=Pfo_`I^s@Y1A^;7ymk53-%p7i)dSEC>DrZpZ_*&#UDgZ`P&8Un+^+wpH{CPD z=g|onQ)s6svpB-d2_K%GEat# zeWFGPr?ky)rpFH!JSfV1GQ-|!B~Wk1FZ%g!82bzyl7*Z%`b5c9dk62$fMEJ{qXbLd ztTK?=U;V<2I7ZL!azDPO3~F#O9(7iRBpY)|#et&DRuRdeGw|VMLJtD8`|mV0>XAzC zdMn!dd)qmViz%hPWY{stw;d|nce>A(W66fu*9yDs{SZQal>)duM`WO0 zKRF5N4sQ%T&H+(3z(82bH*hc)a1t~bOa;K#Ic6RIq-Dp}>edh_;;fQhP)WF=wIV zKa-zVaWMg#9f@i?U-ru!$&3XbTFjdBqibz4apyexkiqFbUTxCr(W6$!;hRCyXgqLy1-|)rpm|&Q-T%n{R>yiM+4^Cg z?JA8jMQ{73V{kzHX(b-7lZO8i3s&k-w4^ zFMgQutgsEF(u*6ire@vKTU_9H>(*ji-Iv{?XNp2C^&GxTV*`|^<^mz4v!5UtX1>@Y z4*jBpSYDkiP~Z?ahBKcV_r9+B#;Mcedo&_3=J}OBSd)~Ni4mAOMzOU^B(F{V* zx~IYZBLEdfD(!yJ`~x;`@U1s5OG&C;yGeR{#!WU*wl7J~gnsu7!291$w1RsCfhWxw z8D$?Bdw=}1EYaIM(jVq&-Vm}D!pG;1UikiA!r|NYrx&6dez|a%ds1%nwp(Cpgo|%l zS1c@ebLanC@%y2{O$j2~Xfi<;gQ@(>Wkt}l3Yz!&68LcqI3KTRVjecA5%Z(@ao6*P@^ zO~O>W!4aJkgZD3`FoK1@w}JTLqK-(K6ozJkdc&9qw7Ab)1*6D%%iRGkkr`Dr(xr?M ztQr<~syI+UFk776X8OB?^=AOd) z4P#Eu2QZhQOsP^c*m*j5_a$~_YBi554R5e5v3sB;>@8;^U$P{?>V(c0!;=;|=cUMY zfg>&IQKIdBn9W=O|6905^)T}SP5#)v4-*fk>#ZNW-fA=zS8W)E4t9Vt^H$1cHKbRjd5HlLt#l2x@DE$KQw%Vk@eGizy=YP;Wtc0 z-9qFB|JgSnyQNKj`MEpC@%pV2_l9ob=$)u-l9PfIjuUBQB@TbPS))d~%cxj03jiVA z2K2)=UusfKLXGq?m&64(lL{QYqtzWhcL=qIsjS7>g}aVff?*9S8RyNz!NvX7KuAgb zj9&&~&k8{tRqdtOjy@sXK?INzKRnnUs|IXlYle1Joe=kk9_XIsoMed=cZyu=$ZR`5 z4T5K**e|rm7dbkNJDi1jA3V0$E=sJ`8fT7q$E2gkSoVe3==)+^ARmBL2EfhY-Q;WB zUcl}YVHUrs2zmsnTx6O4_fCaiWVwDKN5}~IM7t&aeFQrFe=hZ1ZG3iq$1bhOE%``J z`Zbj(X$pVJ034Im)uYF+ATlEZ`JO5H_}OQF#yK-)tVwOPCN5KX}GF7zHuXI7M&fDSz;>wAzria|Y0)uHoNNI3CQ|2cmm%A)w zX72i;JHkUeye3@oG(-M{r33$cOBIn%Q0}$Ui~oqhcI2G`B#!!*-YixAG#8;g{2RGF zETuFqu_EkYWSHbwu~lg`X^m0YItMu+`*kZwA=iEE>D=+jz1{z10qP^IBcyQO^JY+H zbI0}E{8}Oapq_-rWjGB2y)vbkExO6bvi>;eM_yd`yMZTNsDj*suJjnM45(qQ zsL_Xhx5qRnV(gsi6~qwZYTKuP-s)k${qNrSg8Sr`ZzeP*g;T3wnl zx7+DieG@2~HHfVUu&G+)1OnvZAg7qCFb(DGBnXK8p@2X1HpaI2Bl2@K2gGfN?c8fU&}3|JH3lM(Q~#7S}pY>3m7yLrUB$ayEu%IF;fRy zM7X;%KDv*FvX>$f)`w-6HeY@qoO-MkbxkU+-VkS3@$Y?A-!Cb5fxgd5pnD!pfA2D6 z2w@Evu@^VV&YWJu&NnkfDJpK)ZV8;f`nFUVrEPWza$nxZbaq)YUVfTgAcw0j*^0=9 z*a|OsANFa449MKEv2tjMo>gMx9cDFnDp&@@RP8!VKthNFxf7ogg=2I;7-mtGZDbB_ zuSiqSls9IOtL8M^Kxou!P8}Sv<;*z^HoND1FOhaTady^VW<`B*>nHxI{DM4fqm(>Ed3?;itCPUDo&5H3^3kSe@P0M&sX#1 z9{>|xEpyA)IDCHO7^wMlOC;fNuhZoZc4Mm|Ui>OMkFPyx%l#OTC;x+R9~ZiXI&Hq> zqk4d9?B}UFPz31`l#Hf;S-(WvLq@M=-Bs~+>iF?G?$?Jw2<~R7Q0I#+e#>t~MZ>lJ zqfv4pob;|S~V!j77`!ut`X?asH~_MQYwAaI0jQt7w$dV zkR0KWtJ0gOpdgx`QB2*;ad(DRC2WXL#o|)a((0{xAltrS8^7l1pNr(AGcMmMuN}fZ zw#@IdmB{1Qj~&$^1UKaVU}!&7YBVHxiE5$8neOCc0ac6);Ni?5Yly<<b?1gMt8M{9d=-3;eHCMG=-8T03}%Iycz9b~CZ>_qF}pE7eO@+}(Q# z3YBhMim1zL(Ks)@)+%#(PXr!#OA*P89h%iSLrFjD_6PEdRZPH!!*o$c;bLq&A&;G zz_HjC09^s<$ZG~*HdpIVoKTIAjBXVUiS_wM+C<!9te(b2?f3veKiy5&Y z4T2}|UbM@S%&L=bSxvaj1o=ubYiurMlnVa%BCHTXTB%!xe#t!pIXe5vtmA&#^_Apnk&TMOQYGh8XvvQ>9Y1kgD z4b=HTMt*ggute4(n+=DPTB%UF%S@8A*VIj<*RnJf7XFEAed%l6)uSZKK&3mF=RqV- z(h~UAzWjkHm(31GL?-|HR8)dsS|lY;soz{{$A!B~a-!c>Q!Hx((F*>+gHGguP<>&K&;ZDECP|MS(*`kf zdYrp-?=^wJ$^~t{N60dBPR>+6_HwoXsvfJYsrmII?QDvR9($}37!&+mBEahXo4f!# zIH_*c?s~8(fUaE2o85T2E;;e zM8H;z_L!Ipt?~+>SGtoL@34xhy&b>51Np2UZ#G`e=y?WMTzY?NtK`ooUJW79r`GJW zte3v?blwut2EH%QUH42)9KqS*2eXt&g)I9Kyz;}U+R(es*q7Fhlu`$Qo z-w$5aMB`;I(G+*BaEfiZ%#2w6!PEWA8&$h-=bNl!X;$>Ky4T?WNSwsZ*0IIH87XqO z$De?NBkPTG-{%Kf#YQkIt?Xrylc=l;+G%P|oC4O>($Sm#%Jgv^XGt8AKd<8xB5#{7 zM*ry1w@Q4{tlqG1?OU&{=>7kQy6Ui|!*)#ws3?d?NDIp7P;#`=-5n|*-5n!Dr9nzW zQo1J%V}vM-P`Yb0jFBV9i1YJ1*LTjJaB+Ddd*AnYp8L6@mnOtJ>yBAZy$u_Wt96Lf z)vIq?)*UH}HO#*c;8Sx(t#^!CrJLh=ts8fDvBJr6U4)uu7^>tl>8wh?%wJ~vMQC08 z8qJnW_LL^`zFz18KT}C)JA`+gi&1hgQoAvxrEeJkH*wv0t=)x&@LH2=??19LImrA)_wl}Hv7w_ z6S{-=5vycH{LwEz%jac=vF?w=h*k&cF6kdPRXi%i9Pz(h}hn&4j*x zFBGBi&71e9mFH+vrX+0E2(jO?nKKJ0X#s@{pp9J^V+UxxfNSL>k-Wfj349P{`YIA#2J%Y&GtEDWCS)XOUb9epcW3<2QY%kY z+LfP)W`4sTI*87)|326Rj0Sa0-EtbU?5rcG#=`xzDN3pQOv*3nul?tEZ@weRwv-A+ z=2ITzcmw1z)PRTy2~OW&As@e?s09Dgc0*nMpP?Ucp|`WokXBG26NrOtBEx3Imm^1< z*_^$aW)SM#29j2x_d%{_tuR=dfcGM@Y|K(C$b0>(w1|^(VN)RCN3R~2h-riV{>SUFZreHKSNbuXfOg&$r@T)&4AT6U>)cLq+I`VZwCTrp#PjP|J{0+$ExDr zcXb#0x&HY~*S};c0m-ur+Qfi_S4d3DdqUXd47#FDe1pDPELSDl*10pbX3Zkf7ZWhj5{!o4PQuUa&C$Bl6}+e}w-p>u*!5K7k8N zQ*ho%)TL^T&W$+rqfg&+o=VwDF)6JVM2%2RI-lgyhO5~0|GcUn46=at)EFY=Et5G> zUOQWjLojpALN!UPi(rOgR;}QBN&b7D))3wxT`31Rs&O0RZuQaxjJ&Yv^nLWghY#EN zMe-r>lgWcq)4=_J2P4ba=j`V*cKj;UI~^foxj~X15U=YNvco&}i0i?UFKx+@SuFVr zu<91(cRHaTz6YBxO$7v1dfD1OTg(-p#j#nu?tl+T4n_kC)vdQX6D`2hCmu*!B8FYS zaF6q!DtxUFUSw}{!mjZDA4!(tYqHmfJRu2~?h%TUlKeB-rCpr~$@Zu$+p}@;()@@j z7~wpl{1(&wNr12-t~96XUaB7TKtLer%htqIA%dhCJ`^AcDD->c>Hi7!0Ugr6n+$01 z&8S)d!hWc&Smp9-_n^0SZctKyw3JPK_&%?XvMri#Vs(mxgO8to=suI=Ys%iI+G}`n z@Qtv11#&_P-0v`Nz@~^%VJ#9(brO%54q2f(`5llhn}QrDxqs2wcADom{POiu^zDY_ z?ue!%D}oPC<&BQ!tUq;(VkAu4$3ApFj*f}{ps z?s0QS12G}&-Sdn;_{!`sNs4_*JE^SUH*dRrxFfw}m$5CNBQEYX)+Ey?!0xE1s>{Dxa$Ly!krN%6={|`7bDQi_#*p zckYp>{`FF8dxauNQ*M9$VxP!9kdN^1m35k`o&d>U`~KB%psH?`zxUq&*cdRR%C%lc%1{YovqhAZI!~1E%*EoOC6Fxj7e!@V z(u6+jy{U6y=kKPOD3fbM$9l_)JjGpW<>2NoaDb)ZfXrcZ;M7=-AwNK}+RmoopUe~y zMdJw?*S-sWxMv1FF=P0w3d4|YFBxSfe#mPF9XDhK^jbyDU4$Aj=6n^cG}dn>CvDIyU``^-#{t} zWt!Db0u4xHd1mAKbmtM?9Xn+ueUjZjxN5WtjRTDgtpr>~x-a=+hVDf}u%a5jSdJ#9 zKx#BSs1n+rLjPO5GG*6)ZtV${Kcity!@^gJMdLUv&@mixqw8(=7a*#Wc##RD>f(teV~G{MvCg)>?1He?pXD zaZ%+h;HD3BSm~tJGRe$SO>+_KFqGf3T*Kh}9KGCmY1Qe6 zFgWhz|Iv2oP{2nH_{bU>_{>oOvz1T8?!Vp}u-JPSwa$X#7Scb^VbT;Eus3 z_Y$-gK9e0YTkzsoO8ha)oj<7aJHaYVr`bja%VFJwVh$^m;y`r*5&=LHfXW!M#>R}Y z>>SvQs;|}e5uApNsV`;or`a;*N8|q@VN~r0GjmFurpeW~v2=g1CrI8=BXGPn1FOvH z%0R;Q3Eha02bqXJj!I7zc;)T@_2U zS{!|y`>yrrGoRLjb{B9JVBb@iP7b-Gk8>jnS>XTku8vRTw}|l4cgvD+gXB!|VgE!t zUPx0!=%$Aw+e{1j`{N|HQ_!6(MDq8>%Mrt@V{z3u&#+EjaBydueXeH7LeAVc;RRW> zvQ`A)=)n28MuEkx`rEu-NWxsKW4RxTj^d((IDG=LfVG=p=IGhWB9+ z#MtpCjr)P@xrI(!{Ipulyjg=aO#O=xqC*jnQ!C_r<;-T2h0#M2Y8v6mjiFZzj*_Ads?0vnEL!FjIk!il%{dGTkVJBNN1{$ z%|^`$?b|)!D{_VXIhVn@C$?6CmY*VCjf-oZ2U?j*J{;0}KZa&$S6$7j7vt_W!2E>> z?oOaVy9rXXzdj^A()#ztNHQ_gPbG3|@}H=z$}}u=xjLwSThUL>-Cp_af&mR$ol)+2 zW$}+g(zC}9zW%wv1$$l$yX~M6l*_qC!kH<==zDtw?=~d2&EL5sN8DE<7<0rx(|aZ` z^|^;=kp$If&75G?M%MKBtSBT-%WNbuiNrOf+OItQSov)H(_IIZYmUB#ZssP`8nj|> z?LMu9Megw#AoZJsqAf-^Ne_|tVPbz%|_b8}?9sAQ=$n>=*X{wx%kOlZ695ko3m z=9G}R5HgQEfY_^a%-fB)o(u7VTuoENgY%Om56x}*+iXVS|%!^1!O;Cv#xmCHfcKadf>zeG< zojc^yw>Y@SN^dLQ;YyQj@!d5AoNp(*!Bzj}y8kt2?}?@**<86V7k!r*;)mFYFrHKy z{u3?~utk`B>mI{apgZep-yaiPx27-umbB^)pWR9(9Hh=eNg(rwA_Bh^zMfkQeO6na z8$uw;8<-rjB|`}7gn7RM2IYcWaP^7`e`wZ>96P1!{Gy7;##MwoZl*TajW@b#TlLAZITr5ahjz$ad}Dv?Md1ly6sGyz{Fe$v$XrN{4L6odKxm?na~kL z2L$D@LQ2KzbpjA9O1kB;NA$u{I6%IH2q6@!w;tI=lS|hhWX><0*qFw;rKI zs4oE3O=)&nwQH-M4fCZbKU9285h}b~00Xc)7*3wv+R{KG8nM!haLJVZ?IPW6J@eCF zQkqo{VYtX=9SK?}WQzmswN4PDRHQW_I`hhA3Qg{HiAu>K0>13IJs$+o-xEIH)JmO( zKY!iv6#dAo>JoT-4?PSsI;x#n=_~Pr=v!J8} zfpFAC>P4s1{7qp<{g0$sL$Yv{RiF{)v-{Q9H>clmcC@rK_*BxTS!<7vW@6QvXGLyk z*FQh=d0uvM$#F*re=N=l69q)Vr{k}}R(V(ORwm>n=90;h*(O{GE-m&InGyN?_@h$lt3afn?R+vN z!VK`0GQvKb+=Q`7(eSY-rd45>uxjg$DiH$;!8+OILb6wEQU()k(l0;Os*y@1aQ~NJ zy>)<+y!~)Z(#XiDHR#eZ_x`3K9e7VO6YnjsB-FZtEmr{Z5}z8rPq|83UDlJ?`ymy+ z5?lvzCN{#m`Z9zZ5C4H{XwBSex4 z|3YTPJ?t~@pe-?f`U|_!85Z76*%*y1)Y#Pn(b_Puz+837B&%_f89$vE9*OZw&a7Zu zPqYvmGTWRd-++a$`f;NyH$EMHVT2+kyK(2nzMSHDhi)_B=Ms~1G#ah~Vxf~}+T;&)Ry(#%!6!13u8x(Ys%j{aU+8*(&>f#-1 zykP8lI(rJt8whj(u2;K{i;HVmAmCQq@)HmHoi+2_z0t^;m@@&s3-KxPQ$G<2*!%Pv zeS{QhGq5^v6tB-k4|0sp0fFRe!ToZpU(OnXC}VOS9j^o`TI#sY`X)5~#!ZtXW@vh; z8kXg9E^}uu;pKYAilFYyQMAQT?pPW4h-sRk7XjPzf2J-@z|v#dI`OJwr_CYNcE*6| zd_h!;A}Ptl#Gs$Yps4(*kp7+filrIywnW28qOxzGZ(sC<+258+)MT;e>TUC<5^)5dNZ?)WEix_UFj|hUK3_g5b2Yq3onm-ZG;{KC zvZD5HkUlw#FU~veNTRDky3r9dozsYhYiBKa8Q`GTO5<8hA9q?4T1e#DnnR4>KlkfN zQxgN*5`Mn^JdlsZD^WnC2(?&@0 zRAmOT)IOtt`Y0(r?MTY~rusqgkZ+=n?*%xgUoSCU9LaipB#vNGrQD6~nb8f2y{Q)D z$7uO{-cC`rLcQoG-_#LO^4^T6K1&g9>1{l*d9bVXA@b{iXXTA~zlZK-GebIBe?01i z!>{}llWej)`*~J@{vjb>pq`#+ja%N}(kV1n!q@&!c9U(4F6tyKX;l8z-jH~& zpY~^hHrFtQ%i?=Q^t+{t94ZB?Ws0f@h49G6W$SVbjSD0`EPJf@3?Ryaj)0%+FjkrMd%^n6 z_Sxa5B|q|*bFu9k4*MnRikpcR{g!vF*t3~?G&uq6(4dBqPSN_gj~4vZn_&^%gx(wu zH`9qXUQVRF&*$rE@bQdiX1ltpc;QR);&>dDAKpTOEq57k&zTYhnG#9KAccNHcUHk> z*~AkvI!pTKlO;pPkKXkKU-GOFed`?GXsYRba?n{5HRE}eV>BqnG#ag8C9qs>^g}T) z8BclQ#3xi;Irq5EYV+1z3G%INu@=e_>wIsAyu_h$^|EY0<{JjEFw&pjSqt3y!e`_Plgrnep* z6m6E|fYWmr#NWG$os^b#m?}Ae%6r~o%0YHiFw(k!dxDpG%8VCcE7S#4#9DGt6<^rGvP>i~mY>t$djCqsYGaorfx%q`1`DKsrvWB_JpGi$W$=>5rdmJS$h zv70!kP%^OoD|QSDv1P8U^uK2|o^UjB)!eH!x@piOnY8MaZe8sqGCD`W=LILsbJuSk zq8we4Jh}$&vu15SU%!l6Q}feI{$k(m-yvl`(C#RZ8VUnT7Fo5)U-|;Jo5~2`E?%83 zbF?px>cq++?vkw|QUM~eYgRsF>$!wHX|v=s&lp`;EFOqi71>RnTT?z$a5;x8if(4I z#|Kxkg$`rs|Gr67lRqEF$>CN#?oTN2nGKRajU0{yhsTJs+{S}0;u_bR!vUqTL@kYK z$*l6iG&ss3!##|>SV@D*c~%`h16 zgKGR#T1hb0xo+n7YXJ`DG}op%yw8%~lyF-Wbo!`@3Om0D5 zOa$ikZ7?sVbdkT>Y%1t(7T%K41!Vqcr|zT31s*J0Q;w!&YXp{Um!?YenMJWY_*DV^ zAEQ(!8MxL?2b6VG_6hFGD6;w$)y}pQ^UT~Y)sE1p$+SaSQOO%DZM-7ZLw20LV{)G` z?QT2d%@Y|`?Kxf3y@2!O&oqgW7aW$yT{P4T@{Ifz-g&_rnm=wYRWKPXFpK}Z5LXQ> zlMKkil;$@YptUpJg@!aBNjA>ftV7l`GRQozr!6QU7}LS6{2>jzkKHW&^!o*~>Iq3> zJ4aEw7v{Pa1u9cVH8VRj0+S!Jmr!7A?Q|@BG+Y7*`1e0|#HX$vIclT&Va5R5G z4H1r_`7Ka*)bW6`?~l1JF3{ z6vcYtBTq|^C6XiirqHRr(-y+i`asMppLaG>4VEqvUEe4Sqii|@zN|z~?!y1nI^XyY z2OOw*_{djSo0TZ6^VSkEurcyi>7Bev|itl*Oar-~73og<|(_LRgYxV!| zD2xc+u@JEsG(cFkdlFSF@EQ90;^A$&w(`2EVb@5@Qq!x+3qq7u^G+0{(~i`!Rk6k1 zAx;D=-@N)|klhu#93A;%#0-RJzXepGkKU9+vOI44IwfZ#?`oy)1~E}_-me9@i|5`n zjG3@HF$idr=2rpv)%zo}NG>(}notsYX@(jYr9NRsO07o<(u@IRCtK6C+4h>HLpSCF z|Lq#|Q4TumC4-gHBrJaS#QRWiJ(Lh#{QKuCZ7`}7m4sz?|59GAhwQ%nar<7J<@4s^ z_}x?jJa@xRGI}`z7%wa5Hc=nEa3M`|-8RpE+6!@o85d>T2z%%edn;!q){v;41l;FR zyz&yD5U(91Kb3lZ?yRO}vm+#jm-oOuTGsCFj)Hedn2)}>ZvsIEnJ$}Uc@m@AK~^{7 z_CnC;sii%#+=U$^b2B9*NGJBZ8^tMVoSinAi zB{Y5VMl=`4;3^3LTS;|qO3CV#>0@NSCAMx0=bi6mre--Utht%6&YpCDf{(%3!U^%j znQ1wW4Kd_#ipDL$;w76Zcong+=Nni8qN!L{nuU=iDO<2yKzZ;1a)MLsP?N^npWyjL zuIhuJmxj4xje4+gpF4=K!Q4gYR~2YW&KOL&AmNFR!1|l#8EX>uK zLUxc2&soQDk!;a>01A8`UpFS2b?n{CaSuBwSg9=HeQoKb?#v3jI6JTHco_yvP5+Fqb9a}Wfz07qpUr#nd&JF~+Y<*Scz_#&3*0&fPd}$cO8d%-_f&Z^nYrPM zYAOa+{TeyDs5#nR+xRJzbZPg?}?j z+M>P`1p9Z-nI_&OUhHAyzxnLxb5UKMy5F{$xn>S?b8a~Jxh!Dyq2~h`p5(=}b@T3| zSqePfJL#zNB=)+vcB|c^Jhv<;O{9UQUkzb2_@XNI6arv_pO4kw5ERL6MyzPcXsXvx z;{YX7s+RP1TL1NXIJ1@60Aeh5uj@>_%12Q}ZM`LAGc-P$3mTo7G3~L45p6{08u$u} zKbrAQ^H`5vjoh-R0DK%%z=-u`^OBW5>ZQ(rb)>r(PuA`}US@?i-r5j{v0e5a4=_$v zLZO?3ZTmgn-xunR@8&3lC)cjzecP4qSKnW@+bfOgtfZq8RlZ2x1`t7kFDHRgT6#((rYr)v;ooB>}QW|DMDhl<2zLz zb0luXZY8V<63JeH!%5~0R(GwTR|kixCkF8XMt*UMY`~U+YLJniyD(O$s7G+%`K4(` z;_O64DgM{p-Q`?<-j6B;w=0!AOMGx{s;^95|G|%8x91!f!MVZxU;p;`INC+EeYtlg zaYgafoKuCba%XRa4R7&jxNwOQs<`@eA7~DyXH^^PVD-0B|HLbAoM(bZ$-E)bTw2CT zbu;osy5gy{>TQHk>z9;TOEiNy-G08U=c1XJk%pOdmnVeeOQb-=a@R;?O5ZKy^XwIr z%`R>o>E^nECVahj^b%KjrPo&4z3-Rd3sRbk%c7*de{g=DMnvr0{^#9`%M16Yw1$RP zm&P;m@du3*jDwrrzrF3(-iEwf4IX181fIoa&-J_QdnZr?xfG74*v#zw6!mCg=H7xK zY1#+}^6C}CuR`*9^Wym|1 z`#0!lN^$0e!L6XT`AZr5*crqpj5>BqzG6-mBCYxsQ+KLIiq5;9 zU_7#&*1+8)_|j`JZKLE`HfQX@&0PC%1xNCmUx`^$nP>SzV-44I`3bxIHqIrD=Jm_; zf6O|+wG~qJlRe)NlP-FtKLlead|y2>4P%Ph_&&NC9P1wP;n|}mamC3-sRx^oGX>6s zb+&oxnUdRRhoI^yMoO&RX4~GP9WwuvjlQZLY_XPz(M3Kk3k2Ji1e0xLsl4H`2wuDM zBUQuuTEV|-*XcNTyQy~rd=so0(4kjbepaTnSK@cxl^5ljZsZbiK0gn zN5*Ug4V>Kf$#HC(J$3dy;G@GR@2jCmrc^?pt3GX@Z-|gxH#R*wD-Wp^i0@-vv&T{h zkt-W&mfduRTvjGU2woU@JmUM`7BKB=pEt|H`#gzK*J7^XL8sca-!9nGKKRg`o7+T6 z>CpVOo?H%<^=Nub<63d;+0MZW6v94Ln^1USHLhOk+m9!0F;C{J#j<&>uX8I6f1#zZ zeXqRnJNK`y_gDV{nLTfkatESj{j_d@t;}WQ8`TA^gsS_k8j#zf@~Z{bOU4FsM}l@3 zZd0BheR0ighV)g>>=-w60cL4iLuxQQ#WLIbJ#Twz?42hh{HEg%UcC7oDD_xA(7U0K z`&aEl{AXA32uz`&i~LYPS9rHvt6eSrT7`Q6e?aA@ICz}w1NU=f^2GwOD8i=O^Q}6^ z`(-c#!+Zl@*V6Ixpt-V5-Gn5j`@J`dGHz;UvAd-bue}2=1N{2?Wm6^@pNR>J<=-%V zkPnVNr|EO}V*Al1BBu%3jiW!*$MxPYGsK@7J+Wv>Mjox>Sz=?17?PzniwM4!-Y?y>xJv%C@xBJG6U-rNuXe?)U0)wjUT%j)O%@&9J$l<7j>}(=I}C zX&>(Bnk1{$|u5>#DsSf2|f2K`jf5r&C<4yo{W-S25Wde8ZQ9f z68p-g^D=TBMM~q2KFYOH?sAYyVj9EETfzpP4heCV1xC0iod5Cx+<=9f2W7J{&lR8v z8K*jPqapS>V78$Blc1%Eh%Ht6P_N43T<$d093dhy=n@;*TB}FTsvv;+YgZW_GDhG} zii!#{kR{pT_K_&xR&nY|!wP$mOuW-Xw}INL!r{|X5yb+XYclTkc{t!9h|39~gW`UJ z@bIh-*R67_+4Q-@a>ec*0%A4m(`_S~Ed6c{rTAQoAwq38n|))#cUufc+mfxflYePD zl9tNHJpv!!WZ*szj{0GEYyoH$n45_iOEH7s1u|Gd>{=#L*uSEW1yK!KiWRD8tC~Us zPn=}TIYFXiR2e`9)Y8T$Q87m(P<+vmq9jT_&mw6|7+vL*5X@w>Ec=6GRBF|T7D(UT zvJX)>AE@!TJ75vJ5M%QdGWJ`wzIhO>{I{mySOi=2HAces@-ZU87JhKep{NIDBv)w8 zzn8f^jnfn>;UCQ$F%}yd*U~y1b}*zf9%l-83sOj*D!4JAsmPA%={%X$=@yJci%*tZ zD9(9Va=GaneWn2?z(pG(M1@_ivrlUHsI~5uo^XADK^W9VL-v;Ks6S>B?>hz-_I?7&e+S+8_9p1F4;t zHmndU>q5Vij_v!5go6QE?AVt8yE}Cu+Sw{&4^P|J+npElC~dWH&_kSWs_b|(!7Sqt zs?UYJt6))6C=uwNP{XBfG;In(yMt7+-*Sxuk3PyfCZxlv{B{0B7?aq@exUki8Jci4 zk{B|&fLyx{hl2@<^-bVss;YSPxza8fA0&C@5`0a1{_c&0PIQ>o3}o;4KvYXoK5qc6 ziXXU}az@TUyok-L){l|(E>DymbnMja9L5qqN_0Dv#MC~KNRCkrTg(!q+0gx%cVNIc_2^HFldg}(ttB=V$mW3Mr%-@{djk<6WT%8XwG$w1 z`%!Cd^;G4d6%$dsusK zhgn!88yccT#H><6{BgiL`ip+85`x!LlI@DVVG}ldlDPOw5N_Ch^sx_yeu<9Vau<); z(ne_9jEP*peM98owj&-RVeM~er_4+f_v{Y^4~C>^3b18DHYSH+>{VJQJ-al(h+-EQ zh+ifSiDqhKiFptJXe*uo0~v6ENtGBq$vk-iTm)!e+u4DvYQ*W{f3&q_gPcmWB7Z%Z z-4!XHa10q*Tx6n)SG3#=s)0;-+=BDaT6fpQoRQyYxS`ydLn&(-mR8s@M&2 zYK<>Zeb{{A{NYF})EuPPN7-=af=mMet*oWb)m*(#ZJnjfh|>;mo`w_cXJ?i;PWP&zLD5i{tq5AC^|znRsj zd~MDjXhE^4Gs8!JR;opjnD4QC^IW|o*FgHj!Y#oI&VQZJz4>|n&qN?=h@#|pz}o2x zx`Nu4av11Y$z}EV^JED~@t*|nP=l0oNeDYMV00Y29&MoUVGP+%*&kg{3vJ-gxU5{I zKv5!Yn`+I#Pej1bY_GT_dH=xowU!)s-e9n_QCKiEt@yyG1U98N@JYm3x zD`XxY)CAVQer}ex^{8TGm2^O;jFRZO0T}<{EukcM#%5;RVLt%~=;Ozam;Pj<>;3XK z{bB6;i42cLB`hEk8)-v*;g6-Tx2Zzl?iZUl?bT;k6O7 zfI5A-x~wQe6xF~BeewKUNeVgy{yd3;C@AVD5H!b;CUYo5$IR}^zR57_`mnu9_{HsGMk4L2 z4h*L-vi{mWs{lsz*#S2atlFo+^<)53Q)hQbkJoPJ!0A0$aLT$^>U=qLbStpBz^+d6 z$*(gP?Zg%)gEpq!2d_PIxWDScUWR(vb)&S>3Ubk=!K!0&wF^mvt%j>{Bo6(yR> znRx0E*3_&f1GSYuc&$PcZK6-)2jlxcZFluPp4g{|hxfpOr;5;}JOc-2&!YLL8xrZX z#}B<*;%uI;L|>oL2v$Ut$Te`}Ey;=cZ0UkIljXYUIHlHpI_zdzdM#9weL0egcsBBq z!lI%2tGb|i>w;p*SYM*DQ-djR7=HHjD7vzJt$(v@$CO!&&&AZ%<9Foj=JxMaDOGu# zHJwdSf=xrp=epN+OqRk)lF#P-5R6205Y5tipN%-%wu1fct;Qy>nvCKaEG;Zho)1wk z(qzcRwg_kz(HL>2#3K*yKsaOC`Xeb*LmHaHQ&$>;x}Px5RBxqSe|pzQe{=IfkdHa= zdN3JpCTO$2u)0W2U-~%|%wBvm&Kc}f7hqpv%e7o6r16Q3HNg8$FCxILdh z{g5_`DXAn2jI{iPKoOfk!hntRidO$=$;Ja5YG0kRE_w=MVGGk0_lIh(g%)o4Nv>XW z&*e*v`B9w*YsQB$t{>=vPh5j(Wj=bUhgxe)=BUZxkdP>IR8ce&RDM3G)n$jiS-LeEG&niQ1nSAw|@pH$} z`eq7cDavQj?%*Wo5Zn7nmC?e3kNUWzDyH|}$w{m#AMnyZx6jZvA?eG06*N;e{$ zx$8!>;pntiI?QGcXTHldA3YpY%cHh8%DIYcm`8U?6J)4*t$8c3Bj%^8|`W2m*8MPLo6>Ut?LUhY$g6mL7 z)u+Tg(S$VdAwwE!cfe(8W^nKcP8MwNY1}Y?**k825+Fvcca~+fkQwB__J*BY2MW+T zt2g7Wt24=L?7ieZscD0~4oBDi(Hr8qYElKTfg1JWIOOJTv3J$cJi^2$X*;0G%7^@> zf>LSWyZ3?RwPnQwhEWjE(sZ6hiT-{|mpYErg+HnKrmy|@>ASgwg>HAT-+<3&0(P1j z2`ar4sUNTlIGF@8PRqQ%4-N6T&c?TpDHpD#A8|_xuC>%KJ#SW&9D7J)Qr~9pkv3X9 zr5riB=^Nvs&tf}bGChAIC`oTCw;nCmg+{<0vhFEQr=PYelpn7 zCkB0-`bXZSSfKFq6``H%;ce%tF$Bws^#{s^w%c|^+Z%Q=)%t!96n#omZA1;23lrLo zHw&a0Kg#KK`xG9H@5g(W&p9^~=vb6t%dc#1`htMX_8Vg(dAkoX7DnkP`tB#dpbdnr zY;vJh`&43b#*GEq^GWR7n1ketR84-G9hgWPp-pw!>a7JLC*pKXkdf2fb9CzljWuDwRCn z^ILrZ4Wt5BQE#7sVMl(kn5gBk60L#}`z3((X>4VM@R#g4lR1g@wTffT z>EM3eHDl}b=g_tgcWz>JC7V@DN=$`paXAjq{o)QT|L+aAb#UMmwZ97Kc%Yv5)B5u} zu$0*76Wzvg^UH3ytrQSweI0YXPbJaBE_Px|Oyts_-hAmdHut=@d;t)nt& zE)Lz-#oP(BonyFs+1MsThZFva>Ef*OMtJI@jsgGf6)%?2JDiLDPZISI)Amwj;#*#w zn+j{js5YI2@>lKFZ}4*=8;|Gx&{eWumM^Unm#M7IKjO}mnQz;h*Z~h2z?lvyOg`1a z{k5CW8TX49Se|!nBE39l*$DOmMO`Mmf5_Qp*du{w3_K94hqTN&=s%)=hIj@)PvV;z zHa3mydgINV{KN!S|HuM01-3CgSBb09;bG8u34HUo}<0$7RlvH~=LE1tqAFUFze$6<40o`L=pcRkei(S0dIhKb{*qL~f zWHyxqN3A_o-P@Y40_G~#$HZ`K3BDjk*5OUIWI8K+`nEJ4f;=a{vVK?^wC%Cg8-U%7onUa%}H7R z`u>r1IrQ6n735X^orb_ROZy@8Yn-%SDzbWioQdeZ{eQUtBKDzdblH}ZJ{ti;gm{;M z9ppBTKif7pO}!#gz?DfxQKyzxI%P6FJ(51E+h=7(o?CJZCjMjhU@-G8P0L0cc4MfJ zmrC}!3mcN|aWwIKWD$tv5n# zRFrdE{fufU?Z;X%1KBgRGcHirsf&RS>=C+MF~_GW=ue7R?5OY+ZzsY5JWHX6na zKE-0KXvm5-G#o);t1R98wq8$Gkih)4MS$3lreV8LianF+y2aU64i>!I9CQ`<*Q0RO zc)?&5e8hoNn$wq(3s!8$UBtKS%{Tiw$AQ##D&vdL1G;0{?1ewsWv&TUXr+43_ zdQW+Ppx$SP+tHN9CRXGDZL_<3b6PB+XM@|L54FpdcB`lz#VWaVn-^qCHa;gjf$AkP zKl8h`KyWqyifwb=?dPL}_S&TbzM znKY7b{yJ@yk^qNle%K~qvZ6KT*p%yM=_y<7%#`VWp?S|S4be9M2j?n;`6@(4G#Cap ziwFk309H0cuai7KoFooT0bDTPv;*BW6VJaj&c+5iaG={`-b)x?T!pmPrf_!;;60kl zA2|tn6jygX$Sgdc^gVB7>|RsjcbC@h1s;91JS2obS1?S1VH6X)*yE5zv&_U>7upY` zy4`(>cH4fPD&Eei)VHrAK=(KpOv+TMQ=m)C1edBp=C*w?Fb{!FrV#wJ3<-oVo{-WU z*b+S2BXl2&7bOrAs8wxEPi0&7rr3Hut(CX(oHD*CkuAQpe?ezGA_9N$=~>XIuAC|m zCNxNdjwZ+r?2s_7?qEfnn1;n{KPVD^7E!1G1(u4t)e`%Xc&q$DkBg7;#1Yy*D~SC| z#y9~r-jRF_cy1)CNIEvll_)td-upoMKD8GPYxBI%cE~6pg=}hSiSa>CB1R3GHf0eSqWqt zWt(kGOh)`@xALrHtBu;Z^hChDG8SsD#@6B!FwvOb*k)x5jKU$DA~C^V#*aA7S6t9t6$Sn! z!5Nw*A78ig@x;vPn%)Gh>7xzJA7EoIf`1#OD=|8`$y``CD5EIfK561C>-5lfQ)S+6 zlNJpg`Fvgd(F+c=NBdh|v&Z6#(7sH2SG~s65T^93F4A%QZ=HW??;$_iM(KiqgVXNO z&UPE`-M~O^EsvE@_IH10LF}HSCaTDu4{NR?xw2|y=}&nk>YjNEU7n)Z_{MgsDo zQ`*-Gux-=-uJnxoCDSrdqx#l3`s9+9iEiQ0-&~-pdK%JA=>FRN?DX_UON)uvRMJnv z_PGfD;q1Tf{>`TDA{wj5>#lFh z+Z@E78rOEENTEaEvcFitkB(~GIxF4ly>sAO@Ig*rDb-!Pym@&Nc0$YDX1Kv(t|oC| zH8+{8dR%%Kn{y_8aN$Nq+==mg^8J_R;f!5PeKYMS{m6cTi8u5;9>FalsO``1rIw;w zq-{)%stNB*AKyD@J?dP_+&*#dR=NcrP!$5$;9w(ciJS&O)@_E1X+>`xX0EF}F^tLm zcL6eAm!36Gu~h5lvNzQbH57}<)O1)4GnHi4cgiJ&Dp}4BnhLzZ*I>OwXMIs--L9Iz~m&8 zZ^n+5U8(fNfkCE1*!{KDb{1oe8t zs%>7ld2KIrmd3AHf`m3|-1Iwp*eG3^#-y8kStsR|3fsj{OVOuowLH&|Di7IKVYHjl z(@{aa4N3T+^r0$0kgB2#z9lvFjYZd@XMcpYJUGP04QfB;>wECtwJ8tRzmeGAbip<2 z*X_$iuNt}fxi&y~rWi7|Zwu>o@D17a|Li(ip=9@bA0 zTcTug$Fv$%R`ulK!UFHDO~Bj*I7$Fi{fg-O9cJNb^AP}X(y5pj&LWA}dW4GI_}6`O z2@TW+E35*B1I>T-zzH<1#wb;Ys62OQ|^TodBCNTz9Xup;P_9d(ss^#pe zxkk^74ot_P`q6RUXbgHNI4~kqwk-1RtRs|qRa^_`ua2@QgF6zS^T##36?3@Iw+?sE^zSxZsAgNQQ!0f9i$Y)+#P)#+ zZWFVPgj_Qhk)&GQXF6{fzXbfq{GIBe??t+NYO3f?0awp09BNj*Qw?|XGu4F{UBLI0 z(*g4hoRIN0WJMVKQD><$+p!3lnDN$KmBwCP&V2HJnELK$s^kBEQk04$$qr>lA#rgf zd+$|7B^enR*IuQPd2PwKvPWEd&(Jk;WoKSl*S@anTG#l!`h35i-|u(M`yYqn@V>9{ zd_LAQcYx$wkmewlRi37ufAF{!o>=`5Na-ldKKV7yq#09w9DNtD{SIzLO|N+H7!)Cb3B7rM~*81*a?7`52krJp~=XcA|fDcyG?Y!dP@U?s6AuhF()zj8X2IKV3YuhNU99Ak`!XzhTcZfq$u=U#9JwDi zU%MZ=51EB~#~jI4oCOZ3Yy{K^{Zow^yVQ|mZtP0WmrPnL-7EistBG1}9cIT1`6{Dy zoE~>lA>k4Fz~LaDvLAvWrc3xUhOM_>w01o{!04pCWy#6URt%#U4Qq(u&UG2#QQ1Ff ze(fIgw{K_&s#Q_;1eJW2{brKN;@8|}eY7otTPn8%gkIZ72vtn^eyBj95?<%)l_QVX zV*_?xB@fLH_zprw(ELuZS5*9STjpFgYJX}8CQ^fCUS3o436O-~iC`3Y`Qim9+}$nT z4`_J_h%^6JW3>u4voz}lO-h<_fU~-Fg&Gp&@5OXG9bz0PlpbBp`(b80`sHir*8kVh ztPbVM*imgzUAuUve*UVY?pt6kcr^W%;^+h_Y}I0Zf0B9IT2Cp5ya$jM;92$f%7IkA z&~7ad+#&7ap%n9aNR68zSwP4{`-z-z7J19dvD>j}I?x2xIYvQP|;Yh5oJUYe2X zF5dD!8{PKxb55IiFw8*jiy% zg4=GNsWKbsT{BtS<8x9$W!guD#< zt}E)XIb1d`)pzell{>a%tY_qB{Gia0y+G!DXyL_nUWobX^hq~2neOlU z{h1)SEx*Bt?HQtP%P?FmZO|?O8DoUfCSg?;ecp!pR?j$NRrJAy1jcUr)5Y*CoBGdw zmq>kF{4p`=s{h6>rsFo?Q!1~l97qK!R=}kLA~a}l{ci`K$bjE0;a{V%q(UuLUkMf@ zFgE*B)$xqdOuS|tGw`?4YsCy;?iDWJ0*1?N=G0+uw7bRc^K&uLdJW=CJ!fA{Ic1sK z+z!=OuUuvJonl@gv^gcb%{u*TEb}H+$RQMFVw&S_D5Cq*TSy1sQ1kO#0O|wh({J3q zyIhy6hxj-*+cH7+YpuW|0mf1>)`%jf@NM{xIxN#F!ZCLKZY_WG4A<1EjJ{?**#weug$8&A%HP2Wl7pz)3+MiD7#4QR77%|4}njw|IwP}iAgxRwxxO^-lU|7>ytu0(HAxz9y z+`oK;&br_Gug769^BaV*AuB0d6H`6BPAmiQTc%5wZt%7WSdX=156|I%XO7}AXWjS4 z_XW4XNA28l`1+s9u^6u!&vH({ky4Y5uaKf7GXX}Xq>yi`GVu%@gardv50oKc35zpgwvA4zpNfo7ZQWE`nPmcOez4fn_l|k*N-67e_@IEtfs*{#(*Qg8wUgd!TldnKA8lC83(0cP} zwnWoCEvQsb){)VfN`Pm;y1NN!38G{lwHyOcdWsk>_82D5wC?wM0W>2&%8?BR3h8{K z2F@sRtJqH{g!lY!)0Kd=gal%rQ!W)}_Gz5))t8Vcc8~F3dq7~_@o2gRhe6n;Pr`KW z;QE%2^u3%k^M`*(Ur7}1vdAD)#iv_$L8dl6TjJh|GrtgLW?+3Ysswm-m(uaUqH(>( z!`CAM3?pOXmm{8a!@(Qa;Jr+IUOUyl@+WCjE?oF0AJ)%7-d5;Zz$6)2_TZUFW?g*;My!D&NK3F|L z7|d+TX&+lLJ45;kQd6!;s#vd&n~$BakE7@~%pUm^*4<@TA-FEOv%m5@O6MKK@i%%H z4niipw)n=`d}dW#1b^J0bg4cJbopST?;YN?gj&*ChZf-m>!eTbrJ4-7sFPYJCeOVV z`$b9d9hAes;l^@TdoDneDE%Yx-eiH+2kmV2MJ_YG0NkEUc(ri=~|%V=ph9h>7@f25xtTDICL6{=$eM2~-2s|D|V?t|B=! zu3AG{*>SAP?_Q~oKNvAwUzLp{g&*fn7L%90_$(jpUA0%(Sse3L5cN7^uUj@YQsUpN^YG>foBA(niSvKK*dR7e3e2&WkSG+wMdh2I^5SWZe8_s@aO87B5xd{9>pxc!(BNG_b<*GGC*}39S*&6S?bxh9Pn0U+@MGM5JbBxI zlgonaqnQtgKNI}TxGgG<&fU^RYPbBIZ)nFGX$BL^URJUB0k&rcXg2o0-A2`b(=Geb z1`{oh+8P2`i&8WKg1D0jMAwiv5VwQ@eGPa^gLWSPC=0&q>gt+aotd2c0p_2&F7^J) z0b=l+dpjG$PWA^V&Q^!>2kpdnlE;ezT@QateY^Cm#A->)=bLB3@#0`tDT*)19}E+1 z5wi5^6QrEO_d2jti45cxY#Cfxg=nu6KfDLSsNx++qb*{E3QXT-Up`J#Iof76S!=i_ z)RCLhXFp#GX?^6IbS7K3Tth8+936QhWAupMpwKh%R5W#K=X+E5b*b6taipkL{ac}& z0V(z&-)T>Qk_6e&!dOjdEwloveUkmK{ejMAoIBffFtdEkn(PLBPTMxeZtAG3LcPp^bNfWX&vri!>ba@(h zUL*6+ddKoW;$4r~Lv81-Rqba9Rm9;-dBglr(Uj+R-*IR7uklaAu<0vAUrq!AL3;LY zRxF==_Lp~;{r#~~Q_uI_;qoG0sbW9A6kjS|dr_0CGIXRpaZx(o8=9`|-fC?9rdP0< z`^@uxw^t0~LG+1%h-wJRW4CoU*Dc3gIyXO24uT4_@$-`#G%O@D`{dQ{6=4@Q0sD0H zyjNjvyU{hPe#5t|Jmx0xud6OdxjWLPI^NWWsT|qQi6z;N`$A+c5JF%IAr{1g_!0 zgD~Fhj?0%r=M8|{MlRtO9`F7Pd1O)^*4Mm)txx!`f>VQ+CF}jEy*4_Yqop19jXQpYPp&JEG#3ZkhvXe~64V{%3ew0?~{r5y2{yxMm z@dL~C6Rmd%5cGyzx-aD|`x~IF2L#}0h4oGd%euoeC~uqFr3W&pqQNFn?kP;M>!yWpaC%}pZpZ;Lzj2Y0XW zvwLkBVL-XuODe9=IPyMSbFAUG^D>TiEmRtz$B}@f7RdH%_8+fzud`u~+_mM1ge-V-&_r47;l+hixpW(1C__qt1h?WgH(&VqNmJo-Qj2@Mk?RVZq342h z$hHI7p1}?T64kYn<*lA}b$R*r&$6^uBk}@KTlnY?GW2`-YosloD!|jUrK@ zSs7}e3<&*-Jb!m)*_3mgJ@PXTbAwGuD>UruUQ`{MEXYD_f=_ojP^f*}`@^#|XhmIo z^dvs6m!lcASr&*rFlZTJmmHAdNSXed_NL!NXeiL(T3CQyz&c7WA<@rI_Lrk(mGDhm zHm^08ZQMXzND1+<>0XuJ2X~KCcZ32F^f(c~8NIIVxklC|QvLLxMLGLEyT^4k6$hDY zGB#4?pGeVMhzb1F-{z4%^E->}L8HS(5qvBnO$#)~J6poP?dFcL(B$Dg6=c9YcJDcI zArX;y7dr1g7Psu;RYTKR@G2!`B-*coLgQ5#=EJ2 z*ULOFK{&t19`8Ag`j#d+ru{dod-+@_V}#FJLmz`N+EJC>g@U>?yic;xRmUX!*t+q= zm;ToWbI*eli%mL611UQR_DnEju46J)=O^HG-*!{n?SG@g|*a2+GGAi^Ey@G(9&at7&GJ;+bRbKHyCwLCOkIkcc5aKn3ykO z-Zmj-OMTEDFx}1GkOAt$3%@c?BK_llsPOc#R3iNm9DRmp+^jjaya^BBmrK)Ll6#Ox zFvfnl5=ozXd<&2tbA4`LlD74oC^BZ;yfVu&%uP-9IF!7XMp;_V0XG z#9>X>#e?luOM@jXh2q|4Q7P}qyb4BQuG#HWavbLLaPnl{`n|{z{A62To(_Js@IRKt zLsLy2dPiqxb~nBWE1j4801f;2>y1PA^q@6cpt))mNBF!%R zyuuf{B};olyWfq>2e?{ekKt(upk~K8O5mBYZHS*(wyzRKDG>NL}1)fwU7< zKFoKji{cDei}8+8CKm5c;RxkBY#Bm1eNLhX175X(IZxT*O$ab{TeG!@3a?QtWvEaa z78{ADYE?ZgdCzW;@?txJaKLfz-e0i+8TW##SPH~2*+qL!Hi&bA?f3-<)rf1(sTR>} z=_>@OUpUv;XmJeVC$<5y01T+Z_tdtsAy0``Irj%SuZDiGwx*8rA+hI4Ua2e;*AN-Vq_& zuI~1ec!*x+hcnp5!xvI18@Q3Y=B#wRlN1}X7GEG$9|pj!aBV39_p7KL5P;jI>T}oR0GCC$?BdoU8Kx z>6$}DS6z_4>$AA8{KpV6x@WFE^O`Sd8w1;zK0TBT?B8tQRhB~QWlpZnd$B!=t{wYU zr*`-a)?mJ7THwFx)vNFDAY z3WyWOhFH+j*^BGarG!oDfAt8hn)ja7sW*_59@1b|91A?h7eITBEG_8R^~zRVc3GLe z*Snn&x|gr2F#@#Eq)u4IZGF~_FYizEr01a_7~}vS{FvQo0Gm3t+PIglJkDPlPdw85 z=qd$&z_%G)Pi!DD&3cV`L0XMV&DDl>SAdiYz=wC^9~Amz6AYH(A?k-}-&e%_Fh+S6 z19dGLQT4oDH$vl~Gd;j3K+WrZO~n(!1{UKn@%q<-J2zh)!vk!d#2<+ERmdo}&nyEb z2;L~#(tAO=a|ke9ascrA=WjdR7@&!oI3wZV3tBGz+@~uKk?rfJyE^gKm(4~>3F7Q83Vn%E3 zGf(yS?*+T>&rAmFL?dLZ--h3gkuNqbhIPLiwvYjo%AqUAd6;2l)7Ik=Qu~`NA@^z1 z>DA9ysvsIUgCXSFaAqT_SFx2W?+jsN0B4^Kz;n%d5&A>ZsHw<$X}xGBGN@P$osR>t zp*sTSeg)!i(Wu8sn=W2f&pHCUrr&XxTPgzxUI%QtT3X6mxQ!ca7Z4_2x$>Wav=Ite zmAK>@Iv$F<&3`Ug&ksPU`?6<;k}kOFx-+yid1hInsXYC<^?dZ%s885+?yrjr``|Q4p zI~LN*kI#zcwt3=Z=yP2IF)a1?qz!9+8qmUb=CNT!TOYq5vz?i=qY=_ss$--)jh4bZ zv@7%n6K;X`PGe2Xo zIjPnXscf@}{q+pQE;hNPL>`V?cT)Oa*GDs7q5R0!%S`tC*}u0MH(-JU4y|l}Y@>?6 zXf$e|)dWvOLHxqR2wjEZ0G8ci!pMwbG~;U%)@Z)%9% zkiM2$B_`K^g@#Tit(>U@Wi4NohVIS8o7IgnSwkVPj4MM@`SKp)m-sXCy>lR+8gxnY zgYwcjmtC9g?df3!9@xKv8|85Y`V8@8SuoD}G}A>nyQ^i(EvQ9Y9QcjMiq3ZFI1@mn z<%2DRxvJ7qgt-1!aU4FIPfHU@5?n+CG9QfOZ{H=XTOHlCimTPAhi}&n*kTz-ik68J zy$PE7rG~TxXoKb~U#_ReS&+DorV>A*3eU$b@C@zO7++3~mdrDxKlNQS0}wEyuB+t( z?W|+Y6Oq<+Vc~~o!S>Zv})S(fFfu??QUvnYG`yA(YN~fzxVecm# ze`m&@il>~c>b_G zXZN=r?h9Mg&-IltXT^Ft?`(~h*JL2UVOL6^xMR=f9I`4;Pw~S#){t9sFvQUf%SXsJ z)iXa+FJvkO|9S_iH!5ueJdO`Nl^yxj@@#u+>zk1tmLu?15cOOl()&V7r6p=>`8CKT z%YcAnlS6{@muzU=FLs86xqyvU^eWEc>63lX7444Q+zOl{_wP3ef+)u8?>-tfq5bzZ_oYfMt^*2exqw`u4O^y$Yu>w#>#hjTKiY~MHZY*E;&y3_U@ z(E5d2>5sOoA6ry3HbxMMFmRCn1H}J1YV1mp$WZHokbyfS~N7LKs){D|u?Y!~kV zxp&92`kt31zx&q3H;*mt@wdP3RBB=roAd(RsVEp@e#Z`tPMSCGO^Tep^gnJrdE|Zg zXQJ|;<~9ApOQm+1nkJ~c_jG!1;!sSWidi5rClxfvYc>QPfRn z#zi+`#opz|?Vd!^$&(lvhC02Jp={ZQbxM;kVLC){e@^t4XQN&9(>jRGCp^>m#IXgo zoXTC+thk+SPYagZ7ancxfryqOMh#`l)AVitI0W<{Kh<0IE$GV&=xq+A1ZtwOKGK0 z#mFzX-}&LU7&-(6G6s-epcK6-Yj|ht+6%v$+}&-YBFJ*)eD40D?;KngWMaVY@=1z42wto_o>S3CRK5Wn*1u2mK!)* zwrMT>PqNhq2M0L145F+4Mi#!i+mi3ootbEIFE6jl2bw-P2S1%E#`@A{cEt=o1+?=7 zAHSltxcwKeuyl#karna()~MvmWbkKlve#7vlijz!LPoZXe5IN=aIyl=(nl`r?KkoI z4A2VS<4hgTKZ)E(M!O{U0muITriEmM>!go?3`EHe%S0wNCuXt0@pLIe#q(W&xuN}i zoy_n0w?Vt-Kn3lB9A9U+kKQ&ad( ze^eH|-~AwyzG$bIMoC;G(Gnr@-AcZqH<@uf_E?MJl>l#1M=v!=Im7$97Rl@R}gcz7;7`J9SMn`CfFW$e(R!ep*%bt0ztcJJW3UPx_rwc9ba&972Kv{93B36UW;b z+|pYAX@2I%n<(Wf>%$s3d@t^|F5dm3#dFZ!rL?>J?%m(FUuxIe?GkA@+|i7)3zs@o zIiy?+{seEfu6z_x1WkVkLP|1+kU_xWfgs?Y4K24K$oTXhqU~IZADnXT*qWOCq~08j z@$1ppgTI}bMZ@V9!rjs%;LvaqIvrRQfbO&4%>?7lFZiXXSJQwR5eq=$ z2wh?$l>+dzWFRc+e=SCvK)Co1U$3ry=mGkMsZD?E5YW8eWMp(t@0B1H2(y#_vK9qj z66%+3=|2!b;14&yB<*C8Q=xbk5v4R^5JNAW{9zfhQHN@<#q9x#Vcz0j{~T49PeZ>!0G*4wUhXBDp!(H)#AkJuJUE&F;^b*xL_hJfrWevDZK-A)MN!Bd=!sk9d zQpuOuF6#t)Zx3Q~daJFwR~k1Ni+GCGHHh$2yPVjv`x3I-H`=a>#M4*Q?9b zlE$N?MB!xHd$X98#v1H99w ziU?eJ->a)31uug5&BL3|c)WK%*7_Tp?C<%?R!upXH+Zc6cD-TPDgOIk_!yzfD3bk7 zq_NnWwvoy%j|yU|fbY<^GlOTTg>80!&WOveIlmbgAAG0KgIzRP#@%YDs!o)vm3bsQ z$#Eg%3Tqjb5WKfBwb`|O0k-iaw!{1|(>;)I z2{Z_#hq!g)g_81$VCm#0fhD5wp|FhA0kG!nWGdj6Zd%dY! zQlE}X)u<9L;EUWh@sS|G=Pj&<8&R6xLMCXvJbPYQex^jFQ61B_{9QGBY5e=ls-QjVTT z(!mN~8+>q&HN#RV7r>nSOOMGMUY%P6`N`$u9iZ;=@bui7;pyZCSx~L8Jt0uO=mpJR z+VySzVK(bK5`vB(z-5z${eaqwoDAW=tJk!ah!pyxJ&KI&=bVA&>$|5Zd8PbbeO+N; z6Roo0I_)FQ3umTyYiDzp-s?&p{v>wB`4Ofbh*Ew#RPP+suf-j)^0kCSOG8-)L^*RR z+UAha^*n}$Xr`I+PKc~MAY=d30Y3=p^SQR6A^jF^cSw5H`1+C{1l;umHe3$i5N~Y9 zL|Y|9F5VI_HgwFbL2c?L*<3h#Y-1Tws%z4mzo!Vx;>iY4@h|piHk%e?6FXF?^2!P( zdGoo4$^}Ti{S;=$IMgkmGixzn;%)`9BAVwX35_>OBex%aIMm7`9OUQUT zRL?es>g#V;p`;(rm=#|&He~icpeZleZ(r3RK8wHJI|VMqQRB;kHiD&hyE%GNhBEK| zp!DrOqz~{6te4A`c8EeYpg&r!fzc-eAio^e5pR@P(X6kG}&v_c}> zsSK`_FMVpjJS1v@5@W@h?Tns$v*skzZyOGy*VV`bv942xXA_@habY|}qiomTq}egY zm*yoetuv0FI*A7ZFsy23ANmPmbVYfTqwmJrG>rQ7st-rx2x zc!MvZcdaM>0^7B_UsNM_gQjt=Pc4v2U(ArjY@YSQM*$lnmcD7WAoC%loeY2hhkDJv zjt!Fz)dtgd6*u&e{^{LeCptA0caOF*>RWLap=l9(|{h0?XR0o01BV)O%$y2B|4n0U6y6)z~_0DBpdXb#ZLR@?LO&ly$9x<J!|lv1nK> zORHaqhkIj#g9p5W&2gXs{9iXL!2_Q4Bt>EpW%@{cF8YP8 z2}Lo~nI_m`9502AHyrxasv?S9C|W2WgMXB5gul3rT+oCTYKQ-nWTv?KT_7EO+2v8L!Zgzu2B~Di zHzN?DLgZ$~sXi(e`{q_Ce?A?@f08iN;Xr7@6y+!IoE~z~YTdUFka3HV_iVYJ{?3B^ ztoPLexXtK?(5*?e)o1Cc4*Ao0_CegztEewW-oT4@%=V$`aCr4J91jYgRF@VhOe`M6 zzb~W2%Su652nfRisyJ(Lt4rw0`jpPF@FCUZo+n|x;@@2cp* zA0E@>*4%}k^Xlpo*dMGDkkCJZY1c*RI;O@cfQ2urOHJ*4(wOYU|i5rk3B1i;Ec4>(RK$mVofmfzf;nP_i(?>gM#qbt!slPUA9GKj$0 z$nh6~^V>C>8ijDTtW?G#>Hk_nv%i!&npeqIQ$Z~CesO(dG*7}c01eSRnx^Hf^V0G3 zPs;nLe@QxNZJIC7`A)OIK!69xG45Pme*O34N0Ev?LH@8Ko1^|BNcYGIGNcuC%{jO; z-=%jTepI^eDV=`qOi)s07NT;HF79vw`BW9=aJew~AjH4n>znO8n4 z`60Aqhg{b8ig|VBXPqBK2Gmb0FECZ-Hx1V>O2}i=CW}>DjJybs#;HpE09PJ3G6QH6 zkQH{i?}*fF2%mTQQ+_$F=POn$UH5H9E3oWo0oOxj!w4k!p&6RCVs_WdvGO zhl{S4pKf;?5G-jyVko#CX-^u1LIHNp@ge}__$jaz4jzyZ1yn9CfL#fQgg~~9aNhV-56lX?#(3K&YT&r9im+*2*7BLyCS6``QB&HWQ^L4756x}w>DZxU zH`86Qt9Id5G)b)6(siEKZoDhWUW2#1u>k&({d8#)<`2FKJ+V(>#a7-4Jo=`_)-n(ivGRKsSJ z9h^6pGau8JoEN#0Agb44-IB!?e7r!X4$wLZClJ6&uF9sv7QyG8zc7am4sl?ol8Q-A zKDxEzzW7BNLv&x%RT5>C<#>1IA5k620xRG_n;~1Q6zQ3TpzKc#p~w5(bgwWT(Z$+# zWec&{<%cV;;$%wS+T4FUw#h!9GF-Hf?>^G*m4fDyU94QA8FRe{=_md29jVun`a7%Q zg*Hc@46N&>GOscw%Od-NbnyKocBz-M&Ld|9a)sp{hePh=K6i|OIT^t7_Vcbro%j50 z-`B9=(LOisz5Q!S8g%}y5TZDFQ%=lV^B0)t?cRV|crZ3Lw!Ijyv+SEJ^SAU)qD75L zGd?+pXcGEUyN?9EcS1=25i7IOWRkWNanU0!yPS(1KZ+l*>VHj$VdZmqScsH=L)+kL zOX~!Ny#D}xpbRp{|G?shGzHrE@vRHxmPqU+o@n{%hO@17pq-LY%eL;j^KI{)?YB3g zAIX{6VRRRQ8LZZ2=AFd@9*qH?n-kyWISPeo3*bB$Tqo`*GLmkr>Vs%Ds>Y$5KcVCB zA0XU&{ar#oQR)d>rr@j;l==Mp6Y=qxSYcRt(Fu{Xqh!gqrd%R6l>1a?t(j9V=FU($ zKeO!TJYQnff;qD8Yw6pCSl`Q>UZp zY~PQQ&*J0=xk1}hWWk|iX%L@^?eD#2clu^I$i{aA<260s2wHKQ$262$uUO}{DxDD_ z<(GA3+`>1dXJMzLTlQt?11jR>iVISJ9&6+gCqHf#5_;|;{sUl4q+Ms{n{TUdz4_=l zeCl9UZi0o!Oul!~?qR-j#@dVF+A&8GkO{AvBVq>D6c21f0Ag#s5_Ius~C+mbsY zoZ)sq-wflW()7(V&S|Hy)y3$LWst2$E$Kg*0ySm9|77K4Wxi`S{-q4e2>;fZ%5UNy zmJerC%|`nq%628$G(h4^oCcN_v5zDGcIG+|uQR^{igU~W{d=-GMhS_xr(q`wEB_KR zrq6bg7f?Fs0>88@{EPN_F;$A60)pkA#jXDlCej^?{sxez*}=-{>W`MlP;g7l|4I=9k>~%E zFc_om8O=!g^#j@e#}gWT*VE%Jjc#D4eSA9sD6N=AK9I*tczpFi@OV_oQa(2P)=00o z#K^C4h7j#6y%SKK!F=-ql1^1M5kBMZu8lm07zvLsJcMV{wYajI>jHD|zq4x$h`01n z(!`k{4e}>T>CEl{KZD%4i*v7#`KD;{}2vJ8;92dal;G|LI- zkH_7KaXILsrWmQEV*q1hUByOY97>XSy|bW#{VMM!g!_;oAsuK3qNGiI$cfzD= z=?A)0G*p#xi7~P zE^>7=^CH4zdlmIix#5Yuesiio5exB`?U$$Y+6-=^e&_Rr4q=h(cKBKATC8iXTQUB&4W zRY-NLJ1AJF4yAkM_nxWQI06&rq|Clzm^*mtG8v&-m>( z?-Qp#rHCaU*tEJjCH!M zkdQ!c&R=xnd>p-iEu}O=gvLu+I#uPNOeryUWm~iqX{edhu)lS>W4&LwH#`v7I&0f~ zJYDQCzIA#;8mk>^oF%pl_?f*aL0SU@Dt&wiw?9l0&xEF?-%$jq09Pm}H1qRA$=205 zog05vY5^bCgA~oO*4EbB3(c)t;uo~v%X{HwyPn^FTxh5+2&>ai`skM) z7jhb_%_UMiOT7I)I%qe=RPN}i=`Zm;Md8_wlI^;q$jz5S^dV2L_^D}wM%HK-Up3i;z)qQYjVji74Zro&0HHDP>pavn9$ zbc(B}sPxcT-FXx4Jv_xu-292wR@5eILvIO>LDI{R(O1)I|DanN|*t zS5xOXKI}3WiFKl! z6ZZ5p&^L7N(GN-}EdvLjR|1u=+c7*#ZcJc-R6o6k_e=okLhbfz{`wwPbTosu5eIxf zMw(hS(!UDj5|xx(-Sir7Xn0>w8((r7mhf&CKxAVMEoYWR*D8AjXeAxa*jnRMJRU`i zj*h-f)la9&`8fZ{#%-{CI(r-$>h>yS8orxKP!Pwe+Mdm<>oqS{2@Z+)WGu995%n`a zEmgLjk-YJ-D%;uX>)jRccTy0u7&&(gNseUJ#LWw@7S)U{2_wToh4Yvogxf5)~ULjk)PMUza8Au?S zn`K$q+2@CHHSFK0@}S*G^}yKRA8Fq6&*1{lN$1)KP=NvHwx&F&c!{gPT~D}o%24K+ z%4Oc5s^(~FE^6jkq=u47XM1VySQJx@65Aa!&#w=PpG?(W*wK_8TUBO|XApbB{dkpR zQuJf!bf=zne7&wZvTeT84NE&kPhOCP-)^ z`x-e)mC3LEw42+TSbcD@H8qhMYFbD}zTy$=k?{g+jiU^ue3O8MsRi5zt+<~L@v_idiFi^FrieJB7gW2D`a*6L{9vWnuqbnQT zXY3E6sunIjWWmay3@E&=Eb__zQHC@b@)SBoS0Iv@{QNC_-s7SkORo#QfciKGJ)2F;@A=F*b7Klq8*YmL*Yi zJe1hLe17p3Nt!5z$)|CI;?Q9Qk^}YAb9IX3MOigvzh3h`OLl!oW1?R`f3fWxPB;}K zl(C}w%5mq>xQ6<(C5=a?53^lBI0zuQ`StP!?Q)(25~ZWrZyylby28oBH(yMD+Wgp; zj6a@f{Aj(s;fL}2^ojkvNL<8eDr0W(!tLbI(=_NnO~L71%+g`cO{XhWe9A*5dw)E4 zjzJ&Z+e-~*rI$4{P|qz+Gn4W2nHG=6p(iIM)O_LE(xtjK=`zUBaYN7A|FMmO4OZ(s z^TV=iGfY}j?GYv4t-9xpJ2E=OL)|Kl^gf>N5>O3zO|}UZxBhcSV2Mpx^Hrc2$8Ldwlb@Eue{||Ki}#n z?GddF0_tIqRY&?HMuh)$j<1?A115y@al~g!I`onkhEj9WjYw{H&3J&;I_zgJW@)@9 zztk&Y`O8>7X0>xUDF+O7t9vLX673!&!)|^5RvHtP6LK%!O&^9hJv1N6g3?otJe16q z6o`wbvm7oLQU5|XRdoNeYMO)Mj{Nb%r{;=Dap3qH2SM+%W|~|ZJ-P77m4G3Vg^ELa%hJl@=_$_Z3p%%zRv+iHO#oP=Yaz_K;u zqt3MD^U3%IbZDQ5Bx>(}^okjOR5|Bmx?qt})se|Oe>kz^g3hS6Z{^P=33SNz^( z?0-K~lIM2`2_dXB-lQ^6uLT+5ow{NV8#mpYtM5>#+&4(dS15dZ{$Lw^+j2 z5LaMqtp%HwSyxKCL5P93t2H{kG4^kc^@MZn@Q!`I`Lb6=?&Fl7Cm|{IY&K_hQ{hMF zpUVd}rY*_L-&AD3G3t}FY{i)f=JHqsYOShMeWN-GKdme&wFZcwl(}R<8u{jXFqp67aoYZ7x@|iCCy0qxQ{FkHwHg@*B zdy`~2?qPLB7amhnH)O*r#;%@%`{!-Q%S$bl!>eE{+26Uj+rLzW-RALZp`oGn7l!QE zui2Kt!Kkztu;%Q$7%@Gkd}v~Q|Md&*{@)qg?JQc>&v>PBCdXkd04uxmga-}?(Sa0H}euk{KH1x5^aq%#Zc-2#}uT=5F zM~OZ>*g*OnLE6{k4x+jF2t$8|J?F-%QEu$8C88O)W`V=^y0RP;`qM+wd@|Ig;=$KO z<^nyIv~kIxLyM)PmQ=GvbwYs-I{EmQmq?=(-sZ+DE*hR$GVOEQ(>+h<(P=nC;T4D8 ztVHJoS>~$21}-5F509!$`YgzaMMl{?82KFYt7&Ln5)idD>RDuQ zGb(fpS@pJ_smGO#11Ewr2#T5dJou%~GJK`&tdmJE_;b_hZuHM#j8%>x|3Ll89W1#? zZd|CiZqdR9VU$8YC-#V_Dy9`@mPe7`3C+JHblVvww7kI5^M*qQr&DNnZW)^VqoU$H z01pvWC4EiDzh>D3U$H+PHWC|5vu)gM9WuuWIy^#!KyOldi2HnY>q15CE5Eb9O3lvB z4xDw2V2p>86o}sggl;)FEr2)>%!YU$x+uaP3IuE!Xx4Qz(H|iR5t(SEdOjC}zeNlT zah5ka>12v^x&CB7&)WV*W}A>q`G8#a{B?^Ljpycr1Vk?+$12=DvPRr+l)flMyI8m5 zy?X>pP`?WZLI3ZAZR+)r2*9<7Tlw8{>Ia#_Ya}Qb2qSXyJj}UfikHO4Vs|d4hIuX! zw|3sMi+S*Y+b1EvpF!}*&o;N?Y*OTlTGwGl%5d4El^$9+^lMVc>*0gQYiHjx^+QCr z?2Ko}GNa$0T|98OKNP~V(KjHod+l{)yd(ZZ{esv;QooN})KXmexnLF*6}u9o$gR6a zmKRbTQ*D#BPjJ3#{QhWTdh)giIF$Nxd!{%M@6NvK$8@W&V)$M=>*CEGvYSpQUU>8n zlh7j*<83Sjw<_v0OU_D$22z@W_jgD#9b_0^ksHo1Il;X#befv_JM+rm;qC%1jFb|r$9D)v|SV$J$pr{u8( z*->O1yKH5T$STR+ zhhrY3A~RWq^-uHWA81FJ&ti4^LP6`&-eFq`LE06a(q7b{eHjZK0H1-B|t=| zjydKzz}=H%&B9iyW;MS*M~jo)l@8YIko>B=K0g4HKyEk>c&)=O|87=;Cks%>KK1Yi zKLQ^&802S-+y&IueRr+7`dxkVk7(yPnV}V|-}x8^-8ALi_YLXgbCprWrBVk!4*u*p z#JiKZWzvoiA7w=2dWyx7RkewkII)|v^UmLCb|mlipxoEg*m-i(_<+AG#RmD-6(Vm~ zJ!;vq$u{25atT8uI>ZB{Cth1w5m87V+%^E`RySX<1@NxCK2+m0Oy6@)D$V(8^=hWt zJkzp#C(rWR-z-cp%C(K0>Ls*C8Y4ZI!RMK2ufA8md+>qPkz`J>TxZy4>X;s%{;GJ2U%aKdfOVnq1|F zdklPFz`OM)L8naDtN6NGnWovLgJ%hu$nySUsh);Md!hL(ew*Bh)r*vJcKOc8{4I|< zeNOdq0hx}OifAv%le*_-RZe5+`#ik=if>?%*{3*@5AwKLOM`NK(*{IHZXCH{i9Yj= zb~4WUyUCzM2;EjPCVzd$#(qSl!FR!VodduSB$A=4UJ`<~jZeIOLUoM(VE1aTyEBJN zeDYvfk&M?EINOEiGkNe+zurQd!EvNBWm4ES!No?u4$0kY_`X=;tl`9L`_Vct@OpeL z(hgA5mQ{sqai~+y@f2yB1X?KnUY*E_3GqPXBaq|j^8FM)UKeNavy26+IL%0${il@ zIIq6+u8*PIX(zh$JuS-_dbK9U1|U|QpOp}9qf0RHuOIplSe}ux5iK90yys4{+M4;N za;8pmg^?l;ehvTSsE~H6`ZaB0+D5GC?De@_AKxug@L)gNT6kJq=6Y1LW(CK!enPF} zVv(@f=1Y*Z@fBY-_MwCBut9wy*83>w!jSmsu!h*L1H?&f&tNBI$J6inAnFthLihHk zFT&CGFCN5xjIfBWgr?ajISyas1W+=kr=LGe2e%%-I}{rCo`cB{BkXeIAafl>KR@u> z^?T0soFx+H%E6@l#7_y=q0p=t$mZR*z-+CGUiOY+U4sT{5QE($AfU(+4s{eDg2pMu z{ASsU8!|=Q*#0(fqR+bO8%G|)(HUtqI9JTq$3X_Y&#@d`bS*phQ+q8YvM5k{_8zMX zi&x1VTu6zt6bsP#0};1ie`s6jd_3(5+|;(TrX~q)>8rxWaGal?zh?5l>BoB&Q=_mG!tn)c193D>HfqQFIg zr4QL(AWi|a@PqGJ)?ea#mgDXhVV+*rIS#n#*ZpAAT0+tbbGr&u7Ak3r+; z13sPV$M;cQ@{;f3F@~e0=S3vUc81CcjsC@SN$YjA!ZdVZChEr-*=wlcIrI+{2~C33~xl1tPls|gK|BB#-a~* zZCOdLAKMqws_nqVKzI>+@50|tGwXer#93KAz_DHo%db&l#ZHGapFcQws}884#*(6V$-Wv zFxSOv&yz+oO4Nis17n}n=a1My>RgkU!pia~dF?+dd z)U4bBsY4n2V`N^%Q?`b018e2!4u>`db^gWaSytw-cs#JVon^yO?i)4rB*cCq9F<$ zT89cBZsJlPTsAjiJ;R*Wj=3l#1V+r@ZFHw{(N#8dh55H=%ff$UTP7B9x{A$=iLR7eBC8c8C0{FAwUd=xORhuHGYLoYgGlCFo7V1h zX{@_Ca)eLP<}Hn|47?>@F9lKDc($h&N3USi;NWmq@HV;B)3gza@xX;4ZTQFGgLF-Q zzB51z?A|AjWk1!1i#Y7n6MZ6W52G#!2wud zB!UWC5k)^$FrQt5a@!$C84GhpP(3b(HM1@U)L{6>sXzG zQu1;#Vx%E_*m7I((EEMpkPs%Ies{OU>*8>XWDT3FDI3`c!#%zjBDi>in*#+`_O-RP zikDyptJ1oJGSS%Q`EQJ?{C*Pn)C^YpbUA(9%Bf!cc`M?p3de~hjq>BF_RK`!Gz21@ zig%WGZWBtI{LsxG(E>p%4I}@>LwKn>(Lvr~4S|Zp;nvlwy!akRcq&++R|Wb~(vTKT zFFlEV+aFB^L3F=vBM`1?7X!}J?1UZ78&BFhD=Z=ci@XP(Dwx%^XsfSsggEKF9Opq7wYw>2T42uc4t~tQ72(itUP{ z>vXFtz$d{m`YaW_#&k1PdBxx5WW$%kSI??wP<2DshnwuYv_V}~8Ka1MQCtm*>PJrE zC^9Zi-3x}$*_G;RKbr42`wpY6_QSBYZ!Gmf;O0u!^9SODZ3euODG#-oi!9l{n;%3B ziqn3sG7}0nYi>iK3?j;z!$RJ;J-rlq5UCiM4pg!c9*R5YSLceW2B~B}H&?2JdxzS5E z>tp?2Ex?!8JZ_^}&3Tk*77u$$h%)p7qVaNOTl{%DmRu)ifk7&5Yy;8tfm2#v;!Enf z(3=_K)v^Ui+hO;*1p0)cvl$_m+v_Na(D3!o7aRU+V$Rl?{RfcZ^I$luQI^}+W^>*J z=fCke4T)ug5iV%@nT8K@C}B6XtUIEjqF=1&w`Xb-$w@}6U&f`L6^GE56sOWGN$p*o z(*-8&l??}X@aE0yc0f5M60DPZ1C;Gcd+%d1=1Tcrjo(^1KEAuOcl`X*&-WsZjS#|& z#q<5k%|sUJwNDXFtnv&t0cHN)sf0o9ec{~?;~8g<(gEH0RVHJ9^fVu(xX4!=D(l>T-7{Srg8{c}G0h2I2 zsA(L+je8JvOyI=7!nAS2dyiz;KBX}V42*j-*2~5O_3a>&H0TU63j3H_PvCG*;?U8I z!&)jGGSyxeYgfXdJ$x(r4Yv*wv?p*)fL)AXUqG=78Hf0b7sd3{jv6%j5m|mbH#F03 zne3QEyuL_=2p{to+e(VVj#G-H*rmml{kPYxW%BVkM%VfR-Kwu_5CFM9kPgPyEGG=z z8*It66oDC?Nfd@3DmPOL^oj9e%QcF7aIfZmlyJIz%5QK>$=^ahK@e&L%qy4+hiat4 zs<8r*$Wq@F+WyurIQQ;%K_$a#Baq4mTvJJ660?4}LyivK5s;2!rFgY3)|x6;|B% z=1n3(LwT?pojvqrDbKycMy4uutC5*BkiSKFMfH|i*CUw;YNp@uSrN=L=p(P?ewGB1HrpcA@Ph@8se(~)^-c~ zICQ63#bR%ocG z9Mljin^-HKM+EH{dWN z=IB3IJOxU1+1&(@VeNb8)&G$`yiQ;G#Siqw|K2Lp2lO>7lfNzjam+a1Czq z6Lz?+52E=#>PuWPglG}Zf73;GDQb51^m46fi|e<#@(|)mm7NdUfZLE2UC}1^K&Qd&L&mnkyeHV zcE9kl@vlLCJV~2xZ&_dG1%MMCUU0KT(5NDwKzw5>qCM{hwGx(w-pROFQav37M}iuMdonF}RSX-X1gu~u03xMUAR)C8 zQ45lW^nvsD@t@@02OyE@x_kDAcS(CQe%aAjZ>3Cz-EQK6yGkA>{xN>W2HBOp2*kzg ze#GnIu?~%5DJwa!=fC%jvjNn?I*K(bXDBtBWN z+A`^m@jZCc=-2jWF8h2*5{Dp%U3akk@XqLer3mRGc3B^84?c2x>y4}vh>6mfq3liU z#F=vHCU#LeXAgyX_*x7aa&6pI+SjI{IWSd&d1wr37aYrxpi74E#9gng&+hwNzjOLW zj_~)R4PCARNik51=jP|8AA|k;5;3(`SXA`Wk#a&N5$n^7j@^GD;xVcZQI}3lzLj$m)H(AY29`&bmIFLZ|WyW~_vHS}b8UY_Iqd6>i2w;qGJ`*uQ4_ zZ(3*aH098f2fjR)eK{f9(&#mJDl{|I;vn7%qqRU1kM#1&`bU+LZGU^{V=$M!(^*1_ zEW;7wU1Efh&Av$QpS#bQ1zBA7@mvN<*Q@k!42RbAyI-H(5x_u;3V>1I5%frVU+lfivjhMN3(%xv~Fw-?IYx zYa6R0^iFJFrF&C#QB;(6{v3jFGpCPSr<@(}r0a^|?i!j(yTnP<^ttks*dMZt;0CH_ zx=4#rYxFa$d!DHs*2}q4{d>|C2QkIwJ~wy#SH2T%HeV;OjXARrV=!_@#7~)loeX=eajuD&^V~GZb=HRJR=fRHpsdfGAQ`YHz-I_EXwZ>wzj{4?#(iggo?UsM}sb-cxRSG}e z%wXfhof|%gjm3Kf^a94kNSx`0C*-7-{@9Z^ivh_*0r~u-Hmq+N;AQ_2nGI2oFW4~; zRu0&3;)d85F=Dp?;OpqJy z?>!6?2kr8Y^b-j#anIRAP0j2o%DdutE>ORSu-)>p?6GmBR=AipBroSmW$lxg030zF(IfwrzE_ zxcyOaZlnFa?MfpJ{pS;;|8q+biuErnDN_K7DoQ(~ef(4(xXK>#xwwl;OJ1XWJUSCwHWcr>5u^8HS;EY{R{D|x4 zik&CMgPZDN2Tu0JE5>&Qz8f;zk zV@m-l`G+?}9q1$rZSExuG>AJ{N>UH)!7jJ&w(PNZf4C`J_K5v^JF^<_O?88(?oELn zF9@|ENfb11he8x9r`o_wr;9Nvop?STk?-+MMVGq&HLm*H|Lia_QusvkFsdRJt6*6q zb*Jkl`eqiDjSr?-P@(rmaQKX`EC<4QU^}b(Gufd8<>PaJ}^P|=@T+C zIKW5?wZMU)1`uh0eWRUhgV47E-b#Y-O@=50Z$5yTj@QWCo0?wN&aam62?1G=T$%su zJHX3-yTC4XPfj)4i*3(H0#OjE;Q|78*=Eyw_I}Gi`QwmbFog&|(=O&aFc-c*VkazK zW$1|Nd(I$#X8v#7RmRX57ZC6;y?$^S>EXju<#U@uJyHhFwW=%8vZo!AIfy_#8uzpH zWyEgJ$qq$>Bl?)HoB>n4SN``#Km51Xm+@0VyvvP+drnL&1R0cg^B#DK6_s=Z0=zKl zGkZy!0#}~WZhViYL-$nr+p>oKv5unR-~VIng=YTft(GT#gl*r#o{~&uRr`6!y)gcb zsFA*RS`_8bJ;MGhUnSM|UCzGgz};Lz*;}o?bL-^{N=tj+EAZt!$V2@vY-%%}3p++P z7)DB7)^n$|U>Z^Hj)fC4o9;+(90a_rdS{eiusCX0PTgt*Fx$yVhO3JOgv~=muj0n? zMtB>}mIVbnm6tuviyhNn&s(b0w_)9?Wf9!Z{j~i4;GVJkOTB<_l{G4=QYyZbqk4L5 zLj86)p7}!Z^zX*sFGFm#?}SQS@=5x*X4v2R7Z_YcGb)r$Tnqe2^KFl-4dp$cPTDw?`sobC!3M>eKfxzxP-Lm@DV2=JOQ;bq_4@dRA6Fxhr_dQM!43Nk)3=ooYZz%s(@eCajZTTS} z-hgs;SfWr|b#586B;O-=;BzeFeTD9_M#k=E4D~nKoBCW9GqWyzD&%EgX3fwp4)J+8 z)gp_@c-MS-OTRlZKAr}=8^8weaP_CnVZ>mo;YS7k&o+uack)XdwQqM2Dyvz>Pu1iN zY>laC9DmC-!DLd@Z%cabMw7qDLOSi_c-U(3mINHk+W0Yx<;X<6cPyex=!I<=avJIz zDqzgenfu{y2rA_>_68(03JfwS4yx1bAuE&@hBXqGm|Ew?9gzc=t;?_nvTE_ioxh#r_;yg042!YoPa9-VY+*>M@qN+ zSad`9r$M$wV&p#1>W*hr1*tlRsj5C>(*!izoJ~S`L(!&d=ikglXALLW1-P`3XrN_S9{vm~xC0 zG$pw89)j1ub@*#^jsJ!Uk?&?KLr%=oh&ZKd%bZz1dD;1&G(DPp zwwyZ1X<6T~k%2uXCi74sEy$u5KWxw#!FCcc_@OL&pvw`l+M2bn4z*;9)A*KeSTrBN z5IsaM$?8<8Ir&z@Al}L$TQavy_NQAJl{Kg^2@!{j5sO^&pup+aV=U!DSuj9f~xmN@-ha~ zq>;t}t;_IUszaUTfKHsz-6&WcVYC$H1}OWBg`@UkIYZ9R{p)Zm$yKl&7Ee!4Q1l$K zv}6e;H6rV4zdDJ#qw#1{cAV;V;SAbNJ`|n34%8(?)c8M`D{d#9 z%56`sYy**w?jkQco5H)Nx$!ws`(-Cz_9M zz;j;bw+sHNA`tlc!Z;ce12;hQRXi34<|aUl_4RjP%d<5y&sLb`Z}|*{1l=Pm<5O}i zP@2i`TV5)FXm{uYtFmwo|A9ja(;o>KXSHBtBb1K&rEEX%=rX0ECE#5I5Hq;d<7R9h zLUU3no)Hp)Fjpa#4fzX_KMuVqUkeLtLk)b^(5tC7PFnB&9QXHFh(DJn9-}`i*q`-C zq(xv)3W^-WDdyI(=91Z4c)JTe%%wO{qX83vKWtH~$J^X#9Vl(N@G;pZ$%vb)HnI&Z z$4bFnDJZ-<4_4NbRT>i1vP9@Y$tv-o+O?rBOfn z=qn04qgOtg7xer-eH=lxMvkQF4oKa-vlhAPuXr4J^WOAGP(JLKr5k2u{hro4@$ici zOQ`Gjg7XFIdQ`_C+Mrdk&hU|V@ZvuJMt*fVX}iN9(6>FVu097T zi{M%6x(NsjW5*2aZLp*@|in}PiCw~5s$B7uSn_N znjl$Ody10Y?iP23=&AIr2E8?fz)=9d##CqrbBG-s5k!4?j9BcHd#NW#c9+1<<4x_K zk%oNtFJn2I!)rf87WXeqPycQjvGQdfdb7pjJz^jnobcu&xTYbTtw{OJg=KLEI-cup zIM?ARyrCH`=@1wzp%gNPMG+3;X|<;Z6-ZIz`#aY{B+rdg(Z?f8OG0TagOcJ+qbnzNWtk;Z9e>jIJxBw%vtR!=8e#LnvwMqm5D%T=`w!iYh>1E>If13~;0 z{`>898^0#AY!Z1e@~vR!aGiJs$WZ$6KgXXlg76z?!elIb};#U|D7J6L>4&G(;} z2dibhKgI4WfxXOYzgG;1FMy$v_OV-6aLxVLXapmt8kN{4kVtC1xq}DVDghZ|TTA66 zsDyq}`Dj_##3S=uA6h?ks2h0->y$uHLU+q4Q&jt<{>O+45d>(@Cn%<90(TzL);_%YWl zxz5&)7b!_NVK%FabhiJAzTg({kfLd{xfJ)@jE3+WGvSi9-28l7t`3Z{yd#^pIJYEF-T}iMw%MnOxz0GEE~ce@`?eF z;xR?PJGr|($HiFn-z|D0lOoEV-z-N#wKC$D>o3IvsIpIKl^`tZQr2_T1pOUfQHoKj z*#aP7f~HFiO_D{3(}l5XH|*;}{E$eAR!?oss%V8%hAx346#9$hjS=^Ux*i_VRwa{4 z5KXDQrl}S<6`hw>4{~G=Be8L}LWS0qpE{Z6i0^AYgf91)-imm=KfJbRUt-%|Pbvqr z+Vfx-alY{~VZvq6W?^q5iCYd3KD}$j{sz;En~Dx;j$?2iW;NmECm7Vi!fObLF(GGn zV~Q{2`ai<9f19t$9;=-K#~p*@&xqCh{TEwrCm9NAfy4@wtq9%CY~2I{or8me1(0vb z>J%>Ss{*MD*vVj0&tgG-J_X%vFt|vPESHI2NMRW2Q$@kN_UOkq7*XJ68YS z+r;9t`lD?9$|Vzl@~KZHfQU3eZ$1%zaTw@$i-&;cU9Afv8-(KK#kWXV@VM<@V}${@ zHP1Ec=Wbi;+{gSiZ(Q$JKIStiTkrOe>|C)ya|$8Zg~8i-K;d7_o6gRH^vil)QsRkf z@ruk^icig(<9PXJdpw1{w7BY7bL&{GfapzM7Jjr`1QGx+3h7k z;v}LN?wWn$Yv0fYIB1A2UPuVPPP>zn(;EP-gWm;F*;Y6Pc0>@~0ruWK-$tyj*H-x$ za1%xYi312r`uEZrIsI$&_ez{U}mI8~q6r z7)Aex>d`P@LC~Ds4OjjZOe9~*!~>`5yeXJ#-QDp4ylTm+I64qvAM&gJBSsnhVLwea z8+9jp7h!i?%dh35dt@ssb+akB6LOuGBTi=0km6;o6!h;BM#VLPuHvJk;mosHHdZRu zlC9w&pU7r)4CHsn#`O;U0_4Yb@6rjAyQt27E`Pl!ZRD?qri$5o-s7~(inJrP=y+DA z@-IY|KP*qu6qjip5!tS~*#a3}isru(1LpdNjOAafKg)WH=3<~9RO`vjqP-HaUZ?x_ zn?KvKF)p{3>9D5nNf%$h$K zfYrpT9G-aP3irzg^WJ6orrMyZc(7nVQVF&SX-K*Uh{=H)SJoMIZ$S6aIZyT9%kEsoA9r!19F%e)JPZVdRi+d@*>% z1G}zqi^D!HPgo-rvvfdPs61#Uj^{J{1q}HB5xcS+0lBSs@_GMg2WtS+&eh*#CE0mV z-TdUv#XQ9YUU9<-FOXDj&oxE^ap#3!IAs*!21ozN$GyAsfdyk%j7`YD{zHCAqqdAC z`DdDj*LVaK&wjKMdOtiHZojhnN1_d46ny8)w><&*!qr zTu+YctOKMhx1P&66?H`M=byaGg+55j@GEvNu-QyM0y0{VWRgV#0bwUgdtO1=Wrd{1 z8+E$=Yc)z_8nhR*U63q^oeXkaX;h&(sGnPe5Rv2WpFTq}r?s<625>qa zcTfK*#f|Qa%XReGK4mJesR;wkh>wZAMMnk(wEs9jp>DMb>lXk~?z3K!99hdKGi1@3 zUZ_jwQ-wZs(cJ3XYq^x6P-X4CZs?bW|ES|ZU0;pJX$%&F2(t`oV|$;#Ew`*Bu*UG3 zE-~J?xbhXw5KZjCx|89aVA)~aIb@WORrr1QQ6XPrC}MS-^98#DRj(%IeV^+H8uGJ- zUAdA=o1x^Prtuq7=(d#4ImD^{#7^8mQ08cy-ZXPx6y<&vyCCFe(9>)8L|Qqizq!>h z+^BKz#af2j2Q2QJ{i%tvkgs9vO3I~)<_VMgtb0n9yB|pMJ7pyEv!Z|f9Cm!E67BQK zgkqyA-%NHDi>kYr-@T2hLrZ@~``=%kOX}VIe&r1Zoe&}R?L*3MKnkFj;@(F1%jA;l&upKwzp!nz7g7l@lz2WnB;(r@`kC^d zCYo^ByyFD!tQS}DFg#ST{sn{Fz~W1_<+^qJj_k7n8Hy9JVVIn+lQ`4QkqEr6nk{=4 zadElWoQKO#uD_dBT9A&rG-h?BpX%Whn=v-uqH72_*FRsa(BcfyLn)o_yXx0(qt@z~ zxcsv>Zu%Rb)Alp>V=jK~+>idP5mo+%WH!I<&VsmOE^Nl{8sd7tgJ4 z+Qffz0%3r88G^Dya zYJtD;bN8NjHlaC91>;_m(U&fJk&1IOecoGjBTY-+<$)0ufJUl3!e83b+hr&|zGJqN z<8HE$q-HC5I4DbS$bZcy2EV0-CheE=Eo!E>wM((sJe_`ieGi5_UDc_-I>7tf++=>( z|LmAG_36bl>j~i66U1T#9emRq-&Gzrs=v3y; zg7s`Mp7M?rGkF8MOw?-H(pun5vmnV-%OBs7uB`dMM(?RQigm5!Fgz9=m8CePk@j}r zP4S$}t^_a;AQ8=R-G*Ra(L(MJYEBTa2@n~!RECPyIDW)%$%~-Mj&qI4#GGbZOE5EY z=QAKv=SqT(runjS6XSjR9-3#WNzNBcRiN>h#dq@&&^Yb1&@~<_)*TG0S9xsEUV;DU zKIYBMO$#80pl_>yJ4ne83OVE3R2r*}YW4NA>2W<3F;f#HkcAs&*S_~d-LUqjL@HiS zr(Gw5-S(}goIePb^5|3A55^QyZ9Ou+*4qT)=j?|EGdPGI(L;y%QsTdjYl`Fg^@GE$auNWO$`;K3jHk;H~>$7 zdln2}Awy<>{Ga^xjspCMh6dRw>S_Pn<4ABAg#cG`W57q z0lx`Q&w@`9@u6OoiYyOLo6MnS>duf?V|teZo=? zXKoZ>dgzdG6wG=d1l&zl1=H2BDSfE|Aj5e#al>PJ?Xa&u;71%SVPPvA^8{aXU=o!`o&Qnxty|IamZzwNqd=vy#y;s zyx98qsLbAUYx0QQV6&{yT>X1!8lr%&WsTdHQarf1?Cji(LbjrT9FIhm3SuUe(QZ{1 zMZEms4K30=Gh^MMFTjIs9oeT((U8A6wz=PlV_v9XpZTN1+s5~R-EY;exQ;jlQpF?a zclZQ3&@xw9QSs~d?-+;U$Vf6gx#BVP@u!5_P(63-oi^#P?D*N)6&37B$`G3dn8cl1 zVC&!P?jflt)+QYCin)m;qVP_M*YC zwreie--Ukd0OOs5$yC|-4Tg>nnmx;plX~CXl5-1Jnb$L4{brNQVf3Sc7VbIQxj%%L z*vHj}1rK(4d3omP8duWu2cIw2^9M_#RbyFgD}!M5Bv;WL65>tKMa9T|i#YLlgjqtP~%?MsX25O=|G6Ryvym&_y3p9tD+mX>XZ`5yV8lLax1g- zzP2BG!Nw6446bzo8ma!2eEC3KtK6Q(L#beJs~haNJc(wF0Kg@P)7#_Apmcivz-wXh ziG^s3d7+*b0AFoa6)?r0MtD4?}V#j0|Sy& z^W<46uC4oCs$~SJR!1zjgjzD-J$^XpToLVo8&~QhzTEzF3-^O5P_IIsjHIw*WBD8c zr|cg)^)o>Ur$dWeq~ek1{41yExv<9bSlQ1x2XI{CUgX?yBuU9nUZZBf^A0>gX=23<1;gDASuJ;^5Xoh7TiIc-(=aVe5Xqb%qKcn#WYF@6&R=Y%!@uW6 z`cGxP32bv+SgTnZ-dsJEo^PAu$mTc&d7e7EG3^}8*F@N6(uV%sTqa)k?BilKbVSN5 zDb=piFYETEkH#0qaco+a8!LidX%L71pYlKX$A73xe?>#zw!m0#sx|MOyOn2Wu{4Am|0~0w6j;kok?e zkJ9%BwO7bsClTIgi5=W6#${OIX;C;+rR}_d?V7keP9fNLUBT6wXe!Im?ZPU68qHIf z@@YV7tfH1OXYo8^J2$Ngstx`{!&DEO}lh1{8T5EPjTEYbxDYFBI~Pyo%&&i;A1!2|?@USqnN z3+~8EsRWv37@3MYsfb19N^1oAE9uR^BbbAVMDcM;)SK zLkTmIBX)VEH_UAUfVY3Ql}Z!bsq^uMW~z{AzsnwFWuOBpGC;L^ujXchyX>p3IXZhP zK(?X!b0XNC1ZDQFT`cv!D0t(#?QY^hI`hzKz#=gf;HSUHx5NU%DC+J#n=9wEsOIN zB4BZS4k44v4+EsVc5~MbpyZJqUX}r}T?`#deSF4=O9B;LhF`fUs*3bC(@Tud@|*!2 zjnUDGO934>iiGu@SL?F|yXXbM&j&p;UE9+W6QHX0#Z9JGST_~J*-w+#a!(OQkOmFQ z#G8`_M?*WGPdYES$?o3mDj8z-hmsgcTYg0i%DhYFIPa?PdiojT`GG4w5tvFR!%}Xt zJinC{5cE>T-))-}9Nk1vkssmbqo;bKN-yP4a}RR_GTjX}KL5*#&c*O=jL0Z{QGCfWIBT(6PKbn|ODgf)W-Vz=y z{Rvs+^Q1hePZ$=(6KKdq9x$eVhs7nL!Y!;RW-$IR=U$Q2k1!)#a9eX~RQ#YyymYbs zNh%fF+9a1OFoz~wCSftAFAA`NdbZMpr zc01!}3wnjuL|SA~`*AZFWtj61U9W0P?|6&%JoeifgA1_uA81cE_%jODAKa0-#G#h@ z5Rz5C*oUBpt;9l|N&qPZ`2+il=nxrY7SD@VdU;ZHBCeBa^C_B9vyWszs{b@@E=9TS z*dxnopteq?TQ%OuiPTn7@1kmR%=ZwH`b7C8cQ5_?^NRBD&W+Z6oXtgSwwDrF;0MA^ zd!R>FWuZKv5?;+yexfI$mHvq;c)i9yZa*H|a!6F1o3bpvRxO#--09c@Zj;Hd7%#{Nx|bgV3=|kD7^ukZ=;!M*F*E;| zaCie|?%?lyd#j{YX>yS&z}Pt0DK~_bG^e8e*EmTz^gOT=Hh3Nwt&ft4hP2~lf%sWZJdxf>g;_8t|eHN(mdx( z%jd+ursSz%DK|3{2@kpDD}We)&+!W00J25UKFN3A_cj$T!Zw*SqYg@V|1&Q|}XK|_dI*ND}qhZl#idK+nL*-E<^wMAUT1nxu zJDZnY0(;fMZ)H|RV3+Y5Dw(ITc+_9WNB>P;gFe58@6VmOJ|E=iBHizTy310e;yxj( zihuXM)O}jF2oJ6sMLv-$KLKUiu`nWn{r)cmRN{6nTXZigznXlVzito7--wRa85ZhDsX_h^f zoy)@|%jp{is2Opo)*EvEQN8Jp^dZMp-sb6d7E}vgd3Qg$zN1b0<4~z8joWL!&g8A6 zjX&w|ZFTDjRW={swc5Lf`U=tpdAJL!3}X?Y(LuWBIggv>ikI^J=y96U0n~eWQKku2 zJl~#86i#uLqU`Lo5+tJcWOkyDK00DDEk=m0AbVP1-=f+A!OMSE8tgubVB!N}QlnPa zq;{~}&WbMw9;NIjV6q0Amh*^V>EM#6)>uTRS6BTX+Q@o7z$)-u1&?RHOIR776MrS2 z+=g^djOGlw;xY%*|LP52{FkY#FMk&_*lL5*!*`N5O>eOUR-Vfqq zGiK?N+F)a1e-WJMO&djJkFS0Yyqd2}y$nrMpA{X`~yZ zqy!{~kP?tax`qMi1`&{MM!Iw88fxgyZ}Xn>e&_I;i+E-~Yp->$JCZ(}V0U} zAC`?j?dLgO{^P9v^9hJvj z8SnNR*d}00YdIObLuuBod(GXh^C5Y>7^1p|47-mk3Z8ZoI)^c7 zM1*XyB_R4S4I-C0T@xKxpBsd(#TdG}OQT!P9;lrAPEJ82FIyZY_9ti~tAdVi*G80< zuR;2yj1rpLK6JMothY!punSa2$4wDxx%Or}O^$W4aVP+(gQ3J3`;1>{tuQk4V5aBw zas^tN+tofdj)2${`@zH2OWW9i>qoev;gZ9&%iox^tUHRq}Pp~S# zqe+2oi{b50xk^XWIG$k0 zU-n1;vW*JxJiZaTlDv{b^FByvf=F}~U}zXTR~~DojiZkvtng22slxNj|79E)Ft=qw zMlL*U;cD|2eT(+P7V}rrcO4QwEY>)2?*qdyZ6iwk%6}-;zjF%5!^tkbQN+m+rK!Z% z5-#+Upc3^4TM-a|>+{qX1Z(L;V>Uzwo920^VJ^t)U?t_{M)d`eJJf z%!^);Td(jqXO+XONcaa$FV9ji+)rSg={R3U89#Z|%D$x{L>v54jgAIbUEr+3_wncV z@XxN0Vv%CU`;kG*Ng@9>K4&Yon>?~xx9i@z+6i=0lRldFw(t@qO#MHsO1iv{rHK$x zH#>NzY`ti#HbRA{!<%)t10^WD@wYGcy{Irn!IaN7oYs!s-ZXZN=k#CZ8^aqK8dg%5 zWZ%OjYlo!?AD*~Kxl2Q|b~S6V>vOVYf=D(@i&Z(|Cg8s=cv}^E)?yAKCNi!^&&d~G z^uzy6YCr~D^RLvU@y->hu~uCLpN}S{^_g3Kv8<|!ETkV&RxD%)5gy_wA%6&sK#BgZ7pCn;$^gKOAxm;78B^ z0AFe@bVKY2fySc`>n=${o}=e&)>bd-`k&KOK&_r_?JD{|zhDu2=g!wUDJu0XK52Oz zhY1K>_ff-kRdNo0>B-N|3WbkMIbq1F+rrk{|Tr?;t9e4QP{Rt$*5 z)zJU=AXPAg%pPzayFSPnI{-VPemI~$Zlu38-^8?ldL*N7y@l_F`^aYvsuLa7G2@Ar zf?$X`z~2WZd4OC|nLYHGmGY$`7LBh1q5PgmL74txndmq3x`HvQUxfw}q5|SVn4`F< zygGl2N#KbD5`Lx@@K@kz*jB)v%L$50+&^+G=D-;Mo%q7=FCkP z+kW%R^i2>>uAPld)-9O+x`Gvuc^Egq+4yB7w=TkR?FxxT!0&9H?^gLf+9dse59tx3=|I*M|VWEc2 z1S<$r&5by1xf~b(ZyxY-V*2s6ad|W5$ByX4AKQ|x(e(uj=XK7g?p@INg?;J%35I0g zq>&XlYAjEk<*PWm6v2aUZbhq470q4JmAgs1Cd4i2=afXZJ2OUWk*_BLYXNQsGS7k#bR`+x$a=&~BK_ zyd@a7gvV;~c1?KMArfN554o7$Qwh{7-6nnqAZ9thlW8#_I}`{>906z6f##37!QDo= z4x_Hs=zmI+KkU@{J73B^gY`hZ)#_M)+5#BXuS}!n$C5zC=HBrB*a~Z0%7u`9?J-%k z#8`UV;e+F{9_L)??^9}>wUi4YH(}M<@E#;=K%(i^1T-vxlESB(g>L&)yJ%=veSLjc z+nJs{f}U|%n>y1^+pm~i-R6Ni_40UOXeW%boB`j>~Cz4@b%uL^O{12pa45umO_(u$5TgTiJ$5+K*uGu8s^fI%=a$7%ffMz(|oUE zd-NXVB8I;T{~^3EpbujbD-#1KxovL$_arbb^lzDbLL+|knPuzegP;0Ht&a{-2T_ON zH#yGy1}?K1&hO83&wsB222RiPb4VfTdij6li5bs>HKZ7gGMYp2*eC>N=tG;N6-gIH zjXu8rAQ>k?P#pC0LUn_HJ6eRJJ!ry60SW3s4yPhKfirShZ?x%9_TB68ft#n~3XiCcwR71J$z}{5 z<)?%MgUO{!`v(I}H(TW*1Ma~4a1wz4O)>tiGiH~>FLTQC)O-Cqb%oAP_x~LJ!2Ei< z%{{zpb>Dg)LbPv1686dC*Ap^=`i9bJdY=2U_ZPjL1*IIj;d%GBV+O9%SbO?y8ala{ zonTfX6TzN2E%%+JqH_u^@LOz@)^;U%!ke`{Yqv(C=hn#u7o%^td7vU+%kcM|2mVpVq{Q7S#zidcf3 z>myZEu1h?|9NIX{ngb=C%~EJOKZe65oC6erC(8fX4g+)wd<{w2EBHm0q z|2uN6CGO7S(bTi5S`ry+H<34~&((OGT>5(mX{S;6Z+tweQYUe?A#^vrgjc%YX>Q7` zVp2YVcxB;dZ_rWvF~L9pPmM6r5`&II*Bz2!ews*!m(D8KLQ=tH5mob+TfbGz=yr4Q zfS+fu#q*mNsAJ$M1qsBl|NRUO60U+lL->a|?NHobUo@cs)$^vvJMxT^V)vJOsLj)k z{Se7Yl&AMfdzxadW!%RG10^>jK`8sZJ%H;0fEZ{eo?>_&6~C+PIu043$Bin~J3e8V zjkAdFihe$;&5a#`^t^g*^DPa}Bg*yS?EDhS5Py7Je*j7iO;p@)x8!>X_qfu2ldDYX zVKz2$8Tym{-*`Yh+_qKP6mh5EE{zq7TZ^bU*GE~FY=VZKiE+{UBDHi5E6TL8G}-ZH z)MDn8B;5aIBK_w$>1trw`RN&D*rWqc|u+AFco9* z-+9k1bw{ob(#}BdjdIjSd*vS=i6Y=8fVRpy%8}Cdu}Z?}N11<;8Ad<)4?hW9PW-vg zRLtv?^2~1I?oaG#sHpDR7a<{`zkq%(T3Z+D$=y2S6f$N1W4D5}>psX%3Kl2dJ#2oA z$S0uvV%Awzi!sLGr0nbX{j{%=XQsx{!Z?%%NoAYTD0fN88tG4q-7e$8ohos7YrojuY4a}A&z zD@KK;0eF$jAu4l%Un_~~?ml$xF4|tAiuJIGb&`@XtHdyPv)vVT1OqWQAiM5&&tKP_iLo1Y7VB2;@fhB4 z0$K}ts?DMcm?Epjm0y^Xi|x?@n4qlUM>MyKt;R2O9@FR1+(TRKADlipzNhw=2k{%gBA970U?A@X z>GlWG`Z~_4C#X=Pc=~;(GE$o^h%TA&`#=J8WF0>nIzl^NPrm)Q2PmaH}tC zZ4~l<^j>yk&J?g49qL7yohu45uBT@Bn|pbQK>GmcWAERK$aEn7aEu6k1?+u|`|4bG z=~GL+7~=bXv+jS#VU0Bx{i36`yVdPRg;P4beB@?i-1@fzK zk=SO>F7rJXFT!mtMD!|qo`~%bAuX!CpHnSV1sRN-N^`&drS#H+>eAyL1_6^LTHTS@OA;{*g$ubwM>qk9_tA%HzN`?CQ?Tgeg>1 zs>l91Rky{0yFA*-A!*~UXhM1DS>^qQ`;C8I#itI{Hda;H8@3bv^fYezn>@QwbVfg* zG@zBSlN}B)wmY){KnJK2$-K#B?>mgiigl?A2PQpzeG0%9#i^gl+38V^s;IqAv_%{? zXgFpwO*RB0VEP6%iX&C27F-uvB*q3*q3*?jDlMDU7sBPSb`De7^+>Xo-LX??iGC%l zLZ>1V3wy6efrGzJ&#sJyNvh9t8m2d#%Brg3HGJ`dBuBTLw|93L#1bxEhmhq?4POlP_=1tg}#1q3ytW<31-_6tyY!QT0 zE|u5LTRhW@+a92}vK(@2%dOHPz=GyX3bEMb)6b;>^SXit4($^Da+MJ~c9jwpN46Y> zT&h!N{Vy{X2xb8*!mr}_fD)DE&ld(wET4^B8g?8vl0K4ruMPMvn3DKlIq(NFiywvS zo4*n?zRmw=L+=#|u~3P-A!a7kUu9vp0ZowME!a(Pl7Sq*v!%ECw|_=j3=1?!@wBkA zeqyM@!yBvfl+k~Seu-Q&lHh6%iS0k-qc~$&{km8K*4JfXIF9cFZB+yY7>%C2Fw1Rz zm%z_*J!#=8yW#d;m@w5wAL%i@b<@4c8ho*no_#-2^oL5`fPj7|$<|^7m zl;eNh7G@gb))yQiBU}|i6%}0DMWosf>;7?7KHO$6dh+j`%)Mx|#W$_-_a80V-}k37 zzOPM07bS@s#LewZ(ahW>$HUycw$M<0_PASmHS;&~;YDP@ zeE$6PW}UXk;H6LB>tD|+zRY>-2+W`NpNh`!+ix=Aqz&6#W|=J3YDhn!3S7Z=Qnm^v z7h(CN;}S)J8=%Z?`|TU`nAMYtiVC{65BmcG43R3L?GBK-FO8{Dfrnxd!zPGl*?9CW zhn@#9iT4IkPRdh=w(8xTPr!*!v(%tNXt&;fYvMlvM0;jz75Uty>D)#AvRi6HJS!3u zVrKIrVSKxgp3C!83IYRVnbm|P$f%IBE37ecVA^55f;oZpOVN-OoF~MNx%9Vn>|usy znsszG4rh`)<5+q>0ac11^DjnRi~T)_GcICZdFRcfET-H!8W<<$35DaYHT5MeXXw+lC1 zOk1C!fC*jXgq88!AF+#XJVZ5_{@Je})KC4*digDs3B>&roozx0v5RB~R~9!J)#eIn zljHjb&&z*nAym@hI@{{y-_@nrEVNe@{>iT9}u+jd>el;zWdYbaG;6m^p?RRjGC2;KzdB{h2N_i8>1mD%y?YWApE(!}Lz z)xJ;~X(pgDmOa&g4_j-nZ+Hx^_+!cOO`lj^K(T{S7vdzw9S_!t3~rW4_Xkx3G}&@< zc*Ci1ka2<>`|FE(mzJ12mIs5IN`g215&nnJ7U2^CwzJrryp8dFuyV0FE`k6o)?z3ABOs`fgwF-sI1AN#SGj;-G=U8MPM zn&Vf9ZxpkW0%d}J2X6@{;%|x+yOpq;*8)>?@sNai9svSqPYq`OQL zA|AU6mvL%4WHr+63MiFE{JPJQQ=c0U=a0FtUT;hr>=7xA_F-1%vg>6i$aq^6*@Y1H zr-_8V%^(_2)c69J1TCNq1S(m8nquNtP>mHjiR25PQ0|VFS1QFwzp5sWTKV#RR$Izl zLpRN(?%?6rt0Q*`str9xr9nugW4?)OrgcN)nBOl(+3kMQkI_(}i|1OkiC;xQ41L;= zRV83RK1O;Xj+gcyFRV=Q74W(9mzx|PnT=T%8x*1-yL;=C2VYiy0uy%x#gAt^rn)0v7#%0i`S*AJ(O+)3qLF{IM(jdB-e`u)Q|4xVxTdhFe#hie4iajbNY` z&_jF|bC`NBQq4Fu(3rVY*HUu6Pg`ry$q~PGpj?Kz3jSbVP`c-YW|Td3@9ERlhIn6( zz|36v+y@%!Yek$z%VyaA@!un-*_Zcs55> zmxtSqCs^_hWUeao`Z6O$@4){%TZ}t8!`LA#091bvs6jEiiR$b^6=8Uz-RPlv zpXk>0&X6a@Dbtp(y`>c{$N?F0eLbReo=JVbUqGEY!+LV$)rQYu^r}?2v>9{H(Pjy5 zNBGj~aItqP-<5t2C}Z<4YwTUD^$q3mm?3|j9+G2sla&qMY*D^bA#n-b1NH=e>c$kG zi;8$jL14qa4X&eqZBq=yanLCG=w+o>^Un-!m`bzyGCq8o!D`v0Ns`9~38L>l-M`E{ z$`^WcbcHwVJ~A>QvGdh)6qb0_;^;O!p0PB7o#Li&%-9do60g_C<2Bd4Yz*OcEeDS; zQ=|(Ggj7h38#UT`d+`KSoLZ}m5XUP)t6LXeQob*=WOsF`VhTMaq$d2mHN45H;`BGg z%E94Lq}UBVplg@Ya*?$gr;A$#K5+h%P^@pfkD8)N>s?L!Q}mS*E|JD@me)dsio}+S zgMa3X#SW>2xmbjDBxD=z@{RSymJ~Pkx=i9wBg7$Df^}&sh^^zdAGLEw9@LT|1KdgW z3niX4s!kNgF%`6}YoY3OW`CYeZdr1g#@fi$DQ$Gnn@;UR4vozq(?UxA4$2mICT`*& zHU2GBX5mbk&*S8~*}wP}(EqI*LQ=)NslijZn;QV>QaSbC%m(H22=2h8I`8+)$ zH@7t9Od|3bxumD3Z;e-DZn;-j*5MEqGysE(p^kl8(AJ&ysQ4}aAp}ON)H15PPUbAV zHHFc-SPj%UiZK@#9PLJNR@)hbR^Pj1O>{eF4}5RO9I@y6_+B zzik&@+FoZJk7Vi(&?>5`9YYRyuW+QM)!nu{qz!gT6yHz*IXp z;O+V?chZ~WT~+rRJ(P`kYFJ>6)l%9fyfDVR%s|S zgcA__i6d6oMArp>KSshHKlU(E(OsmXHPgB-@JuljCnBLv#pdgGbDRT#wEaxCQRn5p z@NQx(FHwcY$Y}qx`WI>SC&OVDmts+|5-y~*JMY4OEx*IYwmpMp2Teunu&URj3v$iF z(_bEw(2J|&(o=mNFE&8JHW4#JT%eQ>LWCjRHA*AaiX&p@md9W8CoBbP^qauwM`GG!NC7Tu*M_aMDwy=u=I)WZ1cez!Bye<>j1yeK6n9#+Vnj(}k>uD1p58N!d7Nk@y%p92fGcQ5v}Ob~sSHlfb_4{` z5Cr3GhOK>}oTgr>7=2IAz;Jh!f&Mn=asCmN-#Wkw?_D_p=7$#@yF zNjKwwmnt08KU~mJy)?S?(adtXL{ce7d%=UJ%$Y*O{Ro93DobDfwf);dDSMG#0jKIB z4L(sXaBWKOFOnt6`|1&cZNsK3N{K#3f<2*aY3aGSg@sD#gac5x+Su9#JZ>~FN=^4v zn^2@6P;))T01>&Hp}e%M;%4Pqc-br3U*$1_J#mg**zEe7e_ZGliM3-=`9oDhT?@q~ zA!S{RvDe8n@XEf*&Mf=`zNKKnw4J$fv&|iNr@CQm#K?}#aJl7hOur)qwaB^6h8*m0 zn|3ZGp2Q5<(^lhpd)>^R#}&vSObfzs6B84guZA)b)zGx-pkblCq20CSzoQ;>I#BxE z>wUYx#ZA^FK87wK^}(!%nzQt69Jy94qFvSCb927Y2NSh4(jUXSVe9h&+G%2$Db`j?x7I;_w1WL9`;}!?0h7uNf zI&9BX+;jfAXTbB_Ry=5VtY)~}s_FCnh_A|dzE)fd+#|NJpT3IW7E!2i0{Y=rJY{0fAu9B^rZjPWsxQ{f;iqH|K_FSHF*~p{WVhIUv#M5ob?PMd0q3jn?cF z>9WpX9w}C>v~9Dra2@G;aa`lgL&(Vz3o>`F3Tw9T$SH@<=`U?(a>={hOIJAxVz;LE zC{ci*c}MaEL9FFk_k6yyD%V){jM?L$Asc~7iuTiKK7ww_RT19 zq6qwiHQYn-L67ut!+5$ztqNwqtu^_>2rBWn-W#Wv;3uN_C{w$T#KIuhyRS*?L4P#5 zb)0@WDUj<=3mbTm(ieE(JevR6bBq0q#v?1&r{8?y?prq!`& zB_%1yL9!#X3j4_Qgw0j~!CQ0#uYskc$lbH$PHb*|!Bs>4eWb$iN1Hr7aleI1>X1V^ zcZVdT20MvL5gxU}xW?ehSaw7)!RosHW-pVx)#=mVBA2Y@-dTe4%%mxK1fttI4oN+5 zT7n)Fu`ZSA>rzLRS_GPzVvU}$k+_8Y2FotpG!Y`W!(f8Id|E}v!P9JGTcuJK1$P1? zC7cucPKQlbs#0v~57pi#R=5)*-3%$GS;emfrv+Y9xJTW{EI6l?7 zsFvUk;E!;y{It|wBbY$XK-^-BuqgEw7;t}F59o@#fACD^8T znP;P(I_;X(7d+;1!~ce0Gt3x|@IEMV{!6`7_q+E3+g4g?lb=w)9iD4d05A+Zp>Itz zvVWA(UtwxywleQ<^IG03Anw9_iA(%Mx%oqOFrIYgVcJJqtnZ?BNzTbX7s*9WWAdZW z9_eV@FL<1fH?CUG+IBi;TYV`tWE_5NxZ(1sQpe5Mmd(Libk$xta^K^+qP6#?#PR2N z+7o-1nQ1;AKO5}O+_L;fS>683>Kf%`f6)}p|7>zGYq7C&$F!X!orXUynsa8!Lh+N; zkK9&fp+i;OcknU!@g{o*27-(TFa&F8)P2`m z0c#~vcD-hx{0^_4bAMRca6$oA&Z-9EL_gn<0!AwC<8Hbc=kTX?9Cnh&#Ll` zh)6gXWR0#qqvif5ln4l=ac-n6xWdKboxti05Q$py`xa0~D)cWehc}%3BzmaaV@GCc zn!~oh0!5i#0#jKKhnkvIbeq!cYk-M{K~eqGj%PYSd-KS(_{L(;K8@%N|IS=PXbPX* zoe$?7=^X6h>T;I(3F`VjyIJjtyBfU79L9DQ)=?hZ*VSXR8%y^QJf9@B^*=-|DqXI0 zIa<%SUsnr0+Z}S%B9~`~g}O$Xvl8XX$;nAbZBCMhEjnYn9C>>Mq6?OAU|W+>ngxnb zMaX|0c0avZKI7+QD;)n)O)NnrXu_Q*iNu5m99uy#3+vWh3k@NMx%KMDbl==PQ-t3r z1ew(&0-sVav3>V4-UvIJFy%PWUQOq_jpwVd$*Qu1RG(fk>W>*z1oOM-Yo#gaF!cYu zIZ}l%Bk1(k1xRrd=;`-RD)*EMmAzEV0!nO^_(mY=I%S@|e^ou*>WEN6iX*<;TrLKR z6@~RKM{^^egO|&lL}cfWx9?kvtqXw%GKQ@cA109wilb~I^6;EUIbxar-y|6A&Jw2Q zoz6BDb)nDd;#n06mlJ+}b$6$*|E!d8G~;--f+Ok!DuWF{8jFVT^u8>0@98GQ^X?SA zHh2f5@OK4eu0EIrSd^iv=Q{x>Y|t8ka%t6UhDxlA-I|mJ#>n)><=zo~(PPp%t_4_bTwIB0k6WW*PS4TcxIPg>J;TcH=ZViqK9Vdn z{jLs*`$GDr&UUyn{$v)H%B$%KhGj_b1U9U~my<>Lh zY8>kq#aqJR38-oj^{gSk?8Wa)J!%}0dy^)Si$J^7VqMx02&e%8hZ9-_q1X-jnDMs< z$@&A9{Y2Tuv^9q+73terHg&v{pCI+wADol3$fIiGMKC8Kf)A9#6SyVyTDJUG1JWeY zQ4Ye%vmbJ~paLrvPSL~rnGf&)iU33+Kq}H){-`hg%_`SGN`{TGISrLuEVQ;Tedsfq z_%G8ZRH8a-A?SCe;s1z^R+N)lY|YBys&V~A8J}I1+Z|HZ`TQ4PSM3aY&zjCt7}l`R z8joIx`H9uKJsOFLNlZy;TUmJt-Ubjtdq>>_VrO7{MYO%NlM1xJQDUQg+rIsR@qdg0 zm)^(F6qOiFFy2o5wi{18Jz}aWX@LChw9;{LoUUDVbb;op`raaL_PqxzyMa|WzKT<- za@L`uSF8ndeoLw2yX&OG$8d-HD;$ZE*U1BU5poQX!!I#C<(ogz%D8G$~n*L|CN+pj0kV7p-bHZy~Vd;~Z*0nvYjpM@Rf?(Sj0 zaMMbc<2MKv!{E~blg!X(Zs6HP{N%&8M#THrf#vh931Y8H z(kWI^wr_X`l=Ppnh8(7OdQ^`MA|#Lbp{_~^Rkkdj->`?X?^@Vq6+g0VlRJ>H9%+ji z`>AfHQIEcX6xaU771KvOzjf5oRu~}%`NPHlU_`3N&o*9QMju(8KRV`{97LH1jFglsvqW5ot}YT26aPaVqDAdpAG>#w=ER3lwty11{|)?Ff0LBDoEf$_)g<3+yo8USH#BK-qCTV6JxQ4_mRIxK5)RkVbm^Ds z61THu(zh-f7+$?z-n)H>x+G)SNKI6VTR%Ea{m6>7+l0H*X|)kP-h17W6gj3J|=M@7KNm21MFM{8K2_5NUDO* zG>E3<5alpcSz<(=Rr(nsRW`bB))t2aUDn&PI0_@M`+)s1q$Oi`})pu5%Ea31BqQ*(t@C(DmC!50>2UPKGP-h;N{5 zaGQH|EIt>}Ts)VOQ|4|B@1_d)b2H6RK%6A}VOIsG7-w9->bzL}_Xvja3i?w+il`xR zJj|;Qn(q7EpPkg&U%rnF5f zw0pr@%xa1T+y^@B`SC2U>?dA0`~`{xAe2+gC6;|xX2>kYPrszOpZb(rg+jUB?dUz_ zP~zHUJ}kRSHx7AgZ-FEBF@M3r)nzXeFgm?XMoRb!tCWC7aroU7i%1s4BMf}E8^Dg%esa8R4T|CEUWoO6WXU*?xhgMh&eERzJF<_K{ zO2zNEh6i9fnT2%QwtFQT8`@nH1GtRZ&6QA7}QF;8LQd3!<#wkNA*V`y-A=Bk14=TVIpn z-N);&TU{M>gRc3??+oW*fQuujs#A6_H$DIVN*R#H5U)~dvBcxOb47d(#3N6lCdrfK zArHj18zoZjEG3}Xp{6CyNguUQx9#DIzR&9+Pj$*Wm~om%pP zQ}V#FVy3U$7_&yirndL(sTa)>f2T&a-_lrNu+BfHZY6p7d$~U5V#;LuvsFrIhi`XR z^=6ee5^rf|~&5~4~ja<-G3vZvN+ z(#QJ6%+yP;d<8ko!0pU~e8lQucCUxc^YFLL@+LolUrezENJ+{Kv?jq|@ZsUdYe=LD zd&1A2Rll}an4q0tf?C?}niHO(P&)Q~`}&js3uB_sKQx)22ptGbN^Yo@5- z?Nv+s1ld~ZrOH7;a~}5gM6xt{;-&}8Y=j-qTHrMWfRjFhi7@Ss(&1MVe(~|Ee|dgn z`o7Zb{@3qH2|vr1#kxJl0eOAbs;Xx}akwYrmfbb z!s?hhS~H*UrOhuf!Jsq(SDl;}kRK=dRQMNRB`*%%qh$yaPIy)$-UB(vVBCo&)fV25 z$I_`LBHl8P(j8n?5l!OUzx0*8!6mNPH~b75yCd@Mo4%WPbc}PtR2`0@Zo%&@1<5C1 zf-L+v@!p7YWPbw)69Mo&=s>{!2*||l4O9riHkD6AsY=JF1YmfR<$9r;9hYdu#di0Yb?BcutT>9dsgy0j4 zBdXR+x1GkmzGnnmg*DF~v7~eP8J>;O5wJqGAMjnzHwYRpuWrS)l$Gv?vN|lr5K~TJVJ=b>YeOV23nm)T%il%|^ zI3cI7RHZTE2cuqq=Fpnt6&nQZkzm|=ce&<3>#=X2wgNOBkNao4ib`RV8JT5Y?R{ii zp4o@L`J06%J=c`&MX2^cFCH5iHIdVMKZi;uiA%4IeJ%qbHZ>NC2 z%39BIZrOU8LEpQ+#I^uPP{jq=PgKm9{S#{IB#CWp{QRoxI#Pt7F<{zt>9^#(KM{RF zss`84Dfb*0PFmfd#5pFsHhmM?@(A0FdrI0e6@}LIl6RV#GB>V|x@q+0aik9Q#PHM0 z!p3Mlc2Xw}>K6{DJNh7tcnM^`0p|lc-$3`jX})=IvNtW#$6~0=;ZMnmS=Lf82E!qN z!|^hziZSES6WL|rH2I1x#M|UKM~X0iK@+kzOg|u%cJWb`Q7(V6tZrTqs<(CY8!sq6 zaxm=e?9PDL>{5|z2rgfh5(Ax_0tqhG%Hg?kZ7VbFJtZQoWdw8AHf9taUcP@&x~@?1 zZ=*Q!Dnc}5e;Q~9+Iur2mzFw0-Ogm_7@vkRCiKufOu~?LWiIb$Kve&9Zj`Q2x^EeX zgTJCmC+kW8`8(Q+VNfB}-KCk@`)R}hh;UsrK0~CE7=FYOOr3&L49Z4XaiSA^zpS6t zo>DK9uFbhkU`eFlABRvhO50t3eQ`B=Kz8tP^*n^nOA!hi zj}o?}n)GPcF5u1$_nPyl?&e)RrAQq|D?O0u8(pg7Olq4I4h;=u1Q#^0R@vFvd2p_X z0~#z+3@dd3TQeqbtpUd0ozn z6f=`pyA98L19Zw=_Td{Vdf0H_!Dp7-qO0&_GBNGKSNqd8fu|gFfy?GyJZYLBfnc(i>%;bfa9*wpdn9rg~VR-1FLXP@r(#)IchB%|iFfusmm z3nE9T%&M4W#7PTck9qKG3<#_gKe2wvA_jPs54=hyw$S-qWZz6?@;^uY++nid@#)e* zWj);VG}okei~-5QzMt zoUB^AtTpDca4BFA?+fC4LG3jz2HL9aot;2eNBQ=I;YOrswaMruzg;TAQxv9UXnB#d ziVz&X%^qp#UZZCfz8%*+yHpYhfblQA=pJ#BMnf^O+2+?hheV!)drIyn=e&rybqI=B z#jzxyAM-f>aPv-hveIhacD1Q0+j{Q6kWjd$^mEC*s}f)fldA|4YAi^t4zrxysF)eD@i$wMN$MOH=TlF70) zJ*4s2| zi2QU8CCE)^Azaue#MV={s5nVDc)8hGFXdG?vhf}CmZopt6GTWtPi1d4cI8r(4%kn8 zor<|7paG)yE|l|5x6XxZ{I}ju@HsQ$qfHBpozoHcN>aBzw$i&S@Qxzj`Jg|+;*i-w zyAznp)^o#Q)X~fhAq63$^(Ex`3FEKxxPNiB>pIrzYHhTqAh|_NynM$=v%%!(X3ZLo zGxPet1uGyRpn1KhqBV4dAgE2bP&e*95B-t0-;-8P4Sf8YxvgVAOv&)C6c%lZ`x))b zram#aF!LW6{24RaujJ+*q^gk!JpGo#L}xQ%PQfTzbC@$`6(IlIoPYIe&ATI5QoCnF zU2469?&=^H{V@f+2sKM+?`c(}mC+2TY=Fy#>u9mE5ls9GsG4IuE>2FjrW_2!(-0TEUgtdHZR8jAS_Zj?3b; zRegs;Dt{LA0QmK#>#=7dP=SvNB$T0hd33Zant2K9DFz5YncywMtqENOO1R9p*Wtfupqc#uY2O@8N#I#ORb_5FR9t z0yZ<%zVM{tf+8Fn6xz4ssdqeIC8Z#7PfB=jMO4wE6hu&;Jf(EzXAopahKiDih+de-$Tg?1gDmHJ0uJWA}c!MoXRiODaIja>Y&SyV( zoBF~}U-F^|iMHfg)$-fiDbSIR#NT^`E<}kfp_2y$KwzYe{?uV4X%(LOrW~Z6CX@VJ zByX;ymho~uPCYY18w~k8JWu=%fJX5i6&srtRO3ARfV%IfT9H#{!|s~XWG_>>)%C9E6(y=o{2d-syDh#TfGPn!U741dspxe}9m4abjq)mu+5=6xHi((=RyyGFKlTq2Hu(jBu7h51BWdaB;hDMDTpB`0^k_8V-5oJ089rDgsmqCFj+6Kh z?>>+GBNU~6G9sFsmL>(RMHArWL+G_GnRuRUh+*JvxpH}M?)k|}tD)C#*q^~W7XBON z0%iW9cKafaeQBf1;FjB-uz3~#G_x)Grs2lp8;O!#S#9CT>`4#yrtnS1t#xbUk_vQR zkTgU$u4S5`gm~ws+mw?oF9WHRFIwu@Y+cYaC7>>B^@{jZBkM|R%93iCw(&oHB&2mk})?rO)#wm20B>s?{)$;OIAz93=uJ&Cd5)%}9Hod4f zq?B{`>rZ?6P(s^EzWmx7a<5NIWzUH&v1!kqF~PV$LuY?cu+3suTf zB96!ZR`X5-a$&W^g{r?)FaOKUbi{#FKP4r?Y@)P*)UN>EF8n|z~@;oJN^ogW4<2Oi7X*2AnwEIwP zt83E7Ty8+KT~VLY;vPx5=^;YBQn^9y(~cR{i>FYhiKxQ;O;2Ty7mMFb$|whcQA~CV zIn@``SBQxGgLZb=^9#55tM&g6Pj49&_4mDh(}+?^HyCtDGc+ivq_mWDgER~!0wSf- z4I(AoT~gAWBOOBzT|?Z5&+q>J*J8O?%Ll;BywBPD+Sm2kzYjZGT*!>UU)r7qf>qoP ztKOq~gceg{lCX>VA2a%STVUPospWFlM6?l$+MZ&(MQkPD;N1U590*a_z>ku-j**p27vVqo?# zfvg_3K6-E7Fv;*mhBCdzV5sMKx}@HfaKYc~{oVCGr(vCs;Cuh&GkcV_1c$|LWV$!& zC>Pb{&vsik-hOS@x5plDf1*aE1+^_Fn=2SY9v9Hreu}}Gn5q4vmZ_L__5L{7;5WX{ znOYiTLX*$xR|8EN)~wyxD`6cJ6H9mMo_i<7z`&b)hT)p=)Q6-V>FJ994utWBU~rZ3 z*%MKP#uCs8fH^5pFs1(}fdPP&Nshu<+|{@Bv{cI-47GZB!^~9?_t|;%&M)7cNFt85NbHwC zsYipuL^?xp<(-Y~WAenzTSt3zH&3snEv(=0xi!*Zg*4gl8nHs{8U7D2rJd5TAN$*y zp|s99LngL`Xb*ZHUqZ!WWkH!@Qe0uiJKRzLFd(2E1o{LRn|J7X{F@}}ah{=Qd!^K6#u>L`#B_FFut9R)~v;Hbuz+5ibrK1w{0 zMp<$zeS`px0V!UWNnZAWg4Xi{ok_9E@2Kab^Nm5Yj-P2*=Anw{SK`JcDR z71ADHx)dTS7>UM)p_|^x$_{p?XNk`3a+%|&OAR8-X!X=Tx9u7~cO;e6V>5*`U~wYGwWuG})nzArDIyXc9E_PN?7}#av!VQy)wzLlZzeD%Wbg*< zuy7b!9a&Y1Esx=P`*~?ld+w?s!>zko8h#0)WEK_{W#AlS0@+NXJGndN!;(0FVMp;? z`x9K|B1bbY)mEu2kaF1RH$(reCgt(FeoTE=hlx`5a}eSK1tiTHhSK_&^PoypAfn187gYu# z?fRy{q3ETR*Jn2#mh_@$(m`L+2Rs;}4kh?0JxxrXoyPnBvsrc=9%6J=a{CrBCRN;$ z391yz0ONzgjwq-MdQig<@%dNN?O&9cbZcS14y^S-bR7S+1^LKO`6uxK5R&n!w$PJRgA zEfak@w_pE1FMu8>+re*4N=A0y6#||6M`zWw$BZ@3^S*pty%sLoJCtR=bw%RWVFCD3 zzBqa&CO)>0T&m~7kpA#`_yJKp_0cJWCkgld%&QL)Xv;kAyK|%Qnig$VpRVtNs}1Yu zom=UadO;PDd5Gy-9Rq3fKWhrs!#4gGjoa_EO3Oq(+8f#Hx0UK`eg$MaN_n34*18% z$M>@!pvrg53WCg2d9zN>VVppE_rYZ7=Gco)Ha5gI#m&ZajxLYJF-ww(=@a;PjH(+l_&T2 zp6~d+-h7opY00iHiT?exK1p}pPN2NLp5l|~zblp7KW&`rfeAFj5h9edZO$m4MfLC~ zZj5?e_B`mgOKDKGD#_KIBLo08QIm)zM$MWR(kJEkx9Q-NPZ`-x| ziD;N2|Md>ejkI?A!Tj}!GP%g22VwzF`3(f3FsM?11NqZKF7+U`rXi-Fqz{K=SYb`i7a#QaTL0a`g^Zk0< zCr8as?Ni9_Gj_54=FsCDrHkrp0j^1#3pO77eOY6eqTs)Jv&*JxoD07r?WkavKRk9d zG%&_xp9)=Sgp3GILT;Y(-dr`&5Z@z1*i=o0tzl2z@b=Y6WtnRpB@Fw=`m`uTG2bu( zT&?#Xhx^D@eSQ7X+Rp`F;F7+V)IWJcwBpvS&vK=c-?lHZmk`rIIFTunWU(zpzT3SN zws|v|Wmr@~*nQzii9Hfn#;!fAL69zBlz*ddXxI%-DNyW}$tAvTtM1SIwpWQ~G4JSf z)Q@8gDJF9|O0VX5bvU;Oleq?<=-oUCJe0aqf?HH^Fa?$~^uh#>60k=zuw(b^&te7rc0P4L=->hCW}?T>qq%k$KzuS$FPT(i=vML{C~KP!P=r znU>kgz`p?U4OW&nYT-Wc)3voGU36y>IQRbQsiN7a^4(1y7navI-A46YH@I7LF9Cq%jki$|l<0W-Itc zvvQ$4nSJ%nj9k)G(%i;|b>jPalmO&C2x+S3doDbvG!RCB*Bn$>;EA*xPQPD71DFIW zD<7CMw7>*e_p$4U9(9xnE(*TKp-@zs+JVDn4{JDvX7c30fEiC)-$U8v<@44(*ukru zPap$&zqba==(p=^58e|LnjxVH3H4^kqV8ZfNw2=*_<-^dZrD4+U$Uj^rZ$;2ch%9* zD8z;%c)v|N`hcD5k1iSe^eotUxBpKV*_z3W_%8f^PGUj z{P&tI+(Fv5%{k_gQX_6oI!gCgGDRa0 ztpbE$@XFwYQHxee(qOp~T7_{;+D>ea0ku0qG3Dzs+f5&37FbkVm%EtQ@$LEQ7BH`L!`;sF9GOjY1IFaQa)JhkV~8AvIN*HyVaN!-Vzze3~W$xx_?ItR#qz4nevy z&HnF7e8^;;+l{sED>vo}D9+X^H_T`iUtFJJoKA&B;h?Ch6m19G~$=!u#-$@OnLw@XP~ zn~Ba-*|6rqL@ao0yQ`xfqYR}B2f;k{Q#}b#psZgB`-eEYa?;3Zb_T=qf_zrTkp-bV zo&}<6ml2cgv-o?Ds;fP@l!yU$g7EK}csw>~x7CjUCl6{l^`NK$TQ z6SjQ3;>p3T@Vu)pi$tb)raSv^hiO>|zErw(2MYE2^6oA>&>p~>UH|P(_p6s!3|?GY zhA~*eXI1kz{*-n<)KF>Ib^^^lpz&U;3So(#vUJJ~&CE87U02T=G#w9#Tyy|tVbf6` zTh^Oc#wD*nXJo-u#yp+9W*rtvf&Sd2YEz;psYQ{r% z!O;!RaUNa%FL|Mh4?^LXZPV@TpYn#lPiNoHx$D2=Xg1C}jEwSS>8z8OV|%0vQbs!E z5)nZPV7f+$`(ww#Xx&IZ91EP5&|jbVa6xs0NQmtC>UO z-3I{yXd#abcqIa3(DX3V%umuk<>~TFJy0_#ir7gwKUblqPJW424BNxX%DEZwD>$&2 z_ueBz7AnTA{4velzSc;cDZ(@FLs5QUt~qCYqV@$uLEk7Vhdi-!jV~ZHp2CcLF7`kJ znVJh_X>lF+y-R5Mjxhf{vuF308w1Qx&FAB7tXS!Px)(vNC`g8_n1+BD`*+ibg0O@{ zv~-r!%1wGXCUyGDcD>?DC@tvLV^#F^^d43hSijry5>5_I4vBsVy^(|}2CPX199a+) zmFGW9>3amZ%kw|?kZVD7fF%YOV_es0z*YXWx|$!H4);PDu+xAl4{*{PY8oi@rVb9K zf+1&@P17DUd6X~u(8a_ts4X3=_bhfK$8LWN>-Es~{6RUqd)#v|YD4n>50ITx#e7J? z+jLJA0jp_bC`{JkaC{&z|`T|9IigwG{)bv@b2O8nfVCHIodAn7ex?EWUuoSTEkT|;g zaqNS;Po{5M$;L@C!LN|-bKQPup0q<67b~{lAC;b5ENCzN9B>s(n=4eSxZZ^ zKwttEwhv+-p$*4T4OAX3qqA00Jwh*?p-~wnkGleocvgm2-XSJksxI({AHxrcb}-Z- z7F3kPNO&`Cx{=akdx>we@{Rs5@%r(bGn1)(W?|<7y{^6? ze3T{i@-K1o2Je4J{xWDyf2M%6vZsf6bXCWhu*L+Ku_*0qq7hO@Tsh<@Io1vW>P4D} z2e6~aY)SgY^Ym9zxcRZ$>xo2g+xX%9VwsHGt=ko1r(tv0OWnNE@*3E|O)q~#xsI0R zTZAu36(r&f-`D^XQ{XO&WtqeGcw*%*)H7lJj&qy*wg_!H|JJd6sBoW&#jz<`;iQGN;(8*ct+uo-KI~oTUu_A(~WLVLtg2TM`5<^`nza6P*5^=|DNpMOt+Z6YnC)Kuh@Kb46aNj%quyzj-0-_&v%J zFN(O|1gEVMtT;>SQoZba_ErNW=OuUeqr$&FXk#G3MnC02M@{`%Z;Y>`;B)1>$HQYL z_8(hfUeJkB`+UvLtJ5)mEZN43_t3(bwd68&EJBmho^C8c6{b?^Z}WNEE!+rUV2#jN zWsT|mj4lm4a)couATFhl_v8->e*YFA3V`T}Daf_~#(1iKhfn^dEu(Dm6X6hvM((dF z^Me0EfBI1VD}9oSPrc6Is?|buagrwy367Sg!)~fNfX}{1umYIR2LR0m74ZGL)@};H zWYMp3l}uK9likglORI8}`nsWG%qMi6YU(ooV@IO{?CZ}5cL=8koiDZAJy22Zgfe$H+en=)j0Vx0Gte@b7AubSoqMB{k^?l-qwm)cF_NoS5nm0*{D}+;FY?3*;>ih89qK97KA`u8v94BRa1MI0sojtfiFWrBqsL>ny@#A z`x==S!iRL&$?-A9b82=-Lrqm03mp4Rse1Jf$V&o(g7=UHD?Vw-5|Ba)z~{{m?dUK_ z2U;U2p;8Sdz_ib%`ibScS!bA^zCri+>sYPHa??nyp=+^^4%P zxjOvPnEL_h5m2~X&6OH|pW}!2z%l3S^bLAwxiq0OYqZD$k%AKl zibu;{gL-;O<}ospBr4{(mxuW)Rg{WHZS;@HP9hHr>w1M-ab8|@6qBf;)l}2V+YgV4 z`X((rFzmxiiX@JN2WwS#|0XkPyk&N^wQCbV#%};U|j(G8*p^& zk{()p>*>6LIxO>G4o$4LYzDph}|AuaYqyW+YUw=dk& zi&76yR0_Fll8m>J9m~tYP&$3x_B)TQu`n;yd@&?@%gxH`e@$LQ!1PRThQA)OB8@(e z>sQ%;O0?n%e-e}DR@AUM!RW%$QWV*XunS*Z07ygP*En~C&N%|nW4UQDYPPzkyj0Zc z{|KwzD%oBeoU*9YdJ6upp(+YAj}$PUAuSrqj7V;^ZS>ACe}ht{QJQz=@*)cLF}c}q zy_GKB5n);W2VxsBxdYZI$uAQu61|hOzp7YN+otRi@QT9Wa2a~A779$=Fgj9oDI*SS zamZAb)v0yLTz(Iv;p%$`c?Hq{aqWnBns0p+U4`X%p)iVx%}i7^JNB558eb-45YSdK|N+$42Utb=3?$^Wb_xwV)l#KpN7HZ$S!9aB0 zX=BJq2xOp?W7*J@;Z*741C)=o)HF@Ij+lqbmTv^I2X``#$io}KJzm6@5{8tx0;@-| z!3v>;>vFmdL@Qhjc*y`u8z`Okxhd|yd~7O}XIuBKkSul>_{BlVeZTulwIih>MuZEf z#Q%{<(6XEh%o77vdG)I%!rfSR95CkVH8>LvJ$NXpj=Zk_oC#=A;z7^8%MqR;J%@=@ zP~`URb(|9(xT?l@oO4&A*d4|j3SBtNs61DAVC$epIzEcqvhYt>bp}BRq@-mP<*1LMCC+9TZt#DEGWxh!PB$g2Wk;#nD;;LRHC0P^$A8@E z-?nwKVC7U_n^5;;b<%sKZfk=qvI&_fFp(Y?uQ$1h^F8B_BIv)Wus;j;+;~5x(Ej8j z?hjVHohDWtxx}u5q3XQzozzW;hOYr^)Ggn)lZ9tlJ?BTJ(cr)axf^c0(N5y-9Mf$g zi&8Rulz;iWET3?gCpQWfIy7(f^TgrDqQ#fOUY;efMN9;{b5%`kK2t+M)iK=yUe@Aqs1cq1@)oj87dxhtQInQ8%Dzf^*CU?`FqCOdx`qmZbck)CHu#lW9 z@;Vdx&@f8Twnkv%0A~&O(qRv&glxq=CuqqCz`Ydrz{-t#M= zqwo*YH~H?&T)aU2D=%qMIOX1cwAMW3xHK3D*B@%JIvG8QD4&|TDHq| zxKr#nSr}(=n%2kGghAv}8dob&4zcH0;EHHA{m)FvClhQ;qG!vjvpl?`g?b+Gh(CV} zmo#|TjOSwFJ6cXifrX4t4@Oc72V0(OxF%0ixqeU};%!GHKWi0-g+jRj36%JZz5QN6 znT1ee2MZFoPoC?Uy2gGo?JUUBVzNkeHU%RXHpkeh%KtI?uzWfSdg{cbxq#$j0$NLP~wVL{)rh zc^^o$Q$>z>=tO=+RN{+?4mn3xTs9<-b{6O=X`J-lDh2Tp)* z^D}^rQ#u`lu21tFTDli>^s>Ky;${941?|J^i#(cE%P$qaal%OhCM+rb!e}apOCNuN z)+4Zi?!F@epssuVCy4+2Jb9RQ`|ivd;{;@ms{3&lfISY3tw0KN$U!5IYn{M$+m_Fa@-NSrN)v zs%=i5bwNMfT!#o@_O&pEj>{`|R$#FVPc{ z>ozfimLih`d9fpI5*hYrP@ooKOi56SkG?}Z`lJ#B*wMU!_~qcJ2$mU_!Vu{lO31$wM`u7T4>as!>f`RShXCW_ho7t{9t&j{ zf;7o%TeuT86g?iMMiD_mc`}rPIX9)^7-KHrBXsW)0){tHt~O~cv@74+Lb{3rLv3ZrijeYiVKpu|KGj*0We6CrIK@8l4hByN>Q zi)LPNZN#f+_fEH#H&^({?w$Ai)RN}v;!2lATK?l=S@b(giwyuy0a++8F5KAI0C(sU zw}Re_J&~ek$9}PXY{Vz^;AxA+VJ#Vuu0oTp9N+yH{S&p>GIm6xOA1llS7`BJyYk8a zlOtof@q`_lgAIe4QmfWs{tuW8fURYr04Atj;JV_w{g1L^TKsccZ;yl@6faaN4tuO+ zq`h&z`m~y~v)t+FIGmZV%Wua6EixVqV}TL2tLruNAc(FLY#9O|+Yqp;D`dft#`0FI}X7~P}WU6T3P=Qk)QzBNIYu-hU5hF`wMcchg2tsA<^KSw7>pcMDdT2Le;HV3(+S?I>*XB`_wM!n_^t zJD=fS^N7Qjm?8vI$|DGfAr<+A&!pi9P0_-8+u4_;j!oK!B|LMCxH_{LA&+221ddum z$G)zy>dLwz>Pq>CZ{Ehsg8mz%1D2zusMAXeL>yxo>ucf?yu1gyw!KyDO*deg+NEvD4;-Cn_?=%+Nln+ftsLw2qjTibzM3tv z*AxC}D;C*0duC5RkV4j#-AAu7J#KqNi%eTxA}4RdBpm8pPhufOK$U%QMUl!%L0gGc z>@Uol()<64TT4Gcag8>MPKRkQ6F+J6;tveJ!Z~~m(fX&85go5FDO~1?MU5=l)K(KN zYP`KvPFn;ZD=4hikIipq@tW#-KUDm)@B!S*sG|>^^bd3<$;ui(X1R59LS=v zm>e;2Z0dv^(}O{*)61a@TRv&-&;xLmwA3|xwaoBhtSYR^*^xn-F}zj&eY<+Ou>Ze+ zzjQLnDfRoS6q2t^OoQJJB;%r$>i=0ilTZA@T5rZEkeL~wSm`|8{rgj|Y1x8jalkYZ z_0GvKYL@m37QG!RxDtUCKM@oLVCgD=s{>w@5K2*2YVNnxjV1;isch*8eu<=0RC?!& zlBnUaPi~2NQdV*7_B|SU&6XqxVs_S7s%$v-+Z{=zn-+(AdO3l0lj%b}%uczOq5jvZ{IIIi4d9l-ZaJ5wB>gu{e; zfF)3|SQ>H>2IKLLg**=C^2y)(RhlIRoy}oW$!mS4txPFh^BSKZNRNGEdnc$Ta}eeL z#`M@*VAaCOdtB+8WKY`jl2wjE|NlHEF(fr_8@ zJk_zLRM~DUXRL~mRLy9Nz9KzODtQ|2I`ICHD`Zob(fe)x3C~~SX*4(G5(PJUX8b1O z+7;cvbDLTEVTuoKAGq=zoJ(81@Vme+V_pKW&my+AW!zxpHWMp}S*d~2Elm6f4?z-*X94q zR0H|--k$~hTA!}h6j%vJ^1fm}G9tKI%^+3vZJ(=krFGH1x;%!L10)@+*3lGP#|d0U z-GeED_h*HWqugm-(vAWsmD#;%{k`OgbbgPO* zpgyVTUt;LLvZWBj%Rlf-U$nHR#Y1DxsDb3XT`Thw-uKjo$-}2&LIGlQl@2+x{PzAI zq3B)IIdXuI1Ulp94CpXXzRl2Bd$5-e<1T@CwQJ-2XZr%zqTUzjsnt6wr<_XJXUTFN z*UD51Y;da&QjEL}xO;aaR!fcv{rgS74g;#pIAA?$w&(xPf4upp>am%omMn!Xt%hny zLcIMSAFn(AAA=v5UgW# zR57U4fz^cJ*xSoXxZEHmMB-b~x;4^r5fRxR)nhS@_TW>x(6sOYajROLA~HQ>x@wot zk+Zn%Xs-Gkc1Pl2SNh-RpLbvy=GaPeaI#F`Pi{GsN`dWui(%X^;M>)Xvw7fsLL%O= zu|pD@A#u4DBjmA9Eq>8X@ZWO|#EruJhKS_Bbaeb!VCZpog zAHJcao3_;=)mvDjh+aE?*J&-9iY4J$r4*{`id*$g$fi|P|cx^Cyh~cu~$e&+N-jYv|zvEjVC)Nb0xE=;e|7kBc zr=_OG$ZmMYiV0slJ98IOvgRhI2Vi3l55c0xljfU303avHm_etYa%bj2w&)*=1NrJF z2ARgyS8qs{dFFyomxki#Bz#? zy+gKpHS&pw@RS|Go0+Er18SpBp8ffDdl@w@`-dJVn$gU$ZEdmBQOO(z&b`>&Xl+a(< zV+Z&c&6B7~2Q>?4#DC)`)bWW$A~K0Ed;a))dqb#y73DBCwdl)5QNDQhoX>{fx$SV^wzT`Z2Cj23duJgAc647ezOoA};c11?L3$^bV{4-XF&au=JCR8j*K(}r}^U#1_7 zdq8+7ftF^=^VFBt*XwK2r+MA%y~A_RSP(xLB%Sc{zB%~J74VIv1z6dL*&%u$&@Lx& zr3RkEmYp#@Q=uWru+@teeCW;Bjvfj8U(A=L7e|teG3{W|4=j%5fH-m9dUs=TK6Jm! z1ixZtVj5TBQj zt_e|)wHew?RyP)d_j81%-=TBeTYb@$|>^5!#Bfi zh9ylW)HQiEG!sz<$r-9XgB^YJp&Ksvd7Iw9t_rNhy26kWA?0nFHQjWg$tVq^W!iJF zLeESRzS)gYT!BZkxY;wlKAeAd>gAYrJYE8?I^Q98W$$|g+Y`VFl3Mb(9>Tzckczdu zeQ$LT?y26Bd)w_+Vs90o$y-ekuu=_5I?y$O$w#c>3ovX0XEJg4>-&#CX$*XI#JU%L zi9Z%M7uwc)G!id3Crr_iL4ESR5Bqy&4$u1-6Su(`m9aJ88yc%K3sX-bhTZ0 zpHgAw7X@VOAGV?f0xt!gA(XRe;$F~x3$+=;l(4Ue6<>|i_OGp&JfewX(IQxKaW7Uq z^YIR|7kLXGed&D_61N2*5am+xpkuZFb@+BA(OdXNhkg1tD)mZ-66e=d^46E+#$C^! z1Lgd}h>hfWCW#m9S^^>#XT!Y1PuD}BW-+f0r2V06%Uu|H#WP0|>sVvQewjWeKcUtO zBT1NIGWGg37Mf=2H=SmGqEZdB2Vv^WbG1^&QmynNkzh}WAY+JtieojOCHlMU6YLs$ zujafITM5tTN&hbya8P{tE*=*ak^?0U2U6iW?BRp+L`!yy{6fwj))-tqZ3h^}0mdZO zpYl$Q{f32CUK-pE`<%A$VR0K3ngA$kYv;UR?yE@1%S4VGZ1EVig72~2pM?a5zo?_y zP?YUsjan8TeLyfBP}m#6fU0`$>H@~Ni3#HP`1pI&uVJajPY%kHuZ|*&T;w0%-8{@jz5bkEEv&1% zyBi1I3ph*SXXVi*CML_ayxfQU_yZC3be7%Zx4S_{nCbNzg_8%JL@NK){Ge)x>`&lY z9TZ&b1XKJnK=susjGGxXxeT}0zf4@`KlAhL-hcOevl1F|6u3?f!e`9Arw1Jb*;<9m zF2$s0)6<97lZDHdWOUvSoNL2dV*O8W4e=uKrH3R(Ks5o}T@Nt0Q9vB}Tdx@~+k!GP z#VY0I{<-yRJIVlJHyEsixk#UU^RQSQH3kN|}Ns>wB#rdn>}P z)6DwTRv^jxs(>!tQTmFOI&LM~p2Dld z677{y*s|Fn3CNW{@v;X%J#e6#kUg6IjrVu9zAB21YDT?T4e_=gL-Tqk^@o;_MVgDR z1Uv_T5<&9J+4-f=o^3TH7-+pD$9*E23V?wDeAl|(6}~5*+N}@B^73AiFjX4H4RPFL zOy#clzVkmd^s80o+Y61ewQd(J>_12Pf(M z6pue-e7WCOi_vK;q!uFYS^77e8G>7u0l<>?l0QI=-_NW-PY}A6119tU%KojhKm=zT zjeu14be&HGwk?zG`3?ST#rs!kInVQAu|hV_9VG@1NppK2`uekpDLDCfcZV(OVxmsb zEwh+}dW_tR%G;F@@fZoUS~GPbH-$+}c^Qz?Y4vk*dYUQYdE1S5va#{$4V<&%=H{l1 z_e)bkdm6YR7Pw#2UWL+x=e)KZ_q1)Z?Ln`OBSvTm(qc|IS}WN^D<+mBmhT!K zY4=<^{4aR8`SYy?3USeB>3Qx;He{3EHm{cORp7H84PS0a*Vx`tw8YtpXMbAOgeCJ_&*F69=ZA=g)nQ>covY4ZDPWdi zY2&{IR_2jRnM{=+>f?93lTzQ*bubi@^yqmCX9Kqd5MMz-E$+HSnYK#J@*IBS zms+b)#o>=FuBZ+P7X>xvHZ2Vrw{gG z6_&|<{TlIAzPrF@snJw1H8Lvx(>WBl*Lb?76-?z1hBH72=G6PVh36GTj-(0iO3eyA zHt!kpt3iC)H+o~B@fWUk`fBHW?|MMc7mr0DD=+W)5(D3HjLzr0u8BjQWXc6uEb zHBmT&L0$dP$Kv@DXDp|5uQpV&eaJ*;VzlbE9P84W>D+EZKph6+NCzA>;LWuy+RX#_Z(+7Kz zWXH`MQ>oTNuK0ofZ*M8rd0QJnbt4XHqcoU$BRIrS7F=J3}96{HBntd=k;Xm)vB# z%w=I2+MTqzCz?v?v$dEev3W-a40ujkhF;v0@qUtTnZ zp`LRbL$zGy=*-(0pG^=dp9#tbSo)tfAUxPU!))7}@@t|ZOa0=@eVpR&F^vNQ5lXYX zKo0_&PAp%ITpm=9_Yk|uoZ-Z_h%+xSsH$ZdB(;7*wSSgTyTc&=0Ph2*xGX&T4wN4` z0YQJc>>XF{Z~&{f>%)QourprwF3|eDq^4Dubheu)lZl3r89^Td^LEC~uBG!zXIPti z|U&lQ}1%|2xJyPiB+kp@LYMc`ihX;=y_OF%%t%i({D zK-rh`wb8?2^W5}PG?5&3IzD7wP|ALQV#Y&}rxfo|4_Z;trz+VaAXPZeDQqVVWjcLaUl!v2~AQt6|WjU+k z5e`#YuQ;DCS7s8IdnghWkBu&L(nJt`@maf&??cMF@7WiBf2?1Uda!Dlu@c|xF~6~F zR^cdl7j0UT$(Lxuz2t`Cjg;Nr_HG!TI43pE;VNAbZ6|qGo z@#_`M4FXm3H8*h@q{4~70~)(6!TFg-r+DR0;H?rw%)=UVvG#QF+E!S6w{%!d z8Ms}BP`QA2k}~oqsB`S>aDmDA(35)JVLFXY_L+N@s*~tPN5|ou25Q{1v<0EkchWq; z%#nhZ(1kcPcGB6(nb#^R3H7mI$b#QwE2?W}#5MyD)UBP|S{w)V%is(5z~B9e-WImqU-d`Ik_pG7>g zryBM$n`mI|7Z$uO9eqJc=Y%(+kPq$J3(psWJuOJzbd+VAon z;AW`Umw%PjIBp==nXQ2xmdh$HCZFF}IDe1ttv=Jg6fN2|lPeJkva)H9BR3yEHd6MUMw1JAf}HiMO-YD1MU>z9qJ@~#Hncmtn2G!F zNElJ=GTLKOEo2W&F|l8fY=r znjFLA!=0(sk(yrYq9U@~7syl<6kOKD^LcUjGrE{ZXyIc4&-$Atw&>$~sXz2(sXm}e zNkKum(lEpcb=JMY+(j3Yed}Cg1aJgk*#dNfH=`XyO`?kYUr7k_ZJs|qLhbu51!sx} zcvx`PM$w3bfa^L{)a%K8(b;l)3id}A>vR4D4l>}lsV7crkh6*MUk_Gnu++syEsUM; zjgck~t^$M5)t+cmfT8a-djjl5fVTib%=gBNym8?*1`A}NG~v$3&B%UbgJ7^Uatr5z zdYt=y=v-Rb7?gf|+2j)yf}I;`{7_J~;8nI7_@C=z|3fY?YrJg3J_rMol3pUFf3rfO z58^G6`MeL}Dz;yeJ`7GBDK?c7SL&kEkja<)aEOkmT?hnc9-vF1yl16NIoB6Eu0kZe zv5-%aH_^GwJ#wR5inZ&LpqvGtH>GDfoC%>D(QxsDR0hp`Zm|W>NBLDR_R!^yb4s5o zmVZ&@``YSDf1sCjB&C>6???3zPflv5?y|28t;rx;YDRt9k+9{%&DZiOJn{C~4@xDE zeZ=vaodpF2n?usFF^=eml?{eT(J@UZNxB0&uvB2$H^aW1Pr{bMCt3YQmpHtO#&rL( zb{9#@(frVnATfq;f^=@^g4$j-|F6q4!+G1&w5mjno+NWed;2WC;)eWiS4bof9l&+5 zySK+c8ZNA2BRi`WHFDDvnpI4l6(YWm4J2UZwPX3HNCv;7U%Y3MKNWmu7N>G{*dA~p zFTTf>SBXX?3{{sDWLEz&i<8j9jg()L$t+dLW7myZ~h< zgnFiB=H_qB+arZ1hmy~q zfYs&h8A-Qkdzpc-T*FGpbI8N>V=okBqRh)p2BuW(fvyB_*Ug}&o6$s=Wig1R4B`tv zV=<~-?HBeTA0V$v7m|gjG#KtyYH9yk2V}0Fvvv?Uls?RD_MXkBxmRm9YaDGi@*fsD z4%MNihrtG+@h2W#ol=M_gx8Yz(4(&b6~~7s8Y;`@+ov}?S2s8OPm!rLuh&_&pV`Bz z?w|`TK4;BHKWnoIiqS8$FAFj;F2vrTv|7^iG6`V^`f)r8&s@EV z%ANA)A8SqQcdNgptdY>Hyc)j@`rM4(CN~!?EQ>e>*7xP}Af3U+#-^+q*0U<)zDwS> zUZM1C8C_6rFk#BF_*QFlS%chamemeMtfv=`Xf$9-)hL#u$R=6RY&XWN^lObCMmgx{ zMe>P@NBOlPh=stJQH%H|?7EoaN5_Er^!E(I%&Jh+$(Rzbe7ijs$>w!mpz3tR9q16_ z*=!O7hAf8f^2QDhLpc`r2*djwk@s#WXXnv04jI&_hraW7x>|(t(_($B4eW?tlD$;FIxR0TEERlCcyl#JDSm`(Ma&_?rVY_i{xy3L9QQ;w`j$`H)DsI4Kb^s+%`d)e z;IH^qN_smQhH zCUW+bB`kw@`eK9Sfy(9C)4f%|U_iFuEh#c%X!-!>UKXE@`#&Ms=R0Bj<)eqSHD;GuoPGAxcLHg(Q^u325;ATJ5%~Xj`s%PK)9-H#K#){GX#@ih5eex* zLPS8iJEcoXT0uf2L`uYAM5MdBBn2e|=?>}ce$V56fA3y%@rSzZ&dmLs`oWs; z5uTepV~T^#QC5q1xkoqm*r=L|LZC-dihW+Fc`c%$*8(y-m0NgYo^%s`jiQ3X8&gLA zf;g{j2o4amZJ>JrS3Eo|MxLHD^oLy<#1BgUPYVzT2o!wJNRB($l*-5=scejB$#yz7 zZ(vAAb9{_GF)Y`0)|`kc|J0&;?sk#GvkyJ$5hap&erVMyxYnXk1P(QW$Q5avjq#Z?(w^2Y9|YTJ6A& zH)eTaPQCpcSVax(FMsOo#a4WOUzxxCuC?Uyzuc61B3legvqtA3Y)x(AeOulLqg zS0<(TLeA>42;E6Hx4?DOUwi5d>43<}G(c0GZ*(vn{z#2@FjxI_(tf~gE&+N4`r`>) zfK}|b{yx*Gb|<&1Ik=7NDgkX}wi^68Q8Z~0eMIfS#iyg=W#OE+>h|~d6*7w9CJ6}* z1>KyXsVO!NTcL<4(R1(+W5Ke+3s;ulp&dZ+$%pHOSw5O{yDlI}gWE1MD3TIj zObORx$Ct<9A}Mo;5%(gb%35!`^Aq75Nj`XX;TlmOID?JZ-9DZB5=`Ws z{Or{ii^aK6XFy5!`R7KWZ^J6Jbs+k(>d-|)RAu1emO#MGoTpUcJXGyQYPz*5haA|{ zoi7Zj*q=2>ioc>N%q}gE*K8=s9H}qw<&m4kt6rtN@y+;oOAl+Q6XC_`S_;8oPA|?! zB!m1LKS*{@lyEa4EA8qXIoNd8wz4!r?3UYR1~VDA5y(gP_siO)>(>0m>XR>lrp%Tt zPV$~q7*)6Y9qh;Bg6Dc+UO0d0bSl z;93Ri)eS#R`kw<9mnOVA}NvA`gGO_ZJ}aI`{+E}6y0SuVR_`*L9Z~$;0w!w zhU52-!ZfmsFsj}*<1AhseTi$Koo_{Fm9?+s_GmP@SZ;@{s(bpVq~L#FB$i=H>IjnD z4q}m-Csw*R5ZW>4)=Y>~cLU3~ooQn3d3HQ@gC@_}%iR73SADNP!e`0Ksq3Z07wvyV zXN!GgZF0I=*kAsDCF%DsZQ`l^4F8K6#FTUL1P1$FSZ3kQwya`gbBl*0K z`9P93D*7i&zkL^P%JR6N4L6f5Z_A=Zc{tbDoY1)KINCF$sYJIw9NW!B&x>J8nz<;q z>Jr2GTm|MCqMjq~ARAMyw{U~@$HwY=QzFR2>2~VIOr$(xY`Yuw&fe7rZT{)R-X9yJ zo^XF%i!H+?UFQ-xK={*<8ZYYm)!SDPROv&<$Ng&UNDVTW?R6~1|?7OW`HJV}lrCXVR!D*?VkDVr|Cua};HBxYABKWUD6 z;Bb)m?oVygKpu*tU75-NwpEo}!`0V)egmt$)mPlJh!p*Q)#161%*M zuD0aCtjKk*%$CRUZFdB~=MZSo0{VN%oAd{R7|^E3f5sa)Tm-`o%y{Ef23c)JyRI%%ny#gEJROR>yyPn%DIe=7UUZD#CU;!x~*_1gVN~f!9 zn;arO8arz1>W#~|zH6v7mOHDdlZj)9YH;T@6&AUmPA7kc2(v+J%v6fy+V zXl2K|yJEJ;HJkfMFZLx{gcJi^IHJ6Q5mtQqQDB;F>5`Ik29aOIU1wP%k=FR{lP6Bq zPFiEo8_VI&Sd8?;#*6jwknkk5?37Qg3W@YhlHit&JtD@bJ)*Y6$S8r!8-l~Bn-}MF zoJ}ik_c}BiVO2`r zi>FNl(R6Lhtv{KwPJb9+N$DwLy`1czWyAUiN@%IF0}RNBBx1 zzJJYtIkRMYQhK|3#c%J4g1 zW#W5l#*1>H#+mtu)7QkFSjkEYURDEmy5%pJ!=0IF=qOzzw{uAL&@Y9;-~}i6PQuIc zkcHF4TYK=YC&|pr1b0MG%QU-tV8Dyf!h_T{ozb3sLFFb0XPt&KfrJ}x^ui?fGmZ;^ zx!reIk?RZ@RBUZ4RIpUk@<&I8qePg`CV5zK(?e$0w8HFkUNuOfp#X;P3++M22xIzJ z1?I9S9J%@!DIt3z&aJJNyT@)qAO}P0RJF$*=n^0k9;B0_gZSJ|9O&7OjxZVQ7H`1& zAa#~6IlC0SK^^2F>sQi9u`7ZQo5P3YwIlM<~x z!B&*I6Rt3ZO)!l!+rVl&3) zT7_cqQxq6q&HUF_hU+#}2WAEOD}04`owEz*bQ{#n{~jeRtPZF*QM=r;sD5~lN<>@f z@f+gyb^dXFiQpe(*EDCN!=h1eX&VjVlIGv;AA&c*^(yV0|Jl6&wGgun^wd+UM-#%I z`U3lXY0yqO12~y%`Ho!I36Q-quyYf>A-Lr?HXLF%KX~D+QoCMPH0#e2FiU^^%z>pP zs#(26v`2Dt)U>)P(7Ax<-D{g#PZM%$m*Z^C7WFYd)X|K2LYS8J~6+IX?~aiC^yMeJcv#H|G?*-)SJQL$u6{kF==(wq1dQW(AwOC9Rh67oToiU?Q;izl%5-I0s*{gG!|Ryb>vDV4 z?^F-a_|I+Zgy^2!j&$gL26{T8z_~3qu$lumY~bZZ3l;zb`N-{e448#tXI~VC*Wz2{ zC%NcS846(d%scq8{U8J%c6oNNNOf8$TBmp!X&I-8s>fL!8hwNnJ~!N;dw0CLVS5+B!EuLSID0QxWD~oxs(n?cI60;H=9OVg!~J zTRCojr@}!ei%rBY*4L+VDEB9#o9_ut=fSt1m$1&ntHZhmuA{t{VwUEpanCw2g1n%` zt7gR!z{hB@neO36A8c2vX33tUc_j=47vS|LtX2O}`Fn_YSCTgf>)Ry%8tNh?Ya}#rF1g z$lU66Mj}ZCYdFI(Sn)6ZKyVI#`+6{0g0|XlrT) zip`@%Yc`oCIZiz}u*7cY;H=O2onv2HWmL&cf+5z+Ym{Y?PKxo8_T%%z-3v~6B_)6R z)KYsO4+s#Z=FZdQ&aW!0!et42*J-2wGC0k)F((fOjX4KPFaiVia_a3Jdr0lksc^zW z>}53vzwD;Qsy$XYdI7BianPN4d*Xg(N*+dgdPwkt08fNaUFbqcN#$a5}?`&>zA{dchtaLJPh$Q&_P=!V{ zO=q6S-ieXA`MLhhLOKMt9* zu(}yi@QIt~Y0P$Vl#joqx9kgr>MYB^)@R0uI=H$Z@;a}){4LlLW1oDMp3cvI;5y*J zO!k8GoWQtsYL01>vwL{XJ$-PcAJ;;0VUO{#`t}h$&wq@Y9 z4fWFvD$Jj~C)JELmQf6{=Hy!_CV$m3T)ei7&xOGr)y-=@+a%pBZzaBGTX?zl8a~ZE zih42hME9xyUEjjf(1(^n-A84%gRZBN*s;+fPSzT0fRo@;(?!A34)_odJV?wh;??12 zv<#Zsrgl{350_qhlH$jsFjoI%_fqG>u{Z`cOG5Tt-r*+`_KQ}b`@fHzL%e1Sh@BpO zF*^n+fpqc*Wh!L)g@+%$P6yJh6Yp`BbUKswG?Y$~+Z^A_Ol$OKNNT9LeZBV^=$nzR z`(V=)8IW^pPX&;41t@_K^yC`zO}MbRW$wqF@|Fz0ln?Sg2IL!R9i^U%EKXT}0i{j? zE5Dl^o<+DKWibAkS)+0A5{v_-D8SkqelAy~H*NqqAkz7h>D;%DXECvh0wqK` zi}SM$ofLN#cxYwx)G1pxPZ@;c|Kws%Dl`pnlbo|J2u~oj+}QsAmB#(Oy&bQ$9`13B znd(b(TGVU(_F{rp)Z|RG12OGbVfgEnMdf%jBCCgqHq$AM1zD4#aoPAGY7ZJ5x)dG{ zcPh-E-e~U|l6&4f$1Id?ko_I<7XX=t83G@CWi)jYuM__XMSEz)GPY*6eDi$cJT(32^QBZW&PL+yfNq^ikrD zmpJB>+n{a&20vR;|L?q^|7j*ek#AL4sC#XXLSqq<`~`Yhn5WN}F)eGTJsQ;MX8V|f_mQhN zppSp>jNrF`X@MY*mN41|uq`0aE;j87NLb?!|yQ&>lGuOs>RKqlJ8JdLDNOOG)cST#|h8I2T z?j`gIIMIkFl6dn+)b)uDl`(uZ^26!T%bn}6`W?inFLIAvP4-9rF1p<~`Y{w6I~U?< z9gYgcVdMU{Mjapog7yK>xJoi^kWzso0-6Bv>*{mb{Yml*hU9DlEiS@X_L5-`;_ZY( zk#w$jwBqc@gwlrTDWQp)q1B%I-P(M+&-67tE~^7{?|f{AHHd`U(g{GVSLS^p@O_d4 zwO8H=mUl*1`#i3LFS^&5sJe+|)~@-5g~MZwbXI_qenxpwA)~hgfN@pFo9(M?KcFB0 zMk1X&wNA!S70WDQG;}{Y(kZjKDb;<9a z2bV&ngCWs`bAjf|(8|NZlN!OL7NajOg-}u6(Ty8MM>`c$u?(Z(MvpM0e$Ae{v3zj_ z;!t4H!+*pEDPAY-EJ^LLfIUC5z@tJh2G}Ay7Z$BxkV9H{;qhMW*ofzZU}_w7k%-#( zW4$z-E7d6)(k*ZHGDKw^s+ztC;11F0I-=loC_SIbH$w((6n0WndPp}$OH6yuwnrP1#0^l)% z?;>SJ&*#M1bDDa*4!mgy#16-%qdKuJHCP7!!lgh53*!p|L*FmsCLWsI*O!FHWM`>= z<4>;lpIKo$ZYnvB9u-(};`L=@)t{B*eQ#tZ>x7eCsif!S8S=CX_F~-FZLpmPzFi>t zkE>;I_T)<{<<)D~v324;K5}=wIy^iK%@MRnQmH+y&tcgGSSI1V0~?X&yg0p>0J=Fd zwowX8}0`*T#sy6BES4Q$YQRW zs@h4&I^Ky*b))V`#qf*qHzLmC4wpghM^!B;R5O(w;~zI2TwExCsDsC>C7j+>(rOjm z$B?sj?`+v4$)gl)TsfBZ=65S|j{NFX0gPIC`m|+>Udzw1+$E{@onqx#_SG}3+>W;$ z7#qwg9u#(XmmOccPY#`dZ1-Gs#86LNW;(2Iy(1qwpBj$HIF$eXxPxiT)-JVQ8R9{N z=^C(T13bbYPZ(q}w^oq-a@=%B|3ZUC?*{?#JlV{T&*K&wE%yj{a5RNvmL8#>XAKXuPFqy4M_YRK=m3C4dxP9?9vdc zZih=5g=vAUz*q+E?nCJD2C_r$GL6&k1pwDLa^D(b>X<29=F0!FskTV1fy*=`lMDf` zSHK?**W%}hAVpys^|qUREUz3b^Wy|=4)fHn&D^138tdfz^CP&KE5%GEwP*G7vz$Ad z79GI$i9v_zWh!kWxu4e=eSty=qG5J6X|OTb-IYxBHYr zYq#tT21RX3O|_@ryWTK`RrZ z12wE(xBRVxL8*&qtRy0=^jdfeDZYOIfuNe(w*;Px3Rs9$b?(G_;rA`@jGsJ` zUB45i=eg14CII)4hd(Gt;HymVSmj5;z7P)R-x!o#I`(~WF+3ruDKI#F24aF zHzYiK+L-?6<2#fagxfhl69ifqxG0B0H9Hc*^$_N$cJ6JQdtNOJ;U) zMO6iq*G2n)8xo-`#f}uelDV*0r$11Nz85T$<=brZ;N3HgfF{m$c7$6MVd2CcOJz$wSKOjgG`h(GQIzuiX{=Q+^mTsrgz3Y6su2%9S;V^rO+=I3 zakJe72uF!y&$~&8H|8gox^u>P_75jXACp!K!m;NN77m57jGPyrmE04af3p$H&rmva zZn|fyi5CviaGKB8JYm8ip<(%QbY)MEn%~NeXYCe_8ruI<9hF`dYew{&Aqyu~hP9nKoaD_fd0rK zO4w;A0ZSzak6<-y;2#%PSK69sv(-{=dqjzM`g6;K`)f1RwSiQ)ECCU2eic9v+GW^C zLU=3Y+J~$$S@b<8T8&Lge!g00d7v>a*Xcmp{bZ&Rc6{P|k4F2MX8+pWD4%Je=JN7# z8CSqd990m+Krvm|%lMNK8P1o`VIloF-E({PPQs%y5gOgU4W7Z&WY;uW$lu-K&!G_f z{iyjxui?*4_ps_I2`_aXt%Pr8=ML=y1XeUW?PmP~lOq((B$(XaG+xuI?vfJyGHOfU znV;SN#rJ|fr4|vdKzpy-iRkw1Y%CZ_mWZrxwapwZKJPiHP;G$ z|8imZ$X`CE&$jm^r*PS7sU_Cb&!D z%o6Hh*wCHnfZGYd8h|adEM62l5Em5G^CMb_ykGUo$Mc||efpPYKYkziB}aKiJNy@N z6Z8j{4+26%ih`eD7~>=!r|xX`><&cH0^orz-NKj^N(G9wzG-M3EBAwe3A)e!6y9Qq zSOz|Jv-|?k-LiASnzc!!pg|T1NK_v@d>8;7zbA?qYxRrfrqQMnRTeXr(nRvP05L9N z<>b87X)|RRj^F?mR=$VeB7~r6m|O4ycid?~ISu^{bj6K`xC)dwM)~ur$rIN@B?FZn zrcGp#Hn}T!2%ufMjf5Ie(b9yJtx#Sw{wykdBFmxP!BY7-sr+fZ@Lg`nGy>^kw756Kv~A*fRNBGw%^tWK%+r9pAhu=(@^xx;bQ( zdk)KcA=Vr38oSPQPN&fMdI|5gqPJ@gS3si$0%Z+0RMZISEB!rCceqkaO^1tw$$L&+ z-CuRBeYfU0Cs+m|N0}dzA@ymG+uGU$$-{?EBK9(S2=|&9=zfgbn1rw1phz`uW1Fgi znQ3mh0?e5J^+Q`ZjdmS#VCjKAgG-0yubN)~)mJCX7>I%j2PNQvox2Vg`!^+)n^*AQ zrxOv_nXozAZvuA=f@mN;%Gl^+FH5$dk!eVt=kAl8H@2h%0oF}HopKO?W ztH~yIW*D~K>9nXW5n8z~a`pbvdR57|0ND#2=M&G`|4#;m;2m3Is6*} zNE-T+oa918psl+lzSYuF;1NmqbZzTwmq=b-rf+@8pludvvNe@K`CRX=a=WrI;hBoT zpPI~;d#`RZyvZ&F4YHdXB|I{%CY(fhzdAcBxpX{dhJXGUf<&~&0Lal|U zNAuM8J)Y%W2o%=77kN{G;bY?7+koB-qYnm;TKYSR-K`g^u2`?@1;|((5_*Nzo&yzb8mSP2g=V^+zU(m)vg`V~&Q|YFF|Q2CQ!WhBuc-ny3k3Je-9a;CV~$Rx z%df{P@CAdV4tN?y9rg=Pt~+B*AggE9GQ}63W;3F{;rrCxpBSp9Da++huK#%U=e;fA zAX_}0jSyQ={}MmbrS^jJ_bmX11&9dza`_rR@hm{_3dNqXo+=b)ai?M{jfS57NxBLZ z6|OtGEeJP9ZJFr8r{NMrGy(v^zrXUS(|-I8Ci#ne_$>4fv2CFpWU{7-2@xl!-ed&+ zCR2oC4f!TBzrb!YwNa-0rfbU%K1wJZup0phLxYmByqwjJowH!MV3YCDZ!7&cjsm~nx(8bD;n#A3{@G^btvr?N^KlMK^I%+8W4l1si|>*y8$jtsHbqt zL&_mAX+)F8UZ-h1HvN7b5w}!#yVDxDxlrNy;BYNE4gZk8?6@1=?|hP%4Z+s7^2y)3 zYp&MpP=7O@qVoo9JXY*O0JzY?-(9;O#^_Q*Oa&ZmqQZK|PNitKIa!m@#+|SCn5b?i z+~SAEBHVL^>E#lv5<;(eLRx7dR4JHc2^eY|{rtvknx4dXdWP?1PWz9E7m$jMs8f#C zUm~D#hMON<*xlC`W7P?5O+@-%-)(`ubAfRWx2vQ!r4u$99D91}&y|I%UVZz93+KVD z5#YWAha);2=uKvvVTw;z5fh?w)rcEV-eI8OJyl$5MCI#SjudE!9th3_%2}YsQu{sk zAI~L_ssaB5=W{iS=2^HkAwfprZ16Q;$k*=U}Y?~}z@ac+&n?jio>v_Zv6OwmL93U2kIS-yPIx6GK-<&?f*69Ehu?bl z7u9PQLuA(68i>X>?y9fqQ&T#5F9rpA#z-f-Rnz;4gNN~hGLa8rLLM(O^O_PO5olUGsu7)e^x6JlOTm^m+w z$g9`a*wdSs$Z*C;! zUK(>U!`Gcg+lVS~_{OSIUIb4)UZLK|%;D9g7Fbi`H+Bm`%c$C0j%s-WSO~lu6hWi> zkMCT1xgQUCSJrqM53H?W_{)omX8Pu=a;yIiZ2@CnotnQM9`AX4F#1jLO@}-?902ee zB91ulP{@m%a3jJZJD;QBmjFZ{J8Teo!hC{1FY2vkz-(N_xK##Q<=Fz)r_KIN?#xWA z-G1^Oiw9cIA-5AUW8m}tj`-=4nq0bW1P(r6)8E-J&>xqY(RFIG;HCm064Cttu^ZPc zj5@6oyN$ql1Dq74<*Or7SLpN3w6g=wI5Dnrk0$3!#Lm+g*g=!AvoR(b{TX@?}3$CkEVMy-?ie zFf3>Ks;Z+T4J*T|DSkXG(CCTLMDjggy z7nHUyQ(~jbXvcqvx;>?RS2W-;T3!EaKc3cZEH|;Asv^ta@lww&GcP&nqnr)Zh2luY-uj-JH3`Q$q`r)`NxHDedmHBzt4P>BFlhRUYxv zBWP46gcZ)!9M9I7<%Wb;_Uc&%l`@IX;03Rxqnt~@XylL2e;cl*_1!#APyr6@%o5b7Dh;3xe;nse~^3Pj*5N!rCEjukk_57dr zNg8h)6OW%J8Tz)iTqDP@+<)%&WD@UPWLb(6+R7_fB#UtnzX1|4n4{6ePX>0DufA9r z+G9ypu~=>39a0~b7j$u<^BuDF>EBa(kX0hzqT64YLrBFnsOL_{CH%JIT~jGV=J~xI zybNE__8Vb+)v|<-Mcas1WV$|D4lxX`0qX!AwOQ}eWF>g~8#Xr!xD1Aap6ClN2g*|# zua(wXjdKf!o#za09LkvN4eU1qUSaj9*s6a-LujX0IVlM7U_Fs&RD*>A*Xik7z=~}T_~t)h2NIz5 zPb?k^jKz$$WFVIJbVRL!uYwXAg~R5|QwZ|_wAt16=g<%pjON1_ z4a~19BL}`635wzK-g@E}d>20kHT_=T-aM$XqVDnfFs|s@*joj(CbVdXf&Tb!{7Y{O zJYEx;FnYnipWgwqfmRmdjB{G~_FBq~^@tJ#v!v3Y<|CC0$FnlkrXqL4fC(U4;yMw@ zw-%zK7s%AW7_#!G5dGc1>O*o_!w<7KqVlkSbe&r+Ul_U^BqaS|ytoGJE(~>m8whSA zxRZcrgmP&|LQHf0_teSJ6Lt+@Z4$MOg^cBWE$hVnXZeZFzbARZSPaejYp}R*QK;EFS8q zXc}t!TrICyEHQUxxa-rC_z;1;6=8n5?EN-k`Cwv-+$rL_%&^vv0 z4Zf8bwDBjiuKmtLGEoQ-Rleh`_@+7K^c(lZy~bi}eyE3I`&XsZ`PDkmsJ0eK3+kyG zhsB&QD2c|udQ@)>@NA&fu=gS#$;Ab#IzUTAtL#uMU6dq^w4X^D5e$^k4qbdeVFoJ!09<=MbNM4mp*vwPfyo#^) zbFX8|20AnV1JS9%j;~9HZICc#XxD-JgZTjT0MUdadmJX8B7o_aU?c@42t4)zxx)CK z+-=MvH*ge_&-rV)n{j3Y(8a>PF#BTgSLj&##y650L>&5vG8&?3yB3_fK(mnf2VrA? zHTV&i`er4$M79C7NQuj#+a((Cfd>m-rg z_TPx4hpxppH|$0_n+Nk!-I0g2Dp*yYfn;~m2Ce|vgM9_r7Wuyt7Ly) z--wPLOlR4Zm#?vhFuEXe&<9ZIAx_5=5l#T60L$b4t))OV!vj;#8XYXdKVtnbkf5S2 z@4?C0ywf_S)x*|JV8V5V@I$?uJaB<#IUK$oaPI&Y37;&;|H@p~5(HBNY3DJ0nx78*LK9uo_3r)O)#q4n3M9XwHD~(tF8ytiAlwl<-gdy7JorDfK~$+aVuQ&&h>yW$-FC5IA!+ z5(obo^lr~3TkEb5_Q|>nu7gXtmc;^5dhc1*fwcwI4|+sY6RG{9w(zseh4bVyEHC=dK(;!Td-%axx=d5t0Fq$S6PTU0(9gTcS@o}2r zUm`)2i>{_GQ1Z&YWar6P`MmaUvK^BdZYNuzO_&;9VpKgXg+0}|X%(P{Xun^({Gtj4 z(aE5`eQhlA73%fqEmm;%39)KxGkXEuvcnY|YS zdh*YC`_mAjP~oj`^PNKOl0o{p5D9y zOd|W8hr*mccrDoGuAko{1jWlxDIiq|(6_O3nmU)E2LjNZzQpOd0tXvi! ze{+*&gwVoZ2_^eH?^d;A&L2EeGqV=MYvjApc2~q7m|i;4W+wa0Sq!qV{{_kau@oo$ zjY3%^Nr!!9Kv|G?v0-Ypv(lV#{wyg6XP&Fu`%ErSTy4qxXD8jJ_ptXsJa>3c3R4(C zyo>Vc>vzG-C1*DTHWd>HiVWfEYr344t*YFR7iV-RUgdE)G57G4Bu7)zr~E0n_g8I> zVVut~!TF5f1#`hPvU(H7T9~zN#I~2u0}#g#VPr(f@!Kr4)Op z@(vsjf9SFH@f-T)Y(=^2t=G?-3PdWj$$auwn=GrjXI9At^yultu~qh*Hx2tg>s@Q& zh4?-@*8u6ix)mvpS`exL=|1VnJWQ>V1Np|tt&ZffBilP*4+auE0pk?~1%*PoicSXW z6z68%`1n|JvL$)D(({Lrcq16!{f}c$=6pe(i@25Kc`1^%am;S2nrv__}a(Y#J77RhfA7xS4ADCuWpB3kzLuU*<`y~I8EVn zFAWt&DV&o%L4WfS{bLl#wQclLnALmd-v-mhAL_jP%rpN`U0KY96q^4m4nkW$xtJ;5 z1@?Upg0hRDK`=8i`~g9!(qceFOUK+V)7Ls&a9tg#KRgtGen`;O-&2N=n$`L|U!%vX z$sn~&vIJdmKOBxKk#2iYf1mer_}va|5afw6&5JTrFcVDT)S}aV%~ifIeB?v{*<&j zxzyLt6y7<8<^tl6%_5+Eh7sS@mI#x|%T#^FOfnpGJGih6wa;}M5m zDi+bC3+?5;qS^SeJ$A1W8Fd^lSe~+hm5D_~x!3a?JpC}9QVOE_UE+NVt#L)dU zj>G{=IB92(4q(O;?k>~7R>JtdaADWEeCyZa`l%&S%UeHP-fS*wq|Kt38rR8dgnFIBsjb-qa2vkX7EzSs-;7 zgRd9Mea?CL>bj;w%(L(eq3D7LXDUOL7a#-yu_+cf4EPfy8^Svyf~MOFd9t}k=XCo+ z)&$)OW=m03nTIOvJziEFebZJLo5)*D4=5@NQC?@V%QhWLa37u)c`j%)pdLPG8J zm*9)z)i*Jve!1TG0)3IH*k3@T4i$2)KJlQEB~AOBMkin1`LvaIyRAMCFEI@HyiT9t8RcO&behH;*hM4FNC=A5AnM57az49FCP3$-DKA=)EW)EBOV`J)R zl1cJyy4KuLU5Yz6-HKLy__OZlF`7Q*sD)Raj&+@W^{10lZN1~3ThCnS8W4|EtYEBx zhXg=)@^sx_5UDYOZ^;Yqkd3*`(IVR*%N(Y0;O_q1^<$nEU+@(Mmw9b+tUl^I^x@Of z)9_3qt<&M*;SECsBgV58WzY+izPK$bY7&Z9chaDit>6(=(B;Zb!X$JKdXS;mz{$-K z%1z4@G(#?Az419Ok^!Jg0>ewGZn2hgb1Z25zKpL`n%{8u+FFMdLkl(^Wp4*|oHuGy zC3j*b+jAEN`nz9m;#89n)Pm@i28U@r%WpW?rlC_1Co5iFkL&k(_zX6a;`qJRe!{wb z_*VkkB!^!0JTuN0h3D8_nXP$_)Qz>Ob(g>62UmOg+IDfNz1rTety~Si^4x3MH2-~5 zqKoG;&yg+eq_s`$iSQ-)BaV19m#&%RtKZI#m^y2RN1KxU%<~OaK1ccc*?5q|Y_W*!j~iJE?nYgZ0=Xk7_Bu#e<9|)T{f2yEfY>W+C++rh zyvy-c^#gVsx^U=6;6l4%xbg>_5_}^`_;u9jQZX z_3*qL?_Iw9($Mr)9!=&__lXvh&N5x2)IQwvp9P%pkv&?7I|@!5;-RyvJ$VSb*wLba zL=l!h^F0bS@l@q{&INiZGl4j6nfZjtWgwsPN+O%y?IwSjc*F4?hfCD$VmT)iK^ET4Z z%4Pcjl1_;()X+~?d0_*StIV*|;o{8CwIN%9!aUvJr(e6%1gFz9*o>f)DlQyf6D${} z&DkCij7hSBEydZ2&71bL>bfEoDOu<4NR69sM0Lis_2cNPL>T>H$TC~{mUZB_`S(AL zTY~JShOpGf?%0I>-b&SIoEmp){yu?K<3{)U*w<#|rjT*sM-oRdqDE$+fIN;jrgV+JNPhm3NKw{v*CcysqBKg+LQwnA- ze3DmJKfT1dE1aCvJ>O;cw<26|zl$3s-6sE3me5dmT7v@9a~5NluR|sAvExzoF z(?|Dbov0*IzrEiY4f$xO`aqhGoGXUI3|ox>eg&BjpWEimsSQ5%+Cx?sLE1Nrq}yQk z9!@8NP0_$H$*5->aU5k>nDX@Vt|hiG9Z9nlfce6`8s&tQZA7uDGDQ)8hMuN+EAjbD zN5M;benM3jxu-7AHmKIXBrxyL_bJuT@hM#^_i9d+1y9WWnTx9f zOI^d}@4vTCozvgkr(s@FO*a}h9=%Iubz!e_reL7I|14>}AO)pZHA}60uRTl?l0eLs zx)>nO2qDz9vR$N5T?JleD;{Z`ngq5-SxdhY3jZ?E-qjvcl;)=&Bl>`AJ*Y-0LA(NB z0?gH}eIp5T*1Y2%2Oc`y1Go;ceU<3KT$ae1ITH?QvWaT z)$8aX(lWEhqOab1CGLI>OWcgY@?_U_qQ>@h#AKEJp3I+Nta=a52W$?E4n7cTi^4o% zjUE!=T|P(2Pj`0b?4sT22E8#53y>5EP&;^HfzO1;7hbE@O>nY-dxJUy)}*NR*~ID? z$*Y^xi#?wEdUF;Y9>eJS;#GkNDGI{7f?t2t`0!u)E*6*Cr5BW>&MECCnd3&1lcLsS2%rm3* zIU3W#|D!ZNLp~=$FhH2?+P@GiWJBw}$b*r|!aDo0C9noojROq?Yu`Ygy+E`>Lx2OK z-xmQlDtVQe4V+RxkXyRl_otQ2yNLeteXWLB7vEjTm6=T7^TVf(ju-54EA9tY~p39CYNM!UW{aNP6TOXhh^@-Ef1;*SmL;U~|?uZRYl z&=VDDNVbel;V&&uSw)7P?iyYl*T4=$hcN7 zgjF9Bh)~?s#J#UqNa|k|*exa?>4`yhn^jaScKmKL;Y8>cXj>8soqd~U(w0zWJa=Q~ z2R13g-qMDD;j!ya(>>D))K#xQ(f6uj#GW!y+>ORZ@jeVlDSdNfGENyyE1q}~^b;O$ zb=*Bfp&#yZJPr6TyoK$sR_)IGd?six&@TXz3^eca=g$%C9H57ZO6d#` z;-?4}=>utcsHCy^DjV_c@W}rH zW@4EsTb}Sii7?6^g^l-jYz~LssV>JZsR;jKb+gOhZUOpXqdK-^OgcfswS})@>1%X% zA89u=L&g@gD2N^dP&R_!?hAYlnHidO^zaW|49F-T@iqlarJ- z%9UFA10#&b`%Q@@pZCAtjvMEH+{$^5QX6|>ni=y$s1}uyY25#xqbAB5iUG(;3y!>@ z;C|~_s6&O!2i_6pqZ+_8y!nQq?3O1M#&1$&E~0nff`BRb_L0RbkYoV} ze_Bsi@HULD6i+?^77|e?gQfs9IgB!JYl71mNil-$mx(8j_avy)nT1%=IaO*e*y~wO z+P`eg6QAf1;1=-r5W)P}Hk@&F|8f`mrQ~|oN3qi!MW&G3hSlKWk%Z(1$YRs6wKdS^ z5cD|}LbS6$4t=XRRBb$K9$)YHRhy-Tb`ftgv_?P? zK|0%aM3D_H4oF&xa`&C>-Z$;x+JEzd!8^6qY7jMtyF{7Zxqu=6;KvcrlpTDZ?IFPn zg@O|l{+!mx-z7Vehxx{H4T~;pUYNJPoL0`^TG?`7g+*XiP4Z<@-EdYK&*MSl{8x7f|hOip9E;FaK z9e$@l*CzFVwZd%e+(ENtor~4?OLPxM+k`#sk9^kN zd(B@i5Kqiqi^0s7dko=%G8b)U$CNwe25;>Oj9#50do-t;v$25ztHVA^b~ipqO=K1p zO2H-r@Yq=FT1+hLxC0!@2VXvNMZhNkgd#Ps?L^ZxeW!pVD7;`727GLtvoMsIrIXQT zN?0}`1(u!i_x1WX_@w@PH28{i9$G!H#STCmZswowP_{t^4=?cDO-FkMV4O#ePELv} zK3#dXq;f|ylzU1i(*cqN%3E(!)sv~e$33tQA$A=K(if~j{aoxpvr4Wn)NfZ1o83L# zoa6=kd3<13`*_FicTjsM1P26h2i~?H_;~eZBX%<8<-oP!J+`H8!p9BR&KIV=RF2m* z|K808IaO!c7xVu|)LTYXxpr;CG)RhobSNk(-Hj+JD%~I(R|&tGe9&m>hM;Xa{&9d zUAIy9gG^Tlb|DSxgiorm>zbDdCKW%;v9MjSI`zYW;}sza$0#rE<v{bI zO*`80r`NJM>f9^QVW@h($Q~F*udc8@cHJV|&tFCgvgTgTKrOSO--$U4S0DyVYXufC zT1?c#=|NN~4(|6*4Bgp5w&O?p(;1JXX2==fV*X$E^v;-R6a<)&q99CEJUjRlAmR#k zfAA2&YXb)4x*v2L^}UPyumhuRM8GBp+v<K}t~B)ittIo4@3w$a z$B2HQE^<$Hy*?)Z(24vK!?^3ey`nvn;x=QMAc$@*A#P-)x&QiCJaOq3@G#?P70-6)n!H+x{W4LFjac!L??m z2Loaaxm}46_n_$nl`{jMqIgQbN>>cobL;9;yUBS>Rx1wLzSl8{{4Fz*p$D}S8@EbdH)!XZgdVBYg>U`rW4w4G}IEYRY6<9z zQsS|X@!F+j#+_7dq0j|~iV&xybfnWUEn6;>pVX5qrJB6qI@xLRYoExK4_iJ6og!n9 z@MwhRdURW;?EW^1czCn#IJH*vgso||eRZ1a|LMrS;s$y#>Y9sg-D%Zs<9N(ejziif zd0O2gkM5w>J1H9cFY>zO4?f@0$$=ex6~=fR)zkW;{0(B!aK;S z*78eBN3I=gzb({`nVM)1h2|TdbyLQ6f38$kTYcD>!JGr%JTBM7FN2AEc5g1s?P4M$ zF>z_>3g=5+n-J$Yvd!SteRfd>g>Tgd1@1%$zgb@`)ocseozg)|(Z#G%hLTcH4C)pC zBVM5;#5o?VZGHR_-Oleg8~~ z=)7s#0Y{ry68dnTNQyk}Ao*5PzgYSC=ZifP;oV4Z(QWx|dBa8sfdD9@;nF&9=Od7p zFCByb{M@iETp29niu_>SIKC4bGJ>D#mEv33s3&FR>od7~b(Pj6LiBOHz8|yYXHn5) z?Vm!gZbe0whXLtW{8-mz$q3b$s>iEXA|FIj;9K2i@aCGJiCCwyp?#`lnUwhY4GZF~ zr`aRNS6nuEssk)@ckvQ$JPBlapZ!p9U|E4j^S7pM-Byxj(q86j!@*+ySpluFI##PB zDRt6G!rA8Grr451U-gFy9!&3GJv^zD?`-QNK00DHY5o@KBc~vb&-ykJ+q6D(z_dV zvQOzNV|%sSq!*HMrbk($Pb5}U+uV(|ZMw3bXg`d3eOh20XyV#KK24JDt`Z6tCpFwE zW#3hGfTcVZVjjU&zxA8iu=K$tZ^pHzR7*j++b;hIx3}9j$4*;LwG*ZM8CuG#-*z^! z#lXzDKL&W4;|CdP;@4iL?fQo?nU8k-eb49n)184B2h$2GCdRx?_Q&4mH;vGFYZS2O zZk;jIo$zbZO`ip~-lV@ZGWVJB;!Bc$9Lw4kzYk#)hshHj z1^{g#as~(%R_|B*)bO`U+etlU+e1%z>ii-f-0sJN9K`N@bep(b*de9NHSP3)Ylj0} zlf7j(b#V-*I>EEfW8SxI-Gcd(QpR|Zw*A0{)zOJofw`FLg`AH zzhCWrWf>y0Z&#(4_+QW}yuAs_7#gJ^VaB*Kmq|Y}wx(Sq6@SFiUaRnd-oV2?W?cvM z4H1IIF~1`|x->P!o?LIa1NW}DbQ;=1>4s;sA2oC*fJlFn}gE|PXv<{X!Adx0qs zM$tV%=t97I>n4SjzX05T#iVMItY>krMp392$*%bBv<}z5gWFY3)I@5NaS8c3z#;)M z>CH_s2^un(!p>*Ic>XqkQCPcw1=5{W*4$!#nROk1QXU-^&tLDnqI2N1IWfb&7k0EG zMl+Xzv^H85*bpcpZ5y4aot}PtacoC~Cfz!HL>M3Vc$8i7O#B_s_7vu9ctsci!PwZO zq~pfCgTI91Vy})rhvmx%mzt*JH2eo+e#q*M!@!zH%nn6Gzbaf9#@U$SH%?MPKnlU8 z=?2`)u|40aKEdz}@lK3STfSQ?d+5q`lvLL!yIkfSmFC0^Ue({UOglDveX-RbjmK8u zg`f8PM2I0uVm^Y#IPM4T$n_=fDEW*jDQdh^U1p&^H8CGS8W2uL#=F9fOc*MU@;#$e z%XbAcuKC(nxtt2Ny3Wa5u>NdblA?k`yQSU{U0M2sCDs2D)jtI&-%_|bKu}vpuf2Hq zS>Huoeen;rI2v7rq30{D?-*8#rhUaOdD+%vy3-9LeXp)Gb;yyURMok5rhbTbi0u^P z(7~soH4cAh1`f6BoZp!e{O*kt4G0NL#K1eiZ$K#|4Ua?3(k3c(2~=3jG!cIxI}}C> zZh6`NB+`!jB5Ti5WKYy28M?u&AmHbCrQF*SK1v;NNF=&0u}T2j5m1!&DY+)N0kQH+ zOG`1&?he`tqk?y;tKY)f17EfQFME7k7w+I&u{}%>dt~X^kGYDyZYmx|S~=%z6{i+V zMqf&mUGk02Tv%v5nk!0ke2v%i*+AogiMlxM31KInoo;fUR~lk)N}4B6(k`s?Ajs@e z`#xD_|C_rmu|I05mc?eO@Kja1G5LJ-Fu|@pzr0XlUF}aU^;*u*aV-o=t};`~MSYOKGVLHt~>Yq9Zau zgGAsL7vN;TWCR{UEkCZ1Ieq}JH?Y~wq9Q4tgXS2PJgGN6a_kN*#-S_oW)6@~yf!`q6W;;ChjB@)RrM^v%B| z>eie2TVJbGn@QJ`b!*=H>rr7)F=Bu`z>Pt7e7>yS+FCZPVne;Rxcz<2d*_MXcQqxF zIny1Z-?DZox)Hd?oGXnLPD-FyOFHpP=DxY}_Naw%>vSY{`|Tr!wk?I*q7#P99EPJ2a%{p>;Lyj@eQKRVK6{12c=ZPBTGCNr@_e zeOWGAQycmF;rjW&UMRZI9|!Rzox3yFrfrredV;vPLd~HXH|wI!HSJ*7Z7;F8R(eU8 zL3@d>DYBms7ChJ=P)D(gxM7{a%oiAJ|A^5M?<{9VeMPR#F*Bav0R>rWNA`JO?X5!Q z)Vo!9Z%xO;b5p@@>>$EigUP#f+hT&rjcVj2Me+p zVX2Mn>s#cn_g>*=--{6eauQ&;mtg%D%i_ORs*oDXV_7A223|U5DEt6b-;}+35#1_! z_=CS5yuW-QR^&f-9!jLbZP@q@(0NEr1H9E%c#WUT@eKXTP!cuKGFqi#{c!C5Jg!(b6VqKJEx{}MFqyv{p-T!rM3K3A5&{1?S?-6scWz?fG)`L+cn^VwziAW6ElGWGUIqJ@i5#1D?HFuZ9~XzQ84C@w53rW>^?j z_L1N6;+ULQTAxzjML;oYa*f>CM}j-?NI-QY@$rsru2yf`Q2Hc1&G^SFKDBnMit=l( z*8o}IT;XK&1jfCh(9wrW?>{mO$B}>5l9#)KEw=7c5q|${P=rT=w*p5%Kb2mFk=`v; zcGXd|W06xEqwn}Pz`7bZA0-ko}q~|w<1lR&QW|tGKU~)L^y_ND{{h8%` z2eg-Fpq}lVa-WHSllH$HvX$&lpfu&BBaZ1?1Sb#bwN>QVmHE;e;uHJfV+q1QK!~JH zVariUb5UV0#`$?}t}&#K4RVK5WuQOGR8N#o#<{h2@yb)cQDu(k?R|R^#@#Deh~aq{ zRrt5;w?4uy>9O-SuvwZc4Bh(!-Y}oaNp(mZfLy51Sa4e?Wk6Uj@K->a%Yy%#fx?6cDO%j3M_tRW&Rk=6sha^&Rk8Q3Wr`Zi=?np zS=fBS?hOJ}9l;;d`u=RQ-5nB_q5$3x7_@vdGMezE@}?{v|BdJomG0^vBDf;~J<>G? znt#Xid4G-eVbFTXEPc1EB6vU%_7F@0Ts%CcP-zFiA#hpWoEAR_q_6$SJ-fRqIUxOe z=l05^mhZcRf8Y30U`ZvOcY3YF9%LUVFyWIN4c{U#iq{{(qYZy z@PM}r^k1CQmxr~eNzY?7KX-eP$DbMm=y*oBgbWFNmLYEHN2`WxBWXe(qiq;6(=}_g zs1w#=db{FSeMK?M^=Z(nxU>;cb^0kTaqFK;ckd$9Yb|tJOXdQ-H!vLed6KYF1)t~pMjYDb?DtjvOE?jmbtzQ3FU}ZLb~nYD&S+OYUcac(p-;6= zVG)P%Fz-kopJTX}el*?GT*_v4Sz3&328 zdw)uhj=V zYX~mBoqk$jZgb|@gso^x-CSqhx5L-Sv^X(jS;ZLXEp-Z8SPQ?z+P}zAo4gtLD#^E>|T9P3bP)n&;k9Qnh4gQ!*e(j=&S3Kv@7dnO{+ z-f1Z>N|644S^z;O^Jt@3%3Z@X-TW^@YJ+!pvQvW@x1D6-$n?>1U}^5D3KNKn*cX0W%D++1_vq+*x14X7g_S69pGM|Uw5`LRVS|? ztBmh*8sZfGzS#N>&kGQCAA7PU$chb1B|2j+h{Gj#bZ~Jn78WLM3f8pZ9F+q!2f;&d zuL4728pC9breP>fM?7drTpX$TM=SAaM(6Dewf%hBnUammP@|ya5>hq zc>TNSY3i}r!+6YMLVA|@vA7q>4F;G#A1ai~WuD;-H{X`c=D)W@C}no--D~1<$!7l= zC5}BkhgXa$=>eZ}JgQu)13u;a94xQdlbfIsR9dfvXA}NxFy_4kTzYQXzGEJM3E&GA zvxgE(%-YD;qRFs+tWH)`2+R0T`tHpf^^ZCEBL9g05wkoHC=nZF!dmy1CflzFQJc=9=4OmV;fjMICi;<_k&yzNv+sZpLm1LH0ZE_NNOA3!83E8+c<#Vuq{`!7qP- z()}SSK!!wiG~+Lm>b1%~c{Lct;B}QZET??W9Vi*reqLYt~M<>I8`A|Cco-ea3}qqbvG%IaDWQ zLECE#c8MK>P1k${QW}+z_FF)+LG~9Y3gJy3z9&lDWQZ_%oH0-mldHnU6!RG5@(nJ7 zK=#2_4@Z*H7Vs#x|D9TNkg)PydQc4-8IECTc!ZLaAlpwrk%6E$I0Nee2Y%ZiN$df1^}|t z(V_p!W9uj0rMBu;j(0eUJ^&Bfzkhdu;8e}mfR_nXX!h}khO9Mt#vta{BEkMwQx?2< z5lzF~++1+`cCE^pD|_BOp+j40>ZhC8*I7UCg1IuXbilD)+^T^0SN1O_*I3PlL#tE# z2+M4BjJ{2`2Gf;gHf^xOpg0hal3NsL#_8X)U2@{yl0Y8MIf{JHL`UbGf#rAU7h;6Q z)Ypw(dDw^t{1{EH`tjC_^48?DKIKcc9Tal*8$65if{g$wSu_q`B#?I;1pZj4jB2^q z@IWA&-KNA!To;qEx{iL9Z!EZS(2jdqj*CC?n9OZmrJ7iCDLJ9Dt}^m?7NKy{h4`bx z$P@WR8mW@mSQ;*k>B`;2niPgU{74&#q9A3@KfSBrit~xi{#-PYuAAe{i+s=9Y|KR^ zl#9p`BELMBdbKEEW3YQby_UK6xiu-p8T?=%B?K)Fcgj-`?7$xBdHOp#eV2Zs)UJGE z)U$9aFS2k|bySv$g>}N>kEcR~X}V3?Xt48Rb*YMt0*Cx?JAd32Z@0;lU%t{km_kC4 zHL)!#*(Eq%QFzbtf!Fa^w{%E+e7rU`_jA-w@*f#;7PLMhO)Jm89gOPl?D`&=oRM5z zuf13;W%zbkNkDM?{xKH&lRfhY0WX8hUv<)}e~Q;wD{}@!({1V#l#|qv&+k2b?-NI? zPxHFiC(b6n_*3T#!C%yi8okkI$>_I%tOB{`V`}l8f!Q{{^h^pO#svpKdle-!=ws)B znU~vj*HX}FB_ZDi#8XJ=9Qmg#H@NSIm=oh*0zwJar%(Nf#9W^XAR9nDltnxNRUk;B zI%C|SY~c{~=#bHsRw6({BIXx@sx$h)+b-2a?KVW_WQ=8$BQyjm}-uP z?tbeXwO-%Z@rA)XGq$&!!|23?kJGur!29Qsv_aJWUB%d`!2z!eCAa-mP6-MJ_8L=% zA1ZCtK8r`{p}ip>Lg)6{brYv|r;jK7#pgib^g{N8ORC#%(Cs6&o@ru&DYZaU`82*7 zSg%vV#JOqc_s18_C99elM4NjDM77LX%?|g!r3Ym6Rz-%13icP&WP%o*M9pHN3e*;0%x5z6X5DaOQw{0MT3SLoEo~%V9 zD%l9uA4m~|i8*u7F`W~M#lc3ilEKdM?U27h;UsSp@zsVfe$3HB znbC)PZz`4c53@)O#mZGm7x`iSm@D ziGW=*;un#G_7j6pOP0fkKx9%W8lQ2cNgyjPY`dXc+$ z_OE!u=1g)rw~?KWSfV`=+qnA0f}C~0`Ov54H*kBOFGpRn**9#|w7S9%@$-O9@coRb zl}^TjFw~rIT#tV(Pfs>_*t{g0LT2x`bn&X2`vnJd_#oB=0}* zq}aNZkYz(%I^1;Ack%VqD{8p(TBS?A*XPrf;IO`UbdND}z0j%U6-Gw83NU7Xi1;M? z0NGl%&MR0{w)GAhz$jKq*r#tNJ^KrjJSvwQ$i|A>d|WRdO@_S^oqUctWnUZfm}OGD z#OLFhxF=DjGhj4f+%K;LUM3Nn)49`>QIU4ePl|+^%AGt`e;Qj$CIbh({nhQYyf%lz zSjT7k$%dv&k@PmH1Rqbh{PM&xOEZTfNCbWhTQ<28uQm=_tW*O!;QMT%=%`8UGnFgA znO`0xypAbivM*Kb9HDXBXK1jrI+0#{uvOiKR=B{SlZ9^v;wJGFhNnDjZ^Mtq=q^uv z2yT}#?AMq5Ofb(Y|G_a=U_8v5Zukvt^0lU-o#*J@f`uA;<1#f;;6##10YmfpN{TE_ zX==|pZAc48ddKP5>q>%_;#_k!H?9r3efGeDvV!t=c6-#yK8nSf^+wm&<)sCrB8I)c ze~xn5Jf0@Suun+j8Ev-E!_9fD+TL#|_}dNl<6VqlwT&L{hs@d1hGs`cW$QF&Lko*+M5Ip?jHl zS9zB($d6{HrwWHg%qsrY$0&C;|0)LS1Q`s+58`XROX@LU58RIKV9X9_!WR3R9a$8- z*#uwD;7XVI6UJbpQr|6^dIn`t0huVfC!f09tm=vSVt*i)^S&B4D@d~+D}I$j4NdTk z!r2PhJdg?pMJ2g6u#uWcX7uq}(tgMn9tiCguQI#xG5gQjQ9iP2hNb)gQOf!!1HA-Z z^ay=k{WdyHV^81cp;gXq23G7I`I=%qBUee)q=8XHO&Ibu!*0qU`l;MS@qE7P?D5bx zDgH)opvk6}!au7ipY+%uEpch#=aDt)6Lt~Qe|W6TG{khwE#m8b4`iC=Y>6Tp01X7n z1EfuKQeNbc+yNktsRF%3>gVQYU*posi!IJa2>tm2gon-2`^(y;Y7(FRr*6`P(&jTl z8x921W1hJeFVAFWo=mCVgZ*z8va+a*%J-5M;qHOZACwmd&Ri5y4i)8o3y=J;+`&45 ze(~zRcQf{-chW;xi4$sTw#Sq&S(^8=dFB!*jUGT^9K26TDzFEkV4d4d_Z*4VCE5#u zvtDuvzH*dF0<2moSKwckAgl_Of(CECVXUw$8nqsO&L?i5VPB24E22}7&hD33$n33r zuRi!qejZz(0(6^od5;grVfec79xD<$jA|Pf?{Tlb9TcFcu7J1_I5JymnXLae^$&Gx5XHX`U$n+rs6$daeR96^K!V_A2uJ*B$*3j%yXi_9~GWXpzhBm6AyA z9RjbCTNPWhYY}h7IIl5~EY|Ao=0+E6YN)z~O@p<{8NB3L|E`?SXwzZzQT(&iT7=5O z_%P|DY8n@=#IHf`I6Q$(__jF0eqI`ZBY}&y4YG#fLA+a;9p(1>mMU+xs7WY%_)TYm zN-r!ay60vWBolmfNMo+!Wze$G=zYf!+ja&pFp>wE#~n}=w3U5+OUkY9 z9^QuM>2(z%Yf34TBz<9WeE1maeFX$93N{$M)?p|S5pi>K+de_~GXOA1BDH^g`uv{= zbJ8=VxN#Wt^=0=lGJ}3w3PNMYiv^+x5g6*YQ-G$Eh1)iBP&C~b)Qd|+vWtQF1hBS( zARL6;-Q-l*o4UkESs`N8aV~OvRIZDsM*rtu{{owA1cx3p-ObN~QahU@Azt=;wUIkOebL~!hx~*x6d-NS_^wA;5dN~1VUq8Jav#)_=_gmN-0zydO!oP zz-2yr6*1px`gq4DXdzjY^2-mDTT!3!K2&Q=>Jz zK;!4SuM@)y_mo>)FCDpbwBy}fB#VOV*6hqN(zwjd)XZrmLW@)pa5LI;cSOo$ZsFm> zt-})AgPEFAFft*XeV%7m8={wH>u}b47^RSe9T5{mbyGBxu)E$$gAomtU=I`$q=i90 z8`F~~X;w>3@j||PJ&{rUMp70{*1qQBVm5(vGX^7wN!*0i^TQ*U?{!fGpKJ;UW zlXyxoyA^T2g3gvl-G?YsBNcHdif4D6u&V{+*?X8l88u36s0z|_g69Jm{_TX?Mr>5= z6r_Og%um)i+eh8p>#aF7BX~0g0~82pimA&tV^zt&WCmYf^w^}= zW+RV&b{D3&WLu~TbA%XGAkzSghnxAY>4xz1;Z9Uk^%-*JMCtseVG5i608>`KP@F{O zVBW;1SR0v?$~;^M6}7N6eN(Tn;QVvNqe$nbCzEIWF5O{%FACH?@bcxVrjw~x=1Y@T z^P?o*+C)^sHw_u`5Mqg{^wujDx8PVc=q(hT=6Y)WIR0(EM7hkpt7_4VQPrhHS2Zpn+fTBvDUsz)hB#ff6mi=319zj|Q zej<%M$OJ*34UtUfXrQ#rR_kFG1EktCe*k6RP0zC>ZN)u|f5P!j<96L4uN03pKMTbI&{ zV2C#kVzhp}nyN4CCtRIGTYq$dg`S+y|4exvmzng9l#jY+8ON&v+46qDqCx788)qC) z)sTjO6YC`q$K$rJI)R|7ZvSQ+ri-D@g-E?raVvSC%N_swnNbHmp9cqQP#UAWTQ=##F<7yl8u`y$VzlV{_v z6LCWpu>0g|+!BMjpi;ksLR9`AxCuT0|E+ezz2QaZ3rli*q*6)Y>f@xoMU-Ka`B5Z{ zL$`0d2RmuRhRE`K`Dt;MzEkTo(-tG!`VP6an;!+Pb;ea94@CodJZ}PYVG_IomdXe$9dh~BLSZ6Hs#rzX1 zBIh%XQ$XPv+LZ-ce&(a7zX|&GazM7{4*wtN1s;b_G)iYduCqH#x+65%>xpMW1gio? zwxy9u(iU8t6Mt-qe7(Kp;Yx8jQ><6Ag=8mt8?F&zm zcoloaM}Kqr!3${0aKr3PfzPruW;6DerR9rs2DBQUI1>)zQbx_Hcuz}w`WmB&wKerM z(hJ-JaX-+N5&p>eFj&v8o$pmqri69J*NV!PzG`ZnwdP4gNb{MmUB%wRDBV}Z0g0OZ zzT__FUPt3L)VI%_y=n1=3WadK{pu9smfKjW4RV(>gp0R>*zr2=u)7<~I$&QQRJlY& zz%?3f)~|8Ht+|Q+!J>ctsB>i)X}9(UhVr#xM^U=4u6(URCDnr8)}VSrnJ|@bAT$U@ zCC@C*irLYyP6HVmA5Q@q0~4qq1*r{+UI5l1o>Q9_R5T!?uoZq`XwC6PgAJfO zV6FjNEb#X1fy@dx6wto;z6RpbIg*L-ZmC9UcB3-#*5a@=5{FsGtLV$KRpFKD2-szLmbWEvgu+Q&2%y?PWIBC=QQ3|dF!l1B*8(ZuRD2| zA0+C=wN9m%%GYm>z3CBgFYRd1qsOh_RxD!u=nR#32~Z-`Z36KA)O-z7zeui| z=JUE|8kc?d?cY%ew6Hb0O)n8aQpv<~(5q*O>BKkP2MbszVORDPO z-E^N{UN?{&Uy1-~< zOvm#(E6Lc>S-8ai&s;VC)IyVZR(Dsmtmb}$GIcpVT_Azi4P~elMy^5U2m{*tDjx#- zN@BB*RSW6?wX`*V9`@O%7L58x<%9>CW3wC9OzYuH*i&lXo2f11XhqEXbZsHm&;mk* zg&qA&F)dzM>@cTVaK=2r3A{1dJ}z>|)me^Nx}IU~a9zm}HexL&6m5Ib8398rAlw8fjzTF} zQtWc_5#vRT!1|m129QMPOC&KXiT-NC1!$WL!YHT4nfGzP+6hkLy@f{a_kb=yv&PDbUk5ShiLM93&2-hw#kjou@ZSxXj_k(nx zVuFc>-4ebm1UGMjDw+KIA>27NRiR~uu`jl`BDmyH!8bjJ3np3ZC!PwB zX4R_?jiz?BQz5m@2gNA;cd?eUmAr+81)qpWsDEQq#Ma5MjH`J{$!|2YD-$moe{Y_M z8x&x9kjx>)pES_QbmF>7r)zD_e3|$pw_AATw{WG=NFnI?RuA^+vWBeD?IXsny>%0z zvv`2q-xmbnA1dHLQwQf)#rQhavT?jlA(dW0|6yz-&zU^M3kCu&{~$BTv`JDdGkr(- zMP`CA_2vq*wwKu7T`&K2{9hvgr?b{qYXotaOU${iNs4>3(eH!m#9xAoq`Z z0y$WK89lXIR-Z05C|O)R;E-5rVo|VJ5m8qx_*A?>*??0nZM`s9e&ji|i^}MLRZ2%! z_jL@5Ak#`?^_k$<;e_9IL}~wX?`aVQ$xZK4pNg91wL|K|@n(y0Cz3A+xufM1Al1Rd z2ZHYZa@bKGBxTo4#G~~@}d(m@Vj>Z*!2rlQc zk=)yH_U0o0BQyeoZMZ@MX$uGmxDQx|%`CufcjMZUC;)vs4e-1Y;V2pPEIFB0d{B;@ zecj38dobjg%YNb0sJo~lW$&-w?UGhG#F_E`HvR?g9bY6C`cN~}M6lqM(ssm9TZyt$ zK7cMGs79{h*ERplGW9?VgnBTC@=}G{N%lHbMQYuuv>RGtai^(zWt^=;07?w9+TVF$~AM4BaFTGpEZJoDUK=Sf9%EreT|}PY&4l`W7Hh zBRMM}M$n$|%?$L}eo)wHt#dwJ|Bj)MNjhz@=_~Z?E?79D`><)Fy1N7Tgots_145e| z>I1*>zw-KpQ~mymon_gO61KLEnI=bcR_W8h;0Vv-IS0;mrRASVQ^H^7nMr<#WFTee zYa)G_N4Abo#cEK{`1LjD6Hsncu>62g5L`cvE#fJWVQ(^Gw3t;u*a}ksYBL1H29~T( z%E>FEKxyv11a^GW6V866wjS7M@kXqx!RIzPEg;y1=IH%kKu1;{!;^KG8p>C4ea!i( zVLLO0K9ANC^d$U*#e>s{TK`DH(tzZ}lgz=(yBiuThL$d(kILwy;!Juype8~SyJCS<=*$|pU) z>pEs>)DPUa0;ev)fM$P%6M`o-oZkHH4-ip@Xf!3A0+_5kUwPp14Iy}3W{jl*+8yJqSf2HiBK>;USJk_ zuuX6B=G!i|f{ThaoG&HM7ji#aD;*WDxHWJ)VNm!&_UHj2F=|ir+>c5T?*E4QkS z7!Rx{tfq1Li2tY8cD3y5lB@LTYM(>O7p;HWJ&|558)R$IyVj!}*H}{r-ZWoZ*t?HK z9CEfM@}xSB7FtC`-ghTu*JO2hTH50% zu`_%WEA<*F%61-N?CAFmk~`L1*){376NFFx`0H6e@lf=pMEW!9Db16E-}?S%wvi{ZjqZ(!>0Z zn`RE*a|~nQ7rlNLLeFTNbp;6JWY=${Rtej^%}_?1W}{u|iQ)%Hi$4$3ubAnYJpIV3lI4+iG_jc1nI^P-?QQSEy6Fv`qt z0zE8tL5hZ!M3e2A9N3(@*FMoSsdV#oZ9$G`JQe} z1v&b{Q>yz{j^*z)t7o;6fxA)Sj*di29+0pmG5$DW2bRph=wum|iAPv6)Qjsk@ zzl_F}uxT~gYMI2k-*)fo{S&QSc@z}jG~?e#xv}TV&-!FhgVF!DDNQ4#MTmi}!6X5(k-N!==~ zlH-a#t5$xp&m|qj?g|=@!mFn|O$#nRw=Sl)I){daI?9}5-)-TX#kQWk3 zU8r<~1e_l-yM`a`L=$>i`j|yf82EfhB8X5)H@lkl>pkicY$Qo+Ii3Zw?Ce4Q@`55PJhxXXqpYgAs0nkv}LEz};@k1!Lwq07qF zH*Co?Uui|SaGo)FKi6$ld#AIrwd9;67~M~Yu0q$MX6mnd;6_HY05jBC#dA60&&as9!z zl9cXhemMd~-LH~H9a>wuqqz0tW<#eY_CU?KM?2X`N4R6io`7SCvR;}J#18aJEBc;@J z8W~plLW>WZ_~>U!YAVBC(Y4U_el$h=)k?6O1T+G=XcA!ZD}E10`H5Si+>-vow$9&|3Cc7Y6*`$Mqti%O-C|7d}}McDZHlL%3E zFmME$c1O;2yeH%4U zKfo4Qtkt)JgtbqbWY=nwu{}?R!x{cr*hsPWCp4AqpLxg z`prZ&hVp(gAIA97`U7=xsYS-m3C{!1L2FEI&#{Qb=;Lb4xN><1U(v?i{qRdrqu??) zygvCwDaZ-EISJR&vtWEz(s8;x`AV#}-KXn%AMVLSDstCn)-@VqwPB`Lki+@dOkbb! zu$?pJmXA3HJK`uXsD@se`9ZX5K-R(GL3L0P9ZxX{`g`ES5=c_J3^5E6jtLL?kzQxX zx<0!#O~@RM8Z?ZVYZCn&QR5fHBeU%md2?2ReT}x;s9@si+az62@ zD2|UB$BEdl+#5KuUv`*jy!QD^4cA%Z$@F~tpSjqhgOn^2fNK7J5*ALTyTU3Z3Ef%q zHm2-Own=W52!BcF6`Jo3H5_$2%^o{n=i^apB3QWZhNN6;;@I5@0ZYxhkT`&V;A21q zaY46Ux4N>_TPPSYhO@Y*7jOVT06I@k>nDP7$38`|kzqEF7Jj}d6|aciO68YL{L8@m zcSh&|GeSj7hu*CxY{jQDDo2ktLZLsP?HxsLcu}ml!|UQo{?N{>V*@m$=K0h#z@h%H z&$UI;3Cm(OSKvJs%C9&lHJ-AOq57sR+aG$cZT^O52tK@dIGf7UVr{ zokm^pIVz=Xx?CR*yScZcS)A(|5?SuI=Bj01#^2bhu9tIR*XJSRb@T=k0CJJ{>rV^r zR|pMVC%@g!BtIMUTqTJ86?r;ZmmKuBZ}yrzW^c;|BLlG_NvNsoJVsI22xxV^(erN0 zUJq{#|JCW6h;hTrQ>$~6_s*lfGJJMkhMa=loCCdo0(RpfjR7>~qckof`tp6FOJ}D) zMxRFU6@0k5_s&Vmu@m{}++O(0@rIN`1e3TF&D@|0-kV+D4||2#GS;=EG{mIVwSoEU z=gI5p=^K0O)6&Kqcv$Ji`C^9Gy7YKV3P->@-{y3ZQ{{bMB-CYi5JINyWAbwk; zczOfwdBA>9h~U}6fa9>G;DB|tL7vnRBviW6I3;#HJL)mPlO863;hgfo`SRQo725P) zz9=QUWiWojb&rk)qh9wGAX|`YroJsKEIj$AuMXnBy2GDiF$KPmK9Q)VVQ6$TDUxB3 z^k=x5;yK3vQ6g$jU`_M6@rnDzeP}lX-ve-u236OYJ-%sKt=`QUFtOhP^a#?t3=*vg z1J<7I+HzRKt;5r}jREU5Xns)hC}?S*-T>rt24_t(?L&x5+u7sP@uw-ThzPan&=1=l zh)3&eM=RDD_VF!A#fh+`S=Q?wQbY)k+C+CB8^t@geul%6do_#{QzJ5epZ^ZlQf-b` zH4b~)$6UM7cf6crW6cACbzTt{c0IVa&&+VWo0^ssz7qQM@~34~e7-lKjk8tRIHrwA zKgB%=EcKHkXHm9Hk`{a0B6h`Q0qXs7u{F%l{c-E_Z7H(Wz#~WxDox>#S!23L^p6_{q zP=9P1D$NeMiNA=B_|Sd~+MIbz4Gf?PTNUl=3K-B(b3M=#2+*N&zo>r$cd%Oig4!}z zPv9)C4H>|DHXh=w^f8U}?4?FjuaIElb;Qe6;ojhdP~mExC1scjK%W9ZE2LsBE;)_; zw)6|XT+DKc@>ZHgbfbOL_^89=EIWKbRt<=RmG_F-bLxv!_eRW?skOPlrBvq&zq|3@ zAsmc~2J@Z5TTXv)5OzbEQ8^4ouuFE^Kp-yMNpQApf0^Rm^gdm|H1(OGYE# zF4oLbk8%Xtf^*zXPgt{`SyIipc5vnMaB)y4J->bM?)TNcHHsheev9TvsGMm}{%-cZ z!b3J7r5{Fn$Bdm%LSwHdgJY~j!@$^EHT2JOj{cPbzZUzR_j2KxpcBp-f5!Lo@obE* z;u?L6%tvPNiyO9I_!YTxu4Qg8@6Zse;|@Oh_~Z>%M`B&Did@U{R9q^RQ z^Y@S{OH(&kLLq8Qd3R-pPxD*^A@D#-az&?E9@v0n>pADH__8Cig)s+>`|~MDghMr@Sh%McTG)`FXD@+8t6vyCMnzeEebzeS|Y^$9UpbzNHJi#hN8P}S#x{7w-jBdmdM zz-vAv1E$qDku{h5bx}?+{oZ{@4Xe>T7DgsJ&)i-$abn4wgKE>9C1Q195_LVh3tK6> zt8ro6_?1G0i4!7X1fi`w)8uCB(w`q*plWEFD^6!cElu4OnM=Yo=-#U^vsV45`;@rQ zqPRw1y$Gx4LaSM`)GF1XcH%!9ZE>b6^X$WvkgeJr(@In4MDC2e+jy2cQ>J}Le)|WP z)#e6Uf7(mLY%hn$Em6Y%V86?=m!vJ?B1@}Tq^2ypW*eMmKD%FG3Ki~(lDQN`2|T8c znknIOPy5gKRBHOQ=rQvTM^P7ktN%$R^G&U?uDv}>iKLPmgM;X`EVCus-q5yuFwroY zbDGgEe#E}<#mJK&)yZew+3b*nE&n2zz0c+1rT*{7a`O@53g~BRxiq|wy&`ura^%&6 zafwv@8D$rLkS?(Rn#30;C4MhWLo8r|89}jdY-PGNCwTjxUIB9 zH=$H>e75iIzXLOwGo!W5!j|}rjSK0fIWPXAsJqGTDA~?~GHfb@_wzylYL*+QQlX5NB8vV_7X14$(}*QKq$@oU8Az`7#TllQbVZV8{tc zh9wH6^#U&}M9w~(8?Zr{JsgBe<_z>#Qa=591?c+HVUL*80v=#L&|fflDTsA(;uou< z1Z|uk(}p!~iK;jjL>fxDF^DDfbq@c@78v(Ys7jO&hdz83U>sx*+5czix4muRZI6D; z3L$~V@kW>COUa=B0+O+5X=y$aAyzHH~KHiF-LPWZtkyGNcC6OPZVK3fc3IfkX+d7Sgs)-K=OlVKbS5g25H zx;G{>a;}Sw`4)}VfQxreIO=HH+8s)I;zG#{a@HSo#yEx3DC*!IY>zyDeE?+I#=l;W z_JiotwAJRDCuinYfPP@SoOqB(Ivn?+DELFKprG_1Z!W&$_2~8ar;_%bGbYH>O?9!@Wwilh(qR;-#gf64PSK{jeCx zf78+fTBGS;OBrw#LG7Q^`cf2S9*CUspXqzkGhAAuNv}plM#!i*_ln&?7T=Gq;M(=} zb`)1d^eIj4KfN{1O4rW)R`7BTdc0~>S2_^;6mtMpvHaxGmE(}d`ejAI^qJI`6XB_?2 zcg$AtR!rs^D9l?UV{UwVzIzcTsSSgBKkAr$q;i{jc`w&#_q~f&pL?lIz?k*%b5sVCl2zdGRX>^bBvyCZ%OK6j%{#VJdk3| z{+HD5S2>kz2gV3cPz}{IP1i44SS4;$TO}3*StaUbpmzqRS;jRa#$5{9%_;xk?jKOh zPh@etK^l%*CwqAER))pn?lY+s*a@)GpopXwt63#vP*insr|l2T>-J95bknYWLOjgq z{apaF+nV5OxAS5*8%zb=P2q606t&V+<(}`T=}P)oPn6AtmXe)y=|!ZC)$H(J%p`;e z^6y4L34%+*vt#<+;tYpvuJdg!2)o#7BKN)mi2X6My*udq!jvHi52XE&q}BrdFxa^N zr;7ll7VtZV`^_*5vc+7+5)5oH+V4aU@tG`qPxoHZ#rtjTh45ZKWErMx{}!G0A?7L? znnbzD8R`)vH-(4;$s1-(5GcV?e>+Z-;$%O{Hj zpVy85lDfxrkRW?u<5n1sijQ7`q}=jgk9haO72(VxS+&NJKt6qj-}-a{MMb*#DWj75 z)W@sGOjn=qQiJ#bV9qpdf%ly|XkmkYO+*YWZBZ=K)z8;5BJjw?MV!qX18|z(=^|TP zvi?iY5?lzcNqk*E2~QT_6Zl`S5Ps>(R(U(H629WhK`HfLdNQi7?;5~tALmgKhHx%G zat0(S0F?%-k9=NPs`i!l%?4OW=GpNEK=;3}a1itorH-$GeF9K5u~A*@h{)e zRvm?Z@AvxJ@lzJ!g-CLd%jSnG55FkS`0u!mzds>=da zZ4fBQ7SoO^F_^=>T%~-ar(omVf~h3BuYTB!E~}a16;jy}gS%1kyz)Uuy8<%-k7b?b z^B)S5>W2fU11q1A@8;)=4g6!U^(6*By4@aA#u_$%ZP_QSYt_tGSeI7{MA|p+(1c#kU+PecX$%j05yn)+SrD>;!3*6Q!w;Bs)k=JtFWqH{;!Q5yQtPw(;ZZrZ*`! zui{8WDtrsI>QEJWeR#{*alba^5vxMJBnzZ7uQ!CZ8CRuUPdqtd@RaXAktPz2aElO=8GoUCuhDzZK}@m5|KjC~=F1-#1FyFv z?N-qnb{|AQ#&yJ;oxUki4iSFRGv-adHLFk~WWcRgaz!$xkJF?woV;_?ntf{H7}Sn` zR>qv)pt^16eJG-NzsH{I!ZlLip|W@AKNIt1RDLMCTc8S`3ub|YvCT8cbg7!K@3^I$ zN0%(Nw%sqk81}Mryi=qLa@4VNrE{T9Z6JJ!L$55@yIG1~(|NsQ94E^RUrb;F{_LZK z+;>@l{O1uD7mrnWy<^y*3~`filwiNxKr1BQd;|L7Y5qlsIQ}1A2i}ZfN@+B!26BWL z18G>CF`5vCo4EetIvOc_Qv=zw%vQL*K$C+DLy1115YTW4)&YoBs&?OFg98mx9U+Yc zOH{B@VAG=EPlZ3*bIn2z-tAwIvot>c{=^D4Vk}#YJ%OO@a7f<$_1kFTFy#hQWdrXe zB5$1OonVDfy5lJ8o6|P?OPjc3k`lT8&Fz>a^NWpPLNRu1b2zOcVh_&M-QERK>fQ=| zLdyzzmx(gKJ3s{uN=DdjbiPacrBp|&cyaoL=H=z_a4E8FUJ$=1jny?rt0n|Wvt^5v zdTJfV9DMSWCSz9^v8&NN{L!8B;j0|YF3D^1n1BMMC&t`f5Jf=K>^i|YmgM&TwE){b z(>@-_V$Hhq>_H6d9*Z`wU7T8aF)Q9Up>p#{j8ukxB;z^X(b+b%7gO%*8>3pX{mM3S z3Ery`lJe#rAH5&eH07T@8LU)x-f%=1n){XeD+k3I$M^&r2uw?`H(MJniDDvi8y)cMXkbyRsnx+A~ z0$_ukZ)P~-p4zXhnzT*)FPLlRLn{T1I0&q;69s%eMxqBu=plq46V4kCm{RY@;o62@ z;y2;`oRa62kP;?QFK_|JcA>Wy5Hx%K@vlYM+DS4j~QvxpY)%<;trp!y(#*b zjW-XbDu^aoyVdwBA|=O26cw;|3(&g<)^fYNq-}Gw(oF=4nn4H&5vnXG<2H820lX?+;9_9fB$f52WtU>e5>gLujwGH zi#qCL?z;Qr)&6|AY_)6be^J{HyeNXxQI$;y2lAI{D1?{kWXLOE@_+xH04((v0BLUS z&5!}y0FHzRPqB@@0Nmr_yN6S?x6&Ze&tkZ67E+yCV3;VbuMamV3x<$CSQ;oYLCOZ3 z3V=KC@l_Eif`eBGmNfzA;-V!#7f6L=zZqwWASfWBU0&3h^G%sAjj z*&-(<5P8k<{YWc-4Ch3je>t?q*{YH-mN6w;B%b$!(;r3pw~zEH2wilgyyfU6Yj7Il z>wSVYZ)uce(yZ zvqnH%c;D>Jg4`O{-66EU*blvFfm@>J=`k1Q?yb5tNDTTd-+X`iCNd*b=lY0qipr=` zorhP;vDLX&Kmz$Y*ikn=*1wkAYq(m9K*^=~Zl@TWm4$@3ni=9pz)b7&1#PG`RZw#n!GRy~Fi?B@VDHT?EZ17=72M+^EiixB5LLRCWlBX0X+ z`=VawKG0?{(mWai+x!yh&V<) z^YUhPo~jpz&}UAlumIZj{@siMT%RGxm!^hcH;j_x+9=`Xfn80^^_5`3cD64G4(35l zO?eJ;QtwpG$21#Bd@?+due;+mx+q{SmmQXe)ig zEj++o$*k^KCA}8IY3?2Ky2u#MkLha;(+&_F4i-I)Q3@K*g*xShewj#HDq;G-y^%bX ze;yvKo%d%X#z>NDwHSn594#%+U!xTSsv$EK41l2TD-kP2_m|wum1$-?-ssRfgG5v^ zdbdAUf9w_5h+eq?;f-~%A9QWy>R{irh0Ip0mJ<#WZO&Q>qA&h_gxB2Lw@x!v9&^Su zgWC+^;%ra;*?|*wU@hu;$S>?NKobVSBHVv|E$YuD?k zqL>nObNllo8CAwtc|$7|9PBqWyur+<<2V2^Tu?xmn3`haqd#6aG~Md$=>cmIez#3ra(&ZzOHQ!?vZJ9E<0TpDi#ZUswBkXG=)T zFe>IyRa#ZEi+%@}O^YF)S%t9Fuqd^zJzdPL1Mk2x3T^wl^qXAzc6|7CRM-shLDAgF z!jUX@OXaJMd6D7Y_f~MSymG9HdBuir&^#U-v8QTmdbr%$JArIpXK682P*Cu|#15&W z9+NtJ} zSAo5Spxt-G?{(;GZFEY$2Na^e710!pu0yCaiLhEu-%)SV642Dv)?();JO7%+Po&^; zpKzJ>x{k>PU#g97^%fsg$pa`4y$3lNM32d_LIV<6E*E{ zOodmwO!T8sr*6!*4%SW3Nle(G=->~*b`8J*15XUALc!|bSm-@E+lF%TU*R-T`X)SX zqNb|u-ln$XJGOiK7TgpAYrkH4o4JM0skYozZes@K?5sglCWpNDe)Dg+cI1QDJg>Bs z`Yvu@OOpGEj^jP57VL%Myu-U8NyUbP34cRLw5h$~ZRc#&To$bZ1AV@O${ypIl=2lM zizd;xmD!hSYCZM^Cwp%lXa6Tz4yFi`Cg&!u&)gj{I^zF(J8L0P0^zWHJ$jaiN`V*} zb5Q$Bfb4L-Cs7dw$n@r8*jtouP04Ox5jbGrM0BYIj2vF$5!F3wbKQ&g7Zd5mXc~un z{9waHO)&T>jf_q2rsJ^z!^p1@-3+g+tMcvI1O1IeimXwk3tHQ_X3ofTM#h!{IRfA4 z-z2z#GwuEt9woxBoeuTnmNxTc@R6m}k=`mX6=WV+y2WHMQ1X#4p{z2IF>sCVEay{Z zN|IcN8SbsU%^BLe#V-^#fc1xS8$0Yf;I)oVpY3C}*CL@iXsiewVh;h(0xwdCM&9rW zHgw>6M2h|H&v`LbPnrLTnBZ$=2bKoxkwR@BFYjkgv&cI0dPSEMIyJFzOqlNEW@4@% zzQBP~$XDh;iW+6e|EN%CME~nNQ?=4<{$dcj5b_o3g5u1V{a zZoAAN#(o)`V+ry8ciei28`e|k8njDjUKOjJ=KOnfvHk+_ILn`{;SiG^-cj*(J~wS+ zDdE4AB2~t3r!`UvhF{mTAVxHdN7&lfu3IqVrdvzmobBUM)7)0Dy$4Q0INLQi!rkc0 z=n)E5wX0*&riC!zy(w|U>BQN`b@s~nc9Om~?3Up*i=U1|`=NeLo7pz=^cTjAnI_`= ze6`N})3;Gg`hP}4pO5Q@yw&rTVm}$(4t}V=w4ZgC<6R`bA%(A~Vd&bHAnlazrPdK1 z9)00eMnXdwlF(*D5oeMna)Z_pj&$KdW-Ws&rHUQORRdlJ9v0|tUpw3DVmocTRYh}B zJXbotA2?6P()@mup8l1$VZjrVw4syYlHpy5Qc_SmQZI;|XCGF+e{vv(6S7Y2uSvq$ zSED*P(OrNH&lUOAjhs%I@j6)-cz*Dg@4DlB?GySIgqO~JI6gOeHvgSa&40Ge$t#kKuMbr|}F zce%LIJ-eMyT%WG-ezK&~?HB@%Suud&Y)*%4eqlKRSh#Qg8`?O4u$0Z&3IP$JI~s2R zeUPgmnPHxJyeHJoITvtzd|ddMyhGC>hCVzI(F(FCNtdXosDJ-TEKQxskk9tSmmij! z3les}H#xFkpqmUDi}J9yzqaK%@k+P{=dp z@PKv%L~s!A?uRF{Z!L`a1PxnB=%h{zE)iXR>@N+GvYgwGZ=nvUS+$-^c8HJM>rKJb zv<|`Fm&!8v?Yllv7h+K}p%hGsZq`FsziT!0o&D?ZmicYV`!Je;+{dDU(<-+W=XFWB z^{c7B2uRdOzx}i=<}HtS!2cz)|Bi2Jd$$ffnLJrK+;hw_b z<{pcy5-FJ5ab4+2&u?q92^k=qIKGjSkpa-4fO}KRBNAX44MJ)&NWic8O zLMhQw&||WRH@2l<^FK?P(Yo$ScjE@J{aj4ff<^j7!r+q#5!qn2h$c$}eI_<7SyxDP zv38R4zfT27+^6lM*-4>|FS3*&uB`iF5@4ZXNEfHHOVM~N5@+-2AWlwvWb@y<7RNmpK1)6s3OtA=BDEI+wx)5gk&!0?o7G7YJ_i>Q7sYnnxasUlV zZ$J|-ARpk1iF)uYvYUkTK}Hiqv2_0PBSSDGz4o$>3GrqO)VmiDQ|7FD8tS7XBYrC7 zBxVtPEE+eMuxm4=fC<_uYOVDmJWif6wYTrv%gN-kdHc2<_m6f5?8pGYl`ig%a%_?( zML+6KWnNb|VONa9=+2a}>Kpmp%dc9b-PC+FT@p^WE`YG2Xq-8l<#8rAZ+U=1eHNlT znMs))J6Ta9M$4L`@@s4V4VqCf@O5j`J@UJqk6H3Mag-P|bc$FiQA1TAGS_92Swv;_ zUKVD>#veB9ANZ+W4mkCK4+i~3bmLL$Fy7pS07-bnEL^K1pUNFceU7`>4=9htY(+y^@j3z;G;P4 zgQ&S%9L*y7f>X2JW%RQCZw9u5j^8*PBv6&lv$QL#FmCeX_1>ol=x+{z0R`{`;5UKy zgc~JVfQsZ!Tu04k%Yg{D2Y9;>qu4gp*7gj$VgOEY4QK^wr~oh~dMPiDFpb{V`?JSd z^{p`1k0Ha?C4cyX%+L44&>!PSh3E0hvjdc7FV0Vp$eKXM_%fTwcFDQx zTI-?lxADcPk@L!sm9Ol_JzQm|VzWl^;$oi#WpFdhx*L(MPkLEam%H z&zVtrT^99i(XP7_wk>viDcmynhaFZ|<2}BwPrc*qtvYsZy(Vm=gM(#!6 zS_(A!GTm<4(R}+p^JTrYvfSd@Q{#Q$O;w8SsJWfnx-pPvih1rQ z{%Xi^YWL_z5yGMT$E9IDaLQ4UKok?n;0=s$=1*;mUjq4eb?fQ+Fa_`JD9|vto*z$d zG&b;rE!~m?>_))fl$tlz1kA)(i#oUKXLAY0GAOudetzpGzHOufIK#m9jU{y;2E9hx znNWwH<|%wTef#I{p?3h~(@v;R*Ymmom~yugc1`4kzOj2)tqNNVOh-xcU)Az!V@(J0aJZz`}-As2PjD(*Bd)zBEEta5mSpnNY^A^K`*@EN7!hAfGT2R^i zj)Md)iyw>Dkvb~Y6xncvoA&@!Z>WHoXIQ=kri|BwIdI=NaET`hXtwY z@=<3gMt9RePEouBZS^8WQ@KtR)w-jK8KO^6i%=_m4-lS>igKz z%z4O@%`HRUX9s?THC_)VJAN=c+e6TI9QKPYx)dU+S4$8+`(78qd0)dg4?yEqe=^xw zr_X6oPRhZd1P;1g5Pc_K=6GrFh*L>iE%9B$>A!;R;C12248O)_XyU&0bv>zR zg&CI`oLI`u;ecpYMu`5DZA*sxvS*$G(8Tipfj&1%ns?*7)Qy6FATb9!xg) zOt(Q^itn}^;pL98Qf*U4+s}ucme<0A!tc#6%fiSk7^Dnr>#vZTKycX3w~_*=k|x1- z#%dxpRUk>(jvqswhcCND7(@Ige|4>y_swcln`szoeuR_KZYjs-sB`aR5YXFOwCk5- zYrZ0QoLuLey}wfj1hH08k7SV*H8)G${QVO%bE2Ym`|2ZAqVTQ{7*`?rc5;(X_oALv z#gdd7BAH`QEryo&%8?@FM?43`wxm} zaP`F}B{}v6!H|e$2l~boa(h`7o5Ot{hAHE~XLpfM;fwHjqC62=m95?Z9MItwOZ?u< zk+w)B*DIl=j|Zgh=i+9|q0v%gNv>6cth)~08jLBJ&zCF^*`g5^-)8(Sldi1MKCacU++-1xc|);{TdTl!UWUkNqr$ zeNB;~hcky59@oFrC>0n6tS74dxIAZxu}SXJ(=HN@pj?G02#~g|`0&A3zOJq=ZINf2 zPP&qh$rN0NK*DQiXkaCH_oD24?;DTZTIduK5dp>8ul%C=k3~MGD}^Ug0GBSjfb}4m z?`fIC{=os%g@AZJiH9=e7nUoBW9!X-X4Z)qO8q=vK+|FFONYEKx7{BZBx;1Zz`;Z4 zC>ALz28La`t>E0tjar>1EE2un*?t)>>+`%&ll~Q0bX_*4o<2-`3V{&d>x0=2R%p0@ zu&}*+&OEO>R=Wp(4T}r!RjP}Rr6MH0;g$U{pnbF#*`&{{N)}8=cX*RjGp2*mQB{a= zCi+JiZv=|F=lyAtYj?D7(?cytBUK@z%VO}^dv!vN8hs1%_GiCuL51Cd%jVH^AW8@S zI%I1XCS7!*j-4I2X2mfqlTkftN!E4spfu(cGXb0G^rl1MztjEx8{bk=56TJe4a@9t z$M_)BR+vkt*(JUO7Skc`#zY~!g*hMi{JQw+tO%E90{uVzqR=C!&H>Wu^J-KL`Dy!! zl24C5qZo@Do6|=LM(%-l-C@<~t2!?A*OYiJ{g~lh5*k#l?`L?k;1!bMx=50J*9~ci$Zfol*NOI3S5zi)>5z=xV7-Kw1 z+!*=$H@klt0!guKEHpCycShA{)2}p68@W@xwvj7}&@GaZvGWHJL%Xk9{wr`{2@-YB z&ZgmaQGXhTMs{E8ZCn%5xaW7V_CBcF!{Vl34P~x?G;b{_7Tn3Jpp4 z^AE4sZd|~_ooMi3fQ!|(o2&iYfvf)C3;{jK3;|vaE#6m!d|LHy>x;YBMg6Gs0Co3F z`p$dc*X|bEo+0&whh)DZgH$$Aa*Jyw^K&?9ah7hfU@O$8y9BjgyFTA5g!y+;EOz`& zB-XGW$9m3H4ZYwsAZbGP$eH|~kn`?jxqZKac;yIkE)dF&+=rU`M)LTwc|`A}rz%Sf z^HRkA(~nY>CjQ)}+*2HV`NdR^go=$I6D!pks$ukX5T3q`4LN9@r10dzSa_dE%iEIB zbV+8!lF{#pc_;^VMHCLLT%;ZDRW%H8NT;TH_%+V(53T(wzsA2hWN#LVEzeg~>S;oL zcUcPBX-1^cWI4>8&eR z$q(o2&dAn$?Q1?D*5h%lcz0ayN9?|BPl<-1Gez-FyK9Y1Tv$_u%}J{bY)&}XN>}aX zHJ-Y|50}3!DA?S?7i8SX&oD(kz0#=OaAG{nlB1kAv%faZS^MttqcEI$6}SN#+dTR< z4zPgqA@=$L6fQ1O1q_3%6xv}{h%5fy^X_sj+v!+1-s6DNdh+{wm`<@VTrhb{7x2r1 z>IRs580mk`Zsx7h&af&PfFw^qz*zGk!pl{p$rJGrL|clQg~taQkkG~mb0Ksv5DgCu zL_7FCWx3~jwUJ@TH1XvLohAcX_$_ZO*h7GFgtZ8ENbnS9_L~DF5trQDd7Wlt;F88; zYYU5xn0du3TKEjC^Kei>+}xFm7r@|1w^@+&;CIGg?;G3;9k*gk*+#p$xZmSt!_mA{{LD4)HEFOSS+Zb0%if) z@Tl#_hsfo9N5&G2FJB(R&;`)wf0?9zyAr`gE+{An&ZA#Y zL(ZvJAF5k~86z!zdztP+P*4yyQpF?0{Yu%Q)kBW57v9z`H>b|TQbs3QLOw4YxSZ`z zOYH#lIz`y1F|K6)TWs_xQ9KtyWqR&H?crJJ@=)CI2`KHP^>X_)wf=MAG>!>-2Q+#4I9oQE@`T9=?sfn17kzha^GVe#u$$|qO z3vSt$v=)8NSmW&QmpN1=WXl)7dMr(qpIfNiEa`R?A;T#=(Su)qzI0TkTu2~(wB1oG zpOmc!=ZUyw>zw^p{B3AH#|*W<)w#*OGZ0?-eM6I1kB4>ezFvqWm9SGQe>Um~7%2*8 zOOZ-H?FAs1PvBm5?=#77B+;!zE4TW6jW3ixbTGa!370{B!Sl4t6sH$M^W7fGR~daJ zv-7>Y;sej)=Ith;=pTD$9==^rO{t)s5Xg|Ki8p>YP_b!{7Fe_!Dzm1pyZoZT z{>n0K&-`HH!1o#2#Lo;FRjrYyRte{zr#od?*{g$!;_Obad$CQ8@ukF45OKfO`oSvx~8#7ZZhIWN=9X) zD#m-QyIr@5U3>2nH3~g6%k(U}52Rtjw9mQ&(&0IO2R;_ilI4p1V-)qWovB`rBOl=H zmG;=Kt}Y=Nd05R7E_RZ5QQaM2`$;bKXBN1}=jOEF^bpo_HTbi0mTWr`GamZn4p2_rLaKSHN!r=p zL0q?RJ30Y3NaZBB0VS z%6CGB`chK1F!Ai@3mtjVz+mGdPtvBxshb7p(O!tm1 zyY`S3qYLKmE&3Dv2pPV1=|TX@X{IAXu2>E_(_^GN(p#E74KtF;UMtR_S!X?Pnm4SY z`C53#ZB3{s=G*#Vk=6r7s+Q?4Oi)tuSBBS$a)nF%xfZ-)Z)-bq)C!^R z28M>sdmSMDr)Rs-Zb|#g{i3CVSArsXo`N?pC8wmpz0GD3jBU26(6SaMCk#kybP0Ksck*|SUn&J5w2(Y_pQG|`(7~458qKCd!(k;-iKx$M zufJ~3v#z^&&Mvl9J{ce#o?h5$mT|7>3$`P<*!z2_Z>MHi;rT_;L~Duphu`w&YYe{H zRLbpmnTIa&XF`h0O_nf`2vsK{RA|FlFIM9A)tx;o~$`I3B4+&uDf& zC*{J)3FQipLVY!C;x+Mj(2?pEE>O-&%kQ3$m;TmvJd~a$=Zh0B8=GR7)u}e>iN0a9 z?eO`UKs5cJZ+Z8%<776Uv0J{=;+>}hwnXy6wQw#VlC$Kc{gk~kR|*L8r!hwj$ujFM zDbOIGqg5+i8t(qEP!Cj$0PTRK2zVF~bTbxB0QmgB%nb-gSW-r#cDtDJX_srec;#$p zn$=$v9`^Jj&qcfstCj9si1&Y*6VBfl`16PPTJXCNZ+6NM0I`}t266elzl9^{)OA{D znYtPHS=#jkPLU$}9O<`zUo)z*o&<&evSM&BfI1+606yI{B?!QE2wsVPeisHK5K3d+ zG5-Z0L(zIQM>O_WgG@KmH|7Gd)u|H`u$s0q`hc|>RIKcmU_hUBn^MdakMS_6AtMan zqeH}T>OR?|+EkKwbFqy#>nj@7PmF)THKjUTc(*r8wg#F8z8M1t>6rU|54x7a8M*c75^5 z_dY8$ix{?$y)Ou)Gi^rwL5Sk+t?TE=_;`u`#Tmi?3WerhQCZa#s;VqR9XWPr#i9ya z+D^92{^XOfb#gqSlU`nwmRf|dZrckDwwEivk41|ZE~XxTb|};|@swUCI_s*-S!tR6 zihsO>&cKW1XOwJWbn4qW6nH#1_Tb3yumX|pNRon?_4z1mho7WQuH9TFA1cE&M!c$033&t zWv^D%wBXuSwkq3#KMi$gr|$=_`GTlrSKDOO?8*(ghECNrM}(Bd4UY-qGEKStHn=`SKI~bBT+CQS)FGD$KdER|0u;FXA|7w--7_fKmIO z-xQZ};M@$|V*;Ru?Y?r+aB~M&!)lTUPT=#L(ootmrCf!R1%}gJzTs0X)(cR|{k!EI zu`g9jT605Nh`{R<_we>-q}__Q-Zj0UtzGVJaiF4-@%(I2WH=+BI>h^d1=<#q zo?+z`n_@7mQB;6HW&Hnj@Xenhw%^S4sr=X6XcN+<19)kYI)k6{z3AXBh?Rby^5Qmp zTeT1QrMcfeDGU!LiImd}6KA`IGvT62<;z5P3c{jw@s<--zPk=tzH=3WBN*Cc*VFj? zGb<2LBGj2Y1(t^+sK>YR73cUiQ-(@1T5GbDd`TPTHS#Wut}=c`8vgV)J>O>{zB9V9 z==djowSr#yirp#Hop0nfa{2M;sIznLC0tZ9dvf2F=3fs+#kUU+KUC0!nvK3$`IUD! zEAelhr{gA}b^qo0utoK;M)s-r>`83RNi+0xb^`{hG-YmY0fJ+^Vr%i+lC`h_>1T1gI%>)ID6WaIF#Iz8 zmI%p@s75M;F;$j)Mp8H-VQbIrb`tntX8&RXHeFn>E-R?%^4mk0pmzdGWhs7FHu8wi z+lUkSZ!?Rw#UJ>czu~ngHAPB>Z?q6-@$Im<;6w!ym{5+M@J&g;%u84@^`}G?;=@9 z3Gq2P(S~lu3j=4>vCn6Ta&jgSkyTei%f2^=C7vRU_N>@_2J#I3sDxd-jiw)odc$)= za#G6d-`u-3Z*dnb%*nIlR_!ig^IY%D=A6`LS!V;!Hl6&nOdo4;5BW(SM(xT7UeyqN z?-sAV37D+C8epHrX2`>!0aHYYZg3QJSNe|4A@gxYO*VuZKWrq9+2DFpZ|_~VU00|+Y(HUJOKm3vW=tQ0@7 z;~3qrbyaeATj;geae{E#>s2<>t%4><>{tcT@$S0c$Bkk z!c8UkT9HoJ-K(qb)p3C9T_3&??KO(nuP<}@FA@gGGnmB2ZZnG4CEEv8k|qnUlFBDf zAXF&Sdr2%~MJq@1O=pdc#v@b@iUs>vy?&lqiQme~5r3X~(ft2N#FD??X(Wea({aDZ zGIN98;|^X0<=rrv*w44kp7_4=|K$IHk(l5I#tlApr$83cXDjhD)n}4=KhL%NuRav-A;~@J7tTy=|^O9 z3yrgPV9{mi&*9IQPIiSYxWDo}#{HlqA5BEQ=- zxF_71JB_T8wf8to)59NmkXjV0*r{T!*nYoMUYOOLPat?vV$?;3&$-)OY|=)K8k2I4 zO~Ovf+3?!%&|zBO@iGjSZoPHm!P|qME8RzKXNP=cPP(oe9!dpjLCb3AQSNlQRm2;c zSJd-gO%$rxJ&0=3Lp=QYJnP!jVYka%8w=8rkhDp;JH$%xh#O5p5_k7PVB*`?2oVv- z@OW^s{-3uV7&ll2v5$JirL3wdNT2%yc-#P$g7*c6FF@I092-`QT{>UxXmQC4Bb;6=ud@UD{e2LZ04|12^l#jfVeh~AL`5boN-;6x zGoBw#z4*1JBK&IiRZkWj;tQMKLgSQT`9I!gGAnjZ!SL3CEH;V=P-~!Q3vYI`w7hdz z%@vt*(N^e=XunX;?rq<)jPLCpBr4xf_C1i`(yBm3O98zFAMc6dRXXCm7WmDvd-5Ls z%pJGG&Q5I>#byiE=@NV7!fj2qck*hl*TW*4CW2^Yzfy~?-j!(dS88#5zAb8^$19%t z-n}7N@7i#3>KI^4#I0|H3==iev#tuA52dBf_k$I)sD2gkBfUl-178-ZI&DTnB#0Znq(a#j?$fGT$2wrh6VYcePJFqw76fT|Y38 z5tghUuU(pMTIq>(eo1xf7Y&VU3R%gR~_>n-!LIjg$3V*f@StN=l#2tbV;P3-j0UHnw zA`|xG+S*!S)mWtX_gD_Er2nE9bcPP$T>+L8QW^q{GVu<{)8X{O&Qa|#?7*P4U`x%1 z6NMlW5u^{P>?T?Y^78Nk32A<#ewyMEz0k?XvTRk(Rn9-pdUQ(eb@7qS6p)t=?i>Ld zb6eHKAF~a8NB6M2^vFmfR@jBDUxAe!>IflK90A@@2#f*b7Gz~upKw*x)!-+JY;;b| zSh;1L$3aqn@95}PE*#qe2WbYXJbIIUDOI!TPTY$ z^+xzPrP^v|_`hE}SKBBpRW4CG9ajiC$Qb@O9hQs$Es5bBUZy>Ji<+yvPk8UKRr^Ua zW3#j6vyl)|qab1CYghK3(5iRo2yANmxTPqIvpVeNr^3*Qw- z-`kq(e7!nyVsKJN`vvo+6r_nX z%SA|RC_mZ9JK&@f zzRby5J?BE|gtz39@otZmJ8)PzAP&=8VwfT6N=m%Ey0%uMY}pve>%21b;N+<290892 z;+X3@1XvjQ8OW6zBR+~VMd+>|4vMs!Gzs|6_Rqw!m-o^>)Dnsub7bRC;CwqIx_3R@A?|ML zh+eoR-i4qTy-ybv%XA$Zrcqq$8%*vS^pDee6ffbL1YTiOr}I02bQ^g3FvM;C$jDvl z>UxRsyuD!{AqxsGXovLj5%lR)R`!0HKpFf*+skF;Nr}CzpU1fVD}0%Y(m1wcQ2@+7 za>+2dOKL_yYDrj1f80FFy&qmy;k~kX1%32eCN_&v_HmC+lcE?OKCzkpwl)IayzyFS zj=@VzwI5uBw_m8i7(2@`)_lkqI3+IA~ zfw`BH$$0U@hS)bN2gijbb%SXB_Bc&$$L^*2nSX-n1HS|qKXzNxiIq)w)X{^^GUV~l z-~Rp4ntI2xr3pLjhdarlxvSnYhks(e#;x#plij=9P;rM`jZQ9E`ZA8@r+^JV(#G4< zeL@2kClM&psH+i7ANr4O1i0*qc^?mL9IpP`J#(Jc5JlS*?w*z+k{Eus9tsNzHulZk z@iuq4x#+Az*;TP*?zy?SS%Pq+4-^b~I5)gOJ+NQu8#jIYk}+z!L?L;ae#p&80tBHh zZ3n}_J_p=j@X)ZrsD(idNfP^D}~c0)`LMkVMKV~er>ZUFJ3z;OdW-61~) z@M>1mB2~5BJRz2R^smm%{}czJt+|CbJ>U(t74KtJ4E!`g$F z>J2oCdFN>AL{qoOgLJ&($~?{68DcbsFK^wc(CNhTN_UwqYC}-m%WXjGC~RTR z=vDat9X$S2ml5o_xU_Y}YtA05ys^4A`{>)h`>d-bE2v(6^>Y39y5mky@m$4&O;Y_u z*YIF{rZ5?&+$(ZWL-ucRZ5+q98DbggL{ILzoq>pv!KiCt9x-~w^d0Y`8_ZxLKefiWYEC`wY22E}J?}|R&OtcaGO%lS%+BOeR zs-lS-W8U1kB5`+11xn^&JlLe0-l8isKaM{$i(0p{&=y^+qk9T?CMb&RkQ-t;obxix z29VvS%@7Qq=}E`rWaO|%wsO-hP`|BNFQ9LtXq-w_nZ6zKD%Jjj+}~c|^R9*_VcZiJ zhV$x>vo`^MVPt{;fpkJH?P|D3G+|zX$6^51T@VC!2lj43EtG$AEYhh(qhsErrX2#W(PRg0GKK=A2c@}K@BLvcgU!Gy^3-7+ur2zn! z%!;7z8&DTRI|x<;_~`=3Swd-IgDqe!ozMo=RCkPY2G4-6I+6tfb!b+#!sU%wL1UG6 zJ)k%4`}&_*{xMc|&|FNq|HCc*9wErpSbU=5{X!Ql+Y8T)oB;14PL2^CuBR9m-L<1+ z6Vcw$RwuyD3iU2HK~C%+n!aA?obG{vfloZkEL2b&CCOWiR{9B52?!18J7Ysakikit;S>8MS`?#sF%n?&&R5FM@ zb<{(+vaqmh-ONy0rRxwx?@WC0VOrwDbRRCaU8WfoaQ$@sWl^(>Hiq-cMM3ZUVfDGa zQAeGF&ApXj9qFIIt*`O=weB7*?cuyPbazZ|&iG$)8$9T4&F0UI@c;5iD}EZRC&#%~ zs;Lx5yVC5xs0yqR3>!TQf?!~tLF);sQh=oX1Q&2@<+g-I)w*oF0R{1z^Z1qvA_th# zWP17JFX%?bn>YYH!CeDtBF;}Q`5u7j5PrO?r%_|nhGP(X=^%Cd?!*$d<+csbu(UTQ z6=jqea0`BYsKP<1^Q;2wm2f?&rwb-_!AO(_(#g?IOXk5_dFmEi#>>>_4jh5%XxCVa zK8EqRtKK7@=3YPimoWWWRM|<5-eTeIGdcuittxdp<{px8X0=$Kdyy8gdfMXjmrBri zpD0I4*2$h!Sv^Umqe&_5%}^O)m|yW1p{M5QaQFMdCRWW28MSj|uMyqplpI8&PMl0u ziHfP5p}X9Z9FjT|R$6}&Ce4h?BKHZ;w=>*486+(QYAdSIt+}$IVTFBPb|}`3zJ*ei zTlQ)&Pj0tUE}Rmg}}VanFyHy1B3SoVi98br-=<#|Bt8d zfTw!@|37v%X_$wSNXp(jyJXKYv#E=ay$i`mNH)oqnNYTJGI9u^-~B?U(cZ&dTgXxjLlcg2(&;IQmMzDsZ_0=xRuGzEGc~en7e~y>^mv*2@!VX( z$Wh;Ui`GepAX1Qr+VM78R4as8=%3g}^zrPcTkfAeP6+DO+gTMu!DyIr}U4ujb3^wVj%=R(@suZ$!1p}Z~zv5ZKbM7!abkXDY_Y@oOb)f znW>GZL%F~Up9&_YiwRLzube-Xk%Z!Wu4xlF!gV46lcN?lvtI9G@MWSg!@=1b$c`!3 z%-2&I>$rqI4=H${>j9V?UV?ZX2o4aw>7hMP($B`+n@wwf(0bwjxByq4_o+W%-sMv& zO|8wVHsN7cCHVYd#piZu`e=2q2rKvH%Vv_~UZ zA-T$tN=3u(Q?KPII0(3zNVdn=BRtubSz`%%`UuSqe?LmH=*3&Fvei&C2|hRwm5oB5 zQ%~8$6c3j0zXXP@)tGa^7Z(7`8eSn zq1Ahlz3V;Pbw3}BgHj0W%aF)7poby}If#kwzj`zh09fHUxSpQ;5>&08m?iGY;Ox8nHz7Q=M0}R>13isgE2FDrYyn)|F2q`KnH^f^#Uu6jjJnG#oqCRe)7`mm89tQjg^M#&G?YG%CS7buZwc;Fe26}i*ghqltG(0VAStY?aG7WeYxMsV9wQd(cX z>-MXSWGAfO`Fk%(f%{bJ{Ds)-dri0lS(wnKh}d^gS>T~^p~F`*_}#pFiyGJ&hJJws zEx4NP9FJ#rWJ-I3gQGVvB>z%fRec8{08Q_Yz_9ZBT?;?(b9C$g#HQZ3UclMR0U2H2yGmee}m43J8JA)(vryI1%-PN^tUSh0lI{Jxu+(mZ~&bG zx`MI&U(nL1=$%#`%;E$a3J~>x{7Nzp7ML*f!>tQ+0ntx(EqNfWhMpNj^I)R@x)1!T ziy_u+Mw6!wfe%qWz_-*Ze3ev!Amf@uDJmznopYe8K$b?5l;oWx`tF^u{C4AYa4tb9Mmtc~X_dy=$2q@i`3||rMrDz#25_K=!|Q*@|I!(g{vFI*<%*9EChF*`)NRCI zr&KL$M0?|^wq4-?p=CduB!i6rCN5L3X+eF5{}z!8x#)KA zB^t!Rag{w&hAPY2=pq{zSnDsCd;SL22@rbW%lI!KngZWeOMTKSluKPPCe7`%hzuITgw8~+b4W@j#+g`vS2)=OU#&#F?TCg8F zNGkoam4L!KBNmEpd-;!8jN=a^EE~Kivl~3g|{tyRECp%lv)xtsK~X76{6G%nGr=pWxu39}tgUXH<OVBm!Po6m<3n)3$CFhx}+s& z|8om+l};Zjw$kEnN{Jgh+)I~#|1R=u#-sRA$?cyhLAp~xOZRcQfySE?1~Qv>wxt?R zrlu}{XT$ULSzmPX>Jxqm)O>Ma76f+qX4Xg-$kT{`n=+U+-(;+!=dFP(NM4Yi2!Are zz92L6-Z&pTVE1ZWj``?V^@aBqZ=arJ_SmSx+TE7nCH{8!YZYi37r<47uFe(gl-+odX&fEBCVuUO&>Nh;se zwP+#LtgFZnaGuet%i;G%HPzYJAgO=e5$7^50ki$`a_^fOk31$r;^Do#8HYz_IMY%? zl_Iat+=DQXK@!6Kf5hIADF#`Jw^KG;Y_yP zuYELxX+Pb?$ClwT3KlFk(EZvH)Z+X>N)*G)(Mm2VTBQ) zc*nHW6ogmX4rtjh5aVf)x+NYgyV<5-^+k&y1Z&n9)smvlN|2^kJ{tBY2zw9beq^x| zJx585+mu3O1hCmaO%x%e0HMT04dRgy1H zwdrx2WbZ#9g`(LVX*IW(5RL*iFN7z84d*#X4){--r3%UdsZ3QE)G_igvB#AnVD<-+ zmz}@nNTVbE&p6~2D}sF`@CbVL?MO+yVgO_S?R!dYn?=$)75F&J3fPD&fw2zNUbl3Z zH9H%U2H|%Exz`36>O>$#iHA`c*8KTD!G>(jm4(_2pnnJW6z3*nQLV}8;%o6A%nyH= z(Lgfq*980OlpZ^{7*m{%BZGG%ksbH(u^f~GaCFmA9R?vW;N^qDMI$IRttFT_rPyBh zaowtNe*i|1@t%!ONF1>G;?}^@ZrqZ21!&G?mwC+(|m`yvS+RH=;-kKK>YHL=5v|W|J(9G6+TFEN6d~d%AL*l zeo9XiRrb6fRC6XJ#*~ST0IeF>KR=6;`OW8+mUE_SL&iHh*tfS;ZJ^d*F{xFT$TGG% zB%b~?CVpR&Ni?sajNXY8UFPmwbEiyq5mR=}!*J^L%xqQK*S2*QF~4a(mEM&f+mSAI zJ>41k0GO7*SZJq z*gj1SUqYsK%i5Z>s;CR|S_-hw$uwIwGFMo|@6fIHgA0fw3izE8xx3Ud zBhB%WhldX?cwd{d!vBD6Md9^NufynsIT(v+P=TymV~0Gz6D5lGUGc{u?RqYh2aAds zU?eCpU1c`MK1398YIF5fi?E;p=I@ex`!^~u2Y&YK8R9&RU`(*~1#k+g8Qdus&z26C zlv?-gnEQV0CS`W`;cW-(1tttsFyJi!ZHB3|RU?9&T6fM%#KO^}+E%}2%rjLDI&)YN zmOuVEF_AUMG{3tcgB4}s!d*DkhNAzI(%Q>|io>rTfPNL&Hr>?pmEfUSUIuRX=q~Bn zU<&+z{glpxQ#|)uY1d3~&&3SG^(f3B{p+!z439p+)F~P-ah=n=leI8Bu?_RFv&RtA*IsN zsF2}WQ6L)7{;_KoE@ANa>UqtuV#+;l^HQe6@%N>>zd9FP9TMUccVzK5F^g(J`>E`1 z9Y~|h}K)Ub%gi{t3ANkCi<4ahaRkgsn7*dUvQW8Or3>N3WKHOIFJ(Sp5 z1u8Rek^e=gV_C$_6h>j3raX7Aq7pt^&+jk?i=X#&6#N+o!K##$lwZ&eV*;%)BX-+* z9Bu{=CBU2LKk?Ufp5n3lS<{0sMx0jyX>Uf-ETj$_9&RY0kcfw9<6Wav?MMwhsC%bxI5vG8@>-=4YC|n&~tAW zhbl)OQ_oN0THRC_dTfeQoPM`hhA@Zd?-K*wS+zM+TDtobWYey$(ij;waX!0Vp?B|C z=2xv-nS5K~;y=h@6q}xnNl_8z1yntBI@9;?CF_U>pT#`BacxkeL7wmBo7uu=rc#tO z($D_K@}%dq?s~oh5(bzeh&M|gmRVT;3GYY=1iHf{a2+K$_hASbwywMV>AnHqii*PH z?hvsX_Cx4cOVu=~@MHRz(_YiNf`&&pY)&;*3ZWh~iTq^dh;Cc)jTgAPGlOwmQWTz4 z+fv=T!vcC7k0)RB#aeW@QtclGF{#RY?^_Fxxh-$gyAmuLl+-Hu46VYb>v%wZC)Q%h z^{u>XreBa%$X^@7FP_@PtMA7w_GKuBij_p^B)Uci{Po80wPp18cM|ZvO0smjS}mL3 zkkm<_GWqN;6oPp++V?gzjq#q?n)0e`%L{a9a1wN`rK2KU(>`94@5G%HXET53+sfX* z5^yBDqPSbXg6uemo*wNkvrLUjUe(7ZXYZ10KJM_@{@4O3EI*pg^A$pV&cM=^05m$l zDB7O{d&~2;)l$h>?R?=MVKRaa1e6g|piKUc3Pn={{slmtf=AZv$ami7TJlZ!Rr%pX zyBg6OPBE3F-e431`EMcyS$x@8X`94U(WDI-OFQYBgk8i`3kzmm$QGPi;O zg~tb2Jy(aD`3U@kj4~3M!95LtSLKU>L)pq2ib2d+&_HK-pXo)O7MO2a{pPkrdUsox zpY!EUI=Fq4u=RX%ylN6QlXtU*fSbOKjEqdnAx}8-@Kr)MMZX7Cnq+qw_sea4GWwoe zrz-+3uZY}McvqxvUiM%G&KEo&2$zQM9Lqx}N7fZ1;rPrXcFoI)h(9rYgGK*z{k3B05oZLI-=;tQe*AFx{n{9NqhgD+}~Qd-oY$E z@y7J--HyJhJlRyui>IH~pLT(;&16oSR?xMO+(m3r2c6)sz)D|AGV5Qncc6Meq(kKF ztMx=oez0)(QD-a*vS))i%{-Wql;VndHhjlddqlFV1VK>^5AOmw4~SKWEfNqBU{RiU zM2xGes{<+xxV)Pg(b{>#Ihpe}bl_mO3ZX;y+laXZKoaE*U|9lzjw@U^HKqq-pEHQd zGIVob(F6_|gTG8pBb)^g5jKYyJ*v{INN)L_D3BFkC){*Mo`^EhC_t%DneRd8k1L#jY?MdYy-uDm+;e)(gXJ=;~iHL2Uo^2<$ zzhKD)FP75Cw$cLqO>4@6-j`J&f5lEA%f0kq0U%r~qaj5C7&}xy$&74>%qmhh_zJ}U92DA(H zZFFfL^W>Yy>7pT_iR+hn)!*j2;@g=I_tPm#%xSL`Pm>v#5CsBQ3zQNi3M{gCNjpfs zY7E)2IJZeF&0rDrHbp5hk-<>hAk!*;&@tZJsAsUEF)Za|DEr1dW97uppB{5RMx(wF z&bb=Aj}vEPWg5lGNpJdYV}evJ`b>fG`@ftgQ2XRQRE4=x za{bErFEvP*Fw`Vt3ttl8#6WJmS6~=p75r}I%FK#FeN8Wy?%`+_Psbeg&OJmhBamh| z*QWJMSU0)6OtHc;yex)2xdI$PpyUG%2O)ZyYj$kkf#;(1Rf8#?yp<$MfFfQu`Y0&4 zDBx_YW?!P$qg@h5V7D1Z#L-;)d;6tYp2w^r$GsMuw-sk7L(>WmULHpvN91oTcsC6* z;M;ndo_A@!EU#Gs&)k!`%F1$$=@hY<2=MI7o=w+AG^^U7Sy?66p7#-{c0K&lutLt~ z_6tC;!1Ra-L)UtlND|t4nITP{cv)K;&;8|w}efb;;>8RK}8h-n-oWX;>WEPrHNA=>?t zBQu}u=fS);?HzWwSSNojaRs7Dznv+HE2-9x;5JmQ)#&5+%?w}H3phyk+>mAvI*amt2Xw*k=x27gRnBodATOkm5C z{ShSp4J6Fm!3#rR|E#o69ZqVnt<%h%r~!h7lmsC-F#vbMbRXu&D3hbu9G}j3zY&Dy zh;avkXaO#%^PQT=5Oysuy520!Dak}*`_ST0so?5BjssX>!TM$}cr@AyWT1A-I^0iz zF}&me%v?m$4t9V?evZMKnwmK#d>0eDCR1_yZ)--jO=!7}JFA@lIs?TH+%$02Lr<<{ zY;I&J z;-wjNv)s=@r|zp$msjDP`a1bny)`I=uoUXwKk_TeWU1^A*u(3!j~j^d{yi zs6yd8yD`qaKTo^*@%J1avWgphDO#;=9pu48#tqUY^>69S-K;3q#RT=5Q|pPo9;R>g zHB?LTIhifKpqoJ)@W6Kc zUv67=c5nx38>pNMTg+{mD%@ZCsI(2gF+EXr_zJb%!Vl|DcX}qY`terF6=O!btvgA* zY8O@(4JSt%I=n%KLL}j5UwQg2nhK-G^=I} zV9<+>vXP|lqH+9wh4W16h5Vd{aAO`Fyt_m~E$(HsAwn@$Rl~9H#r9mJ zy=t~f0A3&nEp)|GRF76In4r%uysAIP zDtz*uBYRl%Xj8|+CdoW+XZU0kj&L6b)4Bq_R zPuy~$urph)`a1Ut&7KfkGMF{6=gRBZ|K(05n{|q@nIczos@QV22iRMIAsYCK<&G>hxB$IeGLnYvBVZ8#?UUs9%M}kh z_cZ{U9Z}lvS=wKck7~4_J&;J)8KNu>egNF|uE#+qMFC!*X@shW7-gTphY2_Gc^O0; z_o(Ck#T3QIQ`L4d5g!EpTt&r+R}+%O8>J8z;3%X zk3v_WG#RaWu6jA$>l6Vug&YCXHU~;8Ccw^!7v<9g)S9}MKMxQv&I2nSk2~p)T-{tb zqzO7vVsGbvGw9>%N;~>v-R}5h*FIBhP-hhL&^J)zpSA)+=Jfc}0Dhz1ImU)*LyFFC)}8gpXeZtYxN@p5wu0oRSJ)SE`Y z*8v5f+HTmUUH_&2~7 zfSwFyGnkpYI>l-TPh||Y0@M`x1=!hI$DK3oDTc^88aNJ!wFca5P>B$|6#;{1r49|9 z#PxH}kZD$z@7x-A>sbM858iE|O+ZZsldN*q&j5G`mw_MK>w)=xvtp`C@dj2&Ok~Ry z>#)*=9XVKhen4O4>rjym9itd$xHIvrI*uk*Ve-s^z7 zeI$mer(yu-lxqmWIY#aEZgrxOdqs&ZY$byE+duMgC`m6|KYeafu;(xG@qS4q3-nXv z)n`)z$Gt1Z<4B-RqXB;5mqeksF|R=y9Q%WrS*zJ+&ky%@i&X2M>k9 zpDKB}@N~hn3?|dl0RMrswmg7*hv8OEv3}e}PIdBnw5h2`pO;o**BcKcRa~F?jU=uF zXVRp-#VyrhKx_N`To08qxhV7aejj~+?sK!6NXEdMIu$?vfETpQm#I&CK=M+;mLFBU zqV8Jq2)v)&OEzE`qdZBim2&qtvx(%rJnshMGYXaav=uf4AatetBt=#xJhX!T@Uo=E zy@h^KvXnJdCdKzpg&$MEI3Sv^Zy*k=n0N{ z$U6)0KxL)Cn-0Ozh?T}g5!#ESTyiC`2v-=|H~_*CZ^-gG>Tos4d@#FWAmuzC6^)sJ z5mrgoy$G-4iVS|>kqq%U0Nk2A(gOB54cqn{IFf>T9`0B;=ckC{{3c*6B&kMP(^p(m zS$7*GH0L1$e(eERqc&sr78)cEW1o`y92{u5<_BSq>OlbsWey*b6W8rU{^SN+xu6L{ zc=UkNLt6+QHh|XmTqKMO(||E>>6wEamsgB)Z8VTFSkE=0*+iK=3){}Y%Kj^Pwu+ZH z;O|-~UA7PeQCVC21guu8KO6L!%9Y}Z%W7y+yPlG>X3_I($!0}P9yeco*0~(CsPs;< zm`KmkuCmmAhsce<##7{5UyfXUn^n?-?+dTj$EW=d$EOt@{gZTNrDinq^T?)&bcF8y z%ZVC{6r>xq?fH=oraWX zWGKG#H}=opX-wRc62C?Fvs}4&m7cf#-e7NT_{| zbUW*sKL(+gLP=Ss+SpZhmL`w~LbqRLBu)bZfn*>ij(lwof5`dfRT6~THOtA~_7QjV z&-qx{0&#KQ2@QVQb?d)_uoAvW!ozQ*(D{AjGR!&`AY2}Vo05+l&*+c>jzK2FaH@c> zDr9AIbMtwP8m>W{Xzd7sX5jP`?oL8S2!VD8WCjsafa3y7!NCXo^dyMlHhOAvWG2mo zZ^UeLM(xA$8CpKjgn>UF;&B570WsVH*vRz!_xi~@Di`Vb`1m06{45L#Y=qy)9|G|P z`bURTATs-)r!S)3HF7^yj5&>>Y?TRU9I%!^tVcjg1^_a$^@RTuDkmH)74?#uki!>~ zay!sSKAgM$YOHPDQA{d*W_8f_)S~dkmoB#*7<^xEb4@w4KAm|3%Q3|26C&D1nrKVp z9S2QFG+*T^D*bBq?tUifA1M@uReBD=1RvE^7VY__KHoo=zp}eoNPrq~9dA7xAMa;| z@d?&fWE2E$8@VpMYi^eFxK?shk9!rBRh0?iAO<%RFq|?vlxxfk*{5q_{(eDp>%P*NaW1EN zEi|O$;xadS++m2Smju%M^~9$K&lDmT`JPcy*0(e+V~*XfB{F?8_e39h{&S@1E8(Rd zC@zV0AW-~ZL@~h=m6t<_?;wp`@XuR`i@WU`Ns1qJkiLZ(p6RO-RPNlLee~(a27BYqwOW6!EHVC; zrJ^<8`@d%4O}8daAnM3z^M!ozr|ON?fqjO`0ve|W^{$s2zPUK`d!Mwi zPo4+6jcXLFYy9g0E;bHAOo#zZP!JjcB(t;C;9Z0cXzc28in{EvwFbeX=Inr$GyY6o z<=bCPO-&V{u$c-b+3}He>UFTn6Ip;-2Epd%)rbIm!tMI&?p*Vk z(9KSRD$?v**4FM-&AMOuWxtkT!;NEEILky4Y_*;l*lhg{0Y+UCFjhL zN@QSICFM3zG-bQ$n z2MIO1NyCPQ1;sHlA4^^pfIXOf$%yZ@52*i{Gsh0SGWV{7IaFXiFWU$;jI}Kee`8se{pnwR<%Ekr{I8Jsq`R~4nIr-SUA)Tp+St~Wpu<)1& zpS*Q3p%rmJ@VML3KoG%nJ|2H`KO#}+mVC!op@;Gj^LVR4s`Ke+jSe+xgQb3J&$5>U zgN~Qj;-$uUcGEGbdZ>O$BZ=1-8q`@;F`?!Xmzm-+d zXIDUrc5Bfq{aD)EvvMrAVvb3lp^H_0&_tk6GxqKneB+=By>hFdIL+Vt{7fBqYUM&8 zD~as&DAo8pn^dW1S=A~0mYv(%Vo>UY-)O!GsSuTsusHlUvh-_?2UZ|_Qc7p{O8W6K zI=MhWK;9!yPul^DGeIXmzMpG8_S3%{r_Z2c-+#*&oJvW^MiYaZYq~ z!NE@!^~`aQNB#xoV>9h|yz{BeSGNwZ4iQ((Hf7N)aeB=~e0WUwj)3#$;NzS(51+kH zILO4G#cCPa7VBqB2Yx-1`>>3+acCZoxjmA|oRG9bLyD;#khmU{QR`~v3iSp!V;dVA z5>is_5QB33r{$;)4h%AEyT=8$go?_u z1CAy~N>Z21LAxffc6{8N&rTE8%GwPMBg0i1`FaJ*g?R`w<Wr8;+a_uFV&ro+d-avB-n+FzUOBy`74G+0#T*| zSoW(`@qtvZ;z9K3BQ3{XAONFbE4rzfspQrxLPt!yiME$}_}d1uXTZ0kc z$p~~k-lIA@wAsXKQnVhj^6hZrrftEZ=?yz`lb>U9aWI2+R6x$3`}Eh@g%Lm5!^x*Q zuLszrXo9G9O*R!;;|swqy}FgMmiDSyv+?>wM%LJA9e*yOCi#Hb81a6dL}OPI{x_ux z-PmCpi88kR>$J=$lQ+cj6(dVZDla=)!?sx@-oDKb5kCDCY5sQeE%&*gTRi*{fB5A< zZ|(T2dd#J@Hx5d4#P4ZL`V-MdU+o#7m5T{GqddP?qQa9L#!*SP12iN`8ypTNp8pVp zMpY*7fX_>dm1F*6_;f4iOrILPen_PeHHr1F^hL!^_u+XI#S=c0n-^lDIsGnwlP)*A z4t`NIFk744xdY^;>lT4qi0Ez_Vs0)UmLw84K_qYyx&4`vqE&er4X4&^;m?du1m4#| zDCK~o6=k|;K(ah|u)aHu?-S_rx~blLh^T*08b0&G5l-jtF%4EV*Ph^)U#Ii6!-F(8aPb2o0g|Q(g!-}jY13gdUA4-~IrQpgv<3l{QEM<3fg&@kRAIeLODNN;2S8HjcIQu zL?ZU~_7KbxaH&@|MEX=7F{a`$o7_!bI8>c!g&YJB!aQtX4VqFWjmuPSa!ew}#J7^lDI)%Bl+(6h%SH8AI^AtRnlSCVy&*hY$leDiP_o83Gxmmw;}oj z#&}gWuX}|tHytibCb16;B=~82Dfi0>>iw7zNH*_qi)Ehl>|H>ms$c4DRqnWs(ZP4d zGvKD?7~;9xeX=n3R$lhSO5r`V9F!Lg3);`Q`9ga9@`9-hPE@p0&&%<&eQ|5A?3QuXwU`rj~gyzRjjeYjkX-mJEA3^*c>cCHI zT3XBv7dlpd{pes6hL>?T6mMh@cB||*A@eD z=-ZEQe9fBthAF5=oJ9d#0Jwl51Df@SKFL5@5?+cCk<+NkZJ{5=_~$ma_}&A~1+9cW zF}NTJe&5JA&|C}k`|SLVl2eA!{p(SgOL*sJSZBiS7g(+r(!WBQ-CemoP!r<39|#Bb zz-d4{n_&|H^$=Wc((#M=w^G~|zHvdva5%AYgzg0MhZwHegp$p2i^e_06*=C3*=FbpO}19^U~@$i&xkgd3Ng?nqO8B^r!=Fa`j7LD~IAIq^Q-q zSebBb8;LZDQ-p_miTjele`ontcW*qMsR-2LYPo0Q*UQ_tLBT9rCwsho^YZOt3?3L+ zpXK)$*WNNK`?6s*f_`T@dd4o8xv@WNOeQN*?3=NDZ;aQczMT~rn@09t^#0qJ*JKTy zElRuAG=PU*gv=cV7p^5Xa02OO^a&RI{8ckZQ5yn6=2jz-^!tpcw) zX;=A^J**8d8?p~)xxujn?Q__-aCB?Dt~;{J0epi$mdI-?vZ3P)f@qvY$E73~Z<=ct z@|N37igdsGFVF+PaZ$3Lx=t_Hlg>mI>1)fN#hDbl3X`s$%(cX0dDM54hV85CIH z1|uXRDkM2QO)cr^FE4Q}&YDMRtAp z(r?PJ)>(md?qS2KKvv3o{PzUEC+k|Y*Cfm+2b7F)G)}c|7!UJP{~?l0BzUDCgKu$e zwEf7ap^WF~zFOu^kx^ha=$ofREhvnCG4r`mgJC`ti@Mb!K0x36wO+@9}pvD?MneqJs6K)C00^Qu5!*f_1 zs?io|Jbra!jjUAFVqS5PDVajNo5%3^`VuOHAcc&JjXm%jQ?|D2bQ8lFMjvaBq}KVf zr~Q8A>3v#flOrMesjW~D_)W**L3+ep7tb>S8H;N28-W|ar7w(ErVd?*LxdjwiI28WR&Yl`sfT>jNt3{; zHOYbMY(>oJeosZ~*|w|tw$7Khux__cJd7e(e~s`p-h6UmTCVZ80%jeXZXUXIGgVRD zwnCZ56YHCQ^ZQjustOA9Dx^-Ieb0MFch@d=46+9im=P?eK=M@Yv-Wz;ADfy>+7n^(`~Y#V+-^064+5cSPG_9ctDIEwGMxAPG>-L&mUMM_b|^ zl82H0Wg98cDo}A@D+6Ep%-wN`Qa`pj+qvg~&hFTX{?# ztAMmM?)^>&MXi!d#zGHl-tIRt-BzB1IA*^f0Gzo`$6XnDanFaDt{4T&Tjcxtm@@oD z`&>TAe`ntl&Are8B?hov75*=JLh zvif({{9|8zKNv-8e-Nw34E1+-^F|m^tq2NWF9%`$zgT*?F8Wb*gifHQF^`7ES1s5^ z4%TGZGdBf3xf?t1G{@sF9F#;0#(MTwS@|2-lPBU1M~m0gPw+mg9&d@-C6~c_aezE1 zXpf554x&i`YXAufEecVD{_E}zl^>~)Fh*g=1?MuF-IXz6J2zwc9fMZGO-_E{RHn}d z)8p1XM=&25dcPQq;!mrZc;cA?!v?_JyzqE`4s zZ%yhq{8ZOMkCmWxw`QGT+kEhc&@hjScmjq_d(gf7=byAh&XLH!k?_236!po@dU@)s zlM2Tx8N82H%|mD&XDDFd)iKwT0-pjw>ova(khpZO>zE~NaS>@e%5lnv4ui++XK zXd(N*>Pa734R_af(0}WfgWWW8(ZP5Kj!dwZKoho>D06U@8V4b9w@O-}5ZHJ@;$SRYQS2z$#e&rj_0 zyS-&AXWP1>(fHadv8qMuI$0@iW1|l1@BA+B5<;!yw8hjt6s6;r^u9WM5;2N#3)Jwz zAx^3<@3Gq1Q7<`mE+-h&2}y#=XI=-_WKvKKmk#b&Hi;WdZj&m+)w-sfyxoaCt-7aW zIIhQZK34TB<05C(JK7KL>w}@4yZy9%<6n+EC~Jad)q;qj*;~1$(k7WHsk>G>neFm& z!d2ulUE?=~Ah7CyHS{-9S)SrLSphTSCn5X4coN&ypO6?{s%lv|SH$byBusHb{~pf@ zffa`(fy`Meiv-o60@VvyKS9sa_=QKL@|xd-+e%z)EUPrN;4lx1%(DJ#*k@3_pxnY<66~-L35f~cYrSHVeS@u# z!mzZZLH|!{0ft#ORa$;$7PgneYz{6IAPE7;6mCtQ#o|IFbXt7EhY0>iXlZL3mqhLf zMgN9}6m%w+br$?ctlGJrc-{V55FIM;Ifpky69&(V$}g(gi8Wr?{hS*SdWLP2pS`o>`T&<9Kw+;(g`tTQJrA_>nd@=s;XjAdn~Y zR3c_?Z)UCDS9!4h6bhIq@F5wwrMozT3wEbT^5~|Kovyjz!=+a|SR+<73v6?Bd|LO5 zg}Ed$@R*>^M-A+(X1q>Fw2@(?THS#t%EqhfWg^|WYG;L`pVYtaND|yv!kl;QU&9w< z*+rAf22pH831IAK=qR>W>YB0V7vA+=b8WKB&J#+tC>@Et7#K9_ zFZ*lhqklpx?~>*R&RKzCWy^?)n!9 z(>Oh6$f$$}=yfbi}U7kqLmas63M4v*|uf^+PZr$QQl!%Nu238{6c!J@B@a%y61I!9h$btOzPrAqX%(C5pg08%Ag-oN; zVIfXR-++q=5F%73HQZ$jj}aNPr!b6ur#m3d_6K>AGQ7eR0U~;H9ltx*^(~&~&bQR4W?;5iJ>q4;>VRY!(rH2(I zjhLD=#wfpAs_9M!_0uZ1+118LS}V_Ux--&$-YK$Sb{eu6dS4R{#yhY{K#0TOW_SA^ z;yBKptH~6IY82j^#E*{3vo%E(Tu&BW8$^6_F`(HrS+brVFY?gBd#b*<`G}Wwe#{5v z>j~;j)ul%t>jMwO;P$)GAwJAY)7lufm9vVz1HL{t^hUmakBDJyogZ>h?far=rA^n$ zOfBQMcfa7nYH!*Mp_SwPQ~LlxuD)xscs0FsrnO07CieWk)`N;>wUq&f(vYQ}qBk9l z2uAVC!B-O7VvUxvY~*kDQ!&t`PJE`U<_*}x{^g>=EuDB@b(@GE8l4__O7S{N(nD@| z_qU6p?%LWTf2lE#8}S) zy0v|TNWQ@fXNC;u4({+#=(A=I9$i`gb_?^wK)Vqa#veapXfX-0_0Y^qXlp?O$rbqXXFk#r+!=r&uYqH`|S^LkUq&T)fnCbd*R= zKT+Xz*gE`uY%A}`my5ZKJ!e=+=zXAE>UFWy?)%#DWP`w2Ro`uVP)uZHT$)@Drd@8(21NmW}hKeRrh-G zYK5QdxTDBwI`_b3@%MFWiE~1iRoZUasX{vl5I0}pKA5_I$G+nRJu&9V=j^@I>;@P9 zz^Rp!z$N)u>4Y!823QP&`ipW&)ib>hsRd}zeIsVUY ziQ@76hq1w82eKtAyxu}L^zczjiT=;A{mjzQksY(_yeQ=H*dAFq>|4nJAe13{ml)^^ z0R<7E9{YK>77x{)NV2h*&?a2*fQVSoY2+K*Y>H+E0o5O5WiW*zpB+rY$cF7*%O~v> zvYVF^BNS)WB#`E>s><3+hL)BVRxj3Z_PoNv)B;$KY2gA%2*ZHW3p|U~T9*;Gx$d*9 zX!JdZNLc(UNbyRGrJF1&u?yFwZ}`aSF}%G(aQ)IfRp#@9bvV;+TV)ZprXt6}nM-Te z2SsYw%SONgff@{!ua$aWP94IA8`{EW0rnB7#pQQ@FC281NkScnF@%Xl%s$4T0)p2@ zM=MWVSr1q|cNl*Ul~ugB%0?U-du1@!{r2gVRc5KEt9>Y~JwM2iX=`iiA1iCwYA8vx z{RuyaprD}j#_PVfL!knRglyqaJyF`lmbTRB*iU%Bi&;7ri@uQwVroc zVA^@-mHo$Gq;8GA-j5!^TG02#x|-}@BX=cQUBP;IURa zVoCepq-UgpD10zu)nLBJE_JG+gg@eQG;!35)WqrMBD6t;`k+?B^awkO>#G1&-Y`%K*a zV-};_5-i?3`|HIHp&>#4RsQxf4vYEPIybr4-6&`b-L^@kTWH$%wK?)NO_NVwdQf`4 zocwgXC1*lZ{>?nS-m6LmQHIlpFo*$)0u0)p7DvdqoNH7%HRh20**kE=8@j7TSK^qR zt11?L^zR0<2MI$iONw19^xCi{ zGO3o$*-#@@Z)lqINn0^AWhCqX!be7DVH&}zW^#uXc_jrYaX9?^=4t-i&| z2zzGf(*OFW4y;}NiH0z9M|3i*{9>kL_<2GG?mj>IcIr%=|K-H0wbx-MVDk$a0wbl% z;HX-KL3aRdgg{EjNP5}KTZ--K5TJaTIau>wkU-F)|oxq;{MA9q! z$+IZ)Y2sz;fcgSPmH|q#scrubi?ToyPJeCAhHW=455mt@J9-5HP@1dMv@3hs8eBdX zsU~F@CmNNUGHn=$UkZ-L7G=k<_k_k%`{-Qishq&-m8R+I^oTW;y^oh5C75XP@#foX zM??l6OXxNRo0zl2xfxBOf9|@46`k~ZDm2C+k^LGISU<~LE}wlQy2L#d8$Pb>wOrn@ zoYaakHSZW7=3Bv@tmqZDUp@wI9?e-2zHI}H>*e4w^goR3Y5etedDuxY{_usF87_PrJPYgL zx7zP4>cXtIyt<0>t+TB=smNkZO-&W?YO7Ia_jd`oDq{J7Kq4N%#!tNq>A4P5^rBC@74pGil> zZSi2eG+zEW>Q7Hv)2~(YV`6XM{HB4HWALYxLVW+d@w~3)^aIA8{8tiS*HEiV!JH3_ zIzl`D8p^z6rD%k<6O26;Rr{BmJ{Ezn17^QhD+@p73{a=Powt;BDyUSjiYX2fIf85~ z{8B^QLc?||JFZ~w5P% z-fJi%MiiXtO^19SYcQt&duCor?94LN?@kVcu*s=s zWPA5C?Rg^U9~RPrl$TZU4T=cYCNn(y4kov@C3UlNGk#vEG;OcaY$pZ}?lL|@B}i>a zz)(F%_~9M&)*n`@U|?ipd6CE!o8t0^aRGPVH8eClIf(CCh_~uyIPes5%MN7DrqRk0 zmiw#AaL*UwOK)0AXP%IH7 z%bJmcqt1r!NL4WPfc8=1Zp8FBXopdkb_kxfO-wE=UtBLc8BHoR_@ng$9H_Xzw!4V| zV;oQ}sK^$B5YItRP7HcxfRHL0wpIIMy09SOTgN=U?XkawrefBYmaM@d1kOueg(45? zf_^XDT5|?KgBYY0YRdh+N+rZzeBGe!Iu}LqzS5qwQilB zK+>!8PDZ>xwt4yT&))$M!K(BU;F%o$jr+6p(N#-33#1XD*Qbrm$*yF7TOa%*Ibzr0 z&I4AQFbUz+ldGs=WtZ!}*J31dFHQ`zd1H;XMxlLi<{dP4B{gmkFmrEM4{0U-5ldU; z{@i!!ex2yxmD82IP#Gk7$(G>S!SA(W*A1D@gjLfgNv45M#v?Qb_l)nvwyt{}HynEL zA+jn_B|?h{ryjj1Y-NF&@&R*Bf+$$FTW}ld!#cLp-%Eg}+di!J@a@a_sXo zhH(T0AcYq3n?7E3w!$`bYe%(I>d2FA>7|RQy`ofkjnp=bkQ6p;ZTP!LuK?f2RCQu| z`Kg54M4w%vT8;oc`JbOLnp}~WzLAK&o-kHF9nL|9GeS5KbSQ8SLBJI(tr81ISDb;b zdmCX5yI7cbaY8$QR~dNzGXT#Jcb<784t3HD91L(|D%ffPtZ%vwn>3=I_D$>mF-L&@ z0;+Vt-YouT48*-)2tDkdXWP8g`H(B-i$g?ICCr4t6~H<1 zLFgOMv%sh2_CwavpCIQ1KoS1^8sS;;Y`)Osg#n5KLK-GWwE1?Mf)PX6`>TK#zyAI4 z2j#3k2K5LvIMlIG3ha!+`N5r{r-l6-2HrAd5m^Ie*KTIM_D7B#ys|n;G3vtFvjB%f ze9lYrk?+3#bAH9i^~BfTB>P^s6NIG4>}jyf3=)2(nd4$zKZq`c`4r4SvPR91q_Sra z&#Q)Zb-14AWelkgbj&)4wMMh{1+$X66r)62CjPevp{62NT!O^rYqp*IzJ6!pD!Cv$ zjGg`%6fjpEDIZaDvUMN@3mj-MglU@73CPcC-Db(a@a0tVTWH(9nAaV2Ydj%#F}Rsf z7!jVR`5-{R?J@P$&s0*bjpPz9a!nuC*e#BfsLHl}_%qJ^GP?TBFK)a(K~0Cw{7X-c zn%8tTx?BqEvK$~QN|Q4#sG5E7uV$Kh0Pnd^V;r>3b!Vd`(lwoDD*@$75At7j*IXQM zrj;L3dtMKoZw*DLnky2G10kIS6)J1j79{#M{+=}sh&-s7sG-(u{H|1VzD{Z3X9i2? z@oA{ZF&hkW8>0?gIH?}iICL%0*kePLRVj;eOHn)TciBg*oIywdvY3XbwWmPVE;%H4 z0S`yYg4E6z{tF2iydhw4b_C5zF#lcg&mmNRZ&Rboo=k z`!o-gOi~Up&1O%C|+85&lV7m#<3&UUvP&V-V*i{%XzWi-KMYj z8gS>!72+n_u377U%3*f$1tB$eSQ5zZf6wy#yIzt4eT-A{N!~(GLJ7Ks*Xf-WQ`5$* zYr$sY*3*fv>$fpsL~KY$A2+7AChX1_ zT=xmBzL~pUWsZz7^Ma17NUp5c@qcFOFdKwwm`DjJ*R1lmvT9Q$Ofu5pq;j#w*rMm; z6IxStu4|efRXUC=##bDQTfyaWypWofV?Dg6mDk4*aV&nKd9#>W;__#`8(r3`4DJ7B z2-`2@-gkNNoz2iY^MX;dl~4#E zv;UWH23vgEINm1>5Sj+GZ#!_zFVMdC-5vTZNDU1W2OzekHG%GeSh3uP4hss*z>*Ve z9$^MybjIY~bo$cQX1o~!NK9FVh6+9Z`R}(YzcL)I5 z1^qZQ^SIz-kh0(uFz~U#_@GnJe{GtM;u>J3aD>8$Rj28KnIzxX@$^@we>v*u>Cw1O zUwXmjXx*VCNDCF@sYTAzQun}Zx2&T{JZz9HyXO*thZ_Cb^s&HO#S}uCZ*OG8G0P;# zoGr<{Y(;x~ek{wZ{;>X{H*|Vg;yIHaI@LX7*z+8|gH7!h1<$<6uu3hbI4QyT?na$g zK$e=xR?ae8$~G=}TtQk9=TMNBv~%m_7)$j3_$>FgmuIi#q=(hpMF+gaWBD|;pNXV# zWC$QkMsT&Xw%!hl4yrE5)YK4L15V4@s$rMz zI)!ZyneH8~)%0{BL){a+9d2)(-Jj|EoY~xU;!u6(IlmZX-55an089ZhqUJ0{-xya< zwm>krgegH^__lUg%NA|B%aISQzv#FJKt_#=q&=DO;*r3&fHr--yaW<=BydE{**8N( zVzhW|q4cJ5jTGmoQZJ0DaKW%cfbiig*7a5SnQBQMa4~#N!&Zo_M)smXiZ75lfOy3Q z{u3Y~#&IY?-^)qP7G+M@eSBPCd5!_SrFjJ4yY*VLy$uA^CYV%-GApWi@11`r6j zD(F1DIO?_WK1CU%h|T}YO$}kX>?Q~S-rN;cK&iX;4B&Y<_=hLcLIyCnLgxl6rdYSI zfY-uWW;ElP*LoQhQE0ati(A{tRD!$y8#Z28bY8U~TFE%A;j7uT&d{j{;}Xk-McD8P zK;Uvq3S2Z&TU$u)E+=a8Kz70*lV+uvB=DZmdSSO_rOc2`H97d6s?=^}a4??1Ik&LK zV-~?FcZ&lro5_qZ&trPfRb44U(%U^OYe_b9S!`8jw8tRJ+R!7MxmJ#%e37<*6C=i} zGw|6&-KZ`CGwwQF{QaO7xsziDSzu{HOpEAM(-SGxo>hC%I&DiD)))x(e6n=onbFP< zexs75xOV2#lIaXGhF5;6y~8p$Y^~NmQRXf|sJ(&6nnab!Z6ft0Ip2(?q&Q2OYyy+M>(qQoeARz*`Ko`=|EyJ)JFZ zKtP9rV;lj$5@vE}k1EhYi67jP%%guj<2if|ODP~x!&Maz{&ndZpWiVSMUf;cju5sg zX5i3aB~Xe!!dp+id{1%v%}qt1*j-(J!qV4|vQv^xL;_&~aM8InlBvL(I8DqfqR z_e;?>$2LH_tYt^qD1fEOX-fyaQ@HOuHpylr4(in;P&s0qo$&#-gOQci?g*GKbGm46e zf;gk&yDiKtZCBfz3L^}RE%VV3CFamMb9iGQ1&qfsdp@`ENnokZ?4|Qx>!HjHKCSt6 zf7iq&cP@mzW7MiS61svscjfu@#hRw$6Sv$v7j7g;AO-1mH`Uu-vk^Dad>?uB3vSeh z9K^;s#z6pqAs?3z-cmivQD=Jt<@tOGz&WsR!^w!-`Aa@i+0>Dong-HDByd^w(NCk5 zGV1STeUQ~I0G-SVBzxJ&~Suif?jPl^(FX7 zHunRq`;!IMtKxon#nl)wJ1!!vi%+jdrb2inMBW5$nhTbEBa_j&39B3c+Mhyu1S@0s z0&G-E-{|z;c+FWF+1aKg=g~c{{1&QINmW!i5JJCy0=u66wg)-AbRDv%)o}ly>hnH< zy;SyBOB#|I#N(n^hEhlYxJ_ma`Ve5X4A zAGxT1hK*ox`nX+Pk+MK5K@ktZ-*&4_bo-BI9}Q%XACsgQ%vP0_3Vv50 zRsULGfCS77c5V20xV_<+6m+A2N5BL_EmMe}XDN;n-D9R;04jHE=Qm)~z=j9fpGv1C zI+((6SoZht->cYGf5~zD24x{G=O^_WC@vHhpk{W6#VBWiBLRH<>29<<5_;7n)btF@ zblOnib_5n8Q!Zp?bhyefQPmHSuqXBh6NrWX-RNm(Vi&4jI4H3El3I3H zW8tQu#60VekJKVzYv(Uy2X|F+OpX?(ifm5#j|U<4Lozbj>>s{T)bkr}NL+Pld44v? zt9WLEKo(18HvuO|Z>h?-BokPk$+AohJNHJV0JzubjiQtscHR^`i5S#7YF}1%bha$| zWLRVocw=RYqxRsljj_fGYs7h78ULQ~BFsi|-vsJ(_tnHVZ${*aHc~j+xGAL}hKC%i| zc=0GnhuYlJ&fIXnEi|@8<^KP30i+ihyl?{H(yA((yW!2UCf+Ab+Hbw~8(E>e)Qd~w zh2O8+-*eqe}aY#ty|-m&vc>M=gy9AAc!aBT)ie z@BdcPLdubx$4+T$_sK7G(`DpQ8GEacm_WM*e!8N07iRxk>cOy!;ySEN3O1S!C85q~ z8FW|0Sn{{}o{aqaSAL%{yI~l@V*!>2C&tmyQ4PaV00(eG0MIXSOT<#3Tp-UD3+Thb zO@a0BPJTV^jW}*yH9AzE7k9n)p1&yvW5HF@nwx)q`C|(|$V5g+FQ1)MGyVF_X+`|A zG)leqBPX5KX~Th}l+@RIMQ6YF#ZEh8xLr@@I;zHYngPG7>wNa!7N?mD9Jq6&=4(VD zX(Y&Hr+tty-O$hrBLFCP_v2PsA7ZnKFL&Y}%?ZTlTiAI6J_EEjSbP}{-$e2qci3lL zEpcc;7>(NK5Lx?L;^~FvgTirr{ott50FOVadk=TAOySucZ^g?CWKF$_w6ETLvZlEi62MQsFp}P`Su@T^vdwJT)hDR5 zm*Z8e%%zxpy!eaZD6drD*s#P!KU_J*UEO%d8A;Zdw#U}&ojFrbmcj4$yXG?|2GOM` zeCVH|Yux!AgUYrH=*-zv@+MxA>UBV)t-}pGBgRUk!a51L%9vq~2ZEGvMZzxRe;MZc zuLBQ~Yh~qYS?Frggl+G0F%nGPp{F?D;qMZb77?+i7D!P`@*_jVl*BZ&J%8A%=(U6#-*9bWb4DdJ0zPu*idwct1U%`7ZGcz?H z7l8W;tS@j}0KioEK_m)i!GTUs$zm!KhlKO;8YX^)1#{@k91}AW6Yl2$5#P@7yOD_H zwd^mtqXnD|(Ut|KrXC(l0C+(s0p%A63Lg}b*H%{(OG6azD2CuQS_+`m3GWIagyjg4 z=C>InG%1Mvs>1M$$7RKDsqSS*-D+1EqVra-8)wab^$|>=;dQ_Rq-M~RXr%8pSD+bu zNZL-=)Pk_i>|6`sc8uIY!9NL_z?;)OZOSA$(8Gc2l?p}_$RQx!1T=2QfgwD)3rjH$ znO6|yhm*n2kRn0`S)C-Zg0$BRONEwYDszxdaNW+%I`(x(`JH&wH4zc^jnfnLcRk;|~4WG4?Lw z)t=9z8jtf@=XrG#marpdtOK3==TgRUwlW-YmPWWO293SeD87KN4!yTQQsXco6L%O$ zDapsj{^v`8CSl35ve(>IiIf4?4WqgXtwv1oKS6}1t_a2d_WX} zw4!Vdbuh$uiwEZ$hS9&BrCyZM+>h9?KpO*HH}r_OK><2z7!=wffffcJE+q58QvP^- zmABY?BUH}w#Jkv}HL~lEfqyq3sUVk8pc2$&s9CZKBW=9w78}W?o4B-ZSFQ8eyf1*x zmrM$)9-Y)Q=+yyLkB0-4$`Z~2U>Ny8$ia}GV9jiX2o zJXoOT24To?KwpZ)cA4zJLs(5#$aW)a)cyT306rKEOR zvX&6$9~@hi(YD$*Nz~SGJGLTWWvfNR&6SSq+}7tCso`)?St1-B7wO@mEI?Ipoca1n zmx^aH*7hF(-tihhr4^s8m`PTvFhgCzC|m!;Ie#TslX2QC)N~gk zFF{SokS_VLhJM~*5V;Z=;&}Fv50$*!#ZmlRmvmG7uIsj+e)PxVvJ?7Tv(A#|XCAe2 z?mk`M?j*N0iT&9{%bZjx>N72TgyWil<1~(70qfok7lC2ycJ8}3i6uuvYkM8ycW0~k zgJ?F9vjIl7I(SPz%pCdI!>s#|U|M+dqX7AXppmPjJZ3>}E+3Q+{JZ9bs-t(565wjm z2E8Fb=eaHtr<}GJ!RDNV-eKOEbX63DC4#l*Z3VjCMDT=~*uj_p>x9_C!h#>}NS(_8 zgBh?86vKiQ4i8VfKmhecC{h^~U~Ucr;$#@G7T_}|Wo`eqUA^nZ6W;VxVg`;cJYm4C zC;+Pgw8WoWcK(t3C|Q(5D_7ia+;at3n4bCjAHv?nM_YzY+(K&m^QILl=+^IHikWjh z11ru&Y7`r0|HZt2*0IP(Zck&KER(f`eKu9u zV>~)J zz3)ef=P@sc{#kOet^SymGc3P5U-^zO(}FG4r8c8Rq8qktS1&(1D))9PLcErWLhT#v zN~ChB1_~(FM3VftB7cxVa5V*)Vw+N;seBXJWx6ycd%D{Yb^19)wLh&3sY3Rf6>;;T zJ07b@iNqDv^rrh_|Kv;?ifi?Miv9E>Kx;M>brz82nR;%u$a*PG=XPG9kaR2Z&K_40 zx_Y^imh9a2ktfc60xBTncz_#zJup`9;h#Rz7<8>Qv2Oe9a4E%s&#yC6r_V$1FFawX zZi}3-r}jAbZPKEBb~?_!Ic&3kf=z7>C^j3#U=9t&MQ53J35K z*Zy7MGiFl0Og74_nI3X~)n>B*MlJUU?D=!d#_H+vT_m%=4BMicmlKo=|Gj3X3w?y# zmrPJaSWL(~KO{uR!KwzHC-f1{M+koGeW8%Z+T%O5+qX`M_~|FGIXU)|M3$fLpPZha zKGEb}oL!`C_WE;tpeUye3Ih|tZ6H|F!JjI{6L13VJ0#4Up8<9# zo=-OK~{!gmfrBY;0S(c`I&(=SH7Y*JLqf*gL7Bf3D z(%UUm?zff}_+tzq$anaPlwb`ZmB2aa&HnSP=mKw=cSB|nl`8&oJ*?Xy3@dVm6`t8( za=iGw$Z2dva*CnMovTS zRXjN5zCXEgMu4}zQnw$9=W_wi3#(%CMF$P&U+ik04%Z}T`eXl^y1S2rNdm=QuUjkh zlS9b?TQAXg{-EWdjI|*T^TrE@C zE}%AKHc*~R_lEr}n2E`3^=Y?Qs<7SFoR~NXi%(ZdoJ+`Vt=@c2%i=rPmsuTa-k!V- z0|X#q0D5#T!+r`rM^_F=rqRlK3b9)pR3dhXAHpgZytYSeN+vBq2Xp4}AtZb&lbY_u zs3{rkT0j9-4EuLal>E0{Snk)f`c`{OF0l!NV5(%Ua(r@HD_wI_dYLJvb%&k6nc;5K zW>3YUQPbPHLVXDL5sn^vYa_1OQ{bVq0e{u;b%v~FZwP0ER-@l;Go$lh4uniNN`&Kj zTWH)s;17OjxGfg6z<(FEHQX*Pm;a`vDU+LR!`2;OY>2-A+d%Hr6K}LU z3(AjjVRi`Ur>heB0dT%EZ04;FF# z%;>KnMY?($cS38mXX6-eIb2i}rKH+;goku|V-aL(b))%%sdwa$HDk2Rh^~mZ4S9#N zTPyz=OUmOq^!!8h@A7-8-dE7+HVNYg8`=uj#+%38V#7YzxT+N#S3*>JbnJuirK6S; zVE(EO+@=c!h2Z`$rq;q^T@q3*yPolOF4R!l$KF~!f^Mca{o-#8hR%102_b;}E(s74 zGE*x4!Uy)uK5dE%2#m5Krpkus%x+8(nhAKeK5CQZQjy`x_;|iG+CV#;V9{v0H-?&U zp>}oe$VI$kodGceX7ymS+Jy$EJXa$>QVbaTTT<%%&(H?E7 zg$WeQh%ex{htL26i60pJ#l|%u_ph6E(n?Vc<-klM$in|)7&A(!CQvBxA%9gJ8?zGD zYzFfiYzF>YE#Sy~wVpVwDGa_q+o3D(U2zUl7FqX%*`UU_>kc74zem9%qV3T>o|`Y; zYZl&P!n`P7ePg$aMUG^)ut(}kr*^kVROnKa_1Rzi2J2908U80+PEZ||IRCbOK)|NZ zIwcb%~XkW9Ro_axYZm?7gI= zxa?d-RTJ0szwuM5yMM8xu@#HOPCD`h{2=J%Z~o-fC6{Q;{?*_smm8{x<^A=*E1TVC zmU|ZyqjjP{_6nQtz!wScO*#1g$`lZUjR%B>lAW)gfA4+rha2;N%WA%=#;mi>Wc+uX zr)2dT^qyOzPc2ow292VDJ1u_{DZNhA^vD7dyJPCP(NJai*YaWQD=v-v4?!z)(x!Ls z0UD=tRUw^LOqXrJ(`)6xa}KE=fEbxy>peQDwjS4gK$zTF?)LU_A$Y(EF6U}$u3=;r z=vUX)GW81n#r(h)n4ILJLUGxoAj^{J759!_!pgpzJ_vu^dgQy!gz9@c<(^&|XQH^P zXcFExRV0RJpkc~?5YR;aMFdsgG>6h{%?Um3ekm9t@x<~#nVm~ zD3PJWJsI0HSNpXijo+whD-wP{pa#8lpU#){Mfo3v1h_I-Hwgya6OkSVHV}x8;YLSMoroEi^O`uEgi7gitOxh4>N*z~)eC#|i}Zq+ATyB7`;#^O8oDw=hZ375@)Mz=yx!1~Nbbu%z9 z6tx{|0)r(D`1Tj&g)BEp3kF<5z)(T&&bb?{EoXMiVs%Z)$)e3@DV6>~5YeQnZ+>rA zR}#P86Q%f^yh444sb}8$MI}fka3dt}EmT#nM%@Ra*u;79sOr?%T3aA1}!hh$dexmgl3Z z2u86lJZzRT#*ex(I8^t!?M9bJ?lW_AWAqUbi}6pY(cAOu;)~xWO7!_?KaeHJe2`!3 zt=LF8ek|=VWHC;8gO6zg#Wf#s>F$Yv|M?bUpS{46AnI&Z|7v^1nyFtG5594Ee2rw0 z&%N{Toc8KNHybOic+Hg_ah9E=dbyGO6|%>EhmQu0yT5;$igFJ_@(8Wcic6RrCQYkQ zJwMwTwkg3C6FB#*M}w`kWOI_lEPQZdB-AYi10JKH`N2Z_S$bDgQ>h%9dOK2 zTz(4}{p68ZY2b2T5);3?N0C_ro>b|)g1{9S2n*ucw?}H>U9Ho+QE}zIbr{v#dRJ+R zTyUj|6;0@Y7^Rc6BUayYd>TH#!_)?xFyn(Fr6 zD&~Y=BMWzy*b5DR)NJnFxA*`5< z<#}IlWcRLzR!plhP;z#8dQTvG5VRQVQTK76@>=!Qe|%{0W(4pr$%NUm)=zw+h7kO3 zmJZ_oPr_7B_B6L{@A@PCJa&AM~t6FJN&x<4(q1xKo+5-hWBfYvu;cR#F?UdtHCiIr)DMPiF&iFe&Cst7e z#a0_-73McVy*=49v;#OP4QzM82->#x;HK9>oHv7#lF~ldij0vktU4UZ-IOTlCRI0T z7-opN|BSSN=x1J3kXWSqjBNPzs5bj2w>IBE`q7|Uz>fPhGXgVKFGa%kN2$!J?9Dor z9#=LJxDq@SFPVj36)QqD{0MM!-g2K(_at7!0HpjCMrD8=VRFa$7J+vUuC#&R>i^7G zc}DzGZJMqnn zqPMR_$PF(i!pv<4!%@I+!N;Jgtwe3z#KFOUo8$D| zIu1>=O{s}0_aoB(C7?r#hkHRMSX7 z@!)^diYa_vU3>I{*zB{3-w%A7Z0_&Gxpp|%-@pMMy3T|IPtbaBKbq)+2l;?O(9<* zj}50y1{k|D1SIxXNpX%`+;oR>$Za{0Vo`}i9gf8r6BxVxT5R3(RHxUl*qv~CNY zmT&j_z{2q|1>*~vZ%*!7cET)?Nxt&E&o_rgBSTDeE)EFUCs%E3*uz6~`S6kGyB4mJ zmzV?m)!hNAX?S3p{xYb6%@!%a^!ZVe?d#VqG*9!*Wg96su2S528M;}-f1_$u)GhVR zLpZlYvOXX-Ad=;O=EJ00qP5{arQLka`1{XyKLAD#o$0YW?N=o}v-4tMHF;8FBVBtu z^YLz*IDWF?eRASf&WE7(Q~0KtFs1#LV^>=Wtfr@zun8yIn6Nuq^R6hP{4W7h7A0+a z`>$v?JN0Ixre0;8iNrK42K(L)Gk#Ofv@N~oR^lCbW-?n5)Z7&L0qe#MUiG8D-GXFTnK}9|n&C;rx zns6X+fSv#(W7S)olKcH8C%RznG!21O{n(@Se__sMFYYuuFiDyzNZiBA(LCqaeq)VI=GjU*;G9m| zUn$WR)|w2C(HC^ zcLK-`QM%!+$YRV!oZ2%|Gkq`pf_{E+@nD#^feiyGk}yVtf&~mPJFi8xm1?04K02uU zOWqVh__s}?czYh@f}#VOpn)xLR)Z}G&c+%xh(KJ#SxMvc{8>cPLlVH@{}oCs`()45 zy?%>Sc->w~M=6W4a?gQsa!VIG)#bUW-p*#~VPGGcx|JUgC!q2Fa{)4^1|7n;4#H?K zU;i127Op*bWD8R$+_+3@@n4eEq{GtEC%Iu-{WI@2XFOqK<4j_<2=B^@slO>#%)KnF zQj~{*gy>>&uXqY|o=>jA>z()B8f21vI#DxJN)tlSu|cFU^xKAMY;OZ5tLr7na;s?~ zr(4dK;rqn>wLYc-BZLf%dJ_NhggFzTAq*e5R!>|t(~Agv37DQ=G;J4p9?dlqv3aPI z?pxPybC(uP#Id+B$q;wvA#Ls;mCSFY3|G1ED?h4zrp}2}s8cXii>QLt=u#c#OgDlo67O+ME+)SZy5i5CxP1vXAZ0YJT^j2)7 zcQ1C4|3ib(BUDVLOZ49dIEn5Eq2JV{ZW9;weIHn<}hBDmu z|3D#xb_gyL_)-a0RKSl}mck}vs4~mZH_PD%SDJczkF$MXiy{SgK2Y>-9#k_F4vv9| z+d1XS!T$X(P5;Hh)&EjN@|i2XS|&Y*QLl#M5e&ShO^N$!w{DfXWE4L2Bt;O?m&;L! zH`6a)z*F&5;8R9K(@)+n%uptsJ7f|+fA_ZbfK^4zXFq(=9lG`qd%^SD{ysuE$ z^A|l_EE`m}HRyHD+cb$0uNH-l(Ak1`iIH(PHLj)A-mmjv)MR4t^0!vgVVB6HZTFSm zRhnN9%f-pCb&t))j}z-KM)ShSqFlf73j4pWuaJM#KOTJ3u{gxPsG9LtW299aE0fMs z@G7_eg`73>iOfLxIVN-#tUO!mVU~vslIHu? z?uac8(}H#LT=Fc1t4^w5^8oJH0$UO2t-apBPMBh?7;&vNY+m`8OM$l^n}cSVDrlO7 zzK%{4_%Xl^X-Y2XW zrV!!i%EF;GVVi9&DIsx(yv@lO5?SC-EB*j@8Rr&?BlUkbQUpf~4!r^EENTweUUfb5 zr*H~fjvO%Jq6>xi6bt@OFX2W1xdwy?he9_|Z2$jgs`K;nRvbG+?l)L{Wwp9UcJ|pX zM<_-*NZ#Rlc`-S#LQA&6kEZgm@5IQd$*oK8u77lX+F~Zqq^|W8hF`)Vq8qB*jfeP$ z9y{~fiZm4c&n2rh=FZ92>Yp2RKVP)WSG0X>0)eUy3)Y1z8{qT!MdzLsQi!USj6*p2oSvPvpCr9R5Sj70pUSc^V){6;QcUg4y|$CYR~x zft+WM^A#+-UlI|sD*XJ*u}Qd8bx_^VP2HK#-lp6NX0-FuZEl?_Szj4_5aeP?tHFIl*pa#VL9pG+cP+ak@3{wVf%4hkGoJ zzj8TfYgy`Ftwc%Z`IKh+T|DB#nH&V ze)WgbQ+>EtfCIMxbbz2{VG!j2dr^>w1Km$!llU0oVDaD(fkyj_p$zPM;M39j`Y{cS zs``$#vK!EWgf>h_(;f7ky%$1m$!xcPdkE_J`pQe&S5wL&92C3bGx{#9?+U>-LL?k5p1*PRMWN?kILSPxSRB5mzf_3N(4s zQ^<|dM79<&<7kzSO;Yf506oo=i~1zVQfre2i&xOSYZ~Yd=il*Ju|QlbzCD{T zW1XLz?lTIWc&^D)bX@z}-ZE(O`f;IQfL!1^9;Z-jS`{a^Z^X_S%@NC z<&@%O@3p4nk$5r_KM75?jQ9x&#YrR&yi&2I>MmUn%i*co_5F&o@4x0t_4ja@MLu^g zT)(H$CmS>MMwvH8ChGq?kleIPtV&c8a7A&h<(MlEXnhTymM!{AH5dT zN53@7)U%|sw$*--ir5c~7zt;UP$d)^QxfN1cZ_LG7mZD4xz8Uj9p`JmbEDjOgjhgH zQix7U47MFmo- zSl&sSJ5kO@axv$)jO3HVBEpGrhM>^m0V)S~-`LO#`p+4G9>jckyvN+B=#-eOr>F9{mzj42(?y%r-%j#af?y;f7%09aNYDFD5O9KJe+WMEc z>we~}Kj)Iu*t>7KEZX1n|Fqrt^~Y`CVDo^IFdte|;xFq70r#+>tM2`4?TEgF{nN&Jf>BF z{~|A>F2Yj|m;l_(&YekMiv+zgm<7U;-|LLODjYw!=_iwAh1?!(fv}xzY1h}wTCI|u z_%2N0$r9{{9_b87@?ld(8I*FxxR8zMZrtR&s5h5Od_e|@2xm)CqmmESy7sB(9{$(3 zw*soau3es+G>5@ZVR$ov#<0GK?8dq4zCW__7OQUW>&t!K)urW=R2+6Lc$WVrubsVB z)n;;uUi(+~{5?v~vTc#?yLI;KLt2*7w$wLR_ub35I$bXrBy6}2H z1kWSD+p%i@>!Tne))(=A$CJHpW1oiW*H54n!ZOmRwN?3F_#P>adsJ(c8wtUI)y;~onb|I*dH@_6V z7ycF;(HP}s&Ndxmt4~iCg5iEnmhnWuFXLrDFD4~_SoCeIp`fHTa4icHuhR2P%qv!o2~v6sx1%< zJWinGiyZ>9f7h)J(T!UqBpeZu=AsA%%a`Qt<%y3~3|rJ=HZ?eAzF1jZ|77o*@IWv7 zMKHB7A=BnduWVmozz^W%0@6fS{`EFe&s>1{r6Zdf1l;UcKEFKPXr(UvMJr)OIONK< z#Ho5lHF#Lt9r2;N*poV@YL8YMgD>A2m3Ww?#mij)yJd(H)GIJ`alv%tO%d&WgK(8M ze1~cj%bId^#KjzRn&v*lgbS6M3_=9?8^L?9W}-@FR8aj4E)MsvPbt>{gbyeb#WQ+p zlEv!Nm867q-wRiaDtar$taRr7=H6RQ7n2uU0E!H-9PsFFbZQg6Ywj=(d})Rlp%cEe zU>VD^OEi%z`r=sA=nrf25MA$raL9Z-h!mMn_u|=u*PorJY=B?%# zI=K=1z8woxG=j;A8HE2it#7)ngf{!Wl;HDhu1LT#;ngqn=KLG;*y-2rdHrpp3@G2O zGf_%o9gbo1ESFJ-V4;0MqWdn18ELUT@xuBTs|aG?mcHxb8uW`A*@<01^^Mb!vPM)ZRg=5O0g6d6?HNAQKV5XS9f-lYQ7IsnONm_ zXAag^3RJ{4J8nTYbV9*FNbTNj+rHjYaU7 z0$c2_Tjd{2LgT5MZ=jw%+mvC$rhF)ry8pWQ-O6>Jr$ z$<>coq|-;OVM6fqL~>6au7q=a+>vhbj^N8U`B!&ado@bt!8z&Y0qAb-c_D4 zR${6zTaLv-;5J4I6V*{&dl@0_q$rf(E)Tbzzz&cG1R^9XNVu_5EP$1&Y%j*SiwPZf3 z>Em_Y&Fcw~@ct3kA8+3Jm*ARk+9USRxJe(34Z4WEt5~3J9GTYl*R3_^02N2+ZL#=?|(fT z9ZM6q3R&w~l>fKOZ3No_x+_;8d<2)ZlZ^BpQ*a>&y1_#~H26{kw58yR205mrCkZnb-k0g|;2;KwSQ#Sb!R-gs@vpqn`xGbOZp0f}?KP zloNKnYsFClQ0&gMdM(rXC~Z}n_gg+12nvvAz>6dfqnIg>qH%%jN1RtBOiK`VtVWP} z)M%x+DaKX1tO625u=NM0f*0k(K5{{IdC{7t&*p&i?sDUKURcji)^Xfs@T2zSx|psI zP5O>sSbm$JPG$+31CM5;9ZMvkZ$Qu8 z4L6QJ4Gix*9YnptbteOjv4YZj;qwUU-%dF{ZwTGV^9x#%$B^1R`}(ai7MV_?fh-(%y%FANFckp zT!K!b!cf=eO;|+h-K!H!BR?qn#@@vt!8OkA34=J8kd{2Bdx_O&>YkIs#O-W zDui}Y=xXftLT_<6rud0N)_d6Bxvkw?3W|Q`@>OcgT~;XM&c)erm*Meo@TPKr2+O=4 zD=}<4@C0g4R&32tCJ z5U-b-Wn??A#Qh)tirrZRE()ZMuPK2K8iaU9K?c&vp%Z8*Am@@0tpAEVUIQWqJX7d2 z|0RS2^*UxMw05hrbo%fph4R!`YL!6jUH|f(tw5bkh&mR1g#pBn1Qn=?3W*QIQsDX;3<(yQI4t zrG%lo^X~cod+%Cv);jAP1etli{qFtjCjxS_hqHw1l;h(t&{Ct*jVcm=xxgM3ZD8ug z!Y2t7tj_B6p2w334&^3kKOB0T$2<7dKdyEdso1RzF+2zya!fm*GtXA3x@Aknbe!iM`QNPs znn)ggQK!VB4!lrOsQbn)q1OKMZ8}+Ob!*y4_I7lCWQV;AS4v9D{2zX@Vqt7C6N z%Aata$7ztMk#5t(y>erFh#7kSjznST`;lwu`ldl-Ss28xV|6PpvKwc&SOhkVccXZES2*R{T^{_To4He39=fjBtQlmf(~%*@ z40+pZE_Kr(?<&^F6-$SMKjmGsBuI_r--(kd;PP0O1>N}3P`cPcp-Xu1{W@F>nDV!$ zLzbrRDfvDaoB+Go0RQyav$BhAanOhfaxg!5fLlDtN&CLAVBDgz_pkfz3*dsI!y9dh zF%xp1;5}!LK$|W=&Imlku z&L71)xf1X0!GTsNI6eY++0{)f2Q3SBzokPE=%}}9Deg8P~ zKNqmmvyYOw!&+4mn2^^F`bzk63~Dw%NSXq9p|@8-O^~tm&fA1R31j*N5ekz?iXZyK z)J>L6Z_nc9vs;XCQ6}McT#81-UX5pTx z!UELo$XJu&JJxts_x&tT{RFAk=gqhor(5?;P_RQsl2lqd$b*9z-RAzWJ26%^-Ik_X zmNhqqF7$q^3JH?1fvB5qg`MxkQOG4Vv{v9dEW+IlFX7(z^tJ&|?^kJAse|1Y;4f2uJsa@L^iFv%Q?e zJIqUX(TPEWyyHxCjB}V6X>jNB5TDc+VU>fON|-czX!O)bd2S~PgH=7;$k6en^qZ6y zZK~%Q!K@T<8U)u>tRZ}|=VgD9p1SAK#`$c2=hQQ_R4<+|bR|J#$p>gdfiE=5X*A;7 zsQ1b&Kp(X8f5xN#y=ammYtvNruhc#4VqYO zSW4j?xQa%xUoNGF%)#mibc-7dJLAyk!1G;c5e2J2h{S?|M|BSA7k)*?y=dqXCI%ql z^k6F2xp)#B-gkLO@->}ViVso#>hxSfdI+v|G@1k4FS8PV$lvUF7ZV+AV>kuVAKb?1 z83)cJ_?kiQKGWoP1Dcyk<{7WWE}A$YJ6!Ngm_8XPi+ek5R)Su9b4H=F^16-ULv@M_ zhZHgC;`M)@3^iSedl7oIy>S7YSoUPyL38N(wN1~uj&6NNVCor!EP!lQ~2JT98c7qa@;@HJy_NY((@Nb1F zk!TMRUt_1U{n*X<;|KhY`kuAf8JmQIzjCvyyZB`9#mj4It=|zls-Bs0ip`@)g&}TP zjYlXtbD!N9emQVNgr7HmvcD>5JNNOl-GH|z`Dyyh#zvm7T{?{1fRQHlg7lA=t)Gx^ z=iRgIO&AT*<93fjpJ4+zR*2MessEeF$jkca?{|M6_r3Fgy$g(mSTR}{TDYNz3?bGP zrh=XDO{Ii=aTWHXqq({Ii?gE=^CR>>`ChvZ@whqSkz$F~GgDUr?&YRFZdICWs52ET zi+S`L3E3QE)i?dJB~gK_c=g@-hLuJ#9~)+(Ip zZ5LD3j`VUc(0^{7zP}yge_36)T|MG|{WJ^33=F=gf_6U5b-o<=CZS&qFSBl}I8f?O zZVr!Szf&3IFJci&&sAHcOwSXWM%<+NQ4S>?7|!732HSEAE33KP#7hyd+uDYN_VTU~ zMx)Bfi(_{&pg|aq(e;xAx3T5}{s=rm7+27Ks13TL@D3eLdx^tN5LT51Kqmt<4y3an z$wBLbLPU11!gcN;%bgfO`@P{sEfL-JgE{iKF`axA9e0yx^|b5*v(NN~mLP&{3tS|* z%vWJofAhvEninP|47Nz|`I~#L8Rw8DQptc)y|+(Gq+(@6kZt$gUCoD~=E{?Csuf{) z2H=Hm;c{YOc@A!paH4%ZmiuPyV(zvVSUiZ`=z3xF6-HDliwHRu^r;8AFO`KTbdkHL zUNl^QW;b`7=6RIw7D5C9x`3-B8CDZo5tKYu9e#y&FKf%A`aKes7im8Kk`wo zUb`cMSW0z%#)es)_xZ0tdn4@J3ve`qh% za4h*}IEH3&rJ?C3It2JR-ZDg2U30}`56KU+s2=U`a&Uimdb)6U8gCcX+gJOVNe@#! zwcn=N?`J$v7j!(24T~o&MRvRRKt(<9=-S5%ZoKYSwL2She47WgWHqRNB~%;XLm18P zyj7y1_v0HVBFBuNFlsQtuH6|1@b}ToR`qu{dHEje=D==8$J=yD&br?D72G=CgGmvnOHE z4H#RYPnAy)@k5Ur=*EIKhE6bX(TcgkU5pXUkCbNgAkVKkKwPZkU*JPu)-w*DIM0Iz zi!xI1RH2-c3$GC}3`}k^;yObc7$wv;?V6{^5@y@d0Hgt6c-RQ8@k+jL9I#cXj=A~N zw`XJ|vhzx^gtToi@*fR(W5&xJfxNrHIFr58XUT=Y5OB&+KXyOzQ!>@%Nc=l3U7+&Y zE|c6d)62du6LIm}opSOi!wZ}VDW@yayb3|rCe+w-!tYLa-oK|uAx(P~6zR+zQk1+h zp#qHnN`Y?!s5}Fd)8)a5784qW+!s;-073MXCqfN~=jitwdyf}?FA|(Zo{8l9&0o{4 zziVN8%j>l?7Ejm?_d!_89eUPg`|sl^&OZK?H3{o1y=O-}WWT%4=J<{Ywac2A*FttM z91yM^);y(iw-*-7!bfL_R=*Z&JgFqPe^IbdJSMhIFx}~t1!>6=iQT>BoAz9Ujh3Dy zadV$~?~f=U4k|_u9l8FR7tW{Gm5829zSSG1cTU_8Mm{pNS#TIJO(#YOoN3g^y1d_z z6-N0NsN$9OrZ)OX5?YLAj8c=L4gr2sdk7Jcu-1jTfC0&Y#I;+WxIocAlbN3I8x*4` z1fqYvUAC98zbYO4;m}z#5FZ2sG|)U+!92%iW$13y0utUQP`3QnQ5H60Hxqm3!7Z$z zqXS>;Y?fsH?0A=xRJu3(wpfz(hs4a#SSb^uh;Og@q<&+tl~`voV^a@#yVWGP1#eu+ zr}KRkcmwxou9_|UwVXvZ=mKCU#$hSIrn5B$iZe8uqwZqvE9qW{kjq%Fd7-@8Si#8g zN{;!i8MA}<$B)dcm1*B!KWz?-2HF_&KJS#Fu#z^p^eIGmNN-wv8kX>4N@h&}RKx11_> z`LkP8bkzIrtFuR)K;Pum=c+5!gxs$8Dc%NQ4-1W~vV{)`&JNe=>8DS-b=R!N2Ccbs zEm`CGw0)T=3%(kZWkBm7SNuj(A-+X)rp+X!za(%k3G?ft`dS6l=O4c{h*UL-X)P#1`X*%}TtnKGx6)PcV3RW)J@cvo|a&{(4W8@U*SzG~API zkJd*$^PObxK3I+JzdG*iCU*S%Rhs3$E*G!sL?S@0d@7bHQlWgyI@Nu~lK|HTfIIn( z{`ZpUZAVAtb{jUmCZ<22#gj={2eR7&s7WACk~u`=Ll~<4wCmtnC>$CK zka~}nm2SN*hz`)yuiJNzgNvl_>X>|oXvc$*e4RIMTESrmWCLJT7(XW@B(&Ti0hcP+ zAI<|~*Lf+~7hO02a+|n3M@xv&!JhYC<;|>@O}C)k^Pt;=j}6w~kbHnPnt<^DjE6U7 z*3`0bU=)X@_F;>C-rniCccCr+P8f`t(2)X0&K`je_UV9p!q1)EJqBeDeWV`CsPJaB z587oBq}cX~bEdtCEZk-y65!T19=Azkt+c6mBRMrmlZtNzsDgsdd=8=FVq#w)~&mv$mL z_QpE`aye7YKli3=DyaRWU@{0t_g{?@>`0EZ{2kY&M_YrPkQFfb=V3^$-B zTX`MxQ+LmQA;sHhBkF>e{)A0$wzh|{ZjbkRQUZ4zy=c(^mmnBy=iq1n`ntjKm;ocP z+emxS4zQc3x-&!Yn!*YZJ7I&7gN)c0FHTrZCyOIlK37B{=m<7Lskrz{Itx0tSO(?j zjeNJ_s^Hv2{iKCiLykpT_u9JrzsJL7!-kcxc!4xaCr?ytGU1LZ$%J4 z88#OT(Yi;6wfbx3`z&HsD?3+qGSi#sEY9^hJ)7qGvjUoJ%IAD`&is?)mNOG=kQOh8fL>wO(6icj}<>l`m5EA=8_hnt^NnRxj9&Z^WbzMnrXuS6gL-4H; zep?N>5z@|NEqT`a+^919J{Arkg5k(w^}Q0tEX7abc6OGI@cV52+XKdbxD9zQW?0_| zRb$OejTe=%gU)suVv*F0_`QtX

    $1_dM7&R+Ab_Ld zJEpJi@1&OdR*=w$qVEuNmKMOg=tJ0(AiCOPF?%uN!r5hWXVcJrD#UB`weyA1Kk&t&#SAEf3txVDmZWp^CC?woOIuuI0kjgb+2Gcm`5>w;ECPH1U^BrKj<)A- zBoPnfGwvyu8$0~alPDfyBN({pjuHlb2rN&~BaMiKn;UKN%Oy$_9))3tQxAM62{!U4 z4`Ll+UUCE}XR46mf5JUtBNF-7A4og}KM-B@0Q-4G9N_G;u-Rru^YRHZmQ8p;2C?hT zKV5F%HhDW%tsgOStEU9){hZwX>4UX4ttD-5)_?rim@2WGkZHBr`1Wmj;lSD-%pVto z%B=*xhs+yOC|wud?Z8<0JD4H+*DJ1?bdMuf~27AvD36D0$VXoyP<{Y{x%Sxa_8k_k;hbyWlXIPTGrEx{XU&X4j4$1T+=hc+V_aG;Tq>COe6D=b#Sa zh~P7TJS@16JnI-?YDBwFnL!Hu4y)I7k;Z z18-U*0=6v?^_CA}dm3cL_<`1Vd1QTlAKT~g+1w(_6*0z(jr=owh)5`WxbPreZipn~ z@Or>?DsE-J>Tm9n$B`Xo3trWc-akdWpcSlgI&~Lw8o7yOe#QGe!PRsL*6V(RTUI;r zqOJDSH8#uN!Wx?#fiRc1_8s?e<_rJInCVR?Zyk3=%TE?03+>z$W>}0W5A3U?e{QIo zep!{beNRL+cJ4QCzrCg$X*kG7UBNQ8s5iE1 zWzwV}jovLchPOh)n{u`72L=D(skAZS*Jbe7Ad%Ekyn01C!T1})kt{0)g)aUJUWL+j zhBN#r&6MXsT@NZly23MmWDP0SZ*yyVT2s(a*y}LZWRq()4@#*Q{DHBRSACU^Oc(nK z=2^cb`37x3K>21DjZ+=Ff7VC!#;?eT;&Yut+cWBAnflb-WU?>h$nPEQaWkdAf3wRR zAXSHI0=JzcdU38KkoES$d_{tB`^87!(tcUYeS`!?LPz=rGrjTO)RGU^G(QVjmv0Ou z)jKXZkBj{Z`tB!HpK4iP{^pSJd19|4_}S42+u!1QF^TM1yC~3?!xB=4V^{pz3!T=% z=P!0~G!K&O+B@c5*)_~3Gm806&d$!sFW z*J)`rDd*QB`!>>bJSc9kD$HGKtK0MtAj^gnvFQvC1Q0}M#0M}jG-8KIZ@;wVi~0s& z<6HwCV-v&@*)Dd)9G=-2MUF7B%m|4A8w~0(`fD|mo9Msam-ytTAqytgcP{`1f(HsL z&>)Q-!XfekH8WM-^}vp{-5VnkE_3uQ5SELuqPaVmm1AC^_?8WE#asj2Y0#NX>j(KyIBl@f-s!F}?tC@DbUS}Pc^zSN zd$5axo^?GSkI0;S5M{cEk@&PVxPvgiBx&6g_Dp~OI=V%VuS}mUK7{6Ni%)!)550+q zzp<<{P$%2kS~GAgwdaG5Jx~xm<-nL>PQ0u>J!1|L56-XMyPndYLBNorYzWuYe^VvV z#ueyP8@OUbj%IxRLwbSgb44|y&g|=*1zx^32d^x>ziN@mm|C5~W{d9tzJ)&mtOc+@ zgJ@~km7r+?@Z+G)Q3*;id(`MS#R!6X`gy*f_gFY@$jMHk$Pp7bgNJUBB}fH1;t|e?&$M|q1k!dtSlM^&acMYI3Ngl@=(Uac{{3CB@Q&ntlq-zL z1JdIDO+2fpdB|Myx%VoL`GfcKbw{^)jg+Q>?bGu-cg9hIQNJDAgIDyr-~aq@BniG_ z%ap%>0z-|U8mdh~<2jsnXy z!iTyhZ#cFV4s)927oVj8#DzyliV(=aNc=~EnUU1cIg?^J?}1I=lwx8k4At5OFEdyT zbI-N5G}dEux;}~dcV}qwmG*?F#?@=j_`eOYSL*05{xoq7je7gQLd#kjHc^Sh*jvV8 zjD4HJs2)2pMzL%4AhFO(_)DR@xmwWf3xkZ zi<+uWj7DQrQD0Oi0gf}W*0n-BvRdC;H!mbREjM}pWF5q*{ zt_)`j+AR`7Ji1#J;otTN`u-Ybc1!4=&_n1J_~5-ZqgJk{3Oi;kH{`F}u~NNKL9AMV z4;WymF5<=Lvb~lIf28Pq4cb5tCOT;QG3)7(njDncHS54CIXl-P7Pq29{$M;G6mR}F zMW^#^=bq~W`~}`tC}2eBq+d`+0ecH*QTGa3Yz;;RVAF}td-P>+y~-*dSI+u#Bsdii zdNkP!{sge^U?~c_19)L*ja+9II6bcwruu@<(dr6&+=wr!VF7lnJ4C<^;hgw3UX%Rt zD#Q$lO(!#_X>p<*XTcK zp)S2RK1V{K$63yr#x(+QMe$}Ye{v``ibXt;O19Jf&p2yGXDyJXt`yUR!PNa5No;Q0 zo7IqD*HAMKoE{EJ03zX%k584QXSDE5=$^e}?)R#qcbMsiWv%jnP#+IgFt5F!Cqkt0 zL6&#SsOe=p-ny%@#_80*+X=NA^5aSh9oS0S#+2gmV~xLx4iu+1_vtr_`ZIOrai+fG z{HR->p5Q#K2`+nOpY`X4d(SW9W$U1U;l?luaSaQT)1^yRL_!6*Ssorj(%_E-#zLR!)s@v1n?tbW?+&!K#@@qFn)~dPA zwX<$haaGUA5QRYO#);903lIT7q=e3lhK&LcvA~KD$cq)bF2LjnYo786Uu|N_3Sdvz zId^wiyncf21V17ujvuZljZ z{LFFQEI`=-9xHIVpbO`$f3{Do%l+PmS|uBYd+Cd_v=8Nww;ui5A1~QH0(JD+?JF2q z)sYm~UtB=;4r2gl_p~SHw~y*$f{X8Gi85~w$d+kKT+a6pUkq;BqFDfslsvP&g_?XY zv}lY(A1bYX(;`4JhL3l>9Cdi?-Zn59PD|%j>SG+oE~ZS_U6S`8)bsL}1!M0~am>nz zNLiWWU&7Nkaev_@$rtH^J>$bxWs3Qu+K%Fe5x8k%`?l%-zaJR*LK`nrZlv@}o+mYd zg@px>kw2J?U4_YH67hWXxp&%fW|O8jtJpq_kB@sl_}0%&`z)1pACWzkL8|n%amiaM zb(T2dM_(a>qetWm%e|E-Di@km%c|V#+5B=zf3Jy(3$J4PsP2rhs!ko%^n`e(uNUF7 z;#{AW`1v%*{4Dsxs-u3Z6A3Nt9j<1_=$A#Kbm>!`CoI%!E`oP0XehJYcUood7S9t9 zN|CN0iuChFcax;0I?W_=E=INsc1=^SdN=sItC`685O>b7XitxO>xf}JYCW+RMT^0$ zGrzbmkH`i=E>;?LE^vdLx0|WZNL6}*D?Zv#lON&H8=g$^J!Sv#ogMxUf2|I;W~6rP z*-1p+;JjD9!f$6tZ7YfnYX&EM08+PQYGcV%&Dij8nUnc_KKipzFhv?9@s6+3GkmND z>R3UnaWeNr@SSp?54@ku$?x>qlRj!;yqJAIe@)O|6Eb4u@9MzL|3Bs;?-bwWSoaXd z12T;E;jeY4Arajpg*dB#5!d{T!DUc-qtk_iWWf-r6q4IGqvCg9-$Ta;mNuMyk_B?W z$0G}wwV{Uj0cy_qh2C;39Cl+B{j}@7Tq!rA&kSLK4(W^lJoO|GF581|hE~PH;0gq> ziSzBhFFysJ$rd4^&$|X}{`rj@+r-7WTe;JT^N9r~VE@e^)Qufe6YYwSlzaMAokBU! z5<%)L-fKDF7S3vx*2B%rNyKJvFkzhG9nSlyqae6S;B!_O82w|`-^VX%mMq-S|*9o5tNS4IdT!U_I@ci5)nS2q$O(nAfrQk+as;#?x_(EKX){l;bB?9qa9+F)m;iSN3=^`640fF@e_fitg<0 z8WIDysJo^`Wzw*y~AurpikK{_AN8PuL(*gz0oiTGh^r}C~X zfPFa7)j=4GhN!+67iqw*6k5jg8}P?rr3HW$l?`OmYCB$|M|RyxmeWlVIOOil$Q)hW z&_amTeRF^0b8}gRsU^Agv3rZLQvOUyI8RPf>O3T%YvW*J^bkK@lhvUk_Jx~6d$|H! zTLGwD3#=!zN)h|*pah~w;Rnj7;~T77WmuTSRz{7hE@OzU#!|lMAUlQ0JM_YYIfGqn zC5*p{AGlQSsKFE0QCYAiJQ^_J?_9HiLxg-gN#XNLgm=9NE=S_lez6qCe!YV`wSxq2 zvaAqrRVDm8JpJQ};-RtUT$xbu9skqUmdTew_D5nziRrGodWScm2pzHT(~r}NkKore zZu&J7x2b5@z%EMuz~EQp-OyPR`&a?W?BD4fSs!$eX>9Mqui;$5j9Se8?fpb4Cgs37 zn(Q~buTG0)_6$Z@!Zia5+{2v7pH*&b3htk;Pzrx8WpvGd6)RXv-p9Xz@z)rW?6&&6 z?}b_=t)UVTTkG9aWUbD>VdH%BoSQP!rlW1Y4p!*;>RaoEsdHM0#A5yLVft$;PpDm# zN|8;n;*?Iv*ZgGyd4%o|kOVDWISM zrXwvHkGppQ8 zg?;lC^WDR6pnC$)3{1KGNdf$D4Hb5Md%2tj)yZd{G-Z7=EN;sW7rCmlH+LrM`i=HQ zC->q8$05VJN6LF0voY%tuQxw_){`oII-1k*A`kPe9TIiacrZAVqL?D%FSPe3Gd9K) z+TKeuFUC54flv1Q{-+CT!lj0g%>|KU}Lj?gpoJM3dDx?Rh$_fFUcD&G5Qo zXl3_)38+@e>dr0Qmn0b98BZ&w^_zYJ%ndLkVE3S<8!y?=CcNnI*a|z8&Bl}vEM2PV zb>BW-`S>qc=7C#`TOp{f#x33gk_DUxPT4rA4bc0c%fhp+x!H<119_IVMH76 z^5JQZHw7Us*?(Mq$*yAK7P7$f2E8>HY1(aYA3d{;NQnLYuFrmtG4e~6n5`|{QtNBUeHNFKLsxQM;q zr|3sTq19Wd6GG0p-JE#b+{TEH)K{^ANoCzYETeNIvrSfj*QqkP>fmI=(hGO(6Igg+ ztw#4eQ?qt{SQ`A_y`t}r(5s-GpecvBA^TzG=+_MO!RY$RBz}&2jm&l_OoJv;hW7~zEevFblW^2 ziF)_j9pkx+<$t;M(AUIy#}xW@&^+c_Aoa3py*K16jpJ8s1x6=uOSMxVOxkW_N-BA8 zos#fLs79J0#hH)bJKrO~r=uY&2^_wx{`H>Knoo+3HV@5%0)JFs^8i)^mhu%#u91pw zyVt-a9nDKeLVwl(gmLFy*>Yz^00^LIf)@Y*xSmFW>%czt=#eAXu)F_|3KqQIb;EDQ z^TWdeo+v<|;=J*Zm`18au|0VQZ8Y+ASn_8%P==R;A~xY;y!)1ts(%JBac&?}gqvnd z^2QPf2Cf(_4uPBnn#K80fSu|{iLtf?FG6H+5^LL2VQiea;h7gq(~SK<@b?_Kz(wKx ze}iU$eYU^wjtV(qBgN^AK0+i-&&`J8#Y2_P$FUs(SW-F6L$ZGh*ZtdvNSE(S4{zn} zgore79j#h%f9Vi8t?10wCYpJ1u@+J={ zk>5MrBYnJU6_oc}XwT!%)uWx@~ zYu=pqctx_~axEIRdT-T7Yp0h*og@&^>6?YYWLy&A!$oa%)mOe2lcz*d?M%En_~Slp z>-yz9(9XE`?|^xYz0%+8`BdN1A`j5Xwg1rD%}TV>x)FN`>DcCt9+CCkwl^U`)Vw~reyG*hYp@| z$=A4yo9T;S{DP}Mxv!h|D50XKZt@rUB}05C9tYEW+`!wyxU6 zq)7r(NG+BdorJr8nyvvO6iZN{cW{1+6s5*aaTp9s4`&fE8!=Wx64~*>e3;|mH%0&D z04|ajM9T3C`y2MEmqybl0LBl8>~e7Pg41fM+`H}~*E)I9B4yfaHVO;V-YPg5cRqvT z=7`?q^3YAn;rDlpWpjJ393@;y(U)Go*@XA6 z=)j#G*`R`}9v`wfFG@)ZKA4a>0-hQ0gmm@x0^MT5(A%^x#>fd`I5E#ptW5q5(e!`W zAOl@BA=~Wvh2r@!ob`{5dQm#*3(+QVDP@tqA@^o(OY|2$kHpmQy%K*PyLm+8(N_}+ zE}To9r1>w>#Ng&OC0b_633QGRrP*ju{7-vnfcm1{RY+pn8eRWIsB z^Zr=v>~ulxa|Va@#6-7&XmC+FIG%+1 z_}sVTy((^K{$S|zvOR8~2tW2Wcc#4jJ!UqNBZ=cy0m&|EKS^*&z%6vl2;W#= z7fL6lFl{EOR}{7H9!U09i%`~42uzcyRo$xzESQoQ$#~*(JN`@f9sWHVlASJ=IfmD` z`+@@knJrYW59Cq)mc_imf*L*r#Ujzjt+t}-EpN**0h_^V-5D>W*1iem$IGK49VZ+_ z35#5C5`bIfnt1TE=thL`4qpHjIn_7@BDlt**0Qd7@1(Bwjre?=*{|668>=&_aR#mb z1gD&YmE!9WNwsfMK-yQ>Aw8`aokumxk zqO}$gG8IKG=nN1wHT0b5`!tgeXxUK9fbi%0rozduckC6BvjMImn3!L6P3bm*VYxuv zBB{gMDBwn~;wFIGPuL^g^$4!$SNjr^-xrof0Yuesa)LywVF38Jw&V)|c@7f_!&b?K9UbH)4&2nf z@4k&og}3{^;4kl9$)|Kvug4{*;H zBY!MG^)Ps5rqyRm67WNrJ85*{s-j`rh>#(L+l?hzR~-RJ5F_PL!%QFD@rk7q`4Jp zqu*oF4#@-XJyVW=tu^(y3|)fmt60SRDF%=9|0K++zH)rg>!#R>ZDX#%+&!}bBSHIP z&oo1eJ$QX#N1&s`Gb}3uk_P8XjPR;)*?F0Yt*(=*jwz~myTbWZ50WA zkQX$%yBwD}81VDzaHjDB`Dy2lznZ7{HLh<5t-*YCc-${#6pHG}!zL;aQkulw9dCkT z7;?;uUgbWH+LdXpo?IuU{z%d3YFIsKO#GVpOfHBXv7J?@T@c1>Gsr^HZZRS(eEs|c-Rxey@Bu@W* zs@jY+nOfU-1tkndFrkeOGImt!p2Dy4sTItQ(=XTdNUf@RKJP0Ymi5&9HQr9sR(21L z;u}6t<|$3E>^y~*DPZ7W&e)L?7b+WQ4dtar)yD1ucv^Y-`~rgLO&mVa;ZRTr3`gGX^j>d%omV ze-{Tyw&4jV7|<#OkhWI$K9Vt#=6mlQGthN41WXL*fwBs%7btq6zHwqmW0g7+cY`ZE ztX^#Any$%#6CfCdzzLZ->##%h%%WqJVGacQkH0WSpp~@5jnK*f!wRr`^j8BFG&bS> z?lX%Ck#|Qa22BAF? zW?w-%5*+b&6(Tmlgf2I`IgKmHOoB6lE<3oLs@#!&CadKj~)F2^*g@nXohN3HMxcpza>i0IBhV zSah&6WYuWJh$9KWhO9B+|2KGG)P%&9z-_I&`-30<+vqpb@nTh+aO{=6zpIA^)h98C zVpu8%{8H7AXV1!FGo{7YJn8IMqAuwzeuaNe>Lx&V|8|dGo2h6f=i_>CVHF`5$5_5y z@euZ$@XY2P+hikO6S0Y_4u5v~FuzP5qvlPkTEttfr(ar}OM_M=TYYz*-(31xZ_2oC zEsR1+AuLl3DBQJ2*{dBa_FT`q5P@seWBbOFCP4&^ffV(*c-t#T6=}wxYJS`ztNX2! z$hG49gNjljI@T*#lU9Fvkvf$dB_!1?<{Or=#o>gbrZqZ@&%{Sc)eSW#8%x^So+2H= zT>w@G+h77*;lm+*P!Lja7`){37;y)`zC9B@6vAmO)c5szx0-|5^)@4ZoAq~pPR>24 zTwZZT;ia4j(7x~YgdG~V`#o(40fH#qkBMdbsmk<5|I;<=i{D&=G3QRDrE!Et8aR=X zDTOlgUQiwZf?A0dc;edwPY0STFp2Qkz=2(S4mjJtWGlZ|IRi)#&J?^}=@^00+%Q8T z1l97!*!w?B6@<^rZp7rpF6d97DS+J%8bb?fFGu#Plt*_L6&B8g%OMeh;#nqHda|OoLi5fSY*I7Rh+=)d zk)!yL^jEEPr)>u%08VDidafUaq%hWW)N910>E{ZXkNq7{(t7aBN57jx!Gm)l3dwDs zC)E4zp*`~5n}YL7wWC;h)3-{jClZa==8RK5-bm7rmCb>8kmj=!-YwfwEee4VS z*Y}f#e_KN|jk8^l@?IdsHFp^V35=*G%w-PGm&oaNicZ%bhn2zVptFMw=3 z*A>GD1KDrTs)Qv&T>`1)|2nh+GEkr{dAfM~(Vfxfy=rO8ysfVU&FyABi~sU|rz*so zEWc;U89##&5jKPJ@yJg%Smn`;IaETd9*WXC3?X3Tjh68WdR>SxxUKQHA688}#K^$e zg`WfHMuf8bPo=ycg+}am6@J|Cmj4b8R=%=(91P8pFtcq+#~?( z-Heyl2brJ{by)ikI}6alRV|YJFWcZtf?e`ppnFFzIhCSxV;oilehzf*=C)AeBTE|}RbA1=ms7EGWO79;?PZ|;B znz~GV|H$hgV@5LWz2E8ACrcbY|?IjnQb~9=|XWohkr&N1H z-C*<~1=6xe)p_0SK3hSIkdFK3O{Mx&+$iYJP06=h^GZMA-ar%s(Ex;lWcZ(8@Im*? zs67t|ZSi8#xW-)RB&pNmkRIxMn+vP!&-GDCdWoFmKLA=^#hx0s>1xt5GKYe(a0{Tu zdxkTIr%>f!!3L1_OAbmfpdf`Eg@u9WyR;5-FVi@b=h0Mq7{>d*-NworBW40HmBR)m z{cB%ln0$IDKnpFh;8FlH;dW?B8~@V>KVbi$ zN$+qShP5+641<+bPyGGgr(Y!gD+_Y1VSqano-xSf0evJ`ZLVY6pXlAfGXKD5iBbbg7!qNp-E_PDE6F(Vp8{1 zR>|jM$8#=2P1N_DhtSi1`wZkk9189#*b9`GRF;*Y4$_brs+0p?QdWbc2$7TmgAw{I z`xY)Y^NY$S2)vfvx0y^z6L-NB2$=oCUuO-b4e15XbVhOVm2;LOY!^N~#2^$@wKx?z z95K~R)SFH|e8*u~oa3PNi)-T5c^%Bc7WAG*K27!>E0skp2rjwwU1!!G>x`ehHb0v< zGjknw*yx{ztOn4_1{AH2VM)8i6oyv&d}eF@-6|wqEPCSJTtbO5yQ~=rUrCQF4hhs5 zJ?4z+%nQ$MuAN}bUImw8xJBq73B}X%?{Xb*M4T4%65V&6M>THBM{y4siU(k0MA;i)HqSAIN0Re1ROu*cZ9>0OLJRfxM19?z5!OlH6n{9W- zhvb%H(U1rh<@-jDUb$5uH5u?O^I8Gi1uNYG@DxUOP5;`%p z*0cq@IN)?!#e<2FFA=D!&=46kKOo%J*<6}ZKzbj=fhrN2O2CJ}@CmKjO_z`V4U*de zOjV#Kps{oVUO|Tya;SnZQ*Py2dk~<1!QgmEe+Q>H7%O48Ob@WJppfk&ZtGR0nw=_` z5_VC6^^3PM+Uga?UT{Vcp7%W=SeMZ3|BN!Twz7H)i)C<0<6Ql6a)X|vo-BV}eMKXD zMQ+YIA$ETE825uUzo1VdpUF>%(6%#Qjoh{>)pX`WG*6Sp`m2e(ZQ-AMB4)KtUCJI1 zSu)7MfP3#{RKLZA-T|@sVewAhiQ}Gp1kuu{bN$k*1N@h^(2+ zfwcPg^mWG z(~NCctdKC49f4sb6gSS!q+>4M>U||Nm@ug4m2YfME`lUyAm>A*mwB$nq!;beWRD%C z6~Q+r^1@N2y=x(2$`p^QK4*yBU>e_-z(~W-7ZCfZ^1QUJ<{)yEPV=dHeo@`J=SWF% z|9zyieHU+`Bm~N(oL!;>OBkBe z0x4u48j?D%-zCS-JFo*5!B4fd$7viA4Q%XrUbRs@_UreEG*$dFFkTC_WK_d>1tsfz zD&sjDNUv(GS;y8P<_Da_1fR2S4{H54m@{ruJ^lF42y)aFrL*!=mWFhSMqtD~Qm zXq)iGZ}@6`UpT~S@#1NP7hAXOJ%XG0*cq!&);~Gy$G}AB-7L$h zICn~ZPq~yWabKNbo;T&>(V4CyKU<@QN~uyMjPad4Gh zN*4@5;Cg`~0Qn|pKSLmoAI(wK!CuQdJ<)T*a98~n2{L#MIdol;`DB)LB^I`iv+^Ae zC+zp)M6{LvT|0X{YV%Xcwt=BPccl zSCtaYJOf6060_5rBez)kbvf=ANyVi&A_A1XAJaBmKKy4P0d8RZkC?98YM2nx%}0fCXN>zPK{H9xcd`^Ms*zT(Y~b-6Mnj@tn)y*Q5nACeeiHNYI z-S@&Lixj!J#me*H{bus@BwQB5qzBN8jpbUZ;`n*&?WDc_oU^O%U5$_qcUd)F`BXNa zVV7=~xlm`Hci&{RblbOuAe%b7zg?{4OdB*I2tKU_d zB_m|HZswjoMNP149JtnwUXd4Pi{DU{boq{K_Qmg;5O3G$6n%JCKmgij#n$uRZ2@N|c(Tf3gB;xzZ;-AnGU`a-f z6Hj{dVh-N^;Au!Obr++eZxaR5AGjOG6)qm0h9219Ua&%h-q_UGBY-e>IAY|0zEI&o z5BueABWp#2wt2X1ft?IS%rDs^rW!I}hXc1Gi< z7DZ&w`tm;K*?~0{hWy1zewCB8rDX$X9VE0ZzhX=}%(oCxIkbIIHj+0zw_=ZO;&6@T z@G@r!5V&nlo}pv@d?6yzJcVN}ZlJAw#}4wMpH}Q7X|l)jM`jefu??mAAD+GfD(ZFX z8%05pQV?lWR0I*EWhey&5hSERx*MdWL{y{(krs!P?(UM3?v5eEp*tPo+jH-GzqMRv zo#hdkGyLay_Wq@_0!`CF)|_-d-Ze|Bk`twD1LNv_)W|ru?D1r&lyvf)G0q6Z@l!Ki zgx#fVT6{-TrWGw6okL56I{RNr&zv>6#vAA!toq9c$(vKHZ*=h{YbKd_FF?&z#p{~^ zR|fqte5sjNTxq)Z82Q41qB9+wEgBNE2uACCwr(DweU@?sNG`9*Gl8GtH>cLxFR>G^*ZfoZ_w|{+F{_QEyRG{C) z=|qxWzmRr{@$A7gV2o!_&xw#4=xgO&n)B-pN!uANdv)&2dhFQpX00)mu6o)?8P&sRMuYu`3AG{Rj+u$Ok zN5W?so_1KKMkgj9r|x4T4Ke$GprI3;$#Ji9%lk;!9s!xaISZmX5{E4GL4wj|)NlL+ zZZqKhaQb6-Tv2GpPwCrMYzB z&2S7O<_Y%pL{@a@nt~8D>J^-T5mTwjU%R;pDz%O>oF7=~Ua%o~qq^GQ$)A1x+lWK4 zFkO)gFkGKaTo|SPr%zYvX;UAhvwE66wW-r`=`@E}_Bx&A6Zt#WkX(HY;)ec`gkjS1 zILeVmhrq%IZQi8*zKM z%H`K7;fC_5Ip_>OT^Yyp{wC)~Y`#R*45rw+cSqMhnj5kDo8m1Bn?aMd3NuY!a#61& zNtW*uF{N`B-k)=rP!7Xh#+1lm9+i|I@k^Qok{q0dMP8|fBArJDDCUxfmDO+ zmJ6WD1-CG;FSSQqwh*N>GZ25u%jk7DtM!j7iAi+s-LP2};F4-=2HzOdy1Qz+MWyAGGD2fHNr1aXuz zfFYochQSOHcA^rKF*CgxEtmQNy^o^GH|5VVFxazGu|q=FHK<+66Fd4zN7h~lv=*2# zaBf)`sBKQog*O}#ax}N|5+z`Fnf>+YN;HJ`I1Mf(BwO|W8=}7w(bbth>ool2MY5lo zpq2r>NytUtr)rHqdJ+t>@A4^gm9}^WW>jzb89e1=E;YHXSZi^ah(x&0Ils#z_tfk{ z6~WA+2)NNxofa1>cfT3`^FrQ=Pec#+OQxkGo<2Ts%-#0u>D{J9ME-f$q#6)2_##!3 z^+A-siX-u%M+AndXKb%o)J}f!4aG#W0hgLhi@{}~D4iAmpC`lFj$Wpimm|SZjiK`i zD?_D#S<+A+I&n0=$ zre(LnGN%xjRYPDcGRDl!rm{1oz5FkzzEcDgez%Aj(+M~mHq^F9B~!UJ1sAe>UO5F`QHVE6QF^9Y&*ew?uRsl8pJLmv_V zSPu&#aGT)00qzn`1oFV;`Z|o4q~*2HVz28EsFQUA)GwT)`4KOSmYRd57Hh zS)i0j>1W83?*Fe$l=-!vzoZwJb)QVdZ4Eoy;5@3I1CQkGWS-`gObVfphJ!|Pns3E} zvF{$|MRDhn(i3U(&1Kr@7qeYdf$dhY`=6DQv%>8D%alQTg;bmCyx(YVWE-S+s$eCI z2iW}CepJ^-sSpggrpl2b!=i4llyDT+uo;njHNS0^XziMr+o#+m(8Md^^p8tAMgp^{i&Es{NrU;f~c)S5~ zi-q(^dagV&WG!BjdKv2|zxcgirRf7{ca%zR4Kby2&eb0dI%K4zZ$7>N$=##EWp%QN z2OhPO89lJ>L*6* zJ^(VQe!K?7{n!03&2I2KKbV=lycpreVYp){BhRH0w-Syq9kSqqScT)W)f#ggu$253Mt76N z-XJ~-D%L)t;D@XR_lgz%G%37kG6_wRE~;=Y8yp&%Qu*|&*7$ZP_WaGzC8qR^xeg^x zpYeCMK2iAKeLb4?Jcx5gi=Z_)ah@DFY%vK&)|LpDazbEDf{@6$-b4vVFXOPtf#Vr4 z69{RYq?_wC=cR=w8+1g^3)CHv4?NW}te~L^!s9Q4qLrGOx*lRIvVmpuS zxo!B%s{MH%h*BG1I(#2?mDd@H(r3XI-ksQ3%k@j4L&@%xbp(9!Ab7Les5wXi-4X<+ zb+fAEsDjHzdytjnCcQwg6^t>@BQ`E5L=u7m`j!FBQdx#;*L{82c{$ zyrRjp$T5I6@e7Z?wHdoXjz?s8U*%Rkl38*Kb^%Y_)!Am%Q*&*X?O(Q{CqWI)A<6na zEtgHA`X1c~Y4tp^iZ`@p9myi-UKIYf7qcRhry`uS;&-4J(i=o=-Iy1iLeg2#VpVE7 z65H*wJ=IPuD$h_Csdgue;%Jsp#y!Ug_SeKRi9aET;ys~lEnmA`cSys#XHjvl>t3&0 z*|~S$E80CHH*%4v75R~nsSPWI==B=f->KL_q_4MwwZ%=s)K&mK$H~h~_^T znb%$2-9Tkh!Nm*L;%2oqhES%IE9}SEA>=bPff(@%PM5ZAns>uKeg(c3TIoq+N@-F^eH`ifF=ofp(-YU11F!}zqZ?Q0bmd3VWTrCP`f)sDV&IP8 zq(~Zsu$hzO;nZ`A_gJ)tB5JP5G|H0t7jyF%?w)p))XVI^bly~bYK0n-7krlT} zbQe1?of9{4qu_k4lP=QR!*A^CbjUu$Vtw|)f`XZ20PkYSN`~R0i8(r>NFM8W!{6yF z_0NLDrV zF3s^)4c$_Tro3O|T^;u!pvMG#--Cv)Ggwh3)sDUD`3(!*7cf#-U%f*6YSEOpmn7Oc zqj#idsJu6WVP7$VIIDbO$M#tGY}miqG(+F7n}Uchi zu$N-saz+;0(z2$ns9k)JKTq9n_GF<><@JzVLSN*&JR%J*sf*u^?`}Xeu?tcSO?MJ> z{xKzyU_$DAzo~iMaZB=XA73(2GF$(<8eJ?x)blf~m9o#sUiyjYg)zY3KY#u_*${cb zrE+-Jdm+)&8Q3UD!hp-}v!5SGnDa|YKH&-t0M!IZ4qD6<)B0oZk*qNX`K8B=0zCTP z+KeUyZCze!Yiom38P?8P0)>5&_hDHc2TWdv`u|xrj~1f9#l?v`Mt~}Z48L3*{_At0 zp;vL`0#YH2&9DRnl3p0^cwG}WXvUjgUA@X31Y&7ACbSD83&1tt2F~MAGcvY7Hk{Cp zFw8akxciOjk+>-TQ}pSY2v(wbaHq6GkekO0oP~heY-ucnN)FqjNeFyFR837!-_+at zRq00$2q=@K{u}j}Hn6z9?o6ZcNqm-IwZ0}(HA}G705Ctp0ldq4EQP&@iJ`*=t4Hkw zk+E9Z+SU_TbM*oORld*LJSSUMN@w0B$?o!yX0ab&<>GtlavEEZv2S&Z(+m=|xZ*~y zDYEe>%Tf4hND+u#`6T|>Zsz?1%U^m|C1to{eYj=OPWv&{Nykdbb%;gv_2*de&d&RW zxyf?wLGfD}@y#M%Oa~N0W?c913Fy~JZPC%BIKblx#w({}8t zD1qZS#@5XL&?1@H8OZpp<~dR#`*ZI3{sh8mjF46{=D160-7R_*{R!U>fc54 zEk^5B15<2`Q|~u2-gVYGa01eW#VcJh^VU6dgZmZWE2v3t`dFAbqs^jyCIHX}uQ*Vn#;xPEDn&)jNNc2WNXjS-2Av@C3I&90c%=2a^sV*f>)Rq=MltGw6YU-#nW- z7LL2-N4n&XiIZ?OIIk<@NgMj&XU?B0WXQ%6tOyV*2b(JN{VlcUT)l$peVX6m_v_x= ze1uDz!==gruh1=xefJvXRrnA9UZvgk7xKqoYW%?kXyK+X8MHj=Ym;oJPWm?+;7&=H zm^`3w6ZH9;!aYm0VAusEBlxjZ&M&U4;Nz)X)(1)eNG~|Mok!E&a8!M>Y+_}TKe3B! zCmiP)BFI2q>DhU+>EEouhOPYYloz3=ga=K!;?mUr>LWMD2^su*LD zzxK@Qv;CD975-cXA7UTim2quNlIh@JfIowjcr)5C=Hkupc<-Cyy{Bjmsrnvwfi&|` z`nfT-0HU{Lpg%a@^+lY>SHh1JMp-?5{RY+%=b{ol6#==agv&3ijxMdJD{R(jIVK|g z=jV2uIC6@9^}Mh_5hFNibb{}W-@BL-d|`ga{QmsTS-z@oS;;4F*OMZEN*fxU{@25* z<`@1eB(z2ITQlc2@_itUU}O}6qe||O0h@ibd-$etFq4JV%&`SJJmjTUH(4-3xiLJ_ zW~Su(LXzj4@Fr>o3r;QVpFwQKgx4TwYzsAK4C7+YdLM7 zU1m#C5o$E93Iu%|Pn%#_AILNVxdmLVaF@~xyV|KSKYv7hA zcw9r=<{nD>L}g5+v7FY3mFIdHYwc7{Pb9CP{;q6 z>m5k*0^u^O(6A9f z;%jjFkdvOz?7-Xj_xo8<#(JpSO)|Y*#mExJ!ExI3xcvDlBIj3x7tgTN6IYh5w>^L3Fgp?(R$f*d{^@lB~v z6+Bz+1a&ME5kbyvvSOysR>8#W?qY;jG4jk(#oATt;Zg{1Hph%ftwwPcmaOa3nN5mE zmf-GPxJSJJz`l(_9A71w8E1%O?W4Eho&_&sw?{wR?(qJWtGn{PkM9pg*|3Ut`Mgkz zhROI?#bU9*;@Kaum0O@9OU%n7iz~CO|($BuY25n^W!yNp7g{r&yv+KVPH1H=RwiOi3kSE+HK z_qZNF7y|t;Zg31WLm-{~@u591p-sdnFlz&DtIQU`FQElFv!p0suYhlGbaK)+ zGHQwlG&Bi~Z26g_lcNgqS}^>+$q254G>YJ!6Th>WiTDif{T{nD7O(SDK5JjL;mO3w za={L|{zQlE>7*{-uaK9t9Uc8&<&D)yeiBQiIO%UR%y zx!MtQw`=;MbI|Wj4&3g0pYqqq0XhWa1h*hN4BCyK&o3u7vtf#Loo&~iRe6@(IMPR0 z>XnUTtg6aN^#AUPbra1Gd-&5+F*|!feeiKJVv)A^NsN5*#gT_H_m_4kEf-JN3A1)2 z=A-A%HTzQGkH3&rncQ<&5On)xYEHwiGch!@@KVXbT&zRNx?@{~%ZHZw_}?t%w}RJ} zch}dECl5+HvSpk55F8y3NaPfCCem%RrApC`cuS{A4tj1WhW!rrAc=Jw+ZjTMzcp4S z@y~00->P|d`7j?z6u81#^~K4Fo6#Ilw#c0f7HUq9%gVLh2R{6L27o)H2%4o z+Ko83zcC|ssqc_qS`~7f*0X@8vhUwJ8~dB&W)DK;1)mvu!puXRMxi)O9z~uEO@fc5 zUS|!71HpJZw0?Mae+=1quWu#@JOqv7m@x?LThK4jyol!)!z%;#*qk>9)xn?OIPH{o zZm=bq*5J}AEi8y&M1tF^`*I79n`-6ZMn+R##{AxdSKr1*zun4 z6>aT9^7ndbH-wAl6-&kx_{}71+L$xO!%?#^cL3k z|LDgD?;j{TUnA?IN-1TIXbzCrxG=FH3*bEf+GTU#ct`X3u9GNjBJIZk%5CX+hz+kVWR)3L{+FY=hTmq6q$ zfA8Kn>8*+JadG%s_?diuU7B|_jGiff{?Y4&4uq6zO|Z_-N3Z?fPfxIZYotBddoL1f zlV3m0CO=u8b55J#v2%61JTm^|W<1ORn^h&WaXN2y*Ur3`+%Eljd${(N#*E(wZXJ}| z{LG=N)>*mppk2~0nFukJ-z6LESCBoDB5Y3-p0@TJ5(lr&gqTz;elJ?!w{rZE`)a@8 zbhvbk6s=*oI}^>zePdK^V1ed!9H!z6ji)F!nYGk;?b~s2m=W~Bg|7TL@MeN6n|kc@ zfhaLC@gyHhAjUeX%5}A%6%xJ3%5gXKrMa!c*vPgLKv=kK4|SGx;J#j8}1N<+0OH#bGMG7hjDN!zs!LNNvn&v zs%jY8t1m)X@4CRIdjwWsM>bcW>(U(0eV6;b8D;~s!=Qk7wn^T%HZ*M1Zsj9beN6Jb z%S7u)z_OZf9A7j&+W}oDM`u9O%!8uG^EyYZTI)az1SL*l(6%FNItY$?o6Z35?CQa@ zhms4X-~A1P=e>~kPhwk$3{+t1(s#@9$lo9r8|aVlK(q4~%qy+tt!?V)^zb#F)aPo6 zFiWEy=f(!lHcbBv7!rH2L!a8D(JcB>!w<7vPoa82;Yt`7aink;|Ez`$4wQTOfOS=&fpS2 zE+Czpnuf-HL60YfSoG|u2Pp4(oE#sZ-`D`RgQe~l9k$MJO}V;)PwbcAv)vPA5n+g} z?!ET&<@3j#FA`Ub)kq>18SCpjnLxCq+=tUso9@zK%s%#axDzEN|d zKz)_e)YcZn7&u1(e%0%YVwBRenDh0htmfCwj_UA=lkW0F z`jo-zSX^6kI>+gFy1AMNjdNbiP%mgI@GE*F7MGs{5IKIkJ9-icC@E!t5k{a^Iqm@ zX+SlbwyK~~D>B}o4STsaLTa^2Qq`GTR6+XgrL+%I(lJ{~^sChGQUA6gZC9fZ(Z#xs z_m_%}lcvHsbSpkwIXQ7fL|I}zy!6j`yKU4QMwktz@Zg&%y%{Y3*`sWD&doByito}_ zTZA7kUTAA(x%tP!ZD|yVs(qn&U6{ki5w^M#Z>mxC6fK#3^6d26>3i6tbtkqE17_19 z|D^e0Y(&|9O}?k{eB^m|&yd3!zF~967AoT+JrX&pmO@c&8w|Y%O5QuYyD%9+ zR-UPcEq^S0Tw5_>XKuI{z^zs$moZ`N?z{w4W{%)3N%4|?)9kueT6=74rJQxi(dpLc z(5FKs`Pn6dt8o6fE~P|)P?U=_?*5Q zfanR>36__Gd0xtryX{5}Ul7bKJ*s|A4>N?etl zYN~<{8Ya%hTE&pQgk(@}H0OKe%HpegTu%G!@cKZ11emS;f19Aya=*D}m~g)?wf7#` zYj`USHBdOOA7Cm31Ozzn5C*vrpe%C4&&g}o5aHc_gX#ISZsVa&yk_NMY1u&|rWGnKi-%tFbJgoe8^a;M?lnFPDDZ9Rqa<8DO6K(!3K1rt6%ay5{SzjFJy&g*% zqjaPgOF_aRyF6H{QY>gC zwDs51HoYa|S48-upJP5)TYRpWyNzdUto4}C!)2FYcR*z{u4{ZoC+V}N5GU`8jK0(` z2TRUE2Yvf=YtypQHX*0(qp7@==IyGmT7$EZqx`3)|77djNG_ZQuoM!AHmlcUubUv8 zm&qlaw5&j(c?_!Si4^@*Q*3z zh8#)G&8L%3Xvy&UQ?J(lfNSG_EXS;MyM~9jC-vhWP{=^ zHU6Nd-T*mtyEQs+`Pa;EJq9fs&QK1uHGgwwu~X@gj{)_w@KQKtq)~WHl*DpFY^*?Q zpqzl-S}1h+a_e^JB^=ybaFIB{ASNHqso`q{6kPRyLgS!0s4@ZQ1D4HAz9Pry8sg#& zx8a5<*wI|2vq|d(31cqj@spG^+MivyaNauF+{1$&4r`U;{K5$XLN7_Hlp(^=(slwT z4|5@lyrdmRm>6c|g<9Eszjv(_;WSYw#x}j%*6}G`f|$y)FqWoMO*XkBm#PNF$p1lR zl#ea=eb_R275X0aU#{Os^t+sDgNuoMmBfH#Y0H2yMCK; z(Skicz=utVU$dPJLsY+q==N1H$~H)RiQ-dN$FDxMjo`ytAwz$C95HjuTBuNo4j&;R z5Heo++D!*Y6cYmKZLd*!^u6Y?G8*C5U1YpdYPByA2Rc*AM2Q~p{1Q2u2lw#fMBmb zJjRIOK!H{!Z+d)ud>4|<)d4Nvbt6#$^oh-&B_FH|j(fWaSL_1%7Z>m2&H@0maK^pz zw+lq;b!T3KhTrUs_W`r#r2Mgvs4dXR!id}dDm&s zj@el!W)$nMK`p$bj0L#L)JR{%Rr2rKbu+8KI(1R@t?gN{e7q}F7}LYS6%Uq*ZUKF`SoOv0l z%^_HFldmc#qaLc>3CTWI2$IUqKG3g`>ars;~OHn zg7M^E!-*7r+hE0Cznxu%K9{E>MSP{_gyeKR#rWRe$6564+i#%gbWA5kN>a)dF-rC| z$mY`L^jVhUA$4Bw$Tn`ZU}*JN`McUTSE6z?_*SnIT`bGH8zv1RR?xKmN67(-QBKGL zz!{Fj_|+F|uW<#+qEkTh%5t_uJeWx~>1V_8)tB18X-A`+EL~9)wxhZ_^pwQOLukok z45@N>PFdHRuAMdXMvzma^;0Q_o)*$$mzk*{-s>+;Mt=ka;K-61~!WiJA~=`iM? z&f%h(A*1at5syQ3&HxPdAo0QRIAGcZeNq$Mb{t%<05#y!Ae@}`2#(se-Pr30icNDe zSD~^2zOP z&go>8aA4eZBe&oF2jS3RrQn21mvu$+5fSRZIagttRU3M z`D`H8cA#8ZfO+t;*JbA;0j0|-SC4F8vsRbq_f~Kze&bsXou9G2@ume%&t2M z-PjiyCy_O)T4nO7mb^0%lk)l2gqX_Lh}H`pvV2U8jLz?!;G)nyp1T2kEL(rVO@O{|*)1-Rmp!VZJ2b3g0c5j) zK>etO3ph6iB-`){u2MDUQic1t=KxnN1f$TzdG#;uyVc~)(s3BUi+O2jgn-D})Rvz? zrjH)HemE=7Eak~g4Q_bl{2X}f1+(ayNN5W&EysDEC$SAbus5!k=H_z1Vd>&p^Kgl1 zGCh4s=Qn@Goo&s?)#T0u3Yj)qVrh#vgC{y9-BtQ8ns3tHY&tutae8}|;;8Lj!ik*& zgIHdlyQGwqwz-ZawWLX~H( zf%aM~T9cJ35RhXIw%E@o+-tafRZSO-VBqB*3Sr_cb^N7M`bsS5iCb><{C7qAWaz#S z7agNLL%pyMMOXHVrk@M;-qG$C&E%3Axey$OpbD%znU>C?TXaE`jf+iuJ{@-HT_Pddc0q=k3egc3teaOp36#yqphNUyNxE&m>%9H z1q_O#y>4jSSsCDwsEX8mVv+C@)t)CwZ~l6r2L^nhHM{T*FTR_Z*`)$?VqgP-s{?g` z9St*FUvggg$EGmmXmr7v#E~pD0h{tXt|>%bY@h4+1R4}K57p`dFrtS~!F*XqNBv~u z*M|qD008)aY^)Q^m|&1Cx~UNv(*Q;cVu*79t{bPF!8LMhHj)_{7|fBdx>v)WhglcC z#O2Fr=^*h2QcG~219=WwmrOJ|rVy~NDT`vOc5JZx% zGydT533M9iGHrhn*Alvsdu1+uW$k&H)ngA)yX0B%hCNef!8E_0$g8w3)CmV^UmsK6 zTKL5Dcw|w?+OM1SI>N$n*nL!Bf+P5#GQ%=H`&;UX>P4;VG+M~+eHj5aA`Yk9ldMw* zZSr$}#Lh6dKA6tVpjbkuKSzQW!n5^1c%~?R{Lp1Ge&5@%v+^&ck@_c;QGAa0KuGp$ zn-O2#y6jo0;B(7g|F~SRx=@w*Wu@qHy~TpoA%&we*aJ`+Lhl8X?c!!vjNwnH~afR-gJI&a% zEIfw-M#9_L$x2XeMGl9{1{ z6BUg!y;6xXPLOM(FP^RC8BlI3$6Fqpsk0A%c3~&`{lI;Z9cvLh7a*gOxc*W9H;+3h zsc~xLqrqzrhBF#hGzvS~9qLMRgm=R#-ozr}X|LxPcPUT*+iFELl%T1^u-aLM23Qn5 zVxO_YL0jp2sMQE1Hm939u=(UsnfAn;9D{_nz69zEQ5d&w^<;-M$p=`Z%Xg&?H9pd% zLr1v?vi+JGn(fA~`&0SH`&wz=rPmKgHI6eS`Eykw-x@gojFZvBD2om3=kT-|yv&kv zCOR$jG>t!+wxBGVZWVQn!)$VT^ZFK1tgDFbe9y^Q(t!km!i@H`yzJ~5va?Mx z0P;3*7m}S_{($nvfL8df)wlI^n}aw%@mpnov$wF$PIM7fO%&|s281*lvi60cE(9VHAfXv zy*>f`CVOwbThl22JOhH39pv-9Xmkjan#?5nG5$K-%Kj3 zgOHdf*Z?X#7@l#9Ap9?IZ||<^8BF@6rd?fK{`D^91Cy+*9^l|m0MK>4sDG&*7`<%_ zL@eP##lY(ZllYtWcTorrWb?Tv?j~6grnKchebjPPv(}Dp($!~|%lMLiF+H@3EWq%w zn`Wthtt7GMz|W(+aWpFw7@Omv@2xDSu7%u|Dj?q&x>n~no_VZL^=13xwj|bQp{ku6 zm8X^Xf27^LD(U{k48oo@zdiU>NK%$3L ziGtc)Yji*wP(L@9l!Zmf-V1%1@`#uBBRnffj2fcv189?bK;De|5CC!wk0G4!`;{;U z5tEVvoK6jQ6@16s78j7vg2Eo60pJKKfc1=c+at~2-SO-$|BUe4JZR!=0W2K1_2GEt zIE+4U!+fY)o&L!7NDu1vedm-Mlx*lI{SZL{if`EB$1&m>lf zlS;n$*S*$wS{t_>49_0$_bYXn+!q_mJ()m|9RK-&Y%?*?Vy6ND8{ErKv)pOf^t$t(#@Tr;i+J@E9imR|f|ugxIOxu}9E(H% z!hhEdWmnyOWn-X}a{lXqm*iV(wIjWe>l2C$zv5QRNlt!9c;+_0Eaj|pG5c76a2zDJ zI7*Vdi!z_GF?zVhgzrs(x7!be#f?7E@+!nBAn&zewwj1{Y z&9W3^*G)sV8h`%NLQz&Tjy5O^a`D>9W}WN1CEm&)qc{v}z_qqPr7xF z`|m9Mwj0~R#rA7dM7d@<=3?ZyUy1D$EtrYfrXkvDl}zLJmpBwz$XmH3f_jT3S0~(% zL<)K=FMSiL6z(SsSqS#3=Z)YFjfR>1b4Alm^B*xq=2?ZAI;J0VZTOkUKIJQ9IId&% zL^Ea+$E*M#O;Tqs9rFBJbR5pC!i#u*DgFGj)A1M77pYWz3W;vEW`!nMJSqN6l=Z^g z8M)t_OJ?n7be&IyTY2{6Ut5@KPsD@u+PrvSe_iQ&VCD3#oBwgV*GR@(U5hkqMd~{_ z4L$FgeB>he^tP=dDeuBWNC@R9k+{?Jr3*uNKha~qt?SzXxXxSY&B2-6#of?>bI+|GJlQY%bjVI;?yu zM@dYeE!hTj)KpYdc1PRBZ))CMha&)YHX)hBkXu_@0)O&{CK3Ts0$nNhAxlHAw1Vej+4eY{E74W^hP~k`fc^LEJOs zL)68|&c#-3uE&aPQC!mHJojwww0V5`-My;^_SX(Xyz(@7E8|&ndry=X(wgy>$$PgZ zPSiIpUnots&@hc7Vrgxa2&Gy2eO7@iruXBkWn+BZ*-)z)^IWH|Ai05CbLUN~_;i1| zp0QBgf-B!mN#ib^pWChSwQK|!p70yc+y`>RHM}>G)4fHv$4VvRzX^D?;CD!f5&v3= zrfIUg&XRHU7a3Z;)3TsM6fMuMTlTua(Rq@ zKG@v|7BAO_*Zdy`;kbY;@8ghjcohBXQFXg_=@E{XV57d|*T|7?13yWi)NrZbWQHyL z2g(MB$Yo_fIcF?p}`}DBW&-5;iSWxoB169klV$<6ZiIHwS#m1r~M*cz2Dg|`WK7$ zN*RtWhDf)UL!l7=rX7I`Bm)Oo4Cb9z%KAXK6j(;!LIkHc#2KnP=rn{er-V$BAfwkgER#Dq( zyoWcQADHXiOz%9Uk^NT4z2*Ooq^r8BRktksDYJf0w-u#(fI}67IuP!$hL|-5pa33b zj*uB;e)~-lyJo>4uO~G&V|svgVbZB|-THj$d9ta0ob~LyR9;l(Ot8e3cQ9&% z1ikOD6B7{yq?Q)@0$%u_;x{dqy%&btHn?MCwT7d0o8oAvoU9+@3EQ#^yl^vNrXGCq z$MlgN6XJPCsPdsXowH{c#_MF!NO%CFQJ-M>WnRHlS4}PI!A4{HvxT&87cav#zf#Oe zRES`$M%}($!i3sq>X5)P+IM;p^gg-SYvQ<%uSS(_#-wpR!2R#<-o)`u7(NKmGE-d*9iA0tfFX9d(z&NwAI-axRtThmo^4#h5)nxrQ_;-~5 zE;mefz5tjBr=Y^6XcgbfuaSbO??A)FMc_26?%-fkDE_pV^XxW@+)SK0G0cWTMPR&; z0?86gRq!RyoW9b1ni%RMsa_?(^#Q#;rK)q-<|K9`9+T*I_d&}o``VZ#dT2Y>4<#^i zx5be=!Y0&1D^ABc{DC_o%tq&C#2f!;Ju95a-T?D6Tli_Qyc6MRHdzavuQ&4 z3?eRp1Ux#e2fc9@FRmI%YfNiNA)S7!SHHyPka@YkyIbBb<1AvPMTNCs`u$+&#>ro; zBLfmeuNE8xF+HtgYWL?5q5pJ&X9Ve)s?AdRCzwGk&2-WBZrzDm@DJg@XLY8kX`Zc4 z)2j!(I=N74<7o_AIuHqP?xX(=mw`Ec(}&Ch4=}{a6o+T*-Umy;$yy}O@|#K;6ZCRx zAU>(vZ1^NDB|*I~s4xe!qI+O{rk!%_om`ybO2&}It!w_}K}vC+vVz?^j$f1xMd4zC z`3w{v@asl?2XO*!z`QYZlt)eQUdTJJG!Zn;xS{x9+MP40Z}H*IrfSBRRT7B6t(@lc z*2M#d$Xf1$Q$ck zhiShP2HITQ*bYPr08}Lx7p_@iFW!29G_V`&OO~={^X z?%fhG4f+PtLt}=eY5T0*;Xa)M^LVc&X|j6!nX0Gv7wahIB)j`rC@bNF>@wN;thql< zhVXq)Co-g2HUTmb${B~ln#jHU-I6}V;}bh-zuX5utpX(zUflTrKnT2pBS@#Oqp!l~ z3fS!VuZ1`9s${Kx8!WFsQ+crzovn8#&o$oW*Er+Gg3Ivl zA2YdQC*VW6b;5Lvhqt+eK4S2=8Q&Tq#q@mU9f9;C>L!2{aV{j7U}L$Gtt~%O##^^q zGFUiUYb>CQNce^?86D{#VFZ}QOBbBdN=Mb)QC_WXck_l=+f1+C;dz@11=0-JR#+p< zIA_2!%+&s?x{^L}}fkZIAYU5|c#q zo;I3~?gME;U!UTgFlkv?S)2+IhMX4NlObK)dL@OVZ-CnmM67EIuS)-?1(Fx>yBx>c0(EOK?D(~WrPU*_69WA z{D=}FZ4J$FU^wt$piqxG;f2a+U}Px~k&el?o4 zhafcmfo};>_ui*RJ@YJL$NH^RlT63ws2JTYq(IeOQR&}qLIddvfTHO|J*eSfhlAGj z^ax`Q(;~~x;N|CD0}A4AE+$yBzw!0rZfA2Jj{eOq&*t`~qxv(oKaC`BEyS9w0nrka zdYn5pDQZ;)WM5rPh5x}92|~PXTkF{?c%n1Ol-M@1leoGzfk=7%n;|Ax3<44;qXd)SC3>#g$_v-xrywu`W|s%>LJq*26uaTU5(nP9t+U#bwL|o^%Vm^dy>MBLA2! z7L^YmR*r|ObD2e>NS#q|N-hSCS8a7{*mfy{(gbI9fT0->05b1G3HWLLCvA7LfzbQT z%a-*4)YXG-VBlZQyzMeyxDlBfAeju45{F${pBbL+5mBZ0zckN@kdw)tb4hf)l8v(Q zIEsWZ__H(Z2;a`wj943TfUdwUhzhRd5KZT(PH0B0Zk2I%%E;CO@D z0Ng`6550&G5?*%;F%4ueEU!>H=CG*HlaP}F{h9w|;Q&4ZtD`jr12=1Vp?zm@qDX>j zmi0=>&~luo+sL0gI&RpBsoGz!8$eK%`-hgtvDo5e){w;mQ{vSNy&y-`)6>KABV~Xr z#0!9oyoVMkP`N_RC2)l!5I=FMmth*HJ?NH9nvC&(n>4;x1TlR;Ai_G^T-9kAHwhr&7N4wdAD* z;wXB;3RPcgGuT&n_j^F>i#y}($ioQ!0W*!dFC}sPhN8n)uMUtiS#S()(LBW?n)ayGphXCu+VnKmO{T37d$ zX5;mXZt)Pgc-dkX({5Uz_e8U*+2nb*8+4Mb54$qr&u4m|*J_G)8eP86G;exLYUK&o#lw2;&d~X5IFD1u?^XuYLTKK6%5+^D^4tXU*R% zzjEgRmH;+$UfyVh3Q&T=#0?7q7_C|xd(PFe=V_)kAGhe2+l<#2wQ~Ldw7vCG4o$Acvv!+9C(d z=&%U9gAoyyNj3P0h*% zyL#-&BXVqN^y`jnXKp$5u^e@zw-&Q#o|16V=PQA}dxFDyhOH(WMdb>0X-X|2X94=w zOyIx(DVG-hq{Ncdzz*_Ii$Nm5@Q8ioXL0qM6N>nCW#0YMeoUzDzf%|PXGb~Ep{FfC zWvEG$wNYcDb6&_t!SUNw3M{I|e5;_j0)h6Z-R?xH9K^^SOkm8bR85N>qnDq=VM-!y z9JqgGIy<5_Ap#8@AeEyuGMw6#e+u8CPxs3V!6pTQx>o^C6@&mCU>2b^DB{FmpEM&Y z>&mqJ>7R!pAw8F2DZF#7+rDZ4zIO>dYd-kRQ*aqIb_?y-tGC-9;OJw~c*qs8FaPAO z3m^ypS)>ezKQC_`wn(l>gJ;zd4wZ-i4Etq( z3R&28BGhGdlq<^E5rlS_nK_=-qxTkm339_0Yd_YWO`zgNlE-?jB#s&}41NJ*%XQ^ZoP8_CJ8LU2)-DUUQC(fa%1S%YSSRb_JsHk( zcpSvUGh!jnen?1@Y*k*pi1V|>O{PmElH=T{;eY{J7DZ;fW}9VtovFu>NYIo`nb*(wcE9ANeV|12H= zNz?asY5YBx2U+1zDMh&@cx*b5rt1}w-c`AM(qb^7V5}hXJKeC;_W#lJ-SJfZ@Bc4@$|fOu?~xhBu{Xy^hwObg#_zh{pYQMS=)d=H za_;-}x~}K!a;_PTF&^`A`mR)PsDdl)tIk<`liV89i5PwZAD(0?tJiu~qGFn$?!r7O z%AJ34YT@z{_9Zp$$A;owRj{oi&gu-5SPm%iU*<=_yAb*Ch z{y-4O10dekhs`3dMk`G_2=9qI=S8_qH`-Y)>X2d>9#)ml8#TY|Gw{{8R^hYobGp(V zA}sAFuF)#T%zOdSFXT5PRle}lfWZz~M*j=KFDQhwb3Fx>rSiTMD&)I6^V z_(2JBLG(9rpe<774^j< zYnaq~?>`RcG|g`dUT%#e*IhDKZ^SOUm)d0;yQZofbk`1Tmfh5YTf6+2jKp6w&5B+6 z*;th?l<%-p2Z5!!GS5jB_+!6F1b_vYt=3=0;S%%-Dii-V#8IG{7S6Fro1Pwj#Nn*W zw)YX8>-~f=PeNuQ(le|s62hPn#{*JxFl6LOiPQrd`RtkF#=-SMdJV@<;~F@mA84jbFyD5rQ$E${Bs|9IEVCS!9+625pnx=bLbzT!mg>Q zE08({coGAdCcRQ++J^Dml_6U&vdqN}R6fm~ey3_6Q$sdPWzRrQ{{z-qz+xgH8UpY= zF>%BYK=RX%$uoJz)+et%np?V_MveaW`ggCL>{heF+?^jYRdN5HfV_t0&pe@X59gX0 zHS?X}we&AcT3!g-EeV-fF=CFgvgdUH#8U^OsG=dv%ITmc`y8L;-pi>WQp#lAig%j= zL~6#4_Bc1azR73k1UzO>+$guh#KaZta;PrL+cKT<31J%>#Oa*Wq7{?Ip!Sxlibx)e z8GwEPjK2J0V!^P*xk+J$=vi3Y%!eu7H0A|*EuL5t($FzYx6A7LM)PbZH1A|~$*6db z`1020x!5Gr04#x1d1o))SISE-sr~1JZ@D(%KHlZePV}$qu)d9G-)N|#uJ)%Rd=~ls z><@4LuR2A51SEjm4Jw`!!^?qyW>n0Q z_?X8puxifaBj_--v=6)TTn4bp+D~L;#Xqlm#{J|eE9)};v&i2ysi#@_Fv~-h?)ti; zLFJ2+fT1CQGGI7G)GzQ@)#S}Wnh1Wytv)o?=;i6vgfESKN&6R#2m{6~3#wiuNqc=V zE~_qC8jYZ=096%I$P9k%5psEoe|zE@E6}$A*-Ah}!ZB6=rwN2L!6~=B?czS^+HVBM z5^T|k0xIFT#nB0pF-wb17}209%Y80d8wrXaAptS;C?mRxWmL_4{MJR8N8&kJ*%dFh zkssCr+91S5nCQ9kW4bA5?3%P(%DbEQ8`srN&rK?i|Jbkq037^HNKz2wUVvrV=?Gp# z?Uw-|tiR%WOv=IflX}Xg6a}9Tv>$O{Lsni)ag;`nE2);m%7hhP&k4KNqTbRg-evCF zqk&ZHje1}k;q(99&RM9w7q1YV&c$NapO$3Wr`o#Le!bqcWQUOZA&J;1;aTpWYoI*j zO;G)KSxa>ypt_83aE5PcEk%x~`x4_1$F&h3vl5*Jtadh@@1^H@{cp@Hbp*2un+k`v zhXt{66y8*;-jb_q>9x}#zi^VNBhFszaXZ@Cj^N|onP0225wzGjGX!;UuO{$m-Xwm< z83wI;i>+lDu`z3ny%*|y{+v1r(&$*=cg|cpP?M4)k{zq=z{cNnxx|&2VbE9iyvDV2 zvDDf`-Q(N-Z+jJ{Iku!eK(`qA2ZznqzvLMom8meIYo#1;<6*KU1WA-dIEmHRtn;{Q zt#jiKpV?WXg>sC}crLwP8RcZ!Y}ybicxI3(R?(C%Js<(1HsUrP-hM&?C^d5*2>CjDf#N~*AV$kYZp*d2qA^2D?p(G zx?-nKf5X25x{chpIXM+)IXcV!h>L=H3>nbiQ-D+&LV@7}BFs5tO#0{)(fCEt{644p zU%xe8hV}eGwbZ`I;agR)pe_(?A;lQ?Xwff(^-H46;(a%Re&|DAY3DOJ^7Ff9F@3Cg znj=&tmaw%v(UK6LpEKmR_=3u-<=`WwmVLIjm4^pC3<+=`18o7vD{M;OrLeu}VzV4% z9a=2dtxB~~Epb(5Z42QCP^Z3=e0S-*2t2Bu`vtW>xD%{ zy=CX!)R=RMNR~blhV3^0U2<3Zx&kc^GEWh-&| zGk3UIJ|2AJAe4XDc(s}P%D9~?_q&)=*Al9))Rb1xPzd$8T?4ZAwD||KR<%sG^=BF5 zP?QJz#dNaW9)pzwn9>KS%dts4WW%C$AXUy-bD1$`Ph-KQf9v)HAGeeVh2aR1_l&^GfsjxQ4Sv74lI4O{twEddU;ZwXjyl!rZpI6up=Kdk z37pa=fR#r!)APZg7zD{8poYlPn4Mo2g52OB{o!nEmidyBT~kUXfU)6I&c+HfIs!oD z-{9Jcg(@yM--7{SoNe$Yg-3~(;U?hLLh=`*o+l0zbo>qln42oWu2c_xhCKLop&bG~ zLdebN`zQ@KjQy6q?EuJwN~6x84my#%=e$-+8kNmbkC_Y_BCf`+G8Bu>|NL{iDzV(D zfL|H64R{Oq2TwkOUl{9l)ECcDlE!^l-Z#%0 zKg-$m$dYyOz{xOcI=Q;qQ#FH%u(<2XPFgMU_gEK>LJ~3KY|}CWGNLU;sSpemRT+Kv zOHa=+!7|%wMs}IqCh0#Js05y)wKD~e8MER?`~uaCnZ7D8}S{5G?*iTuuZd*e@@9`8H67j7te?qNGhDVMj^aqrM>S9HdG zg|mZICMXDtD){PMSkrGJG#0qyfB59IQHRk+dU^Q}{f&WL|kqqIua8>i0=O=2#n0JBnVu=62bg(KIInE zreHv~gVZtrahT+P|NcQenRPbBjDkJot++MU_Y0K(LzK%9bZeI3a03XXtJ>9-a=RF! zqrdwjjc9S5sX#g zHUpUV@|Kt!Z((=;XQGAc7NQ^E_ydR-c&P(+NHovp{ygEIx!MJhU#6y})y`wv4K`$- z@#eu%v1i2|dD03vfG7aiDKc_$Lsw7GSzC_y;GhxYu%f#!fI4&%<82Gdo?N+7Ie~Y< zw@J9D_i9&)QS(oIi%$qT^6lPBuC0ogIh$Nt6yDPB^CFE#dLp#nRk7Fa%uR=brx#Xn zxH2z%Ztwr6L=!GYE6tJd2~M#bl8q+@eTw^z!ttCdmp9Zr$RX*%CgP^=h=pwqQPTN1 zo5os6ULbx3dppCy{(hDE7f5EcJJnBnnVBPM(n@%zU?$JzK00|J_JsAxUducBB8b*j)I&Z z*hB2*sNr^qV3PQIO=(H5r!Mn(ImvfGrg?1cg=<~EDI1O3adL^!NsCMpio{0k{&Swu zd&HiA-7KMGVp#35a=MU|zDoP1SiXe+OG}=*$cGU{bwYU^ZYPY`FyAMFrhat^A3fAz zmOwp5XXvRhyj@FqqU_gW_)4*RMV{{_^u^qud?l9;l>i$z9KDaZq9IjbEzhm?Or+$- zDc~LoRNYkI1cCiocFbt&r8>Z*p?}oG+XOEfknh)JzlVjNx7Rf9MOvS`uJsaJiI*7| znjjm~$a`B8V$w|@dDjw?*pjk%e$Ooc9^5>G%2(9J6@D3c63*O*%Sn6m2aDK)hi>ki z)K=z~D2p{OcVf7y2LD(zn?f!F1v_m%ps&-@rhvYJM5&+C3wAS=9?OwfZDa3J9=RZ= zd${v+wH=T3^ZcE%dPcsaH)8PcAwl2v=U*ZV=mXj!n3`Y!M1==BjX$n@`iS!WZnUgP zbxClCDGU@euPLMpXv8j1yn!eQ&?rM{9w@!eevl+Gn4@ez&j)HK`Ff(H0%4@kBMxUs1|C^oh4zqXe6U1Zb`Y%NIiE` zIdVl_s}L8zb_+WK%Qqe6n04v+?XGgAs`ybIfMUwxLZyiW%ssRcLeQO5-Kqj5bIJ#KIXO`ONU)gaSN4T~ zsc72%4>oZ30pVhLf$Z1DZzVEv^J3kgo66}QBxwHPr1u{mv?m=cPFO((YD$Y< zfm{QyTSPzIfK-NBmUgZ=P$rr`r!XfIssMK@;Lq@?!aV|x6IemkKg$q`%Z}o)!?Lup z#@D8$)pf_MgvSj8GrMMj;adhYBO^Ooj>0PT)&a}#`)3BXxE4M7Pddtwe&EzUe5%V{ zB+5~ZS#@P8%<{2VruRXAAKhH?S+(@70lE3Vr9SBiHUR&f$u2S%W%(J<@@GGv;L0kD zkJBrzbSfi%ZdMXQq9|g|Ndzv?YP2&Ek)h!!Lu~ViJo_6^l7SzmBH*_NPnyWgdWCwt zKLahzTx9sUVn2hnpO(4>s*@u&;yx$$lRSjCm+*FX&$($YYh~n?rzlfisX3Tm_lNlLaF{%XMR<=|BJ3x%ilkb zyuNg#P;TDEF80oQfgM`6{MExp%JSGj_PR$-w#>w3SzPxJ7H~bZ3hJ*5^ zx@`IuZrtWzFpouGcDhG_rKQlU4Y3I!gHbH6Ar!ovo!luaNB+@0U*F@&0PGv!A`pAx ze|v=k)S%`K@$&LQIVMQRsseOr-rkMtZI<$e8AjXzwmk4Q1Mm-c22w!-ZH|Z}=q(du zkpNwQun<5f!?_w?{8cL(7DotkgJ6*rDT~jV7V|nSchi0j5Vfu@jGHXzG#pO=2e;y< z!~FA?oa-}w1{M|vbs|pcfgcc1fiM?9m}y7FDQ&`*0nOTDX7pF%9^7yQbQ6J()As@P zg!Sk)qy=<*eL@DP%T6)Z2$4a%Sj7EbLs?NqyG|>ggW z18J>LVo+*ls(H1R>!LXK z!Fb1$F*4t=N{!j8W4#2lxW(;iRNVaP&$nPB-3N_y z=jQ+2Sqosf>yZ5>TNfAnG5es+vJm1mp*vR9+8KIX}Zrrl_ln1^aYYU|RS)f=;D@JTON%+zArm zgMhug2(OzLLodrbCnAb}Sn>GU@Bgm_xbMr+2HMZ@<7Tb1G54=ufV_Qpnx5T^>=ezF zf}lv7jO*XbTLtHWJ5VwPsYy0*W!!ZZL;7J)=Bh0yo;^P+(^s}PMux(-Pyde}h*R9U zNJsHTG>vD9g}y$Hc+*0$_Rm(M%~mWbkmsGo8!cjcP+M4C^Ph{3?xLm&I$v$n_&QGF zSZj)^f!;_YJNP^$_@>_8C8;#Xdw9Eqp&%(G5!2JzkN#zK7bhupk7_xPY*FJ%ce#n7 zM}~LGod(yeocU5zx<#~l_HZ#Jg}J66#}#2zBUhzs*ytp@0hHoPOVHV&rK);E3 z;rWY3azfX%?sepu%UeI1E`IvvgQ3G{1ceG0@BYy{YOVK06!8)IV?!K|cG9EX-y4dH zsek+?a(2+el0}3~Z-|fh6!wh8=0eQ^dLV~?@ouqqiB0fwp>aZ(HRR-+(Xcn`(Y z7Y{t#2Mafsiif@aWtE@kE^g(Nd10wdWJi2vRNldX4?<@i#@cmD#jj%Ry$iglf|~Ni zhmeFV2;i$Z*!YD<;=KN^rxuCxa*$9G0pJQ*J$a34DsZJNm0t98%$~nb-i4K0+cknf z?eTNd$=y{2mOH8h7>01MXcB9(w2R}iNP8XW>i;&ZVukR<`{(Pp_~K5ip|E&?{7H}0du z?={nBw=9Hj#XbC}lwS5C-G`7IlW`MlFLI%C6&f)c38weUfEj}x0%>*LYNxWvPzLi~ zx$mA7#Cfpia+mMw8Z>yqY0p%z8?x@&j;1Fr5htdX1Un5@>(2E{;i+D=HLMGb+un1Q zo-ez3W_w?5U&_!qd2FGGrMIY6xON^+Wa9v#wsy=Ow}{|#gX(Fbqru$~KAl#Ju0^L@ zM?*(pf*h$tyM@f+rd{$!o^5%lfaPabF0OjKG@bs2Us0GY6c~4!BHGxi`StY*C&m`5 zS>Daf_UmT$s`HCvPF~XPZ!Ghua_?EMd4~@>(KdY>+Uo^7on%K=1@TFwffeDa!6+Zi z*i!tX!pgbW4deQubw^N+CV#{=u_;_oQK3-N6Q{~`UMO6k2?B2Al;+LP`Ou?ivrNFxML3ZV;tkGt^p^-ZVW zf)(SIx1cT=?n_ucIxT<#Fo>a2-VAIqr4tqb%*>(r36%{^H6P};3A`8}@L#Esw}&asuT?4`_ga zEde2ln78cBdHykJ$SWJGJDBs{+g+C>@^#QIv*I6w`#P zy|t>@eEgs87dvy;ZJ0hdl)ms*ctp@o-?H$#ed@BtMDwU8H}l4{jrWbQ2b1p{+?4ZA z8Xo&m&F7zVT;FU!3ZYWnd4ATgtfu;{&d)d0XK8c~Ps*ohk^XZz=+5I`A8^Q+y0+F| zVrWD-XdtSyF-=)W!0hgl5*-b>Gul;?of1JqoanbAqOh|jcV)RR*>s$H;`(!ItHd+N zlHbL2S~Px?^Mu}3GtF+$OJmv^Jrw0F1KI$c5v)3#&0ikE<&lAtu`c5;d zw1~&^UhybT~O6knu zo`N>L!V}Dl65jO@8BF?f+35U=BWJIlZiak=!Dj7To1@Hg498_kV#PN(BCY&*AtjF3 zf;fsTd+8ra9}H12RKiskFJR{B$zZ(Kp^faokfF{LDYY|P{yKHceMi?alkM@#QL;iY1l>S4>x-B|~B(xaI-bb1?} zGB4+~eNHyjZz&@*Cy<|WH!{lpiHAh?XElqCa2QQG?8!ZNpr&gjklcY{Vli~G4lc5J zkLg?D3w7Wz+KE={UDbJ|hvP|N3YVYQvp?wS;;d6vR?lu~K^rf5UoV3oy`@k}$=O5e zf|9Dh0ZL(~9=BE%=&*@Cmy@?(Q!XM{ba4Ux-T;@K4{a%cr2>Sn2h%J^S7FmwTPnu* zC{In0R)L6Ge~2S|>i1v-=*6Aq&%vgToXtq;0X%~4eQ}eo0mJUq)Zfci0{QzbhsnF} z&CWS}&Sj=}^C(LLaRtKvSzAvmTB*`61DrOHl7Td8)-7%)Sd)MX5B>lJ2p-Ut-yI-{ z?J^02Yz)Xj2l;Ax6V2P#XI>iU>o*XE>#|hB3snM2!_S;S_N6jMbM0)&}e#BC9!$#rZy1~h6Vk)brf~vDi)S&DEl3f z4Y|E{V4g?3YtAIt&I=c~*VS^h;sl>w{N!YIrM_R_UQsK_#?aurR$_KjTLwR8av7#@ z^^f~I>H%w)$i|LceEb#be)6en)b5cx#tA$SwJBTm{=Kg)3w4JlWZ)+d+jx57_#Nd% zA|oPzsfA*zMkcYmkOUs;#jx{ z5<9osw8j*Aw=v?WtthlhX>C|Uxk#S^Z6bHG@ElANEPzq^?bO2-Eu3bHI` zpbT}<*rVmoKzA+LS#QFI2~Ff`?dH2vEYZbAUHT&DT(@9qc*IE-7iZ`3LB~{zmIRKQ zZb~3-0<0V9g8*z8K+(WhV;_33XW;{6@T7=o$FmOSxx!IZ2%;XyErfL*ToJ<&eN**^ z<=(4%NiW1}UhE4a1)SZ}b%m9c3yinmF-L+sb#)!*7_7d6LlK6Ly!gA&TYR-~i!hS0YyB#RLO5qm{%f@0ckTYO|o)HM&FFrsuk5KfE#}q6#9_gEqAUXwBJoA1`wE*6$@) zd|1@EsiGCbdKT)|NfQa&qK;krR5_$wi$>AM(| z6Po)t*xFVIT7ddX+$Fe$2ok8$Kph3@c~FwU)&@Pb=hQ9!7dr(13)tGD^;rK-GeZ~S zngrqFvy)R>0pM)}AmINRdXO#($PNW5f+G|qLXTCoVB>L{&wz(3C!{mkGMKbIZV6-h zcV(%#L&8MCAVxXlRu|DTxpG)9zT!p`UV^#WRI zIWoXncI;u7J2#!%qINnVOC!o(8Ecb3NwLD|9?2-Z^f98eO!RfZt&VOABRdvsT1Wzy z$+(z@Ulr=3h}y$9XUd}NK>L}o%U{pXof+(CQr$ET= zjvPGR756D|IKcYkhj7ajN07OQf;<+HTV4jz0o-|G@%TJg4`G?1`-_e3{TZar2Wy3|=xu6%YJI`N8IJi*ivKMz58#1^`dUt6ORCcuI&L(w! z2>#>9anTxmLTxN}_AAl-y~e64h^`x8#OboalfWdKguwwh{>lwdOZf8bQ3TQ|Pl|Z) zzWrY?YWjOKO5|pyrICV+|Dg*`|NSe^4;ISLyT+-5BBG5OBF>tfE&=T?0zrXv1xaAY zKiyBid!4-WPC$nk!4}078ygEZ zCjtn7@DTbsk|85l^>|Aa^rP#nG8?Qs0zZi-WU7+<<**z@t|V+CH9|Hi005a^HG){Z z`d!cZAo#NXyQv{pWTVq|KRY$c1Fp&OXBn=N<7(eo2s1b79=9kb{V?p(5FP!-fTorv0T`dME|_({*{nkDzN{wk}P7wiO298A&pY(Dz7Es zb79Nw`KV&*5^PT)-Kiz9VPDo*8!mtCvB}oYWui4>jBknY0(npDb^;En>Ds#d)p4+* zOP{Cy*LyNMG-`xXPx?-Nt@cYTs)drTvcov99;*j-)Zuq8e$@Nhf+BHGLaS|k0W}eD z>1UUji{zQ#@xfRDYH|m3(>>zqvZM%ssY~zFezb)*a>dxvDsp`1AAKbO}WoChKHDYdmspaLm<*mgY$ zlcvE1zvNYce^yC3>$3T0$Q+og+A>YuOlHCvJV*cHIaIhA&S#4J+*8rK;$pwSjP=s& zZjfH1uX8a?Q0}n&Wi#<^Vf?C$*kpss32N#N3$j-j6H`k0!G-3<(#SGH3M>2rHl7wJ zD@smR`o1AAqs|(GQpHRCNJ72&bRqxzafgk_(@cN)a0U&l(-nOS!eBfe9UbMDk%^Sq zi<0>PqQ5$Ls_25KSzI5_k~>E}EplEVKN%q5lDz7o`jt3_ER}E@jmh@{gj=0{rhoV$c_7MCcSqU${anIfSBJgGhc#&i z_mtT*%(oYx0Qkb-KoA{{Odaj)NzI5_6_C%JYEW6TLVUus9;MmwU+mQT3Cl!ZEMYAl z#J#cqw)YbS{lNB#YnMNyd;_f>{AYri zR!~rhGBmVn$WVn@ujLkL+-}%>w=|hrulcw4^0Kwh6^XF ze5P+Vh#tzAAv-j}PX8VlZq_PvC(zGi%n&qG+nTvLyM(u$i<4% zu_o|Pqb;Gu^*g(h@htt7LC!RcH{bU*>d&) zsnw5{Wj{Q)VMsLXbMe#(XaIe_@#j9H)XR&YCuf?N8yaGCmUL zEb3%$Wg>f}AnHvPn=@xnE@cxLn~uSE`q~io%XjZ3yutJ(pEGLf4QOtwfh?kG&w)IK zQ%muL!JZy} zk3OZi`~8!&XB^?k%A09bFwunen%Aw9@fgJi=WeqNS)R}?niJM2Py;ssp#GIFSoP$L zXazJCOPBwMu(G>LrOmk~kX+V`(c^U6u_Zb*^04rKZ%32gmwAR@(3x5wZ^*t)ujn;m$S|}d!PCKsU%z``oehLHGEB|%O#w@tRp+z zb&eqN^34IMtCA3uQ@gcB$Y*o$4LnbAl4n)xU$}oVahEH(&`E_>>EZ3NR+`1;$B8=k z5;5InePTc5!bGY9ce9(~FdOT7tmS*+tUb@dX0Lt(ktPI)8RHx25aTe*!4H;ZNQj^L zizA+3n`ljOD%V9TNwbEnqLfn}{p`FMPUKVC>|}*Ekji+o8ZMs(8^#@Aln{Uh)QZS} zEe2&yT}d*LL-j}7Nb@_q$L}z>9{BpeqzR-@|DwcP#pUHoXUW#-9K2W?K{1UBxc&N; z=yPFIOZUI;p|)vP--_(OG|kHk5zhnSibF#~J%fXRcdtzgI>Ewac>gW(jH+?s4nTYj z?juAl`Q{8AQnl7q_r#eW(^JTH+8L|xK^5*9gt zIzTM%yn>fT8Z>}c&D9#4J=Jq~FDWHLxEjMjRn5>__(U{uWp41%#N^~kSn?&$k-|Fd zqCo8~WptoR{ngeU@1U>C-B*~(Bp9h?kM)h)imTaFq-6wOv8djNOT1lc0=UBJ;=JtC zus}I``M_eAf5&>VnVY9)hHc);;ov#dr7jUm%vkZKu^|~lhY$jf(ZK3*mE~Bl&{B0U zUCDzai^=)TlG=S0iE^I2;-GU*20S;u54j1tgA~gLbesIl3Pb9uDNfE8X(DB)a&oT% zlFwveYx|oiA~%92+GSLsMf+b^!J_J1QioE4+Y%k_jLg{Nq&*s^;bGU-{LiswFo>3x zwOmkRU8qbqf!X;vNIxsMMWmD5!+((eGkE%!bu7oOw{F3xadr7JAzr+$5^K%Z=jq+W zldWA4Io>2*_gl+&j3?{qm|ffNe?ntpV{nE=7{l@b(q&!-d>YFkhtC?h@40;6!$r4O z3sm!b2}YfhElwsYJKl3IM%qv7kG}hn8m}$M&UShH^tdFHjRTg?FCgHLm(M@sK=TzK0o6&qTG?YCOGJZ%ZId#44H&j1A%Y&fvez_Hl2u~8%u$^Txl;sFZX zV8sBcTi&rCwpwj1tuI~ODJ%4E@16sspCq#+j3Gdrj*bpFx#9AG_M1vS2lR`J5?q7! znh8N$Q(5YlFYYxGv2=`rf(=GGm|Q``29p*@jF6=!mc{4t1W-lsidP7B*ucqrual+a zb+pvlTnNYvkQAhM-dwH$d}u2aW&jvuybc$Q+YSzDnmVCS2Q&G*fpUhqLrqG(m8^cz zDA}{VboP0qsTSp!>GD&6;O%oVg)U@7xg8i3UL9%^dcllmz98P^w*P$7$8&f>%YnqN zTV`M3cr6L+V*L!1!p%Y!zCba6iN|q>Pb}G?sQCQ<*8-64YbAqwL-P1wld8te*|}o# ziIvG&vH&V~o3EF;y}q?fbRT=ft+Ir+>~I(i-UsTvk!4+>T zb$8o$U$s6(GTrpI{Asm8N2zh@ClAe|L%DVpy(|HnB+s@7h86H#U_1d<;{D?K{CPL$ z-iH^P}<#EXiO6MeZ)3+u()D zE4d5ZOb8Ei@-ybY+ysOe01)%GXq*e7xwTbZ{bCAwY@o9P;gF)}P zwbT=z|JE~KxAEN@!KFTy#P<0AdVAsn^z}f5f_rX68HjN}pcXWgD<_K)B>93doksU< z@Lp&5^F$zhBGRfqwJ!Zd@L@6j(NI#01={{nP}Yy|A*Ze)rYaweh_NeI%Ytkam9-Wb zA2B*OrtkE1aN7wL7R`lk=wP!p-w(~>IUGu4ejgNnO2nkE8<+GUMI02j<;|al9viX5E-+Do7X=`B=9CRyQ1{O^sC`z~1v$)LBn;O2*hp=+? z2i)awNPRG2>E7C%0+Zv(0ccMkFE31ur{DW_*=tx&4bhSW1YCThpw`gU{{XvyY8VGYE@&irE>pRsu1CLInOy#mlZQ&ZS zoMg$JS*)Na!m=ygG4vKZ(Xhq<#1Gs9fW1^TS?UVW?^FX8 z)QsZ3-~Nf_*)lS+yj?CoyZ%yBHfJVP{?6e8R?$6!I&I1rMj`C@I(@eW=d9#7#8b}= zW_pdNvBLF*7`Bz}c|0UHGhad$pebMLl=YoVtFCNX7z5>&N&8m7 z_z9~mQ?PGt%z1YnwW);+|484Ox!oTQ1ktJa9*1EDH$`4vrNmXNK`F+p)$e3a zZg7Yy@X7l644@eR6W(k**W0_P3x_ZuAo*!f#5UK50E@8dX58&siIIk`h09QXlc8uyl5Sa(GS% zP5++#t|Js*=&|Ra>iczmu3iktyjfq1-wN;mef{0DHE;g>7AbA+5UzRW% zuad#U0-7S=>=EfDql^zD#Lz*^#P~|1Mzb!8Fk+C_CGsx zr4_;_iN0K1^}M=5i;>!8ls=fIz7^e7pmKI4AYR7#)p?0*0ld-M&9_Cy0Yt-EQZZyEnar7&rw(Y}Nq57d<-ImhpEf=(g3O@zf=-}#} z7`23q?t+05Zf^jC#XsMvY2E4NTon?1#zI>^R;DlaF2N}#=#txc^6y?lyM!$i6Se2E z&r9{2wwaq4A`|LeRdf&PSh5}zt0?`lF{I|gw9BO$a18YDJ1 z1%+X2Yv3lhHVeJ6axsBaKVWs$@H{6DnS|E#!HE+xL3BdYVnZ<&$ zt1GAv5Pb+_BOt2@M8g2yZm?%awzk#=d97NzEKR18ql1BI)j#x!p5OS~tf4^eLnncI zQdFZ4akV((3vI=cLdB+8H#rj7TBjzJ*_}b0@cHkbXN5Y>(IlT18o`3-AfZq^(L@h7 zWLwv~5P{HXU7|7|LzT3%HlF0;-1O?lq_y9mPs$3Olg%>N zDNC=F{j|J|9A2)>rVCu)&~QEYFblzEt)-y}^TGCc;XuMj$yesWQ|C@xU*hBrlAnJVr5BQ0~4r1o{~HVXB}d$a1yIoF1j zPHVgyv|9T56rAXYeh^q*+tIrLKN2>1K-R!Sl-elA3T9mxQDOQTN?)LXpWMnA(~#fYUFrYW#a{Eo8R4*czk9^GFKXU&`YMC^@<5s2~!jV`KP)r zZdVCi%)_|M$k@j8AzUXEu1Kx22=SKVJP)EplmX%_{n;@T2V8 znqzs%s$-enPzuWX$^*P`5YgZDGv(RpsuxaTeJX&O`C~?foV6r@`%ylt2_uC@ChThOSLYFQfUTc)b2k-s{gUcW{FNpJ`_B5Obr zS>e3!VJM}k_Z*imZRER*DkG1CXd!D^JKDRZyU(IIt=;>vT#;U_r#r4#h6A4B`cy*c(z!7vs>KQ82OC!Z%ZYzvP8!(70 zf#Nt3@Z$!1e1~;nHOV;GG+!{rXG?0cF;d;S=P{|=PS!$a?X^2iA@XgKm*R1IM1B6# z%m^7Kv9biEx`qe|wyxVK*;4PiP5u(^4(gVo(Ob;ld?dbWWm73<9~8DyqZEf7P}vo} zYOVZ)Uo(0$q}VUL8$YEFW`$ygSC@ox)tk_D{S~RR`Bf)9lG%cyF|LxOOiPgwZ#SBy z9qNzNsIx!^03R2U91*Iw{L-^-2C(Qr{YN~j5#{#v=;%?cI!ur@ZLv-DFyBVIv|O9) zP_6?N9&g%SR!PfTELm3dt}JS|kR_fvo>bWVd)L|AC!qi#k$q0 zC#qTtJ(aQ^8FRQZP@5>J2Ni`NE80v<|EDAPuIg6O>4p(;a76&~BU^eWrTgL*sqi90 zJXYFZs*lZ9mUs6J`~o^mGt@ZQsdafHh9lT+N0+ajCMzt$)JXP0bHI{w8Jkw&Q@hOF zJLD<}r08VA-NBzqa@XEO(ROeZ2w!;HN^T^_pKYW&b?M4m`D^(8zc&&mYH<&)lPJE; zGvTjLkmbsnZF=R1x-I-A(HD%;-dBjusA4TyL%o;PCh?;w^43y6JGq`(3qNbo-cU+ov-7p{+^Pmb z0P!_NE3;lUU$%^SWF|qMk`l<482a_Io)-&kcy4a)x2+{iyyRP%J?Pz$+5ADh@;ORL z1`tfhD%&N0&gcBlx zq+oSWyd7hu*em{oU<)RQZkOMy-VsU?LEK5sd0D1yXi<;a&VxQH@0g>_T5O(2G!0kN zR(t|@F~2$8hc4Vu_^_*ly45Cz$u+XCYFScFYkqp&c{D*=;jVw*!TJ>^D8CYusj)^M zM)vJVIZNrNLax`eX_jPl%cOSxkl_{!tvve5vjz}bJd7~3;700AK;-)KJ*&O1rLJ(| zdIQG~xK@!Uw-2YGfUEr@oH?*lAk_82-X>BUhy)B$>9)S>_@^@9o+3&BP=$B^vXM>tAiD^wF;jf*lI&k$S*L5iM#<-1d;}Z zq~5@Ux0p)L0{LJ_iV--VjgR+-z^W7hP<8s)QClJ)Re;_@MCRvj&8Xa7CYk)o&pR zA|&C%u`jN;+GR2h?ww8MbQ-3sF$?dOF8UO)@rjVU6Sw+Ry$xr(Ynorp)>5bUDtuWz zt)gzIZY-mu5AP_kZ+pehZABWReJ5lUnaA0TKAAqO0YVyayUoqb#oRtuCz2UKRUPB< zz&Te>S_dY}wC&G3z5{k!p3)B9-V?u^uoe2Ys%ja@b=m@yZTjs`*f*?T&H#;Fh5LG{ zM5vljG*}IxMI;Q?ZXABVXT3^m@qtIWWbY#WY@Ft|=DjoCo}_Q3t+PYXI5LZOx;t6Gc0y9Nmk&Ut0M>{&94 zLd!mFL}!kGfMJ=FfBP))cS{%^qha~3xW5FpfqKc1r!1fMZ^dX z&(3tYFQFW10hc_&&(8l>7kUu5?E(Nt($QAN`m*sM*W>}AepQ->)-&aQs2o`L9sx|RNjXf5LNh`UK%uC&@u}a3RsIyoge{^0;mmm&(r}+EtNE) zT&hP2LtKUHG74!50_-mKVRP*(Dke&joJ$x~D0`!kAQciaAGc003oCRT9eN5k)1_G%}D{ z_^(b@5`lz{>Bp5P?@zs|IQds3SL;ofNZEzg8)&Xb*mBz9hO(!gnG=!ufjC%{K0NTr z=W-ZuKdLR4uX<<+tlbM5aV(T)A)Lh)56J#eC)<*asJ0g!^Kr4y?VmxpWHFTL{o3aqqthJsrl?N99VD%;<=T0d zbB&z{f(h15w|6^N(qxNOy|X9sl9cb zHTdd^=b0rsygNuuC<{{ z5R=t~XFa+6yyNrC=*7fO3T|9&S3mT%Y4e$3nY8*|FEDiim8Tt!(G+aiQOqrd$4U? z0q;7cCGhS*-_X#FW*R(Kfb+@8%R^*S*m@y8sJQWc3!sF07W_5#cy=yl`A%N6Se{V! zPTc)@wxbSswfVrUoSPQm>Y~rC-V)R-54Spp4S&FAC<0*?_+Uu2L4U4c12|t0U>3kk zQ)+9;HIn7vB!{yed3SH%Gt;5;4GuCBkc8*xwBFoa6^(uLHPJ5G z)U=nvV&qo-Da8H&dyi2y`VzgL<}z!?X&TQA$;>kk`yI4f4_nip=oy()vDF>!F8 zH+ypBVH7(i?O=FaEp%$+-(rTE7FkR!k3O4HXtKI_k3;EJEL!f<%rT;_rRBARSZw1& z8?EyGK4F@HJSTGzhD6VNgQm7z(?IKDDdvY*2|m%5mJOJoAQCs#6ndVqW!0#3`bW3Q zbS&`a@w4Qx#?RY{2gMUj9mjAoW1%cycM%x#H zbnhbG!V?JvipWHE)1driYHDg)h=_Df)V|rceWpb3*}oD$Z&QX@fW6NxZ`}7_DlL(hn2B1~T8MYypY%Ni7d??1xRhG`h|ta}E5&D` z(d{%$#g~Fr(A)J)Q_$hA+C8vPA#`q!%1P(*o5JDE8Hcx)`(TwZh>QQ8_oaKAlzIw1 z*V@-tGqjWDEwZx(mWYJof%+U)^b{(aTglbc7?oDN#)T|?SR;wne1GctGD`7^eThow?RVAOYs%j*Lc2o6eZ^_FQjVM>lP|9_BHTk& z*Uik9Cfz>pilkAGOhul{53jzJ{e3B*_dqZML{bd5%$9bjSpS*!5qyW)rZSC=YVJ5) z$&lq%3P_nTKU)tjouRF;dum~=e<|VVQ~zjA)6UoYEGpbABiwi7>Dwkgz`nwu)|VZ= z;<=H%2RtqwkOuMDD#A4~k^3A=s+LnZ$?Kg5?1I21s;tzBjwvXQ!~pUp3G~3oSUQiN5Zu5R zHYH=cV>tS;RaD~1Y({d&DX{7Nu*Ok4L?xS3#4dA2dVN>nQ+ves1PVL_BLpN-p;Mhn za=AX7n~UJrSfUzvnp2mx9cMIA?an7npLkd+44 z>456Ag|a6G8U<^thCOd9IM+Bhbu9kKUOsi_F{8Qq{ky|6!y4N^;4LkpE-lM4z|CEV z;7oM&s9zsd9#TFSw)D(T#DQ7bPQUl~?@Aa?y(ad4pr-WKTAGKoXw$Z0&VMpep~edT zoAKmZDJY3k7*WS$>8Nj+#@k0d>{oDP@!gJuM&qizQSa@l>gv${e6yWqJ)Z%}x4F=d zILrAU<)C_9h%!du@~_B0BjRFjlVXf%DE0>zjKdq~=)^uMn`Wg@<09#AOTQm(HpShY zZ}%yjo|{e&^T!_RW0_L7h{~a|8qW?&v&hL`DisRPJwNW}OBDnZl)rI5Ho#%y7SgQX=gVdETV{AcTV{4%GDj zwUqt2)CYSw_;+|88NPYlCeeqnxXenyyfZpDIQYfDCXJDaYGyJ$v`P6*2auYb4)?tb zsyt630fxu3tP&b_Ig{NypYdB(`szk0^7tyPqgo76eHZ42d2i_YC$g)g5*nXvZ`R-O zakV<$YoJhwtq1>1b-{wJUi_svu+UFpQ<`rnu{CmjzdpL&{*2x>-%&GKi>x(b zS7a)-qA>;_5sx?L9BQPOd&ZCfS5P zBSm5QIEP-^;JuLP7lzpti2};aA6;I$=$pSm6PU}bNR)@{^kWj1cuh$=@3Vw?mR+h^ zy@Nd50?F>QOp57)BK`pyV?Uq5cTy=y8l+{AD1m4N_kURT2YS>-wRFhgeb;Of?i+3z zJ?!uFwGG%yZM)g=K*F+IYkJMIT~@eF0n6zVNW(S~_Nn>~5zNVVAo+oScR^GD4=CJ_ zR&=F36v1!>I{o&qn3{k4{nkISRQp!Xlwd3gQ!b7eUXa`yoIaN*v%ij=`_a(~20ge$ zwzbhh%-cm`b^l7V-U8@U^$@?72CWh(UU$8{CE+#*aLWH`W)Q=FY^=4!o0oUgKN~(H zVR-w`_6^W&oQQ)B%I1g}oKK);E2n?F$5N*9L&8y*ch%cIzrXeQIW;FH+r zvAy7XZzdopA&vXVr|$ALf!k*;WwGqi=kj=JYik$4CxcvJ!cT8-WlJvHwY{_FxwvN> zm2!})Jr*&*gzwL}pcjzGQInOZ_p18rm7(1BRFBxbBy;+WdQa9E|3-Wn@;8 zLs;z(Te%*r>VxjPoy4nsB1>z{GS8dc*R{;S-jq4t=`d5UlZQW=R72q7)W`F3hU1@k zq{s5rh-W@+$d$o5{;>IF<%RaQRq4;EQ8{bY&OB@s#fiSJ1*Lu!GX?yYx=ZhyCx!Qi zpwzF3LLsg|7;F?xUpe}&I!2>_$mkj<pYJtfQZa{K^0eh0QGuo%WZ`L0k6 zI{;|wfHjeJ!Zi~?9({i(%_Pb%oBodq2VnV)D=t~ ztNHu|;>PTWCu}J*@jb7cDrGNTksL!M%2u>*Wvs=U_I)W{epWo(D^%O#wo0Ws;xC)>id0&*@>f0H-92wwu$8>D zWDjctfIE~~QcA`?f>ckGkBJ8U19stDrPcYrf~EC={C^$CUzAC$nW(gx1arT&FRrdB z$$kEr@Kj$cW+x?eYk=b!zwwS9CRc*>e@;ax0SJ=|WHbR|4_2w}$y-oiSk9kEs-8g) zv@cP9IIl6pJcAQH)EUcqw7sNwl&~Cq@aXC(2dQ3)RG0R!m`0qIN>{0FtRsW{{v$V@ z8h?`B&d-(W$BIYc?`L9SQOScYej_M3zG;a6qm%8uxUZR@LtVaJhyI8uuK%nR__Vgi z8k(V1L<M(Sc}{$7D!I#PFl zgw5Y8r?1Qp)+uw7kz5_9P1`!&lISu*iQi$EM>)NA0=6OXnO0lU0Yc+)xmh%rC7NMjqmbhHrW%5%s}4SY=qf-F##vP7m?&Z@p~sUF4*OldVv z1WDhh**YpWhxs9ODZvm}nDA-gxeJ2vp81SCTdUW-W;$~#INiba3UVYE7O+(ot0%GA zuEiNS^heyOYCg7_b+c-tr4*{#-JKSTpF!6y+cew{1E=-PUo3FYjL=?4{TO&M%nIA&Q%qDh(`ske&5C6fT7`~9Gr!0S%RDTV zf627MgHdEQe(?{*>emMx);4)7(x}n-g<~?;W~W_xbk^wF+r5Vp|E}g8^7Q%62Cf!7 zYGPjoX6%TGr_kkFr`}>pEUDqa9;x!`wqKt2+25XQ(1G%>Bvo0$V$SdvYdbUAlChMw zDB-Cc`kU^2i)@-4`Zc^(znt?=YU29}N`vjw3f?d(dtbjosSbg4*?dSYnoDq>C~&EW z`jtr;tZfd8p4&IdE0}AsNxUdls{E+kCHsr5WX7z3+=q!0$QnU% z7)TNB-17(`0d~YSGs!H**{+q+p)_`y&o_f^6F`ic#4oBpHOpP)61~$v!&J_A*e-lxhgIdPF6A$gpvqGhrZBfC@)I;E%i zkB$(Pz%p=U`fX$6v8)VU2b;6iAWZCGM@3!P7Ax^4a>O&l3(j)cd|Q=i!z0Gm&qa(0 zKQ9&d#^c^6-Xz?Z7+K2|s~J~mJAw}PQH}kgqu3m>a?zOOq&`p7=k1)8e40yj#xIn} z{cHIwE;2t-T$-3?@BBJt9-aPjywj#2jL>RzI|&;+6r*Ks%ks)@%?=vo;A;dpwjPb> zPZGw^{yICG;j+8V9?!fOCqdRo+gU|>eIZfQeRGJ8eUfR=6zjx7IQp4z`hv0EnjY~c zx$JqjgyD^j(yCINu0h&%Y?GC-h$R3bbhCOyFIC1m47p>{!vkG&2A*EC$3@wmGhGng zDqG4vP#!nos_1>?;Lpl3v+~g!9RmE?&$w70dhsLEaaSPy-HV68-0 z#IV3YCRwC?2yjZH;+177aPtGs*7TpBafos*GoD_|O;McQz5NO(>0-~nn`d{=5`-a- zv?MT_xlu5JQerOT$6~R7i*A^hNR-U`;Q9WJ2#m%^E}ap((4SZNyzP4c-butchKA!h zjrw3p`RGv9;)dQyb80LSWW?emaiSX; zOtTjKqt&lN(e^ljYDGB(C7h)sdLnJT>Dg^&ubi%rrR+Y@R2t|?xMjdkAeZkY%GSEG zUqOyewWm||l}fl*N|)0&t(7vx5S4oMfV<-4VrRtP@PF_ri)`$$Ov?@M^wj>OU-dE(jSxw(3H zih`307w?Rxyw$*TtLN;*F^9`Vvru$wnTcun5 z>Y8(z9cb~w$^E-uq}Df*f|(gv)YJANe(d&X_HDAlIe(K_TddwPlwclsz~gCK*>ohq zJo3@ilk_yB=!}^`mRQ~Y1lW9tGJ^^S_aYA&uP%^5{twa$&h`ieGnF0g(dnI=&p4#1 zBc%F^5?{!>h|Bb`@bA|8u5>FEOMmrSh~Ju|9)HodM^Wq2hq8G)i3u||9*#2B z)B1=jViKBn#;@s3^%&eF3ixjt1)se^c*vukqdp;%lLr#hoE84fI17gZPq&qGG=qr7 zV6sc2QPH?m=T7pKdr{5qHM0ZGxPmbD^L&XC{!HG(rGp14XN@*Zs3fl~#XCU5=|Mdy zrQeyU_i#@98hXUGzc|k^Qf{PH>;bnVID(K8#+sTMZOuyyFPDu=m9sHg{rsVQTJ981 z0%11(N9^^(%Hm@&9T<>5!1))sF*XV@;qTAT(Fqw%A7&<95k#9RvUOQ;6Ea zJPHNI{0#Jo(x}Fk@81&^jJNgu=q3|53_LgD04`+shS8q!dq0SzaCJgx^+rYxZNHM_ z5_BH`oB$BFRy>tWPiZX-A#qkA=nAE&26f@j9!R)q1YQ{{pcFSgbNGFWV(3`38z6I@4QuW>6SZUu2i_Lr}= zb4pLY+`p8ut>G=H{2=AV@WxI<;MzMw)w|RuMMZ2|3Vn(6NPw6OQi{Ab4mCaXHDOe1f_Z24rO{;$onrjx$uwM(c{vgprV+`%AbSn~x@QVn%p z?iP!kgzLv+IfV`wxZ}+*f8mEo`^EB;s?$`G7q|1 zH;BO9L82CgiMm@?;e*1P5f-~JV!q9OOdt)HT3v`hsm~puKSI?}@x^j+%{!QZk8^+% zlfJH-$Mr|`s1_*4}k;YLP)%=(kD*PcMnz+Q%wf9x>^u3Va?+!y3vlGp3v{Y)4(` zU>E1(UBk4OVS>e!7JegEbyW|P%59#+)ywziH{RR@gZD~-z$0vzk5;vjBkh@@Hv(I! z@aCR7;e>4l*8)I9mOQ>XXg2A}y$`G4C0E$SPgR^4R(N9wT>NV#>%!*ujHXZZW zwmf)}rQGLEC3voQJO3UhdxsqSaijvzqCC%xlNeU~`+Tt^U;^MzF+1H)R|X3u-5--H zp`oD+d^c}?g@Y_T9V_=hDc9QCH21;$R#x`**3~H9;);O~%W>c5*S7UYk1hN+d|H5{ zdM3Cr?MbRc?Y7Idt#O0;iZ>?*xhMU-*TKT=(cS<=*8B0J+|Fg{*-$7j(ZHsD`+tV} zN$|KJ&8;x0QV1PGsV)z$AJQMH{ZK;l)X)dGcO17=t(bA)eX^L;!5+8dFjF>a=_3)O z!aq5_;z!=2WQ#{a2Y(-5<8f0&=l|it$*xhhYprY=KA=ujSu6cQOD~E#tN1ys&Bf6n z=AQ|5RagYBo$k-Qh@zj0klE#ux@5oo`x<&O`2i*CAglT_+O#t$AvS@A!?(Ou42%q)lY0ivoqv~O`en)5ntsqS zOvs%wkv~XfT<*O|k#$Z=;K>_+);?H8N#uIUH^R_GeMTze^U2nD+pOYM!J`sr^nm!& zVVi!cmB}LfDa%#~OCR}*Jk}$Lt>a*YyGnhc`7>CFP{i*AN>xRTYwDF$OrNojTCD?}YL@BEGe5}?6+4hE}t8K|=YI`YMqEQ|fpt^w3 z1HwGyAN~WJ!A^zUY^h4|tF|d+`y)-BDCw@i%WWrwpYG;%m*mznp^sLq#S$*8j*gFh zHS9uuNve1)FiIGToW!n%TsFn{7?wfEU=}cdC+27CU_nx8i9R+_0jCzCvD@}F5^O0F=_q7(r*O(X}y8{)HXFR@F`gN2XW)ETI@&z2y!4_ zz`1rC0*#0@mjS4B9KPEokn6c{Vt|{3IH$n!HifjmO$IQpmgHd=5Y8}&d4+>^>f-;@ z_**J;b)F7xG&uK4J~)e7Ug?7qE?wY}FOS2-NIr`k@ij_jhXWJVs3wtMlktR_uK58; z$s32Y#9u#geB#lqx0a;#?TCYVRQb}_!|9NNFmIuv+!p@>#h0_bb|mw#lo|f^7+9xk zfBnAf@tv)W9}`|<+}sjaeU^E<59f%PBX3o>+s~uQ&N2b`Rp)NA5`*TsZrv(V^P>#n zk?C17`L2J!3jM!&%U%uCC);g++8{aH#YMZ1k4)n1nleg{4#Y0R%K)*0^&b3g*4S&; z&U+JcIt8bvx0(I@AG-`3;-?coY08jHWDdqeElKD7wz}pcc11~EZI@6BVvLhcEU;}7 zIb3P@d(Oi~e}|7V+R-h~&1k;Tby0(HZWAS&y3}bK8TdUmiw;f?=EWpJ=i0`moVg2d zbbw~}e{H1DVY&-9o%GB=W!f_0lG#w12EfB%G zoLItZ)@hp#*JK=QrUzUICiHcIzH>21&s8D!P7!Q6A$tjd)Pw{MP@9l=9z4r1P~Maa z-1`OwKX}v-);ai=TFqzkrI-nX$=HVZ$SZ!^e7ra@xRqv`-plL89lSoOw=^7ik*xvd z9PMa(h+G5ElZBn#jp$o=`A<@jWf$qA%v^%UIeAlv^pWK4$d^hkXi4w0GU+byOeaXOgn+f`MwSqeNKhV1|FizGd~+&C)VB zVIZ(xGWXPTY`CrRXRT)IrlHcLHTLGBf2rnKwzGvI2fYr3pYJ3tkyA6d`N@tC^1OdX zT)pygrE^PlP>m~I-gD=SG5hH)QmyW#{{6~Xtj zl0I$ez?AmZc^xv>F2pkI+$U`BWj6fq(AM?KQp$Sg`cLLp*)*546^4o1o^#&mZKw|Z z(4n}<$9Adi#xX5j@zlB(RBRr?L;K4j%eLt`L+94i^3^Ccy&4Qc+k(hrFB zKrj(Rw$G&fqLlJ96y(%!cfn-JJ!mH6UOaEF5Idgb?#Y|lO{%SFK6G4B^RmCqAk&Z5 ziJca7+TQvHE5~P2R$c9qM$`OeFltxs5CHDTCxY^GB!n1xUKAwY(a9Q(CxWr`VDALt z+n+Ysp#v-?jj!i}`R9`M&7{=9x4IPxv#M)HSDmW1c=2CiD^Z5zZkdDb?an}S&%Y{S zqGH5>4%h<2Py)WcUoB=&Tu{N^btHLmrj;&SI5Q+}%M0kuLP($jhif8N^pX<{Izo8I(_5Q;RX#=_-(vE09qf&>J zwb3E$K*hN@hf`na4#{*R0lWehlV!_H;3fu39lSVzSaT7e+xFyx+Lg(I)P@2UG-q&y zTgL9YUUgT#O+ij_6!Dy7He+h}qrD;8yt%zI-q})R-fyDE`*xn0S1ttutWUQpYiUYa zi@Y&+Pf>zox977P(u?P&9(3g7-1OQKT)M`P4BFgdbAC`h4E{+2rf5=9k~iZwppd%T zkL6iD?>Naj$}qS#El9Gxw#gNDC2Kw2)K3P4YpCs}e93z@_uw+qTW5&%zi&0`1ZV_^ zTwtVw4V+{km;WVjtbo6XPBy7KMz$zS&JWAgcirg#4F$sV z$WHWUH6c(y;oL=RZl!76*6HeSEj5Ly86c_PC_xTktnatdHF|c2_$N|wKc3nvqIHjL z^Y&eLq!enU8(pxoHf3i%z!$0sdLXs}fL%ia67z9VkN$Yjb~<`yW(_1Hl|`CAR;wpx zPH�X{aKumOYbf!K?`*Oiy%(ci_~jVV797Pi*z^`oc<;jE*J?sR$XWBVwx*F(a+ zN_p)qy9ejFse!^J&h5Hm6l{^kl8My2X&)rqu9y2z{5qz0gZo7H-WGLV6@m6V&#{^e zSx()V53gUxNvl7e>-yvIb#8z`p?;w~uj)0|U=C@t8bI$I2X##4E!#FFLp>^I4UXK~ zl}@>v^E!hzM6>5i{(|s`Pz&I~W(qXF?nsR)_}O{wl@)VHGEv0WWA7^12<*Qon=LyLgKp6g)*pKO7QPnybL*IrIx_Q7B7#F`TO@pjT+NxdcS z>Xb{*t;FdTTd_Bh;_f$xgfo^l#V2w?x;9Pri0T(KAC|M%Zc5-ry1ec^J1=abr9`7s zkzG}|)P)}M?N&{p{Rd|ZSX*GAz^W=H+V6eA#=HWt9jkibge*)PFlF(uHx>zkV@&!Ej@K?1&S|mUA5ni*HnglZN9=1&s zXICWl2sh^~Lh^|gnjE~xhwq1Ghmd7Hk8icC?4KbQ0U8EmV&S_1+L>5D%tnOeG8@`w zfc0*%bdblH)9=aiIo&(>Fm#lctMBYUMoL|qif{(6^O(;BHD_I*%>Lxn*sQ&(T+8*y zK?SyKa6Ko#TH04{xV+b1@#xrFlxj;#8O1hv(7XS_!=fUo)z%+bZEfCt)mfFhBAD2& z;|zid{%jY1Dxfa&zRVw>_$FZcW#$xP`-Nf_D(fXqD|V%cgGr~B4<}3}8R*|Mp4+;_ z_mq;$y8fI3%HnH!`pPJLkql#Ua@zLrJVgSe2fZ%4tz{kBz0&l@<9xUT*0(T3$$k=M ztlf)XI(qXEmPj6fZ(cgFkky_r7IALs4&B@emxy}XUu>_J(4iEyWEY6Kl(z=Xc;Xwa zBygM9!q??${y08zmlwWVd#`befqfG^*d3X2^j!{RP(%uciYn-7D{YRkuV27+9v%wB z`^e$9?;MZDpuh_GDIq}~OdV1jE5n9rx`GbeX~F8izF1X+ zNtC}^o!~Q=M(%RA^>SxlucTqUzA`vE>PA%jv*87mMwJ=+wg3FR{^_p?z|}X!C!?CB zer&k%ahCe}yy4$WpI^$0>F!vkost@Nn_L}ZluRfSgdE%IY5!7C;BEm3Rfn&yncv;R zL+$z*Kdw*L%6to&@J44f=%>BvN1cUHIA)%#;|=Q*gK!T=8VGbB~AwWy1X zVc=+(yxu53>QKfXmAK14aBN8aybmXB09$mS{bBI?sWY~FQ)KkW9p6KQ2vm3BVCW^y zUxte~lRK?EM{8Q#>DoLwxifs|I5acaph;12&EyNkxV#&sleP4Aq5KKDz8#!q&Ffi7 zfJy`$+{gvDEv794g^dzdfAu6qGL(17Lo2q|-CE;F6xD(8UXSJRC%1|#D?Kh;3|*vH zefMOprBr|S*SpggLV-2PP7;4IfWY*mBS#=5=)~~$>AAmSq|sv)wQfcQ^b)3Gj7Nkt zEP4l1Ry2I9FE9m?7%Bgh7jYu0`1~qckaD^|*qY#r`aHJCmre5Q?jpcR7Rj`B0|a;b zo!zJ}E_XuxZ761Zx+^kPP-@B6XL={#7e#bhO08|V- zO3R%a2-_5J;4GafC!4)3Et|2d>$mQWoq%?=p#oJa{$2(KI{;2Csm>@TxL1x6kC;tR zFm;**T^l`GPZW-O3}JJVN}cae6maSZt}X8Xb(2H#&985-1%DNB;I-P9q;ABt1N!tn zY>Fzy!1U5(Q=+;LcTZE!{ijdk9u(=qu}7K-v-nK4#pNL^z<&shm-CM+ny?QaO^PO7LLd{5L(3-tatBHqGvnEMkXq~@N8-28`8KQJfQ33l7!&&lbiQ~5) z-j6!?VW^2z*ulOE@nk`e`d48=o|p#|F~YhV!GrlM!G7qY3VQBWzH`}MXwC=&>;i%g zhOq7_q^$}ZIXQTI5@dteb=f4tQh0s}-RzpETZrxW@MaJE_A!4t#l=Wu5^I`|fXYtg zSi??}caO=J4SDSKJJx62(&@2kRS&rIb<=2C_w6aFomfmLB2pBCNN$s={4{9cz*)Jm3XHj~2`xA4NQyjTB}@U-Iv zo0`w()ZcA>)Sn_OyS%*2!D73_ykyF*-sm84?DZ{nV&GVVT$HXhmbxlt+L_qF4s+^M zK{LmKt)#~gR@(a<CY(> z`|MIesXlSpgrsYz==PWbvs*Nl!lKWvAaSh1UkzIWr#OG*(RXg8yI-UKS)AKSebU;B zK$2p@HvTt2BF7TbK_?SnYL;a=>1QVu%+I#Yt1-!iKW8e)Xe{9)Zgz;sCRq0OoAfh* zAOVRp3ImZ(a4+=G`Xb#N>G{^cDt!E$JNwIrH^brkz_u_FB?$HP z9np%HPXVc_<6^%ft^#5rocU z)JwkAs86Z8pfi)?k=2=<{N+dcu}+M<9_RfnE)h_L;BGY=`Q#{BOHK8Pkiwj*NuzCv zGSBy78O_^e2X@Wx?1_RIvs88AS3Z`z-y5!-3w6Ag*WZx7)&18;3_E5^$4Ki+%NG_* zC3u!aM4(w)S&YrSgW1-q-@~_Wh4#$xn;LUvwYsTq2{vWJI{NxZY~(NKARy{I}${Epa;|MgJ_5TW9C-w3D_J@zk-5cl#QynRlhli?uXF|Q9vPXVz13b=n#SRO6!4Pcm-s;^})fYm(4yjHd5v%d1|lA7EmMiZ5AfW z;CsaN9O|EuH4+lj^d>D=uuDY7fD{M^H}-xajph=Uo6|1+H=q6zm5OFEH*QIS#C;>W ze~6gzJhR{B2fm==+0}I_HxAyTta}Q5w;geJAfD=QZm$6@&bYAb>P1QW}0yre6~ zM*Mk+k@AHFu;GgVbPb^cf_cUi=If6iAy|6~EQGIJmJ#O!GH>Jc%kqI71-ZlR3um35 zQFo|y?7>$peL}$e?Nlu+)*#FayMNI@ozljTMW)AcjfdvrPD{HXkK7kE9h~f4Zf3+! zx2J7)-Y(fTAX1yN_5ZtE*Hda;_wtIcysfvDY+{2(!OO-=U#FFEdCwm*=<@6V$^Gip ztFVk1{YsiU(I=it$fvPnKW}SQdXS9C@bRxbhIj5b>#J=V)p2s+Q;})jKD}o?-Dl7H z)VbT2jC)F*h^L3mLIsDI_93uDSLQJK4OX*~8;^z|d*Y9LR5!P?P|^kWJ=i^i|6*CH z7(A`wJUhzgdj`hceo)FUW=KgN!Xb&-s*TrvHdGk{TNlu0L_9=Z$-w2Ix#4> z`2xCK*lZ{5gBuMjzl!XFM%^oyIw&SL?j{|3Vf}EP*1f@>bo0FRQ=d8Ur{TT!>-nz6(B9fZ{8qw3j>x>;S(L zaxB4PXad!UCYP39TVh)(ThuojMYzKX-H#^XMCUq8di%YwOWGxv0p~&yfeA`nX$NK< z9o@g=zSd=R#?M`W?CbmjwX)*gb#_D^`+405_MxCa0d|bEJlgOxP86vUb3FXx*aTJW z$cYHg6oPWxfRoHj050B5OT%Rdbsgr4Krdlz@m4@DS(ul4>2uFfKqS2fUqf(XRpv(6 zr7d1_zH$2|s$l}UdS1=yy|2A2^$Ye{c$aMN6J^3*RF8S&=Y+qeulf42)hg$7gMdAb z%8v5d(S*~_1K;D1y{u6XrnqSz+@})y$9?bm0uuJ)93GMSyVD3|x;ulqi;IgFfZbN& zD3)^TiszqTTHcp6?36>Cilw!GQ`_=Te=zbKN1L_&Q8P&o`eT`vz7{Sb!q_tx3@zLa zSN+F_!|&~k!XRFMn0xlMv;0Bf8123rhwc?^%98=t*+{c}@#zwx-mT${)qOHfxR`TXXKj2T1&p*mAGd zQ~iR&PxgqaEPb*%DCQ7a%;)TV_`t~&`=alib$joY(+J+V{}>uS`DVd*nBakDHf~Gr z=}ei%lk)L7>GG4ao;&kasBe$12I~HCaR(A9_QnDx$yR6{nWC{lv828{?6?W|QrdmpuY)V%h z&?k^u8ANCSa2-4!KP^tf#T)F@-(j*yctPG{TFPtDAA7wuShRdXRWn1JGw$bAxTG1h zl|bL@-=$6yp5qB>-+YOmlOu3G@5pnWgPV89np>WSMU1HoW)(hBKW25l=S1_kCS|uR zX8O~YOq35vIpRHg;#gH5>v8bdDNy5ZANli;q1MxojXSC;myE1$9_9c8xUWwu=g)_ zbH;@tf@c~du>jTV|64G{5I=c$I4y9ukY70C$m)tR!?$;*1?s;$i|t1aHu`tL4=1WYDk~#$|bIn~ASXdIYnV9B$3% zH{_h(>pE{rFqcz-lUI7vKhpcWJv(BD9!08?$Ul1jstky85FeoU>; zQ-=@BP0zMRbr$O!{G#w%GWNKwS6IQX?n`1H9yl|{hQ%^9@A`HZn2+itG-k8uOSo$! z6pU3F4QDqA+m|`socAfSFBvZx8|v5coqdtcVH=7^b2JFd{(E_)+j6eRttw}K%42E> zj?3L}A7ltYE`An8VqWWJ6F%oVjX9?rj!)FT@VsF@+i`mS9y*Q!n|7fb|9aFdpSs5$?=rsm>d=a4zByCpF2T-x|AA?N zzzfY&7`I+FXug{I$Dq=8bZCrzUhzH5`b=b<8_sD}5@#^nk_S(o+ zFzU_OAA4t%qSNUIw_?J=h0BNEP8sC|@?*tbd9=At@MFdO$!;>3ru@O%bqZR2t(N=w zvbZnP8OrkPlA2X>^v4A}Ga@V>Tr$>ZaY?YMj^+49t9tbIK6aQ4NfD?61ozwMr;O)f zf`Ze(=uR4l#65=8O*&ilx@C$~?*)QoQLT`k2JvXS+O=1-7QDZ8jj@(B&b>t2SeyL` zm)=CmM3uyi*bsVqAymhw_7-2x9Z%YYp9LDeQ`4eDobETQ{W>q+mCaV~+R7ekC}VytnK1g5yve?BNyZSGvHJR=haV#S3gDK5>rUBK_=wns zcR|fim4j3mz$6dOgBVg}_uRzLHJNvuePKA+ol|@DV@J2(D z8lG#7%;0E9IpX2&9-s1%;WuiIi486?jFh|{LO(-=6Rjr#!c5=GHLu?}%&mO4&1YQE zrnKqN9(aSPblT4O++KU1+ydSwgp_F-Pz9aDQ2FrG6>z|(k+X{pDPh_pt$;dIX{92; z!=j)LVtM-vvQb5;RRAv?EP=1cTg?aJhaC}HK!Q;(=_ zlY;;wCKeRcrIS8S$sv-cYu7Df`O%OmFT%=$bW~rrc&(!s{E@%NeOn$WU94YBQ!DR@ zE6+blUQ{<)j*E%Td6rk}9O45N=wS`?CVHi9DwzJ#4E1IYWhUY$3AxQ3gLbKbSVl{U zo1Pg$9;pdgFCi&T~KQnB_$En$&~LDno2ipH9Eu0H#Om=xKZ~_2%FOL;Ic8hu7Jo|opK#=E^?=Wu6(d&F? z9`9VqK7odZV%BA3XMRU;kgtYA=+)he$ORSR>oCLLy&1D0$r;;mr}67Zh1|6w zXAuGaAY%t;H77&mo&Wqm%G;-*H~|nab)aJ-J#sLMPs8{OFDHy-bO|QN7zkk_Cn;P* z;AdkgXOcAq{PH@%53UIthD+L7BsGJU8dB@q2TAqHSW1Rjw?x1tOwk!{-yL_n)0Rvn z)E-Icr%_Q27oTdC_G{gRuj@VtYYbRjpdE$>NE#ZJ`rnloWHAaeZ z0mU~(z`e){?}8XsMUSw^)RWLFHCx$JCTDHzPuFI5YP?bDynFG{#kpXX-qHn~IT!MH zmzvM>XH>WZD2%kQST){CS*H*)4G_+-KCii5#GfP3MDD3i9suKi#%9w}L*Z zde-P@gvgZkO1HZ}TY$KR=FabpPy9IjXC*cBLY>YUDFHlY5;3lf)^T184_)GpQF3`R z)!NDojW3my-mF>cvejgrVLd9;G$&Qy(vBY9ipe#(p|mF()szyFD>UY8w7siPYm3YJ z*t*5!r#=0e;}hOie)vQWxn?(?Ub_3$!O)y5?1k65!ZGwo#s|HJ&>1B%QP6xV@hLF> zIp0A4qvD=rlqSzv071cEGPiwvO8nUC_|KQe*;J?Yp=qfJ-noRhEapC?Xn&+l?}=SBY-lw#p7Dvnble9&B8Td_aa% zg?Y$cs?TA%V98!;bZKhuh4elV6QDKxDDW;&Q#T?uO^4xf0XMCYTiF-zcrGsT?>aC>Y$NQ-|4~LUCE-B=4l=f|+P<4ZUQry4VvewkSQJt+1lM&{a zHR!Foj;+*tGxb%~YQ^BT#CvfP{5HVB8Er4L zlUUSo!wZ}7eEADK%_^=AA8PYMZ3ebV?l=F~k|eS+xP8rjOnleKx8#0arnvOY&UsPB zAE9N3V=I$0q-rMQa)23u2LjaAq`w}^BlSp<8p)L3xPh#v2JOCjv)mH{us>DVVf*k{ zpU2b9nDJGb5z1Bj%t+hdWud}P8pPOAT&+I#a>hZl3{T&$+ugT2#S;hgoHH8pwPe=t z7zuaR>RBK2_fZ`(y~8;P6WPo=uPsVC7Zx4e*{#MSio=EiqX`8@278}HRJ*?nTh8eW zuJzPRbkOJWu4jOM6w(3kD8iWmt_QX@ZK#3cTIZLzx+oSwo*l}!)yuocdDY@tZJ+CE z6#*?rh)c3t+2lB~q-QGQFAY#ArM$+`(~^>sH+$XjT5{mq;yzvxCk+p4?4zj|FvEuD z=9KU5uf>grs0sxU(1&73MG;(J+=;i2>H}c(6}RgtJnV?TzJn}@5mf}t+x=IUJ55w$ zf9f^3Wr@Yve(u-Pe;wucn>^2VDf6^KyXs*J*yrxvX7b}Q+BBcbml8cgJ6Y5mPFfn+ z`BmYvT?yMjr9IEf|0~f(#*_WFWfqI`n~MavS3tNETpO^Ms!aSkI%*i>;11s^0AV37 zaKw=d?y`zA8Iw-ivVAP*c8fZ-W7oadsgv#|RbMz}VV56vvoh_k*KTDE?@B3|(jO}U zcT3Uu*XJq@)5mWNXa>I0jP_|d8-3c$GwDPk1^UtLlEko(cRxacuB#u}rZ3ksK98^8 zI?xe#_Ze-@>(6(G#BCNnNwQ!r!Dd%O6JMrE#BRk;X0xost6;7hpS9o-jhek!qoqdr?-xZa_#2!l!F@r=VY4(Yq{==g`Y{I?D+GuvgM_2Yq6*fS$?-Z+?;&XFxs8!0P zAS-F0i=SGc!)3$B62hb5-EJ%h9A)GrDHrNpTFZ59=J6LX6RhcpM{jDVLW^50);uJJ zaODlZ0yT>bEu1EGj3mDo%7m5%8Txt;ut2x69)9pTuS&|NY?_$_6Vs-Ss$Qf>XHCJ* z&r$=elC_gffrGt)_jZO>mBf=}JigL)_DW%OT1~FqZ#5nJ1XL*6Gz^s}a^%xCv(hVh zXnGu|(bpMFtf7>k6hzkr1@>51{$6)B=pi@{*PvK4)TjY3;QcUeBP_UBm`v}3IeCVaUD({E09==C|Da%DI9RJ z%)B^sjBY19?2haB4`W^12UJeAeBS3K(CpW02$f`Hw;_>latYpOklR5Xkn1uIM+;LH z+e@RBmzh1UnMh|0s1*USgD961#h{o5?|~5n!S8yF&XL@9BX*3-?%S2*3#%VMoCGl# zrUlZlXsdD0yvhG14J{>WyW%7m(Yh~Z0e^j;+i6>vG#X)%U|50=xX!xT3 za7ZSd8Z8FZf1tB0LlK3bnfn7&q>=bL5!7B0YXex~NqS7TtpVhJbvPt@Je=7i>kg2C zDqHz{bCD_4?>$&;oxIdDdusGMhU*&KTL|>w7FH&hYUyW-Ub*V_>U-9W$_`?nC?C9_2*NP2 z=}&(?Mf?c)lZU&r$l9y=V3|5{bD%fYjQs)P#_@xBx0O>m*4@Tq>jGCz=|hOg#yfJE zOvL7XnI$WC>XS}-YUea&-kK&^b}qQ-`p0F5mtahjnwd~xTNrx<$B?+M@yh%z2CDf+ z9J=cCJ?9#USy$`BF!t4hqEag3skU8f8*Jov##pu%9J@sl;XD(im)mWA*2m#@?hJ>E zcyZ`pTXf*;juq=dMSgQ)qI-Qo`3;*Q6{WXl$1JsaBA+6b2PD?$t=|@G7FrJo8)`}5 zElP))AVZsU@oalV!Wr_e#5qAA|_3b!XL+aNDz{t+9N3W|kA3HLkQi!N|*#CO<2 zVgh_m@PFHto{l=RHVr@nVBeq&Oy33E&Ep? zf6Ozhh2pA*q4icay_YCvY`wT@O;ApYI-;%CUepoGItOhn%GFq;P079*Q7%7V##16; zvcXNlodfcxT0VGGFX8?Gafd=8m2zI&EaK2!65+62-EO|0!MYax)49DKSZC}ZY(K$XjH|5>G z6aKJB?|MBbmCx_>Bsj-&#Zcg%iA2>eYi5!{8=!A*!Nofo6uQ+oGtVL-^IKH%`I;(VEk=wtRFDn7(ZZc%q7oQz`9VbX>wKfVV z4WvM1clUwCr(27Z%hk65G4|JTwrqFPFKv*)( zf=bmhRK#5G|EebmE*%2dLW{Ic!>$N+pzX%N<5Ko|Cg?@EjKN=hS-G#7?@%pNBj}tm zt(lyt%>~__O7$B9#cgXnmRVbuhy`WWEO`8F&U=;2ASLu4oc|zF-cpE_1yL%j^2f@g zlc+Lwvxif>UQ*A&F9~xiEI|;|8uLyFGDfTUqMrYk*bUqq_z)uGZV++Lx_6fgrSB3x zqr&FZE+jg^qFZX7M>^AYI@bhfB(jtOk}7lE*eGDvF|oGOj?qMD1KR z!rJcjkn0zInV}!3IzmyndR&q3D2uoH`|oFqgWj+^W4ZxGqNf?98uruVP64gBr*f`e zFb$PVOG(6xrmTMze^-3)BWUfN29*s&pR5(ayQ#^^ZY{z==c8 zC8^K?PN4tmO8xyLt)iXXirXiHE%RPy8ku@$F+p|Qmx}T!N?RNG$}e1#do162tmX8~ zGo7?ajzzI*S%P_f3}Pv~UMIQ;gTi4zsDKku9+0Pal-?x;*YWNI^rn&$=V2EByCY-I zui;TOm)lX)fO)TGND>9?N1nzB*PI(WPdz~lD+^of5IQlTCg$yR?k448^cGiTO?f@C z)?iw-DtkXEzO+xfKqNsK6WO-^XY)lm`B9-G`gsKl+r}UasL8Ur*$ktlRUx@vt)(Iq zo!#B^5Cj7zP=S7JY09(lU54yZH8sY}8e@4o8qbDO`YbVfY>$JgFVYbPH9}+?3VZ+N z=z8C@>)w5tAAq9}{E~6OuUVXImVIJBQ@`qc?hwUO5I-3NZ=FGbcLY(vgGrI#=_>ALeK4xBd{&9vHVyQN$F;C`4n68zs7s z0;p@NeoK$qS4(yjh}wkt%+mSegABK0HsTntDt1GJ4ev$A+kL*(#q}d~gPg;*Dcb|9 zUByXLPX`AEAP-75y{oRfJMwm|M&<;t;oqU%c;+?9BM+vXS7b4Cv#ioC)jK=J)nr)vs~-0L0+OE@ z>^0rs-S!8@EXMoxe+^I-BT=wt+abdcuL}mUXcCP*gpJxR8*oRF)W`tM!i?2{=6pIO z;cV@#S!1@Tc!(^F*Ft}`ozYQadl;8ZFm%?BGLM$+7i2dJRzZH8G0l?wDF55U!kEkKe#X&Ry~k}lY4&+Y#vCiM$6dEvWyh!2yiZeuw1!7s5UpxzU~ai;0)`EOqu09&>hoDD$&1B7_s%fde3o$=(o69Q zD`}9C>@Uaq*Fw;(0vZ9qT7y)+FkgT)9r$NF?Pj-=G^l-{tj0dXX{kTI0F^eSkgD7l zFX+-gmfe|V+O!-m98D|mO=~oXFX!1YvCu7JGs#kR0_`p9*p7RXjz#(srpR`^-g||c z8snBj-wBZ@bDx`htD<-{=81K;C5Q=prL3_afT?TUD!zWGk)gJ-nM=iSVeb3d@*#Wj z*wFz>CV;$J$mB66o^A#x-+D;p5HK+>)V_B9Lyf2NBB4r6RtX+i_&P|u6?O^?gd_2t z{`%TC{3;UM8xSQrcOY#C?wHaG$p1xc!Y;QQTtn5a8Meg44&{(gOA3ll(svuo$TvA! z?aBLu(NOM0-K-S4>%Nm^&r2vYmHRpJ%G`WbbdR`dvCihQ6yQwqI7| z_zl3k(QeI}$nA6B)vGbX)QzNT9LtmD&}6R<~!T) zCR;XS*acPhw~vx2DrXn=d)s(&fnRBO@xpBh5+BG`Hfnc;$$T>~uJJU5-#$J>pOQ zB0C;TzyAy&{&3ZaMRR7K^2LbG8ToQq_q4RhLd&)VmZ@q`WZ1dhnmI`ru@SllA@(l| zKY%>YHPN-&Ko*urKPnB`g8rT`WV;(-|I}po4`jcnD^pIgAYi9-morMH9zk_~(D#^% zDn~}Ad0cgFHp_`m&r=}?YzepDUI1Sdd|bnR{evZ!{9clmE>0QbN=ChBLHW;n#~N*L zHPx)CeaQcbWjTL;{$rn3(l6p>r8<)qhhfEqdd71Z=Ka6edV@P|(JTDeS$Egr>($49 zICg>NR?&!>)2XuV-%UhI@zm8%Q!j2_!`q%sEO`F;g!YedE7T&QZ&~8HR_HYyIs?x8 z98&Ag2r2JQuyXx+{r!00qokT5ltg-#db>K85qoyQJgYR##zL9yI2J#@w;44z<*uQe ze;_BDB9p3Z>T;HEvp5vhGI9~d#3L^!ddWijvZ4*cu`Qwf=EmbNa)V80NJ=oVPX=%) z&=W0AQ;f$uPgAK;E({1ito2JBTC8w%bSv8d{)V*k>+$x*a0I`zl1S+r3cfPUjIh$0 zMBI*PC81sUT8)r&^FsACj8d+#H}RiXXro+TEkT76gcMIeh*UE)rw~=7lsY=rS!{H8 z5Mf1&EZMpH!#Vb?F>01G)gBxHVNq$f3J7wTRP(*wT184??~j?j`ElBcz82pG?=Iq| z&zN{2Dt*7XMcfc0pya2}1pSd}+&x(7``2~h{1j+taI-o3=)j3ud$0^%60H4$gZnjv zCPs=}PrH|C_Egb}0x#IC1$hD=(W$7TW~Djn(@NkPDI$+FPI*6=yT$W&i%jGr zHBK|yp2M|Lzw}?fFs!c%tEFp!>(PAjH(RYG^s^`N_QOB9!q<)F6_4nB*6L{h9pe@J z;M_jzXmfBe=6lwb@e?wXTTfVOQ$CL-2H6*8^0>Nh3w4&Z1eMD_TB3UI#~OQ@J~NOO z@7O}Kik&+vHas4Piz0#qdglG|cPCe;b^=$+rdq8mipA23FwP3IT4$F_hHT-r*!V4d z*hYUZl4g%>iLyr@U-N2x^_hMHgRD-KwR_2;0K2Sbby$QmrB1c#Cf%Kw1E|?tz&-9R zW>@396Z}{_u?_D$D1$jQ^$nX#bEZBL4Ip$93H}>JMcB2c3}4 ze{_ff(JQ0`nDNK?k&poAKVTYd@I=;=IdC=k9y-g%|1Mwbl75E3IBR~RBfdQvkQ6Jj z>w%J}9@X@C)3^BakBTrO0T5Lx0PVcx`hNgPAo($N=QEkc`hWgurd0U1uJtq(3>$kZ zouKF@fjuO<476FAm>dIK*iQ4oDm@ViGBaTKN!$fU$b*JT?ZpCVLwB+YM^5DyeC1=8 zoLOxlT+HOoy=mB0WTvq-z>e4-S))6!G1PcBXzeU9;BK7TLCk(ox8{a;+K&OWL3C`^ z3pqBBNHwojg|U1O#j*L2`vTh>7GLh^4DMfuoq|aCtj}@Xbv$(H%$Ycc==8ao%8?w$ ztvQ^s{6t!uwwHD5AF~pq)Za#*SgJTOQiL|UoQf*nQ5pCm% za-okxsq!!I4DJ0$T=SES&PI|cS>A91eIFAmD{0lxAyNi4?8%Jv_| zRWdG`@`$ZZJ+SdRaq$@S!>#;dS5#o#0QhBXjUQh6^B*2#>fTd^ld1?kJ%`ZwU4+Hd zp6?o&Cj+*UJ9pXSHUC+MvuiG1NIZIIbfkFlw(qN(0Xdwlfmv^o-m$8mwjq`s_LoKnuEvE#=3nY!VY1aP%DrD5F$3%B z$deMP)x}E&*;DnlI}&?qtYhzwuChFtOpSp_^aET3r8S$`Fyk&0w#greM=K@PgLIz2fPV3V&)!gj;M(L z>BL$w)H#$mgjwPw#Ta%}@81KR+RT@tWb@ z^`XArv)>BdkM*2{eTh5tTI+?V+T)8%=AuYQ5E&J* zHrH^mc#v|&c*L#`eHDO5y&tszn??@6KNXNApc!jfKa7uIr`+nM%nozyJy~Hxa`lxY zlBRP|umK?J$@_WHy5<(2TGA$SN|s*X0iN)}5bf_RIsfGn&)=gm1(80wp_!%3o4fC1 zMjY>0(z?jsqh$MI>+_J8y`vYik3C}IJQ~12eyKCgOlHK2byKuAZc>2y74N)QZt-UK z?%x7`Gxq#Edtu5~S6U0C5c`UKp$Ubv1lh$Gqv;}zy}u>IzRP(ZIo$A93}|q}uN4pv zg4fq~WIr7DcuAWkyv}jAyQU#^AvZ z3}y^|;x%*IPztUf2+8zCVo(foP9DCFM{mAa?da@^eo9qk za8)~xP*9>3p$ImXdg#_6aj<^q3Y*+MN3lN$G%bHz2oX)Wu`x#UB=gNb;Fml$ zJ_Wf(VXgurEUH()qHvWV7%FuyfnbKcFv}hWdy?RAxZIzl!~wT7?+nZ0>G@%0;(HVQ zuLdu6)7I=;8@$AoDXeJ=DQjF^lav7b9(&yGBE8S!=U=Nq;WbmC$@rRA7N#zR%I?0S8y zZ0jc131C?;IXx>m#BE~2dd}u%_12BgRD&6tC6BZ&UO$iR=h#6GnGSvT{fRpzxTWMi zy-#pLpyoK8yw8?Fu{m%T;}En#!f`7zJ*qii>V=S8{T3mXyE@s?w{_P)OaAf0(oyIY zDbne_*y5mR=39|U zqFJ0gyDj<7-Mei^-@R5?-rQMQ5U~+QdBttw_Y`iN-|)AaYMfz_WN9rU}>fx92&*UUQ7la6=8k_F%Vgd5a|-$BOYfzp6pA>bX5Ud{|d|w7nXkKxMxhI_A(7=tB=Pk3%oSDb{Cc0xT z)@^OWssnRAC}+V-qt7_SZMg=6^4@z9xGlP9FveU!smry z6nzTYI(AtiC7$PVpp~ues-mM7L$Fi4#n*jn?)7F-Z&ilXhNYY_J2}avftzOS*n>Wy3;!y+y+aYJ@Y;|nTaDXoCQ1`@8YJzG?bwzrXa+p4 zaUc@CP441S&d<>HJ@7vzvK85(w+$j+pqdplO_(40oMm;bcNBg*>A?8DZ|)NRw6I{V z&t4aVOur_4)Qa=7tEhZmIngy&MDskJ_*t^<1Ln}ue&DEUp8Ig&uRR!%9)fv#J3K7x z3PW%?BU;qP6OI^290rSs!%WM?Qt80G%dWEy`1{15Z#%JG((Vy-t&pTEMjV~INfbA{ z^sz;1OrY3{^MF{T>)Kx0YnJU!eeS>^`os^0MJoV&JJ*mW!?uBLvw|&LITnL z_jn3&>21S=1pW-WI15uYxj47IP1@VQx&o>D4)doi9_C&+;a8gSlQH)Mt;})DftoR| zwi$cs^Xhk1BdCKA-M2(Crz0Xd+8geAGHH>>d+zwr7=Nq6nJC0j>u~w( z-PxV4TPbbROhbpo2j90Xr*9sWzN5L*CXu}J{F=zoACI~tjIhv zb7$T$j{5r$%Aw@KdiK!B83g6vjcUeO*JPCIt+ynJ!lF>;2(L=<7qR0-LyIQRYh(!N zOVHQVZdFX$&dmx3WW#hBTIi8uY%Sp)^Ve0yb|sp0Qs=Na*l}a)DR~fML5*CdW^j znd;!wGuBAnIy%6?5z7DNZ<^RQA<((OKcx1qaG)yZ(SO*YJw)qy@v=1a<7mOjG^|hv zSSzXa&dx5m!=g+gY2hVG1P?Zr_@qFwVW-pDe3P_-23r0u?K{L@H`94`L(bK>r>zH; z?HZr94zhLPEf7!Zz8c+&)S(EC#{Zi+ci^y??!yB7JjtYZ(2)Le;;A;wbQmKnhj-N$v0KgL|EDtUW%{Z9iTdAB!G`u;!1Y$1|E?_A9MyLFABd4c93$X7~f>v-v!X6-If z)r2SRY2>O`zpZL$p*rOJuz(hmjvH8Xp&LI=___Y~&TYko<>*`j6#3r%ydJZ?<4`^$ zTcYSuO@)uQ@_E}}jAhIUS<615>pBX4dw-~LX?X^Py0W??JD%i`JA7i3?8|OcxOh=V zC^3go|COyoP|ic`Kl*~*`b_js8p@Vlt0Hf@A6w*uJlxcQ)Q0{X@=3hXt+xi%VP&Fy z1#5&_+6BzlhQcV%>V$^#pnL<^419G1z9a?^4h_guf~nh-oR*zz=U5Oj|h4%#>Wkspk&a(u5p{#T2rk5mK`-+EuLZCTQk;d z>Z^I}R6R)lYkIZBPC{?K;TS{AAb>zSI|a)>m6FY#0vZ@vn?yz9p`2( z(j3#(xS^xzOsV}CNeD!e%92tD{?DMr!_Y9-l}^eMyKqxs9QJ`S&uw0ae4>jlPsvc- zP2TTC&*?C-#@7*caOKm5!V=VHL0eR_F?+;~jDKa!OtZR6up&sss9 zJRX^ctHRW$2oF1)c=syR$)uAWNZ+~oB90%)}feJ@X4y`5BFKu%LziatD zn|OKRYued%{CDL)EGVsn>cBp2WSlo8M?9w~-JKp6uL`x-m9J^9+NK<2H9G*56{T*q zpm)hP&)3g%i6Hig`;N<@_Fdzn%pNNe)en#(goR=J0v^5oUjT!`?@Jq`+&MP~euR@u%wclN*Lp;Jz|_Tf^F z9&hD$bYqRl1?m7m7gjo7@Ff}iCqE|XMo8GIl3T!R7IX}Z-gj>K{A^;y;Q4(Pev^DH zBZY0ifZ=H%**$f#NrSi3>7NwZ8rd4kAW>U%A=Q||R8*<~Ck054h%P7YU1T80`g?*0 zc4w!|aXjy|-D-OMqZ8!)!EYhvoD^Y0a{Iw(h!~ae=e#J-jcMsp`(5PN(}KU`ZQfVb z#AWribh^^uXnmFD5LwH)W!UaWpT1HV-Zx*l)nrVav#ee7{&$K4x`|%nGHw0Gs&`Wc znLT$wi~_Nn;MD{n0lZ?#1!J7lq zEKj;E4(QIG8kU$YPdac`y!kpwiOg5R+w$Iz6AjXhp1rF-k5J7f-gNbyd+2wM zF|R&s51n+mow=z)Xe_ZUnz3fJA^UuoTc&;nS>v3w^SSC7CVg8A%j%=b_SicgT&g*vX zAp~OH4G1uJ>KsfR=_&E9oVb!c!p`1c5@C3&e5?8ag+^;pgB7;lM=7qI6@8zm{ry_ zfk6Y2L#He)_lE}1WCpQyc0IL$@EW)c0PO`0&4j)(` zNTV=R*BC`E)nBIU^u4jxM|#w0nulCEWr-aP9Ta zziW!9Ylv~ep3crai{ilZqWbP4#r-M&m!Lw**jijdS9XC`Gq(@j6V#hc#luR z=m*O$M7ioISRg2j-}JBxBo$_@thMq@!R(Ct@OV^qRHmuFR9e=(1X82_ zxicR~f$daUGjyyjo9_$1U&SW)e!>$vRgI5qoB9pT(gRlR2gaK#f2CW@ zSp43vW(^ncE8NR!^X=MRKp8X^>5{Im-gHV!Z7;ifw1k}I>%o0Re}m4UM1F0R(zy=g z=V3O>Jt#xM6)g^SzlJZ*ZL-_8_1)n)#XrgC+V)1R ziopy&aoX_oN7Fd?Oi8;gp@yV8(@zSNyltR1eDSU3o!sK}`8*=eXsJj9W>MU{c9%`) zOOQNKhp3K@hjk1PRFvN(2?=i|j8Z(y{n9rrlND*E?ej>oy?@+ydQdC z>3(YUy=~#0A#ARwEMc>v@XXzji)5s1iA=+T9|Aumwuc?Vrz4q^j^YqCWGv%Gcge8P z1@FkKuZ_fE3qCN;0NEiugXB|( z;thx#CH)cbfd5NO|9#>ZzduDEU17>j@23Rw7D60@CN==IuXFd+^i|H?58=ShIC(yx zI)=&x1`#6l#n&hxIHUHI)A~PouL&AMkrlB3jLe6R3jY+x-VKv==Z%B);yn)EA(Jj6kuz~Ik4?WSi#GZbsb z?K~L#(T-{%Y7;%Ly)z83#6jDt+^#yJi|c9tsv)cwn?qxGpK6SGIxijnnFZko~WDJ!NM{dpYv;N=?`y|s$<4}XZE*+Jj_p& z#+PKb8k#Tz_bmKX^@Gq{sfTvCg_vRqotvD71zw}+ApW#K4x2}(= zuNG6j9tvkO-FgCID=`zdSsOq)95vjlWbVWE<607VfC;RDz`>XwAIQmDDp6s+uwa1Z zne(87v#IT1xNVb}!izFEFzJ#P+eYOwORzpl>pe#B&ZIJRseP66qJ!;O{9bb(&R(8y zo;qOVH$u{72JB4|dnZU6*68(#6jh4c-W?+FlhD)8ygZ>Ur=!d}tSk)J}kg z19t2sn|W3`GSqsg<0Up)F$wJET&Ce!`;NWiCtg?_vCC{}S1kGO^{Wp-TVmYxJ8%14( zVA_Vc0|snAh^;@I;iKB>ny=kqB!S@EQHXZlaVe{9Xn7%t1afQkxJfWOjOe8Tk6qm@ z7^qBKb1;_z!-{M3>?6BZU%J1inH793%TC$ibLXflzl6}c-RY@i&#BNA{a7+GIL_Wb-kMRn_U3&@c6?1B`5B9cK9**TdHnZjHfSlHMTZ@GTh+|3 zWd1(u>vFr>8%lYU(HW7JtgMF}9+^rVv-eMY^>9evV&#JLe|V!zO;Z%5RPR0_vn0w9 za)NwWSo;|e75xeam_9A3)JH=%cd{;Np7=}s1oJ8VfQAg;hHl6nI&5S$M7&DQ)!)yW zniBZ7B0Ls5a56Zt9LxToDt%~i5+XnR2zC@ZDH&Y*ziK)Lxd(q(3?Q5;_2E*0=v9FG zAd4wyxm>NA6x0TrDX5HK{6&zF+_V(R>|Z5P62tt^eSzdfiT8>+_y=`JD5Uum`kEh^yVD~U68F=rS1F-~3T5-4nAy}-*cfavf zG4fJ`i0sL6(d8GZ=V3|>1kl9^!5-rsK9$YI5StUxlE%?80P?&q{R5JjZ!5{m#RA3H zL~u@z3Ah{>Uh!;lsVcKBm2f{p7C@QHA`2{IFb4%bKh^gVSfrq|98UGUEI(!9)8A`) z)}ZWIZM@L?^VeoBExVY43yPBK$S7l*4L-1^KCDl;bP|3$EF>+_*q z{ttGl>(0;FWlCyAbG@XrYuruI+CK=d*=Gxx96D@-^fgXWhV-va4C8eQ!i1bzwB4=D zqt|S2BeT5nw`VKXRt0cW2MSdw%RFB*M6##Absv>=6(cs{>goy?^a$+?SPUSR(G zpkKYnlA_oH>+}mjIrMkPfJ;n+Bi}}dUOgrQd4^wefh=EWDY zgBpK4`unwHL*^Uz@0?s;KfJ_Dw?SZZ!5S%zc)gA-Yn&{!bG1iuzq+kzqzLR8TA^}8 z;F%!hn2^RM9L@yBeo#?>g=y}<$s2GalIxn}eSv!#whVZA;E+w9 z>iY0B8JD|RS`pVHY(R4+o@5U+JfAU1vBCPUC(#N`MVHe3@lD8;y@8t#e>vUynAPDc z#t|98y<)bJ{)WmE3Ng|=+Hbv6vS_=j$s5Cdwn**{u$_S5gP#|jZ*+pTHglyNPo%%< z-Rq>z9cwe6(eSf)3v+P=(fi|cri!g!wR)J~V4JL=xHsF~=ilC(SyV)oEXoRA*?C)< z`!`+@CO_P-z1&Q7`v==Jv#QUvC<)fYlWre%QD7s6BuZYzrRiz2F%jictl(RN`(}7J z`Cbte46xBw#<$h%wjHizKN(|dKl0jMMF@VsHQ;XK_l4y|kvQ7lLnfkE3ZIZuZns_M ze$6ZG*pr;=Z%FxuG2sKUgS58cBTtY7i;G^Fkvb_KstwLustR*nf!AN3sMqDP+GL?Y z^9R~*&W%XE9}cSyXY6Wk8J+@>?GuJqIb#*ht)f@Q))ThJp(QbwdHf(;j!l=fiBkM7 zH`u7DY9QgW)E45il9g@&b_DKIpgu&f>~)gve?bE~CF(Q`N+02u*%~zPJKlMaJTE~f z>mzM!gnG*xGr`<5{8p64zCT`W(ueO7SPmGN2_9; z{!vN$K>oJ{k^KISkLV&(>y)rhDfnp{ssokJ-f)j4X0e%Lbf=EPZt6_;^-ZXG!Rb*& z_lFDL-rW~#c3~edI?gf`ClqFJ?($7LwVojc*GOI5ifLiIb`c0h_L z_#lz;b>*mSw-nJ=gm-b9RmE@-RROMtuH@W#b`|2p9~-kCNI06#?&z|LpH~5+Us6);-T(bFZlGmdp%Hag`<*buD0;wYN1jpgt*LZYhiH-MWZ_ZuWh)S0Un))n|hH;T@= zqEbo94PW3*_c{}Ip%0uZJWfRf{9}@l8EL;LdN|f}KH!@+Jsu!8a@4rV##O#_C>erw zWc<4*Of6eO zY`lF!)Ni;+3eW4KTGQam@%00?Md2`Kx}hu@@A$`y{H#leznR}1!`(OGoEcdKUM+!9 zk%oi^4BOn2DK-Taua)9@Wt!UNhmn%SL$)ynpDL|kvgeKp`id0N|FSeZp{)QQJM0TE z{KUq`H-a|ve_;C@Zbu=#D;C2;KQ&ccF?(lcomqk&{4N*uGnFDT1}wx5b14l^40xPzSTT~}%(vr? zFB0e1;7+A~FSl9eDae@Rv9hZlMRv%j#;1PF)<@vE`bBB6G>O!&m~4J*ksSBaT{iW{ z*~WF;6vLtPFq_NUdtHSoL!z86(px;r!vSMi+18(Jd)ZfoD###{I%?E<$kOjurI1h+ zijIuW#_rfnMGhqiwfuj<=PvGtqtI=5F!Df87n(nD{mS_dWfaDndL-lTm3hH2H>Dxx zknD4ceVDBmXZtlKS=PBM_Pv<$)_RnWG*i+McWl*)+Fm^~50|mw^BR}GvVp}qGlI>4`f^0nw7bcc? zkAColpgWMIq)`nJ1F_n5vDN9%iX0-#<`1dRetSgdNrdcj0i7;~zw6>|F03;&?1*?G z#P2T72Fs+t5Cm2N_^*Y~S38o5=l)lDQjn2>{6(6zSa742jzXs^@EG+Ic|%R4MHql( zmswCIr-$3mG2a3Om#C9S8&?~bu%Ew-6ep(ZyNMumhDqwq6Zf;alP(P6%dJSJystTZ2T`Q#~?X^RFy- z4wIeeX*cze*a751yK{;RUkTw>LEoHChm-Jpyaokbeu!WWH*d;%g--U?;@du_AD}=C z!|d$&ITzW|eeok5ydsH$b!C3&Rg%clzHj>YUgK|;wmT-%mCixL zl{18kMK6>w+0axR64YVQJ<^KTzKR(7R-2E~p=zZWhz2(_E-@bDYYqNYt}xiaT;kOH zBBy8m(4Dc-!)3vS9p(50TNn21Y;?((vlov~ah1Zeqjk|hku9N44&TohIpcvjCx}QS zs^GOnWehkPx1HJ4OE`H@YYYdPSKguX?M+MQuS9ol4lVTJeCHcNAoVzRJ&s=Veom^15 z)!k=kQwb`{tG{#HZ)-+MD$AUh6Ar>gA&(ooeJWNzF(I2B{PJ%Ha!y>d1^2Cr&mv6w zbdJk|A*2iP!phI`t~saSuyu$PWc*nKo=_DlRacX|8`#)5ma@+eAcX|DHc}QGoJEjF z3WEL~{I@Wux_}{KXGa9u0e}o56|O^a7|Hw`(`pRnXTU#}0w zej;~!@cTUFw5)SaTfS$Lt&l&gxsXMYV1IwjscfV)*R>y!C4AyaK)yuyA636Zei!p! zH6EFMfivLO0IUSwP{zN~CONL5(d`?wEC*TjV!u`zYC45h1)^L8h1i5B5gI>!>iSKq zw$PJlJqdVT9-XcH5!4}^qpmOCIw(C|XQofqFyeO0Yd&W9b+c(N<4xVkc1ViYC!nVO z8gKXrvOo_|)qXs&_hF7{^7y-Vq#9IL1+vf#o0}I4K|zrMURrQp+SX;Z`BeNrEr5AN zEo4)x*v-YO7=0s?$Hw<%PBc=#>>W$rUt<s0Hbz?WzA&05CCB&7A}9;<86y<;p@~o5{uy!I{(3BuaR3BdOynE!)ywl2_jtJhMYm zBA|4h)`rvt$fVu;4YV6LU=7@7K))gzs^pXf1uBfMG91Hq9=!_4xr{1Zd)gO3CpNpM zQIoseLY0-obFx+|?i+q{)myi;VJC#8B+_v9OW*4#DvKeWl7js{giFzx5(5Swt++(z zg6HLmH*`gfTMNT17k#37^k~H8L;&hW^3(C8k)tDO01oD*6E(kyzV9V;QGY3V$}z4F z6Xt}eTT%X&*=3%xfVNwCk&w@ z`$=q5<;URV`|0nLga}+<>)W$BC^Bd~j|hyyYo&a~0j^_?E)ALQ@t`!mLSX8}XI{pb zj(1(i;%#2tT4f8y+l+m0=-axJZwlhGGVQL{du%WE^;N@k(lNL$(4@l90^1BIv_aHC zL0JyF6=(<{85>F~e`o(b!c+?{hTg8sd8er!k!A8X{#x-j4aFse)7WQ24&zMdu*H7z z$)A*KS4Z*gK87FLyw5O^cQP-Wwgr+cTIBteCk0xL`IH4eM(MnICn|#RDk`$C#PPMG>Y=AN0QYDvth&&C) zm(#QRE1C||Mm<1zbQ%xBtHJ^I=XfA^`D%8qd?P=YQ}hXHIXb0M#Tyg6UKYcpM+gWA zaL~L-p=p_ie5m^8-Y$3Qh+WEv-4yUPaA}Gl5cL-KAAxj$yzqX!>ejsxmgV#2N~h3# zjm&a_df*$q4$;?Kvxo3EU`#TWBv`VneFP11LxVJlTCDS@a$B1|rIW3(@s?Imv#bjN zk(lu#+=^_Hdx+V?53BCQ_8C0tqd)dCS|8)j{h;|MnPHdPHb2K0(^FFlPvZwvj?~F} zRZYlW{(3ngLdv5IQ=ai+345Izy+05!{nXd7{Trku)9`4ouYX|RnFyIPEgQB%&n@ot zVs|-j-%M?O218MU>>_`|M#hz43>Wpj0_C*&p3tm9pbsk9y}q#Bqge(pNO(j*KfF)+e`BWyn^=PP=` zdAWMqpe!WefSoqbSnhsV^Jz;xn$8MV_=5_mcTJ&(KZ;&04XYG-FE{MGVk z_1KWA7#Xga@4Q+T>`T<5W;qs-W% z+ry0TuqB0dSiFTR9}0L>RFw}q^Q9dWIiml*l-}b$6GVoKnrM?eVmn&pJo1A`REOmE zM92Fq0cu*O9op-^`zS7c^K3I`seRGFwRE?0nTx_??)b()Z0E(#1N)=w1U=y`t{YQ3 zrE45mb-OI3@|3BNP1PZdnhcRTLi_H_Sc~GWu>05bg?=4TLzkK-qB-j+K^2mo5aJ%G zIl8O%U-`Fm(H(SPh}k#CSK=IjpM{;2z6+>RynCuUwaP?xmyOo2<#O_qxd~@_Vft^V zTu0o4ru^!YNCHbm*5z!vz=jo+(AR1wY(Q;p>|b=0lTu9UjM2BNI9>py;S+@x+j`}C ziCr!2+U+NsWRvFE()T`@k~N9yXr-@Z#$Jta#Qa<7E{PHry^+MTEvmtjx)+*LZSt+3 zWsXCY?T2H-Zc3dJK4MHcrhS#$e!`&J#VKJ|c=HF`S1`fM%*-7B`;s4j4iA&nliD$C zU7b|B;w@xw)8zHTIRtvmu*oIoD!0Zz;&atQIh*hTTv4((uaHLSIa~z7tH?*(vQ@Pf zj)nLvXSA==q^aZ0>@X~L=CvI5?9hdKdKpATv=;BxNR3@_Y})-{yHbiHq~!2P!p6^J zrYZQ^0o^(^C+4mLpMbHC52w%3wof>mC;J=el1-k=)iD({eKS2Y&ZeU%Sy@(R+nn%( zwcgiJS!U2W@&uxKD@OpcCm{+BB698b&-^>^=7c>CXw?6$0)Xk$ZfhmP$B)m>o@`5a zKqH<94-pNaueTSZsK-WrEVYsGj9gBkH@uss8`|i6|KrG7oJ<(J{iYin4ReNJddcWbc_2Wf!sz$DT#9HyNkM zvG)!gd#_{OPv84{|9+p#U!SY1t8={Huh;YWnBz86r+0vv0#fBTzy{KZClb1y$2^6} z*AeXO?}-1HJ-*evDs!6Ci<(~>)BGiPnz`rf-+Kc8?ya;LniS-aUT?iwCw=X`-^Jis zb(vFA8jXQe^j9LEFyUIAHCMhrdO4SH-A|1H6k?}7U4_%U=M^KT#|r5idp~yZW%iw5kEyN{ksNP>1ABmLIy2GG3uUFCjc>Is6>YF>*w)!f$*!25*Y0?)d zxJ3;0goSoy3ovI+l3|pz90bdQr4?w5Up?3%&T)HnTgsX*6WG}9$Jo`T9CR7u=N!6) z;EQnC-MINBDhhDP3klEN(uf|AqY<(_>dwbL@ei|d!dxqXQT67doX;ui|EO*qh1@h& zIil*_*Tk|_v7gQ7%0?>NYQ*!SXY zMd{v4{+MTujzSOK2FqR%ci*CxIwH2&+St6|+#jdh+3l<0P-on)js#?y9STEu9$et# z<)z4wgWsd&-FoPV4+#y07#UUYCdKRi32)P&gs3VVLqnX0SAx1Ve+-1doE#;+C^80W z4ycaJFD!fqSg6X@io-0Npx)sjJ>!pv=xKrQ--$qXfIYOK=4h`5#PRWE4*GA}ZeF*A=)`Yseix?I zSkESM+3HYkpFMKk|8;age%H4ux}5D^|I=KyvriY6ms23Axm9@V!F6c&ECC+^JX~~= zI~PAuJVo~+!y2YfNf{6AQWG!t^%J-kCC2=bhiUHZFT;Cf%Iyr4*p=l9C`7qiUluS$ zeWT}7&gg285DUq3yv?|tLpvTV7;K1}O3d>$*2is-oY+z|P5*lmSLt?M3Vvl>vsYED z(x00ck}d98IxV?)?W|m~E7OBPnv4jqxfij;5M;IEc}Kf>tMTB7Mj?hQxIwFR&f$Sx za}Z;^3fGJchoCG@z-EH|@9%bq{->S-R2AM9^F;sOFWz=_X#nz5>(3n4LO<_YcX2}S z-=Qj7my0;~Rhpng6vRQtP(PTKcBN5W4(Z%7@+Ghd?(DC(t*%VS97}>l*!?yF#3Pfi zv(iTM{{u-Ge4zviZ>Miy{}E|m)gR42 zA0Wc$ukASV{jg9zuz#K06@PWWuu4pZk>RCe{*^e|@5HAxXs;)%EGYZ@wPf?^r;thk z-490j(RcooCSjV$YL0&1|4v0JlxfP(Bx~4;=2*{OFX1NHSec(ap?ycItY`BvDf)hG z%ZZ|I(a%C}*6ar1ulb1KaK#%90o>mN&wfV;-Oc*mhdf+%LxgHzP+_P@lT(t+_rI#u zh*#BChkH@_k|sb2R44PQ9cnASt$MYIZ9+sS_@|)wv|ZV|y3uWgKQ^s7$@G<=^p0`T6}xq5GH<3Xbd*Mr?6I zf-fJ}CGz~H#Y7%`*Iz=$KNb31AaQayHbI6)lZ2P$mj~TEYDaIbR3Q{nk>T5fd$g%-QpuF8LaYnbATzbfW&Rr239qE{LuyJsJ!l1Ngf38+>aB`*? zJNiCcTPKvU&S%ejB$Oy({x*mQTOBM}#t;u{+q zl_-Qg(Mqw%8(WB)zAd9>GfPVdj5%$LAjYvZZ`xbSAkU839{w>cq=l;bgq@P+C%NHl zXKr#jAgWZFX}7NV+2`s~ZUvsJZ(yn)|#{bQbX@KjHan)&ls z<4T0_Sx$ep9mYxXTK~4lt#FsexY><5f~OTjIQQ~2GgtWOHKNDPBgydt_*VOehR*y5 zq)_Z6LE`(Ww}ggkyrrHQLw@`H=1B(Ao7Ks*N#b~%d_qhyI)2n~5raeFHOd1!5<UXwdiQ)-vNYYE6lJ&9clPcC3Qn-aC#ts+9Y~Wr4gYfR>GK>k+CtkyuLH;Z%MV+i4VVb4-BvkYF1iu9rPcpsU2a5nsGEd* zWXM1`jQVkVnN1AG8QH$w88h|6+{w<>te}pc#CVmq%* z>v~#buVqgVaxMfnyMFqSrFflY-;30oH|k7>@~hOeFpxHd-=gx16z!02G&4E*lRKJ$ zy&^0ZUL4^Z9v${j)<~m2YLOyT6pk({EM7|ifnLjsrL4~#l#zG7`Mq#X&a7|dv+wZ& z{YS7ltzv%ynT^(~Qb`7nSNokpo5*!S{;hV6a#&9BDm5%XyTz72crjmS|K)^|;stPCXM6ZQUZ@WXGukAdzXfl%%DD!Tn3+)s&7cXyX77;u38QMGxG^`@;Al%*Tci)4V|8`F8Y>SxbebiTqDMn#2>#*$#)=lcI?+0h zr>Rzh6TYkNYO~Dt2Rl4S!LVx0gylfWF->tGQb z&V6vS%~O@ENO|k7LhzZ?W>Kl0iPj-J>OhpM@+S!6HK&!RNhtg0)gTZ3_;!1bXyM>)w>dD!ELHThYnG_EATDe z*cIVFPk|CX+<(D;+FgNWK9?tFSnJmE;_NKD^DuW6kAAj~HX`b{o~1~4;+?w^h#m4g*Ik2_D9AJ5U@b49IGc>00~hit~t8e+K$kR2;bUvtE!cP z8)Ems>r{ih*fmGM%vO*ZQAN79**Q7=J!|Qc0IUG+8cx)iez%&qgg4J@E|9=y+}Jy) z&4B_w_>AN8Q`g+K8Mpb-9e)V+8+)GOp1TZ&9;+ug#9iKGps~q)^Ct^3nao40w~4XMB5U%IWd=2C)LV_Od9&Hp#Rz$Bg8`mS z#6PGW-b9agZRJ(lNzy-|9^-}qwMPL#QM$4e56 zgXs+1iHh^UmB{bpOMW8p4fF;iVJlHtFXV$JCqT*)utb z>ys^d#=S`asNh=G*+&zQV9nclZm-#vgsCG&(!_D!Hbm0p=-|w>Yiwm|)MW2gKc7~q zgm(p=CFL~0#UO_PStSSNjK`OZ8W$r|Z*Qpw=i?I+jP5XBWfyz(&e(8Mrz9lQzV`1M zMIREW(8Xou*X1_al&O75P4b>!JpbyM8ESQO=HGZ`*NC3|&~*C*#vqR=;zVc6()|p& zgQ4I%ub7|5O$j%rIE7#XtXEKWweG3_&Y(a#RQ8<9hjMnsr`azm@%$ZyiaM z0pHY1>yn|mGHKBg*!h5jR?k?KF!=C$gFk5h%0V#B7-TLBi;Dn;NUg}C-b6bmWU;v} zlW5#CDHym|<5p#07Pxl}NCZfgf)jKHBInWY7z&D{_B*2zU8LpWBU2TsP+KD;tdon9kF~al)ndsWyqInGgOG5B3SG=7o88KFp2P}!v zA%alkc;2}>OTfqczSVH4k6b9nH3w3mdp43Ef*qt@Vc$%hzQP*PkCvRbNOH&JmxbsD z^SM!m%|9-u)8gtV>78xfr~Xdbqb-!+Ck-W8O^}m-7bZ=xvIwcAH!5Im?WV?jC*d zkIVTmlswqAgK1ieEg4%(@#GH$VpeWobEw|ZegbWJ+SkW9r**Z(?*mB_Yorgppyx`Y8a7B{*QP;a%BQ6iK<7tyKeH@5BF<>Ztd;u!NEzwJEaJ^n>6*h z<0^XY$hQSu(|p7Xlz9IV*ke}4>&V1CcFrCnaXPWEyc=l5o#CDR@jg!fFf zV!ccAo=%=IRpfnM>`oQx?URybnV{*sdNSgLs)M`m|12TT%Wzs00aP!KwX|qg)c)EqC)VF zOLP?E*?R37VSIr+RsS8mf*;=Jj9Cbbcq~MbnS4Gl)kEzPS!x*IXLURn!1@~)=O3p< znzIVZ-MCUGXk@@5NuxlXths<0;4$lUwGESqYlR&e94}xStH1WbZTYv@a;5JvQk-$} zj86fp0Yjp_mp;;-QiFPD-W_k|sCUcijauV_lhslgj@qZw_}@8u?Iv)I*vXP`X5RGJUjq$%68ahksk?Cec=(x6nRo>e77V}D)hNC2LpRgfu9ij5Iz zfi`*j{GW50^7ZfrPxgEKRf^Z`z5MCd_tzt8UBqcC{kW`|Ng>ODSv?ZTo!2*ijhzQ` z1ZLiGvm|j*35iBH0^v3iag~vYUZYHSmY5XxEZ*X{yaynAl^>)8yJEnxI#T2=*@b1; zoLY(DmyUm&y>sV$r$+8gtR@-Pe0R7BuW#2>_|i46C438U|MK4_%M@yo=QZ38tVe3f z+st3A+>Q4q{cYwnLYco@WUU*4GZ#AyS{p6A@mgE2>&1hG_?*FBqW!gjJtj6KYC@)E z=M9fEx`aZI#vbQn64rr1nn)00-E~+rh`Jvb{g$8mvBA5XN=f}ALE~4f#aB2(MMXAU zQFnexx^w zigOCHHXIrG9!oYX|B@RKt>4z`MU6gwlDEzlE)?M0^QjW%M?f+=x51eBAe;O4s9fV# zcS(e746ViM*SDX|5% zd@82|1}Tskls-_*{9h(<2k7$?2^m-XGnUaRDtB0erN@6PX)kF>F}5CL*`c@9g4&3> z&|bdg)ib1TW#$=zJ*YUWG_U?YEr1|GbMrYtW-xcHMMnw~S`m+{(H2du>ESqM|6)ey zoTAt(sdkj(KF70ZCxj=~9xbYU>w+y5hk$+@WQ>pv5EdiT_pww2D9jb@oF3>!c$lRL zQE=2M8hC*rKtv|0Z|XCR)$?iO#-sYC%PX7y#b2%TYG-)7!C%PjbN;=6PEWs^Qp*A+dr-;4urj5=E^jeIFeFp zTgN8GUIncPJ+9}U*O=C%u~sgMgoFDP6<$rbjoG zd*$;&IV7a>`eXoA#~#jN|Bg71JuK5ZRD84Io!p=Hh4(<$j8@ z|NJUb;i?sthrDngS=9#;@*n=K>J%?vVRFGPKs>BkX7JdZzt9)2B^;}rFl%SEa ztKahJHNME9xp&WN%r+)Z76l**t#DN3Xpgbde3kg`gLDVV!~j{roGT+oeO@l!8&B{B z_>!$SsU@3_&&d~4CMC5{kt*H&nQge81fGdz(-GAq@#aXw&a>O}WLz`K(A@~ED*X6Z zDPZ}2*70e4Al2eX>)A^##*D2A6bN>K~JW+MFV<-V9l@Ji|U^Un_R) z8?Q-Doy%xYgB_f?>U#KT@N@$%EE9mn@)S?smu#l{FzdjXGuhntrrf`ib2U0# zhSQ$9Ok6#7Lo{IZ0S$8py+HZ47Tv_C!~WNeI{I?uior!EU;Ko{%=|a|q>cg9<9IY8 zYD=`KJ|cZXjP80@)%e~JA#9rh2IFTWlxKr5gM6HMTM|y6KU4-})gIqH-5 z*wA1{ARrQsO=`Cz)P{hM=jqxwl)T_riORiB=TxS{9eF2SMU6KKl(y32pP6#&p>ww$ zfg<^-z}5pP3><#-m;SAbLJR_Uh~KVvHIlQ$_#S7#)`bC}n?2#87)YlPDB04?DFTx8$CtF?}?}Hf&$L z9KmOPfOMVc|GZhi8RA}5s;_{3R9~`h=xxDi{JQal=B<9s`5;k!j}Rjd95Vc9akA4{ zbEzz-!_@QeCY@Z0TKlF8=kt;wn(_fNLB$0g$F*~3w)YNfxQq38fd%oOC(Z17b@oU4 zmjmwU*eeFW8^#8pL<>ue#~(KOtmZKAYmd^^%D)UH&vRI^h$l2>uR_qzWQ4z`;tepQ4(oc*@M1IqPmSPKEN8kD?Py(Z!C0ncbnn! zVMynD);^#0<4p7l;GA{_`>MZ?JX|1vr~_*sNCJLu$IV3YW{_O^#28X{VttV6Q?cF2L65>@%DE|y59J(AC zug}mTyq0QJW|g-i4mrusfyGYC6QY;cD6*PLwwW#blq=hXsuuStWT4yWt(wy_V|m7Ik+R$ z2;C^QVE>0iKIYueo}@v%alAceK_1v`jzJJm(8<)&Y-U0FBjyN_NMu35u(jnR@~KYj zj)yp^WH5bQ{&vVD=5c9=o1FrJ17%%J=ds^Rk7&VR#G21U$nh9nz1^NKz)mZpN+;E| zMSN<@Kd&b7!6LP-lwQgFk?XrQPMn+pXO~4h-CRHBaZHDA+bv$+>oyve!C6YJz#Yqd zc>b5TzyE@EHrhFp_qI|F`0O)kAJ%FsPkdTmLQay{T`IA!x!iI0}XE;^Ytf1|##~tQ(p0(pOU?JAz zj!fk0eBPk3;lQBAnOqQ48t(Dh)RYVJZfs+xe7XD%%XcT^n12ygsGEa~4s?q@5{b`v`6Moe-3AVJ82K zBJKUk5(1u{sd+Ggy9#rKX_R)~cpSU9ZuH<=7im0qs-{_w{ERg6Zr-3|U3#y~eVFBV z(^AIEZ{B!@)x4>`YlMX)#OnPurHGc7mBfE>_f^-r@g81YmiypIflK%J&>pwqk0DQs zB*q&HIx_z1NIvK!h)C*_<+Y4$3;o^8{*HRx)O+O-vC}it@5FK(zAV@OFfT;;EmJyu zSGQVq6YUmz^s9|jwjajl9^^aPoD{jMjWG=AnV+ht%z1Fe9R8c_G(Us2Zk=R*Dty=) zE~=@V-NOxni27K_&fcHXuKC|Og`dYWH%x>X+^$FT@8=gnbf&E_8fZpaCnrDH!NLew zdpkF`06>#4I)E|-%aXxJRL92R`73b5)sW3x3*7`RXIKWps8ZoF(C|_W6pxXXQ-Y~r z?Tc%pXzt{s@$uk&c(B($I!fDghNMoXcX=B~5NTGakrvCqjvrG=Zs%o*l7zwOWF8L1 zt^j?^Q3E^b7Dna~WyYAT72r*NH#n7aYlA|Bdbj)Sxw#x^9lqx8GE|g$peLW3yAQss z#4E6>BvNa5q%ZHFepm-obr0mZG$Z{&TZ1`XC2A7LHCFl4$b*H0!aUDyd8*l#W$obN zO%D^+qoXmlPZlle%NbifFKr6ON^ypFDF(9pqjHU!nA2X5`7aPG@17wJ7aKWGO zDb8Uy$Tz5cfo96cFygMmuvhY!xj~=WULFKW_aSrwB-rhnnzi=Y=l^ZLs!a*nMmD&7 zUZ?$r{ej+2>-2ACbY8FtU3E_*jTdn2o-6gRMqj4~NbWdf2hi7#MVI~Hb#R&gR`L@O z5rL?mxRVOgD_cN|kvng&VHx$akBbPeT-iI{hK`*4{dyO5lwSHat5dj`hn=2JmW*sQ z@x5ib;=hHP4p|b4RFb4!%wyvu2DP{mOg#*7t;id>PF}x=WW1d&WgJZ;Y|ab?DtO<{ zf;lEs)2d6*|N3(IZdpfd!)Znog3&R<`q# zh<~oAJP;a;kCTAVJ*DFmTyVpm9>^_wNaA47hG_-{w&N_FTNlW%iM}BNI!%+dnf|5l zQT@gCTu?!k){a7Jpj#pjUDefpN^u>~Q0RNOgl(g&25O^ye)H{U)0=x+aa=>- zu@-rl;Wh=o_kpXOGYeYHMH+;1y{JCTZUOw?fDb6=&H#Z*?U7;4Y%uM>c9S!z4cOld z9|INaZgtVW2%Dd0`k8+X8_Uu%y}{6L8Q)vaweQ_iI_)?keE2oG)kbEX5_sdG{xbWUu*(wLJ_QA{?qLu0^%H*Fd@5 zPg&=rTthy~TK|e~ho=hg#I;hgdvJGxNfd+uKeOUXM%{RZ8`p=pk+D~gp6RNllTP;w z{tR9V7m;x_dV?*51Ji#AB4P*?A)W;_7zxQKA+CEM&5<+h^@RkdAT|V7Y zD(!n`o6hwT`kQB@v|Hbda|TZc*SAXfCo1(;<`2;o8U}7y#=cSyHB`Xn!)>2=no+*U zNoqeMhc!zlTc0YFPy9cO)jql9!V|=qz0+3_)~`}mC2>uyV*v^d)rDi#8Ag>qi6N|+ zBWj6@nG34^W?%DACWdrJe;i3O&MXQ4Ra-(V8OnYK6_NAc9P=--jU%Aqfx`jy-#goL z^}q*!-{P1bg&xz>pLWDM@TUF6C}OVeP=9RWj1Ti8!WXP)lS9IitO7I^7Xg;Eqd`#V zlPBh<8%O{$XCp%G-bVH$Vre*Lauao146FY2&v}8bO)E9{m#pXx*Gcz=it;Tu8OW`& zg4!kLIn;;0%_nh5?FehkpCH^E^IDG^dskS`>A7)k)Mb)JFKWY%kyi~PPqqQzHLQKH zt=D0(_RWvw$5^D_x2SCUoRzWjHT~e)=(Kq!@V_eS?c-H|g{aJ%nNSvI?YzAYZxs&i znWiX1uaCG;PGjIYFiu>(oV5PO5S^sSoCZ4`kz+f1NES0TFB!1PJ5pip@z7Q;$a!uZ zPw#NBpUO9nwqLg#Ox+-)LxL4J)$Pa=CJ~6~~ZQYN1^Y?YaDK~@<`oFRxjgM(mB%jX-f)q>W=x$)| z>g8*KkAM9V;(Miw$c?agSH*F^^#w0)RfhC04e=McUT$xVKa$qxu(LDl{wZkw@Jd3m z8j!SOMLGZ%R2_bE1EHr`Zs-3ZJ6S~KB6RtpNkoTN#plGgP4Ax!>Jgns`B;UF@X`Hx z<(=7YRn5P&b*Yl-u@lmt$8KhRH{skY>H5wcG01^V&gTsB(_TrpPkPIro;qUyll1Y1 zDx>)d0IA93b9bY}+7K%Bwg4b`PMw@%y_vEoqN>Pa-eyN9im-d#wdI$aCHC3@pEnm? zoaSAC*0T_LoR3&6KzSQkNLSaD|9X1L2BSU8+)4eNy@dOB`Sn|PYX_^1n8M|*e>m5Q zB~qbLn8n7gs_y=iOti1t&foHxpWlo7v`qf7=ataP?^%ZchydAes~YbouGG`XgshFp zu8Ll@Ni%*sdqJ~lMYNNGk&oNB)kFYOdnt6h+_7Thdqzf=`JL<9FwV9k|AsB9TLIS! zR4f?@==gtyx6!MxpP7an#VdyG$gbL!gZeXXIHkOT+9da=kIDN$BY_y@Ulj{C`*x^Z z@2m$DARNQUq9Pl0y0M*%fov*{BMz3@EG8pKDbe@#a>Uz$b#$?vRfnk^vE12K!_Kbp z#ZmgR)6qq=c%SAI1cZ6?BiG_Q1{+4R9A^K5Cx zL=+QuO~~he<1Q>1cK0T!D|n-b?+I32roXJA3yNt^b|5j!K*xV6hgr6}mMqtIQdP2r zKRyBLwCsR_hVjz_;jIZ7->;56n&dQhSbRNubi8IQ7Z@=MU&jruEbCM7+|FnXG*Vo9 zt}LtKWOwvQ6hsHi|i#AXhU<%WcnVt zMz2>giDEYd9LvM=W)0MFELg4!#@~OzRKHEUxkwa=NO!zd-h}5g+Q{_~zm7IuKjg0r zZ?mHjO4OkFE4Yz!3tm|tZ23aq?2m?^21_@(GgxnMfj}b*tTQX&*nM&U6)PINb6Z?5 zg#8wy-*M?NdAMd;O16Oc3LN0rK7gV%c}yAj*G~=|J4CpzC{?m)w&D(ggFhr%HqD zB6kUMwDLrz^M)uJ>-Twl=>C&}-1LEJh zQqh@S)Xg=rReWW2A<-~CJG`xI3H8FlbQltKHt#q78e+*fQnAcO4)8ApVrumk0Y$A&eJTw5tmx zrTPaf!96L;sHE8oDx{v*OK4Lqzo*Mcb`jIg<34anJZvD&ZtsCcs4mOi&hBm9v$O2qfIS3F-z5Yh_!QAY zGSv(0zV|=ff)?sRl6j~^hcdJ}SIsO5k5 zTSM3Ry!T-Z*!; zO}@UKo5^QtaDMc|>SJeaKz75Sx&jq$KfxWXLzX=cbuzq_3!iYeW1OtKlZfCLl z`m0n&4u#mM#_5o%B8hZP=z4M?#56y%N4 zMVa#bbwm=|iaVz;eJ!^6*3CR0?cJ*kYQ;#-yJ32nEYRlqU9{Nvc&M8?$qJry5fPEv zW3UbKaQ3ITr0O{L>o`IGq9;mO6MF4-Ciy*^ael{jxCP1nB`9C7yY#!locU^Fo2$|D z=g&#OF;th?TKm?k=9sZZk>p-O58RQ@hBTQ9=@_R+e4*MImxiW4)_wbS`4^BWB?^yD*LUrdJ3C_MIP9)?DBsOou;oayUs(KZc94JZRv*%MZ!5bBlP>4(sk56=9za1CsBAhq)NK4pKWW9YtP>m0 z-8&&4Y<0bh^s`(CF@)QJH>|ROIq&FE{V1G=&C_-tekHEi02~03abnI(5bw;zT&AgD z2Qjqc&Hk*J5{zN8m@E?8y2-?`(8eYelN$_)%nr!p1f#Q4K8=Z8;%uiVPMc;dHM z>_&s17_|-;V|2fLb+4iTiXu3`9?S+e&uZ+h6WKtyIy_8H0z~C1VqL)4lz?rgX{JQ{_(RPbs)4vKBulKFKXoi z)k(m4Uhoq#^q3F4K>np(2kKAIJo{&=vEt17H7L)a&p~t)0QuKDl~&$yq7U0eVp~o4 z;#pJAH&;AJkn{`yF5}qc2sp4(s%MIfKbHeg-Zr$h`0gYbmY-G0e&@8WZ@Op1MSmsb z#rCQVcA<<(d9)vLT5y(@6fX8Fa5d`)pU1fMy&eXe5Rcoo2JY(RPs@)IL4vw-lhV1OF5hsQ>* zyK#-6(7)5Zu0PFH9?Gy@F7O1qZ7bH>jodj5SQK_7Z?JKq7HG7&ue>zx^>lDJS-@Er(8-0r>Hw|;i`|+;5!Clti@BfL#eh1G47beC{ zdoW(i`3^|*_KE8k^IYZvNw0>+XV27pEp$(M(PkfS zTeO7Dd8?TFISDB_=cxall33Xy+E`)`x^%!?qZs~eX{N7QY-_W6W-ou&kiwbAAb6Jg z7IJhxL<%LYP)}W$>KpEkj~5yAE^(~-Kl4{?K*E$w`Z$%pK(daSpBv-Os`S4qh$sQk z_3sy-RhuxR=Wk^FzyQ+VCwOuPPd@UTL1V{(9Xvn2g-c*0fpARIwuI-L0tid_jfefi*N z@E_#K`zJ3%GJKPZ*JBm>T{FVmkW3;o`+56rmcVTa_3mgCwvE2SXhFa`y4e~WZNR6H z$jAG_*=)3Nd|HXH|Ao5R4c`oB=1-}6YF8|(u=zrpn|+e=l}!u@%(Y5nJbb%q1mYGS_O^2>nWhud0zVy3ZWT?#4R=@1k*|4$3xQL{VR zeO@5igg@piLTPu?`FC6-6Ylba=eKwcheg0Z%SWvGrO3lQOuW50Yjzs>+83Svql*FR zW!HK$0sO7>5ndN^58xKeVg$$nsO00}79xkwt~P9D(EH(g!FCNoFUbE%jD|-jdF%#8Jo&^2s~)_Ci5dKFg%?fuJ$IJuhz}k9dNeu46&}$91O_&G=dgS&?g0B&;ql|rWAZ%B!^_7Q#-27(#oz2<(r zWAyoBNL)g7oL`v;mRrEc?m_+yDPwZy>-Nv1Lq>`w*M^3mf%wnI-v`lpoua|5T9%TY zV~tZ{QgN*&AH~!}od(ZuB!HACcr(gg90s9Thqu+W?oJ;lU9nRzZmbf#4+#+Ws`Ary zYfsapATT0uN+9C&I+1h}y_@~u1} zf}3wB-!~*ni!N3}h&pVAEip$ZbKtgsXFk4XKnV$Cwb*c-GDbNz@xK0Y6dCUZ9qL=x zNw;@ho7+e}QB$ujh_BMw6lNv(2ZK`vuwf9_p9^BPzu<;7Nc*qu z?$I?G%j~nyU7uV#<+9l-5w9Zijym|^*YJQzEskfS7Ri6K80lG`6J?T=Uv|`4S>7@y zF=UbQkq1j|USEa7+DrKB!MWex-+#(ENiVYV(U9{M<*%Hym>!YyfeiL5d7i4O=jkyX zct&mQvm36mep%|7uieHf8!(zy3k1_t#G*i-3{Lu*{`=AsWNDXB%Hk)rEhP%|5%i2^ z&Mq^<`D1XfK_%2fc!Qdo6^$_DG9VS7_}~QhTw)*-sxyDG=>xOs2T>6?@)By;G}4Xs z9!AO^E`Q>q&8##Vp~7@W(_8SRms+fLD+%71(K9dPH-9U5Z?JvuflidH@0^0jqG{0f z4oAnqjD7B=OO>J_p0HEJvAVsTrCN%VC8+mZe8gcUCG@CqcGleHU4bF&o6}Nl-`v=r5=U zfN?(Fa-6qZ#GAk_D4TK)dQ?CSAsuo&viwJBaNL^(KDu2fkh}l8`^?kd>kKPAw>5Yr z!Ku2vJcfg8oDe7(rR3tIu@p~A!L4b1Oj><}7R(xcT%Dsxk6rIRpGw!8w}Id4{C?W? zD^IpZlxO!{`9KsOa{6vl7p7#Vdd1D-7K#GP`IiiL5m~QoIl56&!Zs-|YIwjQzhup6 z|MkYVS+|DWMf@wAfcA4mf|$AZAKctzSJ}rjKGzuOT_`u%RN~&;PA?p50gD=xJr z#!)+ zS!5kJV4B6&>^0#n&?30Snq76J9+m**Vm9_OG zm|NuJ)bXDVED-FT51~cLmyW@80jies zJ}w|rB3E2Zy@5UezUxhzYiEKA`(ORPuO&vBF5WH@AU%~utN~OV>>1ZoFzSY;b36&{ z9YLJ6jS47cmN?%3HdRMch&(oJ4T3J#b-g>VCBIA3??_)E(CqD-1qz1I{ z^nDT(#Ttsl3aXFnoxHg4-q)85>Og_l_dD}W3yFs;Rmb_qcc?)?(@vXmj?u<0XfU07 zRx+=g7UM1~m@cZ}q0dM%8@ub4!J^>P@}`xBW)~y5jJ2oHVMtt)ix;m>4?5*&EL7J4 z$3l1eqB}8L)V^Hx{nI_xoECy2(fLp9gHcAZAdj}?(bd8y`FFdTel2&ew3#)%Dq>BT z1>py%A7N%b9^ONx4w*sMP%VhA`Sx?u@@^bh2O+2mB7wkWSNrp)w7heZsVn6p*cTm8 z51}X!G~PCV53G1*bSX@AP@E+ZT#kl@0;tO~`9+4OM`llfT;SQAz`>BfwKY-5IU9MP?H|$^j&dlK%IwZ&?=v%=7IjO$UQCGOYMe4w_DW-U+Qaf- zkj&;LN-r2Y<%~ScJm||@&e^qL41LKd%CyA3B8bv8{Yo?4imI8rr!ch48zsWD>#AET zr=0JooMJztg6q%XI_y215zn8Q9m;uOZ#j$%O7*$Kr{OSCn7TQwg>{YD{^%_bvtAfd z86MgZjhP2oz>a@s3H}>vSU-g~b81Qk27wbntXd0Ok`e4Bn5kiEqj&bPHC%PD16Z7P zy)gN8TI+3d5t9cUZTrj2vI_2fO0iu^V`{$fVlz8WT_cvzjgKX_b+whzAHL;_nG|_j z8V0+fXxI95YCrVO`cUMT1uZ@r7eCnrfm0w3I}VfKQu(yvU<=m`bdtl=D5CYPjtU@f zX2T+{=@QAio_DuggZgHf9k8wyyv7drE|&+?&RHJan~x8F5wy0Sdqyl`0^yLm!@7J~ zp(08i$H2xHNO@xiv$HL^O~M=hV$E~Wy{;yZCHc3Et9KHcrSZnuNft}AcY4=Nz{UFu zAVKc<)PPvLcJL@#m8>pWdyA2;9aJ-*)IVtVbR?BSm;|l!7@P}d$5ZjFX%7?R^T6aO zn*Krzo*03Y%k~jY(iqPUayoG zu^i!DQ$n8-2;A;phHh7S@9J4DnB#W@%g)tb-1WTmtbUJa?@zp10FCRBkay-&(C>xm z@|!5R^!zuE2OyF3WX1RV&ivy1VTF1N9&Mpx8K=psL}E`Uq+Ax{Fa1vfDF8i}Y(swm z1N>Gyo=?-r{1$U4?jwVy;4d3$E9Pb}l)ZoF`L{HF;)j&ryN<3$q!s_kSipR^*Hz~J z>3sI$*%zgEKHR)#uK1CyK-A!Z7KL6+5UI<-Qv}J^aJg{fH#&QNio4Bn9V?zaKFgr7 zrN6qeYWsTlW7c~7vE?AFWI{1ZZkdFM$vXSz(!J)s131x-BSu0HogAbbxRu_g*3V(< zhMp}@2o&N9AN?VGHU29pPj;@nX;?}!BmX>^$zlB3>7(H>wQ1h1gsvo3nZhI8s63y4 zZ?rQ~SXl<{_G$E?gTrHEgF}?LPc+jHLM$}i@;bjsrq;-f(>gn8lRz?L?hfWpGR4$K;gJ!U_v z(mVqFSV=yLEf#tTtMDLl)Y&cK?A|Ts)T?9rY7A2|f1s;5jrUQ-+nqZ(Vs{yiZY(QX z$lw-U8x(y(4%|as+-gU1(`s1GWpE=}%&&B(1e0nOmz~fq(b3 zWn$J@!uq;kkXrzr2E*>p>etVSeon53sqWRF<+gAf<1P+~99R%%l!q4qyriXtm?m(- zUxS`L0gOZF?D^`^@(boJjeD&1KMYEmJ<*HFC_0}|8ys&c1H7JCR@GRODH5B^13Iy?xm-q~pLFjo_ARqqD zSLtg9OD|+aJy!*-AHdkB>%X#6TlUJqKOHRi1GtSV@VAoylq=A?JDxv$Zqxx`UW6TXzR|sy@Kx3r;$AXA)^DNIYO) zYX41GKhE8${J4FO-oC(KZVzTz5iv0tpl(1GcZ`?-giRNhpaB%33H} zWQs5tN^i+pmXv)-$Zl+dv6f^Rin5L&G02i4JIOL{%8Y%ojx3FRWbEtxQhmPPAMXF) zK0bbMT#kbob6v0PJkRIzaRzzltyy}uLZmn3WYl*$tp$42i#n741DY`OoDTnXR_)G_ z5cO{kYl+|}F3_L)hsa}7Ayisf|zWeb{Y*FuiFM0HM89zNsSeTW{|hc1~y1})B5 z$Ycc6$Nc?#!?~&$@zxsoASsJka@jIKCW0DO5l~*7egp$--NQxaX|IZMm_`#dbmM%1SRSio#l~&8aqe0%D!F_cKW1 zy)EXuAe87xLsWX1w4oR^9Tc!yP1R@oju#HeK8~`>`Uk7};FPjCw$bqHuv;v!c_5{<+|#^1U->QMc@J7$f^IZ2 zTpfH8mH_;4{^fgccfCAz#8owF=jicuyz>CUso)KsiKhC^JGug$tI_6$63H2cK7Am+ z!eDo(KuHwUKWx6Bk@MnM2F5M4~wDl3$pIC%Ejh7>0FhDVr;uriU~Wr z2n$nh^vJn{$m`x2mLpCYh#BM^1Ss!hYHypEK17;yK5)s{^~63b5~HAgNR$08OO$Tc zaify`LC#Zzd0m=L(_w@+T4hG_$8&gVbVIU58x@J(IFmPU0}HsqP3`UN7u1zJ@qkrV zR#EXPL9w9$5}V_7mtP#VF-9n_=<*@#TyFIiZ~2wI@dp5k6>*=A>cm@4 zZS&qd_kxOC%aHg=+n}DPQvHQWRC0*qQg`s-A($Z(W zj~9KFW=?`#Ng-I7|IWAWiM@CmU2+BLf}M9O0a&cK3pW3?vsF+oj^A#aFrF?Am>XI% z&3#ZJjyMvxq+Fq%$_sxBJ=x;%&ejn3YdeU?asY8Rb#Aq7tIsbK-k=sp?^6XDCs~#z zkBbk5SgDQ+<)$-yNytOQcX&fvhlY40UTJMMkSLSwiK6F2XP>F=o*xT2*dq-F`pS;q zgQRkG3;_-lK*$|Bvjas^ZvY9As9w`Y=_Lx_-hg_LckO5b?LTxe(XF;O{6sCfvYRV@ zqF*y-30Yj_a4M+?d^FxNpWCcJCfh^hchgs{(W1kQ;vIiRVqf5?y&q0pxOw%xdHaX{2OL7y5MS>rR$1xoDPdZJDb zUrI!~7(NZZVrYCs1sxq>JgssFm$aF3oJ$h}*iD{% z4{|i>-?PZEC*Z%MGMT(+OD1#KjB|#Mohv65_RVcpTk3RAN3vNkYWS&y?DNIM!~h)^ z*sz`}PG;5t)=ZT-8u83Y?7YQcQkPrfWPG{xb8&+*Ip1who?fVJ=%api6RMc=<44xt;O`I=;7X@ly>~?Cn@T?ZuhKl)Dlz^;pvrxh?sT0cZX;u$n!ZO&vgAp^NIjSy% z%f`aNE*=5FZHN$Kc1B+5lG&oUlPX)*YghEqj4HY9iqYaurt!hAFOuzchY&UEF>nIe zysU3xcfdYzlHDY~-lEhHSFDkE|HlxAd;TS3%ZW1+|7f}M2m}m%sQ`zHrsWQTqU9b5 z!n{GNYB!{5>n`U#cU!&KjNBhLD&dC&VQx(ADX>9hxvGS{Y=3wMkPI(zMO?BEgu0hi z5F6S&BG)_l31tqe@Z9R}X>V=pNgUfKBDqdxF>pF@3eh3|DrBY>0;QGSR0(|&dv_8| z;4BMW={zGiejq@L_kk-H*?BzE2irbi18J5n>iqy!3HdR9;h7|${-8PKh-wO*n&pdF zqI?fP2%@D|kLtv#VvED@oc0lOm$qGENp0_~cm!9g`}&l$OeD+zIWqi5hWLk7H;#en zNFA~#p7H*_>E=HZRd=?b7OnmfDB|pMpVlcUau{tk#1eOdPM&PGm5g@>n3_*7K*=y6 zfSCp;S5f+~Er2}a5DeLcG^`c7gNn0-DS`BKq7Hs7{b@bmgq`8zo#Iulz7fc7$VLDn zbe>>926DKBRt5I`?->6Nz)u_r^^eZf8`r~fET8)&XISy;sPe(1!iqy1LNN14Cor;U z{KI$;RG>iY_-m@2V*#*OdM(S}b)WAjZ{yj_f#>4cS8kt_Foqf{7K*v5L%?+$U<%PTFB6;fsP+^4H zOTw((D&xEQ_E&bYly!)xD`8DJ(8jW0Mb&i#%7(k+@2hp<0A55IDN1K(pZ*Um7wyIP z_PH1L_wSsOuoj78l%{*kc`+z{wlC@K90_FP-?AG#!fykk+5VLN{?Wj|K${Gg_|{?L zwuLqmP9aFHK7BrKp&d0}?fTPWM0MIQ7=bcsJr!;ivwq>^(XM~B$KQMgc!_6g%NrKr z-7^LzeHE9>U@OQT(7Tkm zskj!lBGOjlhWfc@(=M zXA-1mCq%wQk-wmSFCu54iJU}{RO!l>OYc0QKRP_DUSZnGC>R7Pr>9owCSC$5T_q`) z7nmu)MsnQ}PllHdyMlu@W3$LkG2RsG49nTkBj18#&+|Byzj5wte4t8xKr~#_Ml0oB zB_(bvlZ`!Ti2C*z9uAAj2~)_lKN!N)98t(COYepxEPFDxop#aB1+~RI-#w1Iud0A? z!4SG3&4iDGR1T1;mdV~IlSWIPWbx!H*@^!28i*c1A`~Pk0fx|n^aFUYqro5mu@?nN z2|Ud0b%_RZGa)|p03O5*5TX?{T}}O#`;9@_Uh5g_WmoLzBQUQFuhD#QA36ejjKB!$ z2@E43fCX3|8Cb_GfyFY1P0<8%Rt9U_nu6G@&x!zH|5K=6_s1 znrQ3vseRkd6}OoZToM=se=}*V%9-w8JH)+bZeMN7mD~;4|ADkuHFCE`2aRpLSl31{ z46nhe`0otg+hsR1OV)3INto@5Aeo(8rv|^i{?CyrXlIzj;>7buZ5SSoRZC&wZ;Fo4 z(OqlFd3$t0!n#BPL>FLr0NvP|ma}opcDGn6?re6w2ho-cI@2lx+g(*8*`_e4Z(qd( z?T^YGkGC_-jgBk>mE6zY3N*cffgcB`K=Mh#P34yR6fLnvqMwDwk>vU%i2V(c&(koU zWdygvp+4s^{gglfx8Z)dm}8gYB@?j+tok8r-^wiGE?zhW#~$ZDA9RcJ)MB!PvUe!E ztYd(1_}xYBoPeZHt7G)*Ps?*~W@||}AP0QD44hz~GtyY_&SC=l3s)-TP`&{~^v7=Y zC<`xto%WJxk<^{7nISRp1>qH>jb$_1HXAhF%m;~$LT3z?n;b^E->kM)TbE3pIryPu zsfx>@E=8J;8kUq7Oia)uG0~wDg8;DI_)K5Z#0~#mNfm$h;R{*^<<>;_#Q%a-@&9c5C zC%ToVL3hQ1_m!Aj(wz7|D?>1-YQ*m^LEB`jelwj!~cNz&Z9Lj)sQY_4du{Mo{!c zp^N<<%@C-nm#_ps9GuWbD&OkKjSES|qLRI29x3-}!q8U*B}q0RDpBf)8#+HfvS1nI zFScyjyI6>y;Pdm4MpNGQldm+-_jiPSx)2SuCnOB1P!ImcqOTV`v8*maRBh{8H*Q1OlNLbW7O>^!Gee zlJqRi)k!?M7hoO8la=$`pezj&+mFO5eEwC;`}09*Pr6;eqP|O<`M?g$!;YiT?o?W^ zK=aWdt75a>r-iWt6JD0HdWfeC6^^{%{hQ1|rCh7y_>j3W{ zf-WEMQPF;5O~A1T^l#%-K&AmZ7SJeM{|e!ot$Q_TkQQY#mx7<%y=niPdOEn|%3ZSV zPJUgaorlgWVfkvm^GHE1^@d$ZUUDv^!AOEW<4xc*N=?JNx<0a$E8g5q3@O2702NV@ ztcU6wxV-Aj#H^o_o^00Ivo@02=cB)UX)lC$^70SEyjg2Kg+#HsG8C zzzmO}B+=_JtwMln!oI?+R#p1aZ#@D3{A#K(SP2;yI`?70y9#g3ft>C5Ui7sO!Ht4? z%r7-Kl?()phD0!iD!LmDJ&E&PZYd^XUYrAyBuHI}!uN=8V($tdYhw%*8mkvcTpkv&J)# zcg{8ki?ils7+e0d^HqL>^dJ0xiEp5#1KovW(>rgTwvqPp+=#fs%=7i%x2ZcA6d%t^ zWb-?j=bTI$JohYq)D}AO9;KJ{efOdGOH-#S#hU8>_U0Myj@qHA)z4Ar>0Aa z@BbRm_ad97_33epVN;ufoO@{x8!(!D!~_vJ4g4~ye>}+H;#c!Hx%$9w4&3fjgX$i$ z-IwONCMW<;2(a!zH+m?30i`Pd(+}o;2CW1u=@@duA_G9XKt9?Nx(G5np&G^u^-_x` zLV7ie&NXku^hlFY2ROY=4=L})$2&uj`13n&wMv)hVebgFWj(Yh6wcA%G10~JaEvNt`aG`!W*NLQEy^WHHnXRDAs5~!$slb7)W5c~jKvV||kvDDH zrRm~I0QGRpRh~x|?4;szz{U@T2;elc@3=cVp8&(3fKkP5G#()94)%A>Z>*b${{i}d zq=|yXcM2GIKwGbaH3WEJJ9qcXBfm8ED}cMj;3&v`p2~U;#8*Iq2}f zWUX9}WIoP2nM_6(;_+cyyCZl16;tkT;HeWMfpW_Yo~Ziz`UJtuoy_i7qt|Cum_%|G zMt^9g89&wEKz+(CFA6er8km03Fn?cdzPn~sS?rwE492-@>++sk;bx$ zZvB_)JHqVb7qcrfeR1@~`PpWi&c>@g4g3-LEJbALCq`dVUzy0FSl?HuxECg^uiTUDrVA0J*fu|(ttqk&0b(O7!PFn z0E2k=;6N>C#v7V#75lT)NaC(e(e5oo*;grCte!f)*=Nj~AQ`z*Ceay~Ue++R+AiIpX3QjH z&14gJWDc~?Y&3#=J_zSyM6H0~;h2YwFIOHDc^5)u+7Q;Sj@8J~7JXEe*+Sy^-frZU zWDj&YfYT0=EaT1%+WfJ40>S#hIK%5aL7;6Ah!1XbRP62TC3wX->!hEetC96cMLH<8 z3>BJqz>LNeS&S^w);_d24##bxxQ)1=cw*v=W%7!Eg=nd;hM)_fBDtqY`aLGZ+Tt?qeQgbW{a@miuyVFc0&xa_v3S$CPBYuMIhx1h zSfA5wZ-5b-XXs2Dhx~*LMFLJ@_xKgaDFV(2z$aD}xZ(E2`XiWDAay_o$|p@g#sOUa z0OZ19%~2)eRdxLaZVu_)9F8xeqh}8IHB853M!8 z-S(-n@&$q1Z2yHP_h#;bv(*mIAxnmZ0Ty-|smX4aM$WHyqf^*cxKXN^~0$Z-?Ez{q}lf zXi8A(-o43GiFtEg!H5-B4T?n9!_$%;o)SGx67#;xc{@qv$sk`8=rQ z{FV|SfQkl?WbvRS0bqM-05lpPhXc?CI_f423cUeD6HYwUpFk)wHGGj$NSp`sdi^d) zXiEWG-VGtC+1pAQ$Gu<*l{&ef8XMyoSp{|v7DoxF5hE_farh$YC@t6E`-h#GCs~_L zEPE)^Bj|sMUtx=Qq*0zkKX*>8%a!nEu10^<>%zGi5r<7!fl)|J&4SlprP~%6&QAjQ zU|;JSW72`SZUQVq2dCz!ui{(2a>D8tXBWM#^jE@owit~qxmRjl5o78`S7+CK#3`5B zhpj@EzWYw`d)S3!yPrS|FW%xIXJ6j-yA3<*V#UJdIj}!TRb$D7%EO!j<}nv}#O}B=Zh*1(2}N-?W1dwp8L>ZG#tg>ywA~wD*RIYk`-Y7Cjmo zK?Sg-rewJ3hMkrBZt&8)J%uR!^#eM+^gv|;5up0kWQELs5s^9tGuZ#uMoIR3u)0qL zo$Eirr721EH8s(PZ4qF*%grD8`4FaiH3XBfc3!q&88bU8=}N=BwT=A&vgihu>f1xM zU*KNoBvl#ukF3LM`$^itgsnBW;A8i|d5jb6b3tV>Vr(0}y^dy0o9&%-4IvIk)Y}gw z6RV1+2y*ULdp%a7jit)%`%>Jfv0Q^wJ zpNk=TGGAze*=JJfGFG;`F}=jrkzh&%GSD^HO_GWyfY%zECU&|mR87iOQmX}DV1~(3 z8>8D~5}~nQ6(_I+J{9XP0A+MH_C=)gk<3(&U1aP*AUo#qn}Nt(3*~$DaU{-3Xc{?3 zAA7kp2sLKuN|HPdZ&a*|L8Nz3uYF?Nsz#dCfu4TgCc7YO#t6u*75h5>UqWtxYCt8Z z#>d09XIugUdRMlQa5%?&ja#F(usd(~c2h9-gT?oLpKmXH zoZb^*H+BQp>4{@$0ks=#OkT|Y`tVS|FI z3+%stDO6rBpYHe7ozOdszb~?AvRQs#sL|fw|MN>no2rOw zzpup9{`*3|Z^VD^(SOI$;XwHB6!|~9jD*Hy>p4rAI=g#W{+{wQ`=2b6JM;h7O8A*; zZpurbx#Z6ZS;wDzC4IIhF_0-77|CCzT!ac8)V0v;Qsq>2Q z2*dREO*>?DA-cV8S&8oY$&qIB>L1Pq|Jk0#e=JO239Rn)-k#c7$;@QZb&bw5`1_f! zm)i*>O8U0__%4LU7jT$m!37ui{@%sS`Dx{gWLdY5B3O+MEeJ}4_;T*)()3Y zUSD`!Tid+2_@QOgtEzsT?0WFA<%58wg9Y*a&YH*bsE^LSUm}$0Q|JW?j76m3$T#Zw z_o-yXp9s`|yFUCIb#IcYjFTlm1P@@j^G<0?&#ZVa8>ZW$2T}~qBuY6wq5y9~1=rUr ztvxI@_$%m0=!@`-Uu#ePJlD^)Mb8wr_Se7bwS9OB#o6?I^2mE8C*Gxa*0)%9=lWe3 zR!_jqH7zgdzO4l|%1PB@P%Gq<8rEc12RFY}t|f|>^nw0;_RG@4Cw#Wowmh85PUgNQ zyt>*6*C{qxTrip}-#L|kKxw^$Rn1m}LZ$MeoxPm1lU_c!15FBrMk z_RpQ_S^e-w&?Zk5j|lvJ_i>ABERDV^_n9o)sB`9g(Nbu2vh8@{jm#)6lioht2YQBY z>pid)azj0~XC)BZ9?sb25?$OpnhE`%15L$3B(%(=0B(8iYNoIQv$roDCQ$;do=foD ztZ05KYT8bn904_qM?h7N_%BauA=J2#buVt&rsCa z-}ivVxPGM$>KTkeb8Wo3X4eI`jDrU^vephz4p=Xn6m+X(um3*9-Tp`KX2}if@c#i! C;RqZ6 literal 0 HcmV?d00001 diff --git a/doc/img/MH_05_VIO.png b/doc/img/MH_05_VIO.png new file mode 100644 index 0000000000000000000000000000000000000000..31bc7a4ce7cb25ba153b8f63be25dbfc93560610 GIT binary patch literal 342089 zcmZU51yodR*Y=%; z$Nzht=Y7BDW6grKW}P$VK4IHAHG_Dih#R;etRQ0rmj~MYo4#V@FnU75hDZ!=U2B9>d--R zpC2E2=AVTU%i}Qo=ht#_w2dLUH5GZ`m5&U@8lbv$KdO6@^NZ@CRlZy4f!#27KYQPQ zp8%ZN>m9?^N2vTE)+rjpAi}D>YDoZ^QGXH3(U_-V{X$A9M&#o4c-RfJHOHR%zb^IX zqCP&ODi+eHV}tzMgyFa1aA19oepl}GPtn#>5%du5&OCNs@;v-L(U=n#jlhEe&S>`jTJ#J^nR*q4-%qYW*nCGTJV3}W+<^>$6`_M z#}x_%|4*MNsKK$*1YMNGiuoNHV^3iiPg|~F$W>>KKK57Y1ykM|g4Za2jep&>nIVm4 zWH&RIwL*Zir-pbeZx9Yu&?%5f6d6zwm}I_NLk~IjJNDFob(8Glvrw=-u*qL5;%EBL zqyGQ*-yoy|+jg0JTn(lE#@$tkQ#rz%J{{I8NMds_UalFM9x~`JeJI3 zi>IwCWr$ipN;rZZ-)w4x@qaIfp{u>haoKIip!wK7%WDoxT)4B@t*3r}r;90e9J(1NRsG+OXroJjSdk%wUO_Su@r1AK&e)UU zPPp=@Z5*1pM5yJ3Axw2^u8uE-%rHNf1S|@pzm&bb;ll~JLxYghCP>7j`d79v1Zi`( z!yUzURa6Jvh0c4GZ>czBu~6_H6~XJf1}<;wop>shARiQ6LyZG}(3F^1xF5a+Dr8Bp~=>wbmcAxkkBsZ*Yt`|33D4}2*D+xAzEAelnAai2+@ zjFY-Nrk=n>(*G-b49bKPsvxBM{^h*v+atbukPC>b3Z(Fj8&5}=aZn)zBN)#ji+MVN zJ{q!As?P~}5yNilqxi4IxLK2gGF)6<5-W-b*cyWK935eUR2r}iOv9=~qg3wCFDy`m z_4g?M_p|6#i+3xGlCKPPYlz~f0KaG`$C}sr#E}`Y=f}5ky2P(U7U#_~P^HwB24%TX zdtk#jXd_)6o0qK+_(K05!tmgc_#7RMdJFK<2%azu2FvZ(P}^>|oU8G@cx zYCnDX@=;*hYoVpLmNoFzMe)<F5kNW4_B>u4bZSW4k zLfOFDQrUnl!$a(dP7qEQ254+d^u^X%C0yg(taoe!ITzq=xJNM`fbO|7YrDXvQkM`>4$xLmg4Yji;8% zBgdQC`D}|;UfFLet!ol*)NB|e6SyRwB_SQ}{TX{ve5WDh{lKGIt2dL~kLc#Y;^N?8 zkyYaN^4P;{6eF3d9iL1WAz9s(3He8@9RdVd{{};AZk;S8oyB;t{g^p>s^im6V(~tKU_S#M)C*Uga9+lsU zs(<4#80XH%099&7yl>4|_3NL0NF7bi^R&`H$`PT*9cEDDO#*j9#in)VnKxm5*ya$rtc3Jzmdd|@7v0Q(!4 zh2=o%TlQsBz~jRdxl-k1-980?A%x3sCDB z3%Y!Hw?0!tD0{t^yEGCK`>_Vc`FA4T!OSs6*B0IPvo~G~wLuqVS?=Q=9>QxslcEHg zgScoLH!jbAJPZFY?DtOwhLNe+45kZVPdG%-U-(}W)N5AlzaJ~%)TSua}%={DIH zNne(AJE6HPe}=Ij_z)fV+C2Cc-_qo^Vphb@qGXkuZxhe=qh$w-BJ}px8@;p*trhCvhlEihHDRFLjyNZ~T}FmTrU8FS!wR zbOzyVX5x6|(8Z%nFZ7p0&8Pa56j1TcOKHvFx!Yx|JF#y9nTg4#NtUL{@!qCee!F0% zTw)dh=xVHrTjuKX-!)BhX(Vx%hJBy$H)2avnb_UbX37c~G!4yVA|1WgO{9Hn<3V(0 zPS-(@8=>Tp&oUY(pn-M!>c{+osaSol$Xdc{30k`I%etks4YkVB6T7LA;$f2bnxc(?VD0Jr}|jovpw3VD5w zSW(C6^>0g!r?6J!bG6blvy@qSux*O2FhnqpLQd%)$O*+E$@uxp8p9Rqncr^rEKyeY z%UmCB-m65A2AA$~eTi_yu~xZOJ}^D*eV{rXo1MMS=LsErbT^8ow!=QAQL?=CP~Hosee&4enagP1T} z8bq4nmNeW0;luqBfp*Adj>h&QIX&yFg3{j$xo#qn42!6C3{8pc*>&iGOowf$$~@nj zja)W}NjRoRwEl}?@*wT=e0w=b>!Mu1nZ zP~^Dp8QmHjb!iVutAAwer@ei9GgB#w+o?DO&t|Trs>P-;gE=;zo~GXMxM27=gVHWt zz-#h5h)mQ9u`{l}xWPWCOoxgWfv*STpY(ipGeG9hg9XQ>Qa4&LnZRKR5gRix51v_l z_#1K@x&#=lKMdT7;9^g;ntBrS&NxSs=w<0K30*y%n5=H-PO?rM#uTNn4NZ-DZWt>b z4tzG8ZuSCnu_IS{m6*Zo_ah*^0P*{ruD?9XW@if1_%sa!jlfq z+2vaaVDTV1{#NEhAO?Gt-yghyBZ3|F>{=8}JUb2y%*1iJ1j;2By|0!_2n>?nC{e?? zr6ei7dtNKaRdqQ}_j|D{araCyPfsaOZrV`(6A?jq8jQeul!!apat#jOHHa2lYwH%K zyfNpxOHPC%yVafA4JG9U?QF75#_F zC>f$i3WZdRLE4Iicc#p6OUlF+=WirJlU4I2Y%D+ODzZep^`J_xA#l7AxY@Z!wbMyJ&tzS3ldC*FLDp%YNLRy7xX)IxD&q9 zN%izENcWj0eg1RaSm_~QhEa8|IKgS;UHnsWoj9I?O!rBF&O(qJ1=Br?X;B)4 zqG)P}bKi}qAdiNMTs*Rt1C>O6G+zQfB25P6eK`VzZU91$Ob-? z8h*Fsvu{FFz7^B#Whx$rhp1d^Ea$9?xM!wmIrpw3>{Kf+rymfCT-m$5A?O#hYrGvpcK*SWA!A`3D98!UaJ-;`+u=`r1RkH9Fysz1Wr8~ol*n`p z2(;PB1jL0g2daLKCxzJy{_2{JLKgTw0cg_KNvJw?5nLI3I_dew*q z;0wQLn_Xps;I!*1j?PjQ6YBXJ~E+qQIhW|OJ5BpWE_;r{C`#_7;BPpYCiKe zwu#j+|6bbvJ%Dq#$0nAmuSd9p{a-y2js#4=WKv;t`&**54h<7-=h_^{-{tM!4?T{U zHOYFWyyfWd%wi}*gwH!1$A_cp&5lv?UcjDTWs}_hT5t1G!^&zVhLrn8cc&(dM4r`l zuGt4C1Y}8(r&~gg|I8o-YoH3Yle1=du+(i2fpmruQ2#_Cu|dEwap-nW(y9vY}Qg0&ihJn52*HN%{A@z=9&iNrt%oyn?G~Cy*{%VE7I^pr}tSeh-YO^mae1AtlORH3<3qDPDP1tgwDR#nNIpW7pJW|$4 ziZN_33EOH+6R=V`Y(}`o0B=`Dq3d^B`|VcTC|g=u*ppR(CoV_K4BfI?c~WSOcW9b0 zymDDk;k-Fsvc9|915g^VB1!*>n_JMzlg}u^5YU7}t&>01r@gkA%vPsat?R6H2!Dk} z&a@Je{c`K3*L}fadpySld0&vRlLQO;fqCR}g2is^C2xvWaUIx7U+C{#}R! z$dMx{AWk&mE6STo4q?P&;bhm~q6^@N}z4u-}yI{GLh)X=4b)~_S3kL8a zX<%i!aalZpz_`vykr>nau#YYA;6Mt%#5|+2xQ%KKT!nAF%z=fva=-&!j=BQkOOFGh zPl#ZAtSD%IP>6t=@UkK4&xSlrfgk`8*XR6`a{8Rl*{l_WdnH5!K6T7~ib;TF2O!6vkipm1E^YQGMbw@a&itf8MrQsWCJw zqOSoUI0221MsmQb!9-J6 z5Z2ELoTB@rNDAXaFGq{1bvh0?SVK_<*ru3BPhbx|xX;?5c)^1@@$t-4nQ?$Xo>dyC z>nbyvD){3Q5U`M5yVB%qvyZc!Fu!Nb<4RWje$=ecGYtox|9jn%q+=Z!Qdj2dRLG-- z)kY^lQ8%8Vagu4K!vX_t#$;7sH#WAeGp90dh0wPHJF$O7(0^Xp-Q7L=mrC(iq&_DZ zZeKv@i?5N~FsNj9kzy&17?{2NGcQk9R~DpvSiEu~l*8 z4(A({y|TAw2jhbsR9KHz0_^PA{O7d-JtznKOG447JI~r|7E3tvf{iY~19v(0J|}9p z(lAjY(vTDH>7%}VdPB$~52DZ3M6$$;Zg?;jE7V7VfDZ@O%)`S2mgK<+QTPdVQ0=#{ z6{G|JMM0+jXz5Z0h$4U~rr=hkDzJ4r?*=;yyCMaKN-9@_bWXa5 zq0Pp5jQKkq6sFDB$2|b-9qARo@)7hs*d8J%H5MMvny}@+v&t(K(&-M^s zFE3qBjyKppCuQ+wzT{0!&@3jsKR!Ml3Wtjtq$C#<*Vu!L$NC!8Ks_oS0P^I+;s09q z=uJb6u1x&Wz6)b-jmKT3f)@b0!Q7@D9x9)lGS+ZAW{BWHp-`}oq(r#plMTU?)frp2 zcudn5+Nrl=HvA`RqkPxtQfjv8GL&OVf-m6FHC(9!edk+t%CcT=X4zGvD;TxvBngab zeb$2Pz;<+JLn#t(x+O^(76(BjxY`Q0iL`?buYn~^LeHrom?aQ|r1b6@}3K|xZ# z(YTcU!-fVk<9xxGRiRg`xz5iCsl?4-F z%zpDRl!+tw49ZgGTbop8Lg_BNp!4@ot43(PE-#vV_#K_%xwQtj%B#+-Dbazi)9`Hd z-MgPjv0xeCLS4^1$HA@!fy#38=%2vC*Ecu67@vVJ=3?bDPDYio-|-XhWlR9mBESy3S`%_2AV*C%$Oh{4ZMe(&;pyV z6l^!T?F{h|-DkU*S!xxPMPpix__-?h*Z#fYTcJ5M6}h?m_**dTklnfn*6an`=kq7= z$1i(ydXPy9MuL6y1-d1TRj|gZk16jiGL{<>$1~E+VD1}x=?y=C5w0?%Sr)@xZb{QJ(dFdV8xz@2b-`$>D~ zMgA^n&@QZXN|XkrMA(j%@?I?u2brR}&P%@7Ex;?|O`Q5zGSr0PRqoajS6Nwo{)>)E zqp~Fe%ZR$OGb&- zvG4J3i=Xf2DSA6@>f_@Re6NINNehP_dF^z>ydrss?4CVZUHoBKt-UW*pv%EM4<}f2 zoDPBO-mfb)cpFa64Pfm%`u5+{q88$r-FX3*{1wI6en&pPD(y)`)w84c@ejn>&apE3 zZMr}|=4$b}i&%eEIZ_5bu_Ig(S8{KN5tBJ4Cin7UxdeG)uD>N@O5XiCU9YNheG(U{S$R>6VUzbDbmH*@;Y?C?QB z=C66B0MWgYnCxlU03KU9&kLPsF}=wQXkXwR7K;DW9X=&;V5MGW22uo_TH(T!=u!qh z&^ag?9-E*4{s_fm$U((Zi3i{iKM-K>k(w z9V`=^ttN>E&Rpapb|~+)tKYpvW8MKTAN}AZ+czlV6D*kr)M7M$m(7Zx%+BT114J(Y z;nK1+!10YTgLe_t?%(y(3!5TCLD}TcMO2 zpoDJqdt2muJw#ekBy7^x!kVbo$0*c{_OX=zO=-1De@|?LBXwPw!COZ?QcjV+b#cNu z-}!*4)PcndWE<^UbUV?VtSTG4C|CTZQ^$3(q=@@qmvoLQe*DGDKvP3CQ(Y}QS`tY{ zzd`-fEVUl}RNe9W<@%f=MZyIsdW_#{v;_uKqS{AGgm|i$18k$HvhR$K>YLZaB$z>l zq{4YIO2!V=|4*h5KfjeG!Aw`L;NPpJw|{;N5afPMN?yz-AR#Xg|4q*!_yBymw< zAFszX#-uh%?dx+B`~}s4j=fIevSeItkTWe!7XpQH{duI#lk5V(%993~IaBt9gwr?8 zE&3fuHwni#G?=b2(sA$nq>18e7?M>#6&7Oc?CgN2<-pVHwSx+*>Kv)A8#&SupsVKm zyWvra^|goZa@H8=FvSCI18D;G>B|kPFdxn78{z|1#D?Uj@EQv%JGMObjySkz4H4n1H(EsSp`6%PWDFn>O6h*^Lq#yS73g-c zFn+0GO)pv=i;8^O^f^DtQ^e^cHsg_Fd3EopX@+V~jc&LC+*(M%Sfb_pk zFfXz#sVPJ`B16=&R;%=_ToNCO3NaS<@5_!;%t5qkN^|N&zD_O4P|7 z<9C#;Kk~Mu`77(=YSMAdYnTR(CK-dFp3(q&Ln?% zQFm-w;aoI=WRZWNYb9uF3s%Zz9ba?sFdOnNq_8pfnf&j*2KJ|~c|fTZa~}@P2g322 zzWrj(>=+Bf!Z2b2^QcC=#}5d!K6eM4I|-y7YgMXONLVJW^a#|XFVC6Wk=PpFBt&_f zq8gEpv*Q|b)+IoG=iF$px$PxUTrn>eg0;Jq>up5ygmaTRk;Dk`VDZ3d&Ri6`q)Etx{kw5l)iA)*)LA zL&tTZX#MbSUB)zAmMHvYP?b)*Ccmoeb+Yv*3a^*F-3ju!lmBD z&LGb;W=0^|eXT%$AP?@5SIGLcchJ8FE>Y*;C~4zjbQxsM{sn1}k=A4ssQo5X@sJ`} z^n&W7ep6&%`S)m~qz{iSeB@+fIhovXw8BGDTIuKO1UuHsf?UaLW3&v(dE>3N zV;O&Csm7LKU|D=cFMLTMmlE-GaC4N&RR)@#?RVHCTRv%vjT8=$ch3{u%Q@eEW;EXM3Q(FE<&x3)M^`s#6% z?rz9+dsepQ=a&y=tK2o!B%~mrZ{5o`;7S%RGf@hXj15`)9?4h`0wVmNl9uA|kY)JU zG*wd(j2FeW#|4U-TyL~5!t?|<(&oFKJOg!D+T?sZP@zxR8J=&J6nC5j)Fcn2O^>}p z%3iRS(zg$By__ukSo3Y9L#{%kh*U<>lexm?T9A_MT0KoyQB5@ai#)V>S-Bw7%ujvh zL+e0*Gc)wKI#2JpZVu_w>?xu5Db16wMP`fA$sr!*wdV<2AChu7wvN5P@yY20f@+Kz zA%kSK3# zeRS%u>!ro;kh{K_WKoQ)Aw6zUD1czBj48nE2$;=OY1U zi>u1C-}5%c4%Q%(7D~p(hreA)LQ#QdPp+2g+7#Vc-+5)b6Q&I15DdGz-1fxQ2VDCe z;}cHSPEXH7wFRQ76VKkeQJy(Y1=HiZF5YL8Dh`~16U?6}>#ADfB&mWAu_&^qCN>^Y zGbIkR?!}j4JVZ=ke{6&A<NDnp=Xry<2mds(&w7w=gW z@6iN_O^fbUapN14%NUU|5Q&O0rK&F4qI#5ZvHWq{=h*M4vNYFL5IymyyUfR_TXFNg zZVfoE@SwT|*`^MN``Y6eyGsCtI&)v)0OzLXXYPTH_nD#$re#Y(dsy#)TE@p z7!8rLwik)396mcxzC1%evW#$Sh)IMyD>v$XKLv;{aO;JXs2$-&k-D6@Wb88`+l6{4 z>Zg7Q^O`%PkcB$Ajud0@Qbua{kLm+6WK2I6aC25qVA(slcwTh;^Gqi-ASpDp00A`o zx|=#MFG&#&D~?NuB{Q_IHq-58o9IeXuT%paU>qWOa)?Gw?g=5K5|7ki5(F_5r_l!)BzV7>=iekK_ke;Ttw&u zDi>@Z0`vY)9)>ngU43Vs4xko$^+FjtE=OohG1a=w8G@>2A{R|IWmA22lXURE>jNLsaZ+}iEIZaaKfn)c+8v*eDj zR0CiwxjhR)-1^;Ky3QP~c>5y=$@*<*+U!Y;GBQ9QBBz;9=xMF29cyvLqFf?v7Nb0%;BX@=|zq-~e8y=$NgU5+cq#g0apUr`p!T}dZ&sMY3yo<;oQo+~crND3 z*xDrvcGb3v1b$~rXf3I?KV3h3)!(;0D7$kdU6b43(npcN@Jf2SSl^kJxptVO7QzTY< zB^-2o#4M=6wtw8<@x&+&!`?gFNPmMYh2!pt4;9P!u}@7z;!WCc?A7GxaFX9}(&^~s zRwX}He!3YXDaVgNja%@ai5`%>tnXf0H*`BtETy(x^90^_1u4s&K3Hh-nvab)_2roJ zoAUt$>!t8?&T7d-)^1HM&aP#>%cS$ctdQMcZeBSa8%Y>O|9aU*)iz&^O$40@9ZTWE z265*|kOp~dSEkL3hO~qeF8)B!A$}tsr)K3hRS?NG?#cW*ZJJ+3p53?TfoVMMi|4TgZLdh zc6jCJynis=o|n9`+UR|5pM@NB>4^u8i4cU`$)uiGuao%MG`GBAg<4^jwXSLOT@JkS zMWG)m1u%cJ68(inUR}$G+ZJC>#*jZ^q-Y2|$iYn+Gq|*nc`e!fmxw#-?(Vh%Fa8MH zCqmz+U6%&!2XyJh(d3q2Y(9zM>$uWP#ogtK3Z`#w+1W8T%Rn-dUZtzwd!s@8-ZBD6 zClT1sFOg}pK$P^dK0u(ubnhF^BfhP%EUm8=s=1;@l$jof+4H69 z^sWFxLH**%Jk`cS~U*&kAc~I7WxXkGDc?W+5~fN6u0w`ps*e6`k80dLR&8)2Y$2AZ0x~_IGx+L6g(tRgLT@ zA`=%3a*sE!*52N&U!62Q7{jJh5W#m{TI#NM8=}f`8P`el) z&LDGPhnluWku6L6ENi1?DO2+akHkGttIy?*fw0v*P4h~|>9s08e~d9BBbUBDHrchn z%|06*kzf)ZZQfMsBJX2nI4=VdVz>{H@2!OTH~Pu8@_P{)8ABlEHr40xLPZPx*IPQE z{gXnqZ&nCGeTTv;&_ZrLD99#W({Zatiz4iEm%wQQZ%4)zNJ&?`aE8hpBREI>Ud~oW z$GWegq^ngw5yJJ`o1I}q%B=L`&Iz&_7n3AO7{P)lc;a|^R+|pxQ_58Ks0W`|cGM&_3JPh>B{b_e zP|G=e7p9UM%q$Ow^b=yD8{*Pr%r2PDbe4-+l}L(ca>NeKOwFTZQX_rnJdNQ{WEr+yV6KAyW@t|Oo3RHj zjNqbN(rdBK?K5{0Gj(8|{kNX*Kgk__yVds1@zl}(x}R%Nf)IB_u+K!w|j%@#X?ayT@TT2%OmH&A&AShvP{U^S0uTYH)pOx zWpzscYARAFPEF3n&hJgXn+GINRpNz6Kr)&@MaS&XrO@9E9&S0x_CAwXTUh#9(bLEm zNYeiK*LfeC%v(s%3D>V0r^lzq#|sd;8-81@^blPQ$)vB(n;pL2Y2Jwu;`i$(+uqvg zMwGXZ%LeR!S6K2mIbAYE&_+}5HR5S)|B4iATNN>A3wT01Q*%EKir%W5i<sxnBHkPv@i0+0M7Q?3^LcE~1mv0gEHKYRY_Udyv*!zH=C zhsJXQ&h8IPgLsE?X|{Z5rH0iMG%3Q)QKn4?T1TsSx*TkzKQ=t5fC&*6$PkpS&I-1T z?GL^<4mU#&RFztrmUu`4wfa_QSb>ZOha}JMg5?~JS5A$ud3fs=w53W06ifVqUNq&Ii#>2K`kB5V zsz;b!BJ7?;-6DpVq_JwKyD-qx9*{T@k)_V5Sdjd6yGr^`1``XCB(nD9iTAiP{6V?2 z>A5&Z&i7}zL4mU}uZKJ7a@}x?gvG2>-Gu-gy0ca1jDW<+P_=oVTb7zNl0Bjck{WG| zuh~OCdt?^DcfD=*r(pGf!(VLyoyzQF8SvEs%6UY-aUEj}<6uc)Jt6k6>xV-rKw_&g zdWj9v&A~>(E1Qb3Z_fhuI|e z{MFe>11CD-fdJEz!l-eP0_kh?Wgw%T0&b+molPXh7)0?tBhtgCRmNf$U!`=xhb**7^e-Zn1VqQ0F|&7mdjX*0EH{U2 z?F8Y3q?SaP^^;VODCHkVV}LB+GuP{l?0JF5mu(G$j6IM)8%`ozrRWt`F$Uxg@XY#k z?Y_WRXh@AsQ6g1YxD9K_a&1Z=V}l7&Bj-^zY?OnyA*g713~&-u^X78|z~+6khD2(P zt2s+VczlniGIusa3m#9iu08nv#U?AAGjS{NU=mrNr)#9UY1d`)O#R~0e*h~km1=BB zO;*b&?e*Id#2AhFY*C6q(P!jvNh|NPlMFRF@+l7o^-eJ=jXRC;zx+sv-38#PTkqS; zgO^CtaI5m>2bN@uX}^ySdH`w%SPw@N8nPYQ9i5<7oM<)UE^$mil;5WPltOX6cP&9@ z$>FBv^=JLB>%ag9pydRO!u=+oOUxOzdZUa@JKOjWU_pL681kWUiwDPH`d}IuQ9fsO zm79BwFD844<2WGSfAp=Q?$KKF=JP(89CW+8X+Z!T<$U(_~B(MMefO*g54_UfLxgNTveTtUG zUSe(=!ZXjK9INb|ohwK&8u7FDE_-dOJxTioBYE zk(sy7Y@?3Rey_8HX6{QkmRztyZAQ#nUgeT*N`9kVtq)|W{=CRiJ$<8kl_o&PN><&M zs&ES6Oi&X9%nGbfhXlrTw;(q@mPNL`lQal}U0``(gbKgjhdxh8Bqu7EWYGavDnQng zLz&}%{Y*hN(UwEKMI(rHI4LIHBtP(tN1x(!(Ms~M;%=Ffv3Y*XSK4RUF^P8C(beK{ ziFRr;uxsgI>O^@6^B!xa(%~R?vVGK(>&JrKO({8Omhb8U#dTYB+1g|4ZLSv$qq;iL zqDQ_tM0~Yml!dhajC6Vv27p|lghJ0Jm1S{3Q%F?w391e)BsLcT^eTLOEoAMz8QPlf zf^>3*t%>ha@Fo+7GW?oZh7K>#>*j<5NcCg#g|!}s<8&QSF zr&#k$J9Y;BzNwJC5jaf8|I_!R79d;S4Dd{ijS1P#E9rSp>*M~(l=EZMT$t7BaPGKF z+bt)&y3q9n6@M>)7>`AD2?B^7mFxDjqNHIqve zBHc!j6=Non&#_|4tqR7pFEX&C-{>A{SLCvc_HF0q)QBdUT)6Y(Dx_hkV7~38H%-wU zV17N|X=-vXaJDdmSJ9n2>#xY@HRz{X_99VaYMDk?M%Ow`^T2+igymJfHLMv~h^1K5 z+k(7bssw(LeP^snEj~Li&^i;a4~c9kd`#ya8;19C@lXP`7tD`=yvx4o4f*f$V?ITg zH3Uk--EM1=GSx?p90ib!cd3fI2ghlH1+19SC3^0w(vz2IXlGTr>zLP(6_;hhvXmX` zh0NJzssSwj$SXdD0rMNl^%r`5W`V-I!cD3bQu&t%JKhrBHB zf*Dqu_3pM=`#7RRP5e(L>UWvwz`A~>EiHdY2V^mpBkesObi+31c{*LcT{HG!*xJRy z0)%R6+M2oFK@4b!Kq>9Twlksy?0s+)#~+uAlSjXN0pNMM!(Ww>CQ(v`m6>C4{gYH{ z=^{}{FMKc1{&BhNhC=gErRVuvB-=+5-p;cCz*Gm+EnYHk+S`EbuUo3Oeb(@~B4pSo z456^cbVvEjcm`W36d0hWhDLDcE=wX3-x7I^Se_uZ8xey+?*BU zBhQ7#6p9Q4)%G?pVJU`;3&-9Yb{$7jfK2)S%a@^4&1Zgo0k|rv9HKC})%wh>QV}CB z^<2MZq+8aFdIe?iN@^>eAYoNJ??j1Oti#|Izn+iL!k-{B1~fxa-b-9slL7FB!{44@ zFwZJgVUdUKp^Ez5^lO26F)B5^yp1#4*NR7mLRgpHD9@k*4Ib*+WhnF0+<{uzmvLQ} z7ybzzRafuAQ&A`Xskqfy6JO!x%_tzdUz!u3s`&HE2#im6Iu9k>_lfqr5tg+FaG@Vh zMeqUcF^_j3{;17sHF5R(JX($SdsKrvFnR|FXVB3Z(foQ01mXe&PCH}jZ95&`4ZiY* zd$K=hB7>W zphCF(VzTb1tW*q9zzSC%{QD~sy5@yDp!T3r)9B)}-ELX`J-_n~q97a#=HzpLILjc# z`dlrmCHl!O!(jyHOIm>;exi;5X-+Swev2iXSkS01j9EGO5C2JvQ$_Fto+AoFR%aE9eHRext~IDKC1m-E+3U#Ec@W z{%p?A1sE%QuTnxGL!RMrlW4%qNHLgur&Q7vD1*S|82KA4EpeHp(<}&k*AlFvRXTK4sl^aMYQEb_1n>XQ%tueaBVR{51jI}h1+m8cA(XZzG0-RUeg=QV#&P5Z0 zYf1xO9tl;78K!MC%8pkj4%rF>-T3QsK0H1>1-x#b7iIP7|G_Q>CIjO-$GCU&Pl>~D z-q9NpeWt?1`7$wc33~Eow<|*g(jyGC&_>N#_j49??*rJ8HaQAoF3%y5qgeX+lUT4d z-h?OCz1|*v+OMtUsobr$O}ERqu~?T`xXB2mn217@*+4b_#p} zi*K&?FZ&Alwf9}D^?(2{y1F&QnDC0R7JiCEQ@oeQ0L0s5)mV~ytD)8EQ!hD_6>LRR zp8|$u09#JZ`}5vgVd4abtz0Oi_~eBD_@N1E-{0r=pAX+^bfIAbvqpS|B~kEKkyG&t zR_Xl$+E1{AdETEXkYcr*i)n^b%tX@3kdD#zXKs1`l^-}>8bRJ_kJz(Qc9hiuXHOV(w zyScsuOazBn5^;Cu&wxD(02<7Gyo7(ab#L@&6r^vfI(p0MTVv9oUV z!gL$)lLNPTX2aq-$XkmX^O=;^0r!vHpJJ+iA?R`T&r@^TNA}FkkU3e9ffM7(<*07Y zGaa=jBwyU553|lrPxIQ^=n8c=Sl9+~@QTQU5?{qWunFOKIAka1>{rB`9!Q7@_Sd{O zECv>xJFu14ViPd`e4Mf7BfeXY=J(vx2e8v|u9@=g-MfHg^d1Os@@w#DXg%kV%^8&ua-$ZjZ5nS~q8`60cax zd1`Ka26M!EBxOLl0u5N#^(149JbYok3UQc&o?U}|Ry-2cL9yg~joaxmN@^GZS(=mn z?h~q0Z#YQkdU%+L zaeKM%b0DpAUZ#eTDSX)2N^ad4Pd+vr5R~rmb@aS5q^=L%RAL)FZWt`cNHQ6hSHe>@ zHPR{9i7V0PBv3S@L4f;ytgfyq(4=wjOTX~VGb%4qu(mfM06;&=P5@2 zoSY2%{#|Z+x*FRL0M_>Qr?78-eY5({KUQE7`i&>l648tv6f)oD{qT}s@SxlVod4i0 zXp{AVg~Lj7bpRsdX`xE5$G#!<7;Ni0=A+;p6s6j-GH0n zP&Gb2h0930PaOF6S}D2^F`%CEI)Qa>#k++!jaD{*SGrX&&NnDqN(jlB*qX*T{7d-< zPz1m#$5=#%MzgwKkpQlIFifjlgIOPNWCI>hH8nioTmF*S<1|UgW90*sL8}rd2hz#YHr)U9=9ok%&*{hwY^p!bg%E+%zs4 z61uXQotf=eRpnyqW}E3QsNy_wHhihUg6>VtkB-lNUX{f=AOAi|_<-(f?37b$QVI~c ztyEx=yEGxSiH*a1msp9{E*rS`3V^@7rY7pM`5;+QXnI`Y+~ivm-f$r5%a{C8QtJOT zcnC>NXJ%UNR?-UGItd8AID7@#lt~4@n%2Uj4~R)$5F9RM(?Y2AtCaAd;9IKe>37tY z)68C~>)M8pYZw`=%c#;(MH2D2S<6a);_i6HY?@y?XMMGNuCzk<7$HZD*>_%FZd_NC z%)7?xtiqdd5mazhKA_i(5h zG1%G?My0@OXtMB^e^V0a71*;r04v|Qxa3MhTHNq_m|qR>WgTpb9!^?!@VIhMPHe1L zZTWw6y$3X$UDpOYNRVg=qIaT1^xg*1LkN-(Ve}wG??#Ith+Y#l(IOHektn0L(Yxpd zgVB4h|C#4~-~apG?_d8~v(}`Jd+u}2-q*hNwXeH>wD{`qgQdvxqh1e_Cpc4nsQR3X zK~FH`Fgu{e+?pE;jU3HdnL~JOwxD1KM#N-f?1>#5*5?1CUufsh_*v@V@kmwVZOuB3 z08T;02MzAb!GXl$mr^3N{E0k$S{-@%BGH_Qzc~h6d$f=dH1P-Dl=)YL{fwHH4|{Gb zs5a?z(bj4wtqZ(f6^`)z&YSs)yozhmO78_nN}t$ae>%m;&( z-!&yW#XcskElI!rSMOhGR;9*fy}xG#l}WMwR8+(hUs(ONfXaXAm-$0p zKIp-Oi&6VZUE0=leXEtd<(8a)uzf@Ehx_W;-S$G+9XoaMfrOmoJg4JHN4_Xb;y2$< zf@kJ4Xw@^wfgN9TfajuH?e_tBE!*MCJz8dw+oS4#KA<9~BVR2l8()x7H%Qwoz=5K= z>Cfv)kYBKKCg=D^%^oK1o}LyR33nyEw`cbr4*U;VtjX}6NpJx3N{Itx4`91#6srms z%3rg-j8I&$Xs3;!)y1B1rZ!cl;zY;JD0IL=?4?jlY>IItvpnHM#DK{6d*q~Gum|1|yB`_rg0rf|2RTV9e z2Y3Xc|7T;uR(?#eu_h|B&*gKC9MI`3DOY4Uj}$Tfa!6ID(P#KzC!+7V?EazLzQ9H+ z-a2J2af9tO7)>#W)Pk+K^xqJIgZPRX$0nS&;Bl-+*!y-s2N)1Iyh2iu0QwhfjSNUUxj%jg#s+N>ZK;XWo-P(ouTl*m%FkNF&mbN~m{zjgndZXD|R>Pe` zB)%P#;#XA5TRBp71%meFDKl;>xdCklo_oxK%k>24j^E9VveXc*?6NzkRos;O{6dt&LoBLwOj*AbvUn|_jx9XCVm&uYih>lRQQ_|Esxlj0p&U<@4aZo$muR}0b)B#QU4Pic}dC8K*$kVJf%mAgHk?_YO)2Nso8|_Q5jCcUqE^7U8QwO(XDi>rJ6>uZmU&c>a78Wl6vaGSiE|9+xXAiU)IK>XY<#RGVIsKWN)5H z&#E>05TlmRwhVg>vA~Py zqRCRrMvRkVAJf^S6|O`DJ%kPtbS0ArWE=anz7F0DI@eu$Fb`hv@3tB(xaFL*tv?Iu3ZLrjt%qxV09eF&iMV-lk8Dk^Hy$b9oKDTq+FJ($Z}oa{V4-UgR$A7W_at7(EYtC zzw$Gc&D1^^Q3br)D_Vgz%vLXZKV(`BUhhbc2%>p%V$l+$JZr#!BrOnXv7o+#R13P( zTn0n8Z1khM?Cy?7v|Pm5(>%OkhCY+b&o$<~7<7IzanFC&Z{P4Z=nft<%uklonAG`x zD7Vrbxf0{>un+5hh8mt(G;Q9GkZ6{a3m@a-TwL}fP@FyeqAxDoFx>Z^!P2bzfbZI? zsj1Cbr$ppZEWEyIdIySPBY9o50a^0D)XwuS#O+A=O4K6}Lp-NKC!G1vR2$zt^FG7S z(XwAGlU!u{9fIv#b{n+XF&BI_g=ir^*gM{T^JC)v=3JT zgua+VTF+u}kcUEvzS5bbO@i)GE#z)4aT+%}wF^VIBOzc+)$^csz*aJjpkYIwbHi3V z{oUvGU^<@kVAehn9wjBls%M*vDz7u=^(##gx+|Gg1(2tuI#eAmIhD4Q*@V>a+v zu<@k^N2131$` zS$AR8{CLmB8>kkVIuY@a470<-I(Grvh3yT7i19fu}o#&1|7dTgU33} z{mw04;>sR4pG*%t=3d>i5ZQ47ZJGTAqsCgyqJ&|nc4*4baxEv=mzGK{5B#9Cu45g>ywWyD-#k;?@7dc0n`QF zlYlJ-f51V0g8>SsiG`kWw;_=_Uzz{s)MIb1rV4(CR)I=_=kX8A>&u?sx8-WQJ0X!> z31?#cgOImf!!fic!zDr_wb$+)XBeEzAnHX82VXCUYtZMzHmJy#8#kHx!eXV{d~u9f zD36}Aq%`n)#_xy?l6vwAnI+XZqiEYB_8x8CXujpbAR}>Wl#f)lq`88N8kvmd%$_*- zYb!eC;wXcR?b|V4aM|04NA9FvzRD>uc@C8p!W%s z*toXaSd7*v(J34P`v#t0f;aZV9PeK8O-?Q@L=aa6kt9BnyrZ&sN?Rtw%>k;BUGApS z>>)LCJ#xYT0?GTMyc^DCT$Ta7@jeG4&SP|}K$MHv{|=s3A9en956O-NWmgw(Qk<9(Dp5j9Gu4Tg zMGgBgVwLmu2VOZc*372Ov*Dk@8@TG8W#|wmRKCt=(+MFdike(nV=s&z-sCrl9Tq4e z&5wDWN;UWiD{adink;SKTL5!)H0sdowT9( zS7>NSg^dTd2U9=mP2@E)^aYkAV%TE~jd>4#@WyRn($S>kCe{Gr6>-T~o#k3PH@oS!Ud7hH&uS2!KsjX7Fb%`nXV z7B0B6%+hi6Dz~LKc&V;+rVw#Z>`d+2eIl(1O{pIqUUC27wFQG86q~k60e#lN+9yB!-^0qFHk@7M2B~?pL(#?eVZj>phWjr8GU2-Ei zHj9HL+4SeGEr^=a)!5m@gpscInhV|?EDNx@K}#s*&xZ zVTu-Ke1}#4iaS*XzW^BcP3&MH#7%YFQpSmH_`&}r{e13?!gxnhPX5hNxbwOdqfM7e zzTOQPPTfrS9&D-yw~4aBE<=2%iX>Ayl)Z~_oyV{?@wqpnrl6 ziL5()zWg9`lNu4qQLz4Fr|J)f$)|HbX8P7{4)W|~>8!^jsF*U!tQ1alt&n=$Q`Ii} zf^N_jv-=fO%wTy7t?Bf|!~{~!5*L&!8G|rOIp4I;9&TI_tm1chU$!rsaCo+q74}wo zgySd`!!55-t?!~K{O;>vu z)(6Oepb1`Cew$JmUs5-$f(IfFJ$Swvq@xJ8zl}Rsz~NJh`u_*=@c#pOBB-y#1cy*K z?o|mvRepgT7E*YTFMo|MF2|oix^eI(idr}NUt9fXguMGiQrJ9HbZfknVM9ne#-6Rf! zCT;u1QrXBxzrST%+pQE<#y<8i6R6;V8+)f0PiiKNc&3u1T0jpUu}Xt~gj*neVJZ9} z1O0%KrC=-B)w<3_h6X~^Pa!$M`xm#PvX+ZIfV2v_fjf*8yS9Y6*>Gb+jZ-LTtLG&J zaE{>mqQRMH+gh4;tCg(ZuAU-dI2PNI069Q<8F8!M?dRj=C+IrL-%~ixX~Jme=pKA} ztiTrE09+_wTb%!u7lbo^rrhE1TZmWdN1 z>)rhqLw=2Rv+Zt=JJEhtTYPoey(c*=h5o~qn`>NAir<}>?70|`qnH#58g6p+d!qmi zjM5-g<=K5VkBx1<>Enol!UF3M@^#I!aL8q470x4Q^6d?k(Rave2!YVW!w5wk1@Y_` z8Z6YNYi)?}2k!}s1SP5Z4$0!Q@IeKlDEtAyy!1y$h6v)KS){im>-{14L(W7j`~y@X zFgm%H-1##+;J-0SgK&tIj_l4gEQI(gzxf3pWIaVkoZnSWzg z?`$39XKGADv^cBD>{Y^{C7+m(4-xaC3KXMBc}!Mu&35PBa39pYD${0_n5uFx1Sh4I zuC4UNBq(7i{;bnYed23yhW2!O+U{_D;wq+`;%JJNtAlr)!^2(FC(wO*Z^qkf?uRK4*c&}I7I)T>t+G~g3sx0E)RRc zqw!(V{-5t>^;HBW@Q1|WE#oSj1~3P0|DME9Stxw2KRe}he$eYu@0)LIB@w4h%Oj{- zwualY?-*J7_{3xD@Jt7vLj?U~S4dk>F?cY>61tS#?b4?J}JI$HP@#M6-g?v32 z!;c^2o3$d<9F%C{GZ={fl8anN&WR(8*w)7!hAK5@sHjTqidE!9enckev-5)%v^7(q zUJ<{9IbvFMCHbO#VjCfMH|sN6Q6?bF|E$AWm=;5b8-&T83<>_E_(WI5)RZ|aJp49N z=ri{Nzi-ja1c5=n`s4_{KO+LrnZoe02=5V5qHGjU=7D3s=z4PCnDF25G%gXYezi~u;1uR)wZJ>L!`$tEJHP7|2VCKv1@Gnp9Ri3UEyG(nGntOZG0B{~F zcSy5Yg<)Essig;`+T@?t&Ee2})^8>VDjCmpg?zonaQSodDZi~+upY-_NNCs=93zvK zmDPrnzud_R^bvR^N_UJ5JXeFG=}`)`FeIq(cRF+e$hQKH5YuAy$E^a}(N1tYU@+9w z-cATTDAF-s`}@5ecoHN(90Pi@&HAf=?(S{?E^00|oRDhrr@F@8bD^b14v$JRuZar2 zTVDLK@|%T>;RWSUzRN;rU>KAb?%T*pVg~PjJGr45h4eU`;5@Q3xYbOL!%R$o7_7hj zcFr(jNK+=Ta(ezpf-BtbLBv8@OG#>?#>72s`Aj<9W||_Uj7Jk?EoinFZjxQeU5S_bRa zVbqrLpcpr4er0ekfeBF2lbdT2>rJIFS*KpH(7HgiF1)-0FBktz+gjO~2xVL#X$yVO zD78B;>3LS6F$J)IJZLF`{~PY|1!F8&EA^ywG+v!!dr(v0(_`+OXT`NMkN(Ab{O2GT zQS$Mqd#-)2umIDJl^cI1jbCLu1?;7p*by=NEZjB@I9aUR>y^>{{%mKwFM#UBABV>L zR9IvVLo zQc@Ad{9eWiR4TVOYxcCyR}Jc$>d(9C&1`K6`=Dp{FXsg=alzFaz<@l}3{~e3n%L>v zC0?~e1YnXf`(iwsHN9s(a|_Oe-D6r>TC;y99h;xqWQM-{6`{uLPYF7ErLVw3*LmxH z1P-g$OoAR{6I34!ChYst{Sj2&%`Z%}KQS)#b@!tsJw9#8iKL#H-1zgt>ge~=k|CBy zAwvAIis75=M^BGFFp6Yq7xE@E%KR05l2o~N@mF*mE&3kLpkR1tGwUwN!~RVPJ!(0b{){#0I)Q}|Gq z(jz)h01TMuJ-c{ zjRXh&!1v<7G4lT$a653o0h?% z>RO-d9x;E_0=ew@b~8X;QEsn6#F_F&M;}j&)`d+Yye!?_DbIk)qr?Q!|LS*K&&x75 zj5eS-GCU{jkgrX12O8v#ra}mq;kVe?*&#t9eXdEGyw2r<&NlGNoCC{T_`>Sr$B)?FI=HH8kF|M%q5Y3t1hl?V-p5SO8Agdt))VH+ zgEB0%SIKX*>|QLZcx%rUmYQRt^R6$53*ASfs~zyQh&A%2$wlx@=)9d*!R@H6M zdEZ#Sb8KbAjxvc$62lKEOA12q*g{wRG9hkAo5>4dF6ekkFzK^U=9Sxd(jwcy3L zhrYmRg|E6x+ltZwpEO_)#s9bGgYt|4Nkc=Y zTqYhOnAoaF&?;m3aci17a`W%+ROnCrS922*M(^DjcPR@_K0 z&H*gNSe?Jj%t49Qr;%54Q$Xl4Vqh8_3twR0EFBl9oW%v!TwZ-ZMiAM`297N_svuo} z+3)ESP_wefSOW2Z!&K#M5L*ynLJo)@u;>H$HCnj4@4sak2XGIFX9dN@mtykucrx62 zrN(~Q==7cSN}`FefgKXGR$9+&83-O3@ULeCFnOW;B^+xHo@r@oTWn1HuAGnLb-p+l zMZXv6HFWOQ(p0PA-gq%J8rOpPvs*Pl)4eT)uj3kn6XnF3-ZfalUsph_yv;Yv+{cRF z(8xg2k(W8qnm-w*&cQG|XP?i%NtW7G!sE%NAw^8+LBE(LSt6;eSEzsw@!s#ZZ1}Y4 z?IeT#Dy5)4!Ew-$CX_Qr88IbMbQVE_tJgtihd+82J>W_vp5AXIZ*2FnEbVtlKPK?VC?@w(g@gllne@vup!dPa!z z_N=1pUbo2cAQ)T#AFTtQr+@_2)j&_hE7i*?S>bmXF>#beo`y6NI5VxUOoM}O=lF_r&GNQ0x0zrvK z?5XUFfP;bd=bI>INcR)0Sq)^GM}*xU)YgtI)IW9c!OelVH*zyq4mn2;@t<}sp3&UY zFkuj>ieaUQC1~cM)%PU%Gx=IJV88HK2XD(6Vp?)iL0uOvFL~xq_@*Hk?)ku_9^6Vd zm{7~$%H6=-bmUIVP=zGdQ&5~(_FY~}%{C{U_wo_rZyQ@0UO=S=)kVOv^ch1<^HmnwAMxI}R2iDE*Z#)(lE#y0tc z@9Hw`pTq5I*~y^&@8Te;^zQYJ&FVFNV~>%iW0fxKZEbDfJceOI?9k88tglv!=5)%`#xui+31;iRawgVA#>J zMzrdVSM~^tRv=rEiz6)kUx=n z=lUN&ME96^TFTh;2*xrcm>lL8z0ft!!s&4BoW!h38Da}fyzykwpQYxvOzxfST zONU0ID-S2^UC_}I)oWOwc)r7YB@`AGCJ2SbkohkwRjz(5o@)Bb=rt9b3iG`ISbY$6 zK&{+TD1Wh%`0k?}kA{r)n8&9ffm5o*lgb&2h`WogB&hK?XU77xesX;*(MR-;32_|k z;@0)$vmt-ycBM9HBLv1GTK&8_3M)UlM?Ne`-5TYg8^6&?DiIN-z%7*p?0~o_op)NP za}Dp$$Ez`6A9S$2{exGD19Z1TT05l_z?(q5qtQ6>;zzSb*uWDNNgr!@5x?1*EkA1-KBiME7~u^2`0 z$#xuz`m6CMsSz_k1b|fRa=dLWN=E`LEU|~_a}@srz_u_mBYiNL;lSv$=6tv7cpx_5 z8pM$q0b)I7mk*d3jIKd~^okZPz0HAJYlA=l6j6vy)R_m|P1}%;eDp6Ml?@3AY1p)J z9=A^Y1op##Ela$5j$V=3)#U}aw;q;oFeNl*Xr>F5yw6Y?YF^mIhv|eAhVsk zr7g(@Fp!;{!Jk$vcM}a2Eb@373W*M$xeI;Um6GztNzYWS)w{jRCV}XNod+KF*`Xs* z%pdT|uTdT!N^0ioy+c>>*0NMY>*KBZx8{K(KR4!lQvrvj=0_EX`THt-1Y0nGjaAGB}+B1Kq%#Utzlhe;kA<=Jr=P6+s%jh^BGp4?$@Pc zCB&`J`Ov}Ql)*~T?eXjYf~S4_*mQg>`SRsUfb#(}7}sGXC?XOP0(=4zJ1T$v8ov+tXplz0 zKX~ldD))>(74+O)I_{=c*3w8gPQ7yilbG|T0PmwKrU7$tSamdSSC|=QQTEQaHU`up zz#SF@!rXC(>N+7aYnr9>)bsAsm^~kSr7jI9cdy`k^k@BNyZ&t26dj8K5}B{6RZfnK za}EJC0jEZ{baVh*6@TjV3=lJrxG;E0^}zUOIYh9;%BM!@L`mw(``Yg|dtfkF~`aqq4dWfm%R zTceNUNAJ}UO+l7^XSR=9H~COdb>jF+_=Y%z_rYYKFX>vT2}bWthlf5HqY4T^M4Cqk zQP0-{2#nvFWsCW)v(5zjt)|q3=*eMTs+zdsqxuAU+OIce=Ox{IRkJlo(jM_~^=nL| zfq)8#Qfxp4)iFrc_J6-&u>*(^zzO#8eX6p+tAO`0F%}LE#Nhh^@g(S%C^8@cCj*Wj zsb}q7C|;k=ISu{VudNvD?y<1I1+#6yk@%P;2*C8wk#WZgus+i;bF6{7QbkcvE<)Vg+H%c&=g7~*| zW{jK7N~@RYsuIcl{m-@9^gKV*3bm5NSJGS=$`LVZ@c|vcz%UG(*nnC<7*xKToSglj zA8c_1j@RK9D)zVis0E12U@gaL{VLqde;e@u(STQ>qA}5WSKYfhyz8=uW0wEeH=qAJ zr2PBz?`Qoi@GKbMW35&=r1;xt!!^xSi{@2_2k~uFkY2rF^V}1mfPxtfX33<|X;$^5 zv@1+{Z=O5g+^@N5t^kTD;GK^>KgA=)(#j~e2JJk+xk|?DV3{Ms`?!!S-&Gz+1E?IT z8~DJz{!NtGyAE{%1wB}B?$6w-uFSZ|L!g+UzH7pX_tfVl?MD|=sq0I6sh&xPxK^_D z@V*~gW9b@ujRjW15kT+@QX4QEp9RrPK{~VT6c`EYT~*R<9qR;!V`IRxVslpu8Hkzt zqNxw#d!p#lOFX;_BvqGn*2jN~cV@hQ)?Q(MT|Q+kb*WWgpjb;)KpQ9YnEc&hh@DYQ z!vyd54D}3ox;M^pAnC5SPvB7Evkda@8vdnhOxKvV^CU|q^8@#~7S zozb5OKh*vbEOha`u5kTJ&zo;U^z;KO-O|K&O>%|}ibs}O)M69!^pfhnlRh)ISd}_1 zmo^O5u98KDwtEPE8RS=xYHNtca1@STdr7@Q%fFiuzm<_Nm@M$xzG8q{rqqI$l5Iua$iOecv>y=W5=R29f8U@6|ee-BCXhl+e4X1eM?Zg28lQ75po z8&)_n(naGRI$Y9&Bl({BRQ}f6Y|t7t4TD55YS;;ILFyXRQ#joKQFv<)NiFuR#lFXs|quq#8Xm z*A%I9hD!JyB~m+L*zjSv)7Q#x45KN15{w?N?zE<%J4uE4HA`YY6N0z`4mn7N{EuFO zJPKfx2bT5C)CSWOJ+wr2WQcDNmU{Vc;QtMWUUmAvCa4DA<_(K8Mlyh00>=jYK)wLC z_Y@J=dL7BCDxIgoo)TN3gz%La)I4`xPGl=Ywc>rm&9BtyAWMN1B^d+y z*bLnXX&o8u7F41symxZ+8YAOx|06fqCO1^V3sJ8TZc9kfoA}=7Rx0<$9aR~~VCrew zk*0~Vz7&wKQ=^e*-bIj={94;nUNa=!JxI>S)NfsaO9fjFh-I+IdvB>{3~#nuq|g0` zNy^nqd#Wnt5nv!du9umsyi0xq6ko%yeoF~z)#LpG<-v`QVs}&fC&%qC#VZOY+QsK( zn$o>2YgVKB>hDN`dILp#IrfF+q^OKXL48=WP&=C6;9J~4Ldu_tCy3~mKIj)!En!l< zH$t-F9sg7TACH0OMTYvsN?Q@xZ_uM=RZtb6L%OW@x}mHDcwMSaGUV6any1}0Yfe4Y zgMhKN2b3ycNq~-)lwV`D0l<$r;5vA40KlfFqQp4;qo8DkVh8a_F)~0gfERdHoRF;S zdWj_xJZ>l068EjQHsLHeCbhC0tWwdv-_0?W-4`#ti!)*C4-);XSz!|cpqKc}p6U2i`S6lXI&V`&{jI^RySsF?RxXETpp%(r+h5vQ7oz>Ne(3kHYS#q z2I86l#|oF_e%5o}(d@Zg=Cd0xX*iAItyyf%2U>!7m(|_iEP=pf>FevOc=51s2$(D` zx>l`Ca|%u=fCmNqb1qg65)_rOr52wT7MD8vNd~HPQyE282N%mrd^J4`=cA)zWYGZ(LaY2v}5fOm|fk^;R69xwdOR?xRkjO-H zKqvA=z%m?iTfS>>6ksy-{NS=)siTL#Rn!XLmR~2AjGZWP|EzK|zUSM6qoY0?2I7wk zmtb{S2&ZIs6wN$;f-7Bcl_DUyZq+%aSwr*3Rr-7 zRU(zX^hgo@+U`oo+9{J9fqzcfD1($PpQqOTnL<6YjukNmQ82V(29OE?8Iyb8Q2(~+ z{8r&5KD`bq2An|fRT$)aDGv+=!(0)0=RmQ>lE%GtZ6yT%YPT-Mru+W{p?Pc&;!6;{ zhTEUqOS+sn^PalEKL&!M;QGBGn>(^P1N!-qM9rPE`Z61BDZH%}kU2g5pc?d5OlDMO z8mo%1^UX!7_@vOid|S()CjWuiI1?LCTN4e^Y-`+vZg5g~=S{zCC>stu@U7+j%>==w zw8z}tIElogW8d%EF@o6AB)E>tkIPM)w0e>4J@8_p=`6tRn8jJG`4%(bel(5}D=m@B zs!P4(--+M_Hzn5>l~B)b00|2Fz(uv<>I(IE0IdOH0#I34aPlZtIZcuAWKUbWLIKvQ zDzofsUt+hB!jQ#&INuD~eOfA8j7pz$LS^hIQfD32&fJ&+eoTg^vmq!pdhkI@oHoSN;;c+i{uM(xB?`j~X@h%pF*+ zPVEBnOq$DDR#0|azpYm^eo;1-U(nkBNJc|cFyYkyaab31A;p#*=aJwK^LLF=+jOG4 zzt>aHd+X#D3hYIruZw7_O@+9=Ru- zIewAaBq;l5`Shk$zvI_u#fv3&K=q2I0r(@yqsF-}>IiBO$B?R{;kJxNMmO(LKQ^6* z&cR{CRX;#aFKFtI#H^Wkkn3TOa(GhWYPQ1XgFAF(e|Fqx4k}SUro>w2h|pUY_%eY|@2p&YSNhJ+ixC&?up2;IGz z+}3s8GXcc1e`5jARGz;Rw_*02zVXN=n>RaMSDtz|69nl(*sUm}`jU|87T)$L!Z97X zWKU2?Zrz{980=dT1-I_pImzkS=@r3lbwN^5*aZS0y#%>XIVo z^Ai28NjuZl*rYJ=X5p=OlFzoHn>`**(XzaH%)6IFeU;BltOP$=xoA8#3N!cBf)BbW z8@~jx-S)Q;;Bl~U{9{jnpX%<3Y?ELH-ne(2+d9nf7d1W1DE7&#KQVwY0);F-a6(~L z&kE(@tdB-9*G(kz32p+g(b5<~0O+SV{&3FN3OF?lpZ^{2&K&(M(@`SdZK+!7WbM!u z-YC{DThG_;h?rK%mLAjLNP(D$fRr&39NR=s6PBmWhyS9<=XuF_~0kSgfwXv)9O*|npZJ4YpMUH=VW zum_)Jsit$eALQ$~JpMMc(yh^$Z=N|^dZa#&@|(_`ixv2t1It+oxLG-L_SogaDXdN# z@&UHJNcq05)qe#gFte8@bD16JT@>X9+5r5iN`UgkR!J!<7kPOb#LVR~YO#ox$Vm*I z9x2u3r!!|`5B>Arp}o{}V^siVXw>qftuQiWQl#VusfT+78> zNCA+e(*St~0X}}5cA-fX-Mo4Ryy!8G8ECO!8FuMR%d<0_UqxC`t!zN&bN}%&9w14u zty0HnX+V5|R(3Z|v#br^6f`vGTMs%K;-)jDRrjRwtTOzOJ{kLn@X4+p&-&trfv6n`X5FS80xy=HRa?CN~-HZo%VaZE)K$c&B^8hWOK( zLYx1NF#molE%?`dhY7y)ZXo5sx17hfIJ#BX6#1DD2%W%_Tt;58#-K~itONO&bIgwj zgZOhO!^~526$3}DPpDug2v1?>t3~N-`hrwm6(z1Pu380pg!jT;M{z&|QN3TV8~P&f zMIb)pxPNcd!piCz=s|(*Q)_oOF{pI`dx2n(z?C^hXe)AW%wBF^%(DyqKnE>KMN1le?9&j*Z$L!4Q3Pr1sd`nfy` zhgSF>x4DJrKX8qFdf{-=HtrP@IBKSkrypRtKXIjlN5xN;=5M-kxb4?W@Dtd{dpPhE z8GO`=NyJZZz3BJ?EA<*ddi<~-AZR(xWFOr@gl;9uO(uldb zvrU;1&NMB}2XqVLUadt!VX-hP?Ag7ky_q^6vc4>OK zRUd*3IN}?l~R$FWMB)282-+011?jU6MNsF6d9!kD;b*RB`iRKFDO<3VSo4xi!(*HEd z_qy8tg~o@9zpJ<;n7H+bae1IjyrzHCjHH7#na_(;aUa*=iLvxDHkSVU^4Chn-I~(0 zKGx5zL{|-E*NsVNf-LQ3e5HQw!_)?0Gud63^ZpWU7~!a&nUMEwg@VNw&P%60E~)w? zuD&g%j(#_({kI-)Bq{(^7M8dB{tWcfTzYy@NIZ-a5^#AaaQ}4gQ<`cU8-kq7iR1$LKq1g>z#1YsSB<9q?mMKGE4MVXG2|i1PE~joGltw@R+Lo zr^KQBC^2s|WdvmEQq6bsWWLez6Qd1-el|K(Uv@XZX}vQ++D364>LB~0G1Jek83*EQ zr<0!rgm#VD#AZugk=*B!sOyMH1CO{XUEq~9(aN3JA=!SfFIIL`k13X?@Hj~a#}UZ7 zKmrH#4XBPlXA5+>Dww^iinp>EUP#$!zYEcuQ85-r>IY(6Mz&RA<&cP_Cly}*(E<#u zNP;Iyll5_}c+rHJShmU=>y+A93pEUNJVdP1d_2kdbY5~+aqHwVE_e;&-??DqLhI&t zGTq_acLbA%`K93Xi~gI&{nwkc?(=FDQ0flbib5Lr$k!;t5`=ZBx~@}pz(i^)XiyTU zHylbgNW^H~;vlE2aIcr^tA$Wx!-@V7f6IfJN-Ktm5xejICN>dG+pX%zW32X9yk!O& zDA+^8D6e_$SJt0uFy=OR=>2{aC5%6kC69@uQ(^R#Nas(%B-6 z$>5}SHXPl37V1Lm@ld69G&PI*ykk#c6zTGpMd_42>=T|!!sj^5&7(eo@dcTXFyI6M zkig1{-O)E7mubO10S?oknnf|8$ey#zM`2@znxLLKu!kA)dHG@juX6proI5R+SdKGW z-3sHWU!DoovZf1aTfb8u=HCiq1^W#sCCkj4@u$2|7svCV z)Rk%A2Tl2GTf=>OR;9L;+Q86E^>KTwfXde_0=g$IT2d<6Q%Eh%_F(+{@ZJ zd%^=F9D1CbU4mdi8Gm<7b%Of@WJ3_5;8%saRUhEIGV{8}|KyLyfC@45P*l~m51;UdLO!SV4bUNget1F$ zhhxoFzrGack=Hn zZsERKGy?c4U2V#MNdhGXHERnRIfCx|K6#SdwfF-pFX)^@@+E`w`=qaPZT;dBl1>(1 zvC&o%47glO+akLOkDEFQ_)yAN_w%1>!^rXHuz#15xc0xG0PHm%uliv-du$Fc*TBXe z*Q%+tzgYP#>U>G!7~G&}`HLZWl~0eCeKtnx4#hxjMgQ#LZwBqM6S_Zx`$n29ZzWZL z1W|q>nKePhCyb8`hqS|Luxfa}HbXml%SNz`s93K+JG`KDAS$PJqHwYqq7T5WyXQlK0WVB3KN2}B!!ZI3rYQOz=ep4Wi}ny&cS zcK`zw%M4qFhbfJ|r?_1Tj+y5aF7oTk3Wh`__N0B>AzC@#@m#K(T{{? zL1vW8+70m=?{UaIARdtN<=`^|I1sFr$e-$3;!PUv_A2n5{~`EvxhWZjDdX}oU3ZP! zYh|yFGnhn3O!fmFL8>$SWUn~ta61F$hde1kF7#Pl|~RP=))?+eD&sS;hLcC_+u} zk^d&d|MgZoAnLW3efJx9Y#lCEx%Zjd*JN^F#a$3cIIz-jKG4)JnpkGp@O6QL3y}w-B|{E&8;4y zIq1rhSEta+;Y|vX_r4SRSd_YixU9A?&)GAORcirr-N=hH542(Vk z{s!=Y=C-!&ibObqdQ_u5QCssF1G6f~x2zLzelC1Y*O*Kj1};M%9loUlz z04xBlIP42_F&)HBI(0R6?(Hc~xP2acJrMNp>NYNFsO!@duOsqIB2o+`0%kn^*Q%FK zm4C~y(o_N1A=Si_whl;@n2#o~+D-Yh@jeH|l}9-iW!`#65ykJQrL0*cB0p#K;youE z(WaFuq}HxlhY>XrUn^gWpniEGQ-Q1)TYd3mL7}BrdRbFzZq_bZw1$HHk)OY; z8F}ss0hrOz(|~!SF1}YW!Usu zJ72FinM>h*B%4I|b^H~d-c80@g2eLBqvXMhewUSl%a;x88_8u>IUN0<{9=jx%rEhw zJnB=i(`E-;fGP?o5r8->|Mubu4N?dw+KTlL!_k;53}dW4f2!N2tjp?3dFHy_2q|Ac zOuh~S3g)I&7_qo@ju2=q4iMir+}Z12qa6*rm4nd)4~P9d3X39x&*B|d1fEG?m9Su> z!^I3dkh03X8h7G)?+$|XgH~^F8+h=x9O~Cs9PZ|4*=M~+mvZq}xwhMFi|PMsxd8ub zfE8T>WC7oaGHs#Ik)5N`s{oG??1L|fEN^Xjjcx!Lwfy-U8Q2=m2O|dP>a`LeMG*wO zb!=}INIK;}Ur=IjMHE5cn-(jONcCoYj)3~|8Sl=Q1zpRTEMnc265MB#GUYYH-){Z}+m6ns z{&ryT9hUKT(RP$Hgt7L^W{8-p!(M%sN`sx}fP8kJSAG#is+NE=vTR;7f|%G!*Ju#7 z>Ix@1oeHcaNF&qU@h5&n0~LbI`uXMGN%Do~fGOi(vFZ!iu)zXAo!Dggv?=1@h-bt+ zM(PU8?o~eQYywIG$(U(|*T0S2^ggZ{+IP5QVT_=&_fa0w5Ak)t@c@yzDh*VMct0|G z9U_%n!gr15E{-JsRF~*{r)$2-$Y?1X{pP7%07PT?wP)K!Pc4_-tFv#9r|TGd4T|Hh z*O28js7J6Dnk7jR?Nb~#@5NSzC1OKlf)$PN&=VLWA#u zrIoAPFrUMa(bTTM7tq49$Dx zZu$51RR)-@2t9vSIRkSP`)|5xF%L)pv6@<}B}m1zCp}P}fiNynfAR=mL9ZV6SlKsS z0`&}DGd^5E84d+;zyc@&EB6OAceb0!(3fXhNI%pW48F)~3Z9|Uv;n*o8D%_Y!A4U; zOt(b|)V%{e{aIiquF8PK?lsT@0V6ls-enk|%aJXqJv4&v=Q3xyZ3YuCHGu!REq{r; zY5+noAt9k)tft?cXYc=Cq#s40JoJ+iA*iiPXJ}X1h!P7*kc-+6P@vORM=ZclFv*Dy zLFOlkDjxBDcbYt2<+NZb&tXLCHQYUm2KVlOxW7JGQA#8jp|8b)TUd-f>};y>d}XV4 zCpNfmXAutCCjgK$|9dtp`jRgf5` z`^^s!x_xVBJhbN5-K_1L6Ty&0M_F>^-mLQI)baYM2jQDPAuzo^-A~8afq;fRQyanT zL(M@xedZu^o-Db0X*4fxx!n6Y)g}}30YBDt8XlubQn~NdB*jp+5imhnkYw z(MT6b7KCyI2^A@*fa^wmW$=d!REV_@R1oriM8ru$$0jbfsRU~WAn}Zjfg^hCC4+pI z`P;?q&7t4|o9De~gB%XvjUwz0gcbl@ER^RU+r0+I2-rQYb&GUQ{j~nCVk+HWLTnZ5ew`qG9V!hdFi8YN(F?y=QQH%}s&@`;y)V&U(ai3< zFES;c1tVnuId_3cRknGi^MO{WfEk0wmSxmqGR0fLvHRs@rP8SY|6yGp&XuT){NCCb zrLP|{UOquq&@T69AN?-fOhk&w#lUObPF83%rgz=z%wwkd>(sFu)N^B$4(tleSWPjR0)lL_J(4^V`xagFLh*czn;*z zO!fS^Pio5jL=oG+T)2M?qnj)|I1rs57-bCl>@A}Fpy?P-uuiFstNP6alV^|;q@qwz zue)zWLUldkY?XY!)vEJSrUu+rpjm)>36RL4LqnuLh$IZ^hVj==S?ea_OqMq3ByNS` zaO1!mgkxgfbMN(i2M3zsLC0f=hydnJh%gM1g;YV`O*m$gxvi$D(5JrA5E*Ni1|y_%O}$(s05dxrBnqmfmqX2+yL(?h9Va~?A7KD!XQ zH%-EbKEZm5#dG*h^K@H;%~!6s({%Wh>6m?fxdpeArX1Ka_v@W*rW_fvzqBYhF7c+l z>2V4@)v)tLiQ|LSK-h3Bl_qCBijLUfKIoj4o@9DXEw@E=(VL%#&AEGedsv;DV0w#A z$u3o#OdK?R7(6e{brSs@MiBjqB`W3IRs?VWIDG&gOgh3xW=kx(Ai8Ar@uCR9`pGm0 zUg?ni3Cmk1pXSFyXQ%k)i3$|VDeXB6b%y*nrg^UQz2~7I|-UjM0 zx%81&O})FrZ<&ZyFG|Sr9BuZfv^hiE|9^_mgxEK+bew-TEd084=dTqFGjn}!F9WOB ziURaPY+J)HAVg+SLzsFoEZd!(-RIE}4*+9)GqP(}efRzxMT5SK+(&LzYw_ZezNNWQ$WjQ8&uH zu2uN8Z>_&6C9@cmd;Z+`V(gLegao9=Gt2^H(v0B^GQ==PB*{uXxW@v;Y>I3{#$>3n zkp=Y^Z@z_wY9?mYo{g(FZwtRxj~RZdd8P-f{W@lUqiM2rdX&HyXF{UG1}(A@(d$r# z8F?cccqupp?tny&o87ZOwc;M~m%j&B{JHr|eCOCoQ_sF3OQiA@>5V8kHuGcJrF`Sl zRA8>)9AHVzi32eO?Iaqp(lzce` z#p61uyL5*$VTTkb2O##3Jpi03#hR-c{!X+u_Bwe%Zls|qDr2V>b7m6A5he` z$B^~Y+EYJuksxldNI7Z|xpQ_BsuA!{Vy8%APE2-$0!x7=?bkzz_^6i2GWm!T$AzE$ z@}9JQj(@WE&2rrkc*aibF~OfaSnsDbtaf0#T=phNtjZR5`xdwotk)_4GR)m7s@MY2 z&**5{fN#Oi`)M%7+PK+l?$pxinK^i(8Z;$WDw7US^_f^gr{k;7z zK9FY;HAGDAradQcZ&q%f0|%Q|5=UUlMKVm_c?0Bi?~>)Jy(x6w?GNDl$c}&=hlhtp z;s$KRU;@6lse1RDiKOpNi%E(TAT!88TXt{vJku2nvI0mfUFC9j>6FABCn%uFg=kTk z&8X3$3{y0eUDeK1RM{2ip@4Hv2Y`s0?`_DtP-(%7J62nnbgl4Ns%BOMs5x?O4-w}_ zUj|tU96@#NK={!xg)e>LgC^GJvc3r!7fh|tS6_U9b{k8W!^F}LS?M(+%I5z=a zGF$K{Y6g#Hn3Mxkmrqmfz!{m;YH68oEe-Wn`&JLgsYzih6!iU=@qVdB4^qXY+{R3n z%v8?3+=EuL;oeUP>_jEk4V89EMzvrrrX>e7tQLV-q#KNuvSSm-Jr><{Lt%=(SW6KV zY>noizUl2E_=9G8;P>y(fjUs|8$F6%W;#A&{cQSXo)52ex#{ zhv0ErLy-igLZP7bR+6RSU_(Q;)SmU$E98tR8;(yN&Px84U}Ww)rRg)layHyxE5ZE2 z@{y7CbE#BRJ4x~q|F?h5NMH8eDyOKw)2&)Zb2cXxmZbVytlkZ29^R_jx^!Jg6C_$$ zsXn_HSpQm!$)D^)gb1u14J73rkMn`CMVp4b!J_R?(b z$lgMvnAVtG7E=Ft1F=Mx2a|<;9|KPkJ6ouGEcTsNiZJlAvZhiz9x+U>u?xsbS=)2Z zr}XI?@lM_g4EN%*2>hu`(vGQ|lbrRUOT|laVXspj%Wj2vO?QRS8sG|24B!+&iE4!7 zx%PLv_g1~hyT^<+tsC&L`gSRFZu47(ao{hRlyeS2|+KC!n0dZ`_ z;}>7s$@x7b(tc<8>0@T;5pxH}M^@jOJ>x))ODqoChH|aX~=<;q@$) zB2)wP2E!L{uMNXZCSIiei<|zX{m?6cd;3BnxwvPrb6y?8g+*ZPWs? zv|$%8OU(~#j1kKMcUin&9=ft*F7VX&W_ZIq9Mqcli)k-D0EwwoSo}!3@pcdD>3lce zY0>D>WngQ)P~M?~%qt({`uJPj=g(ScVZZO5@nsGTHeiSq`xM2W+D;-K+XzqTdml3< z5R!5+>*eI*T8d1Xv)|f8gAJK)cm{}p$wG}VkM>uI#)5tM_GEc>`q(QN63o*9Oj!FUGf>YFR;3Us(~ z%{%AA?`~3}85n9n+6}F#VraX-=P-Eel zE%owK&_3FHE~g~aYjL6oQ+{_rGC~UrJK}uX;8`&Fg{A0iBrgkolKJiYtOjY6LpFB@! z@NivT@#^#pn{|J;SD#8;>m@G?jRc5~!2-m!ovdDo_0;UAq)vxh^&F)s3Ym8HPyuvO320_~Y0eV3{dD`=Jl|jjohAOi*4yZ>VIHj_`AA(QkUT~`B2qdZ?<}3#nTv$u zU!eQ&Z*m8jforLdTkUO_mL7>x=l>t6_tk_E$8=qX~XG@HBjF0A&>`8XQwmXm2or}SfZrYC*aY&R76s6Tp5 z&g#w4x$PTmJ+IZytJuQ|Z-JED}JV(St%&kdC3&?}lvYP*uTd z!(GKI56WxUh6U8nIBj3R#=+RKEQL*ijnuz9<+VP5i2yu?K%Fx^rOs*9XPqRA%>c~5xd3uZ-SeVUqUd z_6I28p?U-38AM|Uq(|^Yfj(nNrVcw^klL>CZrcBA#E3g6q=3`!J^ff@>+blwus!+Q zkm{7IGMP$KZmA2F_88V3?=>H9^WMJVYJ*+lwi$j4QsCf_Fxu&BM& z+~GZUM1(=IdD$@4)hz$*b$NYYI&8HN=aqb$r~?i}tx{G&=hl6O?147+n(2E9C-~=lz8!$JY4JkO zU$t9uJr~G0k&L0ml~6p+-BE)h3?6$kYaNoxkzk@Nhaz7ov3*Y7u4V`N_pcEg$__wd zM+63LZoQ>H!9v6-f7M$u=Uw_Ei#t(y)KuTx41e!i@uqWmZh^2x`%?3I`fKaIGi@i7 zKKt9x7)1jadtj$P`dMm&DI(0lkT(Nz1wh&2ikW>1Br zF96Yi#p@P*J6{3`lgJ)!*7ul*{3a1h=bFcSj(&{0%aaW-)Y6TeJAV2D@AGS+H`Ai^j`IO3c1KD5+F1qK@kuFHBYjWpM%lAgz29plf7&vxzmlu7ak#l& zCH6Vow5dBiEh|XkU6%Vytx86p{>(8 zRBPUM%c=by?3oG*5`HXiwdzYd&(J*l!UQ%UhCK*mk=Ik-(V^Y!-n0|5$U%|(Ic(C$ zN^Wt3yFJRYk*wG8;%tqDs_c$*#G@#`@ne1?zog`u zAQi$(5yu6B4GjtT@wCp_co(aBlTz}D-SH7u841aER@T-qarm+53bHiyN0PZ_bvn%I zefiD9Hri1swS}PAt@eNlF@(#IRNpL)?5pfy~rVU#jd*BcTA(!yWiNN_(QOR-aKlHoJTwt-_h=TTx3* zIn`+MXmPT!gZ7PBxeK*NDg7 z^Bt&pVP3QD-U@qsKzs^|R)BfQ`1lsUL&XE4>;X<@>h(G*;$z0;Bg+EJsXIIFFp~xx9UAI7mmy0WD|5=XBDLalQqK!4HY2HdiyP7p zye#H!Y$nKu<*U9}D)*ALXJ?*nb;ST&9+fE^)fBJqA9M$rOH5=977f*Zl%^zQU@b~b zO)Wk(^@>AlaLwj^(=@t=mgO!cGHqZHSw*GF_0gdCIAIld=%Dgpx|1U#NBhQ+U;M;o z+^L0vxcN@k%x3FM>I!i?$Dt;=@+7uBiOaK$TqAK?db0_c|9VUR{KKU}?QDYT7u9?D zcdqheW9--&zs8`B=&{BZ>71bD6l7O>9OC><-Zlz)I{EP2s!e5B?ijXC+a zdkzNW&>_m@HdfG)z%dp=ow<7eo9fkSUn&n*9Q%X+^SBK2Hn!DjwJ@%d%4Bfm!M@8> z9t|l`B&YxKUQ5y?s!b>Kqi=O$eKd+>HIHcO=QSK-Y3!Os>@Kt>8>+e97?8Egi1u|I zHS*yekfj{dbgXXbDLjmpZq#()oepDvYsgQC*3tBzcAwesfVnewYgQ0lkX6+(vmpC& ztBhG#1gWI7X5CYaU@h4xN4tsPxLNrOPu!xZ$2E7~fSFoTKj3@-_XOTQLsoiF`kM06 zFN~*7QIF=Y`*K>g;q_uo8@72)?yd0B20tJ8j3n7h(L`|yrIzO=2J9JrAgr2^XU>HmA<)Lbm^Jc*rAHZ6^BRN{`@V5DB(Z1 z4Bp>+`uB8^*}5OnF?J`a?5kt(y*1xu!|*M-A+$J5&sWZ#Ce9l~=;Jlby9R4+vnpdY zyFEv*}V{xRYf086TR01+?~(s1P$v=^{g6v`y6!{qLirZ^E;nSuL)awMl!<)^A&4&v7e^h9cXan%Iz z6={JZ+!XJ7$%rHEiW41a`d9SZeyJY6*=Is&`bhk|&NAjk{pSd@qJ#k4gg)CkY?AH( zPir8x+~ViR&B6S|Xv6yb@5bh?%(fIfMwUqel%8C=vF))C`xaewvKbO$ZaTllwcx(#@D_y{(TN^^Y`}lw?FU4>&6x4GWd7g7g7C{|7rdZyS%mM zeevSOH1MI(y9kDf_rU#*A@sVQzW&v>KLsB}**uJty6xkyuyj%)Y_0D>;3Z14JN?U! zL)aV|>HeDUDK>xOWA}Rzge0h)!!qlnm!VyGBRyO_Ltjb5u}huUV$+85q{Vw-veds@ zTpGC=<>kW6`<0Ae7P82>uIP~6@}KnAoBbB4$;Rxg9$-wXvby~9e)Rhj+<`m7?6#>F zmd&KXDE7QYlo^5>e>#?Eb}5R3z?)i^GYMdeKU$jt*r654{SiVK;Il-27<=XEC#3hN zu67b#!>E{%&@(%01env}1Xb)63uAJ*rqu&(yQfga%H5J|$IJ&VH=+KhJ{X_qPnpP! zUXts3Y}~mn4SPbLBc`r?^)3}NZD+rqOXnnw5&aBN09ZZ`zvv%zr0r5MWjB(GN-G>B zcU&A;x7{)d;KNBR<0UdID#h=rsp5J#k%H%5)pDZ9`;_U|V5s5hdIsVl41ICt zBo*8H;q$*-yPBMz*xKavC>9SWRT{(cE>P=&PX;tSFkT1Y28g6)w)Xh0ybk&qRZ|?) z0BC^%P5c*)w00Mcyvq;xC#D@`nnfF;<7nfXHhC}V{FC4QiJTkd>`yGt|2nTqrpQw& zHZdQAIvrT++$_k&=+J9Mi(eJ)p;>-J{$Z!e`;R%%W2!o};xo&5w%J$r1}p`Q%0?Jg zVioi$s~8wkNWWR+-w8NFRzYM6>?e9d2Y;d$C_hEHuUv740RW#tkm7x@GV?a#aX5q5T7aXj7-F*klele4Bv;>JUTwW ze|lKwDysxrM@}Jaet38+;bMD1SWKw*G(HpbJ3mNbF1exfQddh=(B)1gLuljy+w2DjuJH;n}Da9n1qu{`5|#{HTrcUb}9#PYM}^$7n@V1VtWrrGL`Oyzyy>ZOz9^4iouY9#0n5 zv2$+Ox;-lSc$jy%gX-qZGXHcb*t>RIz~kr3QE{CA8Cu#?Kt4C>^ua^-t(Kbsi4f1~ zNd;+1c)H2Et^f`eAMd?#JKGh$t*jseQn$e@Z8XX3n@F2GZ33@Thi=cl?_0>#ix+pWOo`(dZEylC zZ%8e)A=#B&pS@^cXc)A-2Nx2VZg^C(#>U2KF9{nPEOF#U_*AD7>pC6}u0IPqeL6a5 z!KwG}o?r(fdKfT`EOX!pU1i~@2yg2@jReGU72FCZ9l`Sg+Ef_aLWTg>0O$yu{4p3o zoASwtk->H0FMO%>=sV1I{qtZO1Nn0#mg1{LztX=;*SWr#yNZQZD#obWw+AoeRnP(e zJ^SfVfa(`+i~8r7+G|qpct@<~F0`*}`|FmGr@yt*7Szp*|8(}qpA=H+3C|9R`uP=U zGHssc@`_~|3n+}b2QD_c#jg$-1hODXW(+HU{TUWim2}~qL15dn?)GIU+3o-Ze%Gj{Y8jW7Y zqB(yQ^qj-PQ%A(^h}{4x-ub!kBzoG2IL%hf#*|FXx{`0$Nsu9a$BNlPs%*$^uD>v> zaL93CQHF;oBB=#~cSxG_h`90P1~0?b@nsWUI&GI0PUmqO&*gs8=Hc}sMV+>=iWA|% zqD2c%+~Dpk_U-NE5O2-MuU*%p2@N(-PQV9Jty_w_MEdNIjWyyD|PYj;AXk{cPrj=t_977A#2%Wd;s!Pm8iF@5!-bpUqcM+eQ zcHcuMNYnAwC;cm@-B-NX0J4~BK_beKU61%UrvqUgBdAw*Il(xR@O7Fz?*hwXN5g+# zdhj^A-|;H)e9Xg3Hn);2$QA2LVwnv^$(nrrwKd}*J%)yTNaWA7uVIL1+n?G(AHx+wPnz!eSAN?L;&3+r{)87r*5#J+ z6jTfB6xwzdDV;dKnfaCKU3?{C6+~hyAbR<-c>tkm`EBPc0|Vn<_hB#~%+?iFu&Lwd zanZ4p43O$^0V7$B7n&$>Xe#Z>7sU|ACpc2M^T_tf zU@((Sg5Nn$cNEfPBQVTP2EWc80>KB>ApBO1i_`ANeFaO(?+2xu@nr48B*K<#Ta?Kn zIk#I#cMNi3i7ZL!2k9Z4LoY+7x>iO?y)b`YBw*UzDk)*|I4WF0 zmSp$9=cwe=`VL*!=Pd$fiRB-4M~?m#ofiiYrZyc1JTlC-y()bV1l&*Ln&m3BeL&yY zp(1QM9XL{B^4khHLMBg~6&a}8pur2Jc&#B&JUm}yxX!I){^6Ifpn9fWw5M!pd*Zan zp8mx%Iwp=N({5U`TvF{CGpJw=JSygmmg`avXH)ONK)eK8{=m{G)F5PQY+V3nzV2JU zE=@&7LXaltBLh7D{Ac>P{_ORYcNJlz7d!GxucUXjPDY5Suy{|M~Hb z*RbDtvYVFu{8G1)yiCYGTkeXW8k?@&SLuZfS>xi@8G^-U)1%bET$c(i{Fpmy0K1^* zAh?PGt!31mb@Nx%Gg!_Q;51@j#>&MR?e8&=!GXteUFlfQ0KUmREcPTs`+)f}anN@B zr5=6ELvYw3yF^{5B(1U;5cYvfDb#V2$(qfST=Um|8eL`$gIo(+7eN33{6xEldHdF5=jc*^d?<`Y_sUu*O&1ZsT41p1UVEgF{L)_(~|C; zWl8)mAhO}5V)PIWN1y6Ht+u52UF+*)>5LXs0VoBU^oO%h=MYA*Mps;n7&-arjyB${ z_w3Iuw+J^N>sr*eT65~V-W}X*Aq+&1tQ3#)&|f-0pahXfwGh!gJXTvl2bEoB1ObV` z=lUoNWx-4cT*7Eb{jp3ib+-J`vgJ)k8y}HAEPf45&yy!dqLy-C9_qHRPWg>2kO(n8 z`guPHP%nUc3B3_~b49j&g;cRWvN-~$onuytoqy3-HA}>Pd7C1jK^#|9qFg?d>)$Qh zIs@bsD$;zLJR+5h6po;9nw#Bc->!qUGks7tDa)=HM)@lfV1@_wRA5U7Jv!uWph%%l z;R~{#b1n0jeO?@m6s@NC#5wcj_2JLP4ze0Cx2WvnePqlbIbE!%#z&aPcdMb``c0+o* z2rggrz=N?)!Zu=A;`_eX&~GjdJiXi|PU7U`)c)8>_rtrGfOb*}XBpH}e=?mpA)1RU zx1)$hsPg;yFH0rArk+{bslc385&ChyGxeuv5kx0sP!Cq{(8SlglcVk{G3N+3P!4L);Z+ZGk$sE z<5y1w&<-c&ht|AU{FKT=`&;FPNRz0I+*8|lEpe_PW7_-BHcUk=3773pFtoUSE3*{7 z^=`kzucBB++4h8k+fXa?drgW*ntohG1liK{Uyn!{lxOr!Ctg50T-UH&1u?JVN6AqmkSCHa4eFRNK#`pL&TCuJK0+D8xd9Iq@q&SYqd!OxVzZDkEyxriU zpz;~V3FC5_{Gh(E&M9ESRpSor_8f`}_W%Py$oj0+oN9oqof4u`+BdO=%^PF@Ncadfv7;lBh!>7j z=yi@GA1o>b+yw@5Bq?8EvgpHeZ*sTu^kUKE&}&;~8re{ZkB@WdrPn|Ay!qlr_>u~) z+_`qOuW{#5@j#>57dZV;4Mx4VStst}@BgKv41!Pj+Rmc*aYT55aGT+M1Cx<{MeEOR zEokZ;&=8mzi(xxpcG3DytIg^$O5p?kWfpt^BmL|`&aa2u8vJ=J0=B>jp_2#EI9YUz zDih2I;AQI?|)Wp$*gopCc zPYRJ5=gz(_H+3XTbbg;(Z>sX4t90>g}N;W_H9ntx~du0B;k&$*|%>4?=P5|8POb8z$S)9 z2XT?ThZ!3?>fM);_0;3^c-Yrhft^@BP06zs2pM`-2Q3NET>mzM316AbPt z){R=k+(j?_LKamcNuiH{BCwIV1#4~~F;#Oii{GD7?gMPGn21zc0qO}ogmQ$Y{J3hJ zrL!9W|Bk9heBx4#oGr&If=Hny2PQqFXt)UI-yPne^SYHAexK2(I7*w;#gEyDltxM`UR&iONN@&irhAv4OC)Cr0VlQcCC{50t^+*YucAGMfjt#dq9|D1giExqVwBtc z8K$1L8k6V6m0Pv@5Ydyc{n^GNjP17ri{oHw8#L`+GV|u;N_TP9X`t^*W@5`=RRGL} z3Ou*$5bH*_Sv8Xva(kcT>Vfc2hJvHN4VxWaAe%iPDj+=Z+_JgzosAh8Tp(~tt<~~b zI~8?)Zp&wRYb9l?LOJgK< zCbn`zldu9>EA|)XpdufGdfO!Dk0P3#&b4`vq>Z?=g+~(R0n;tTs z9s}677hoDayB|-M2L{S|7n$@X%J|_uulTbEv|S(;EmA5P(Zuu2<5o*+#7G1mjXDL( z$Fe`2#^6sU-xSt3YoiAza94}r+kB@#85DDnG#I97Q;pE`#(7VHm1gznfi^K4F`FTV8WBMq=!``d<@AQylNbkbUZhq$DPpv+p@j|0f_x^AS7FOri zc&h0s&5)xp_TqfMa+3xC-0thUTR~u1u8|sEJr2Xe@#Q~<%h>7U$FFwYc=ot^ zG-xd2W){MGx8Q28zlmD86$UT#!8Ap?0J-=>Ej4ZMCno6Z}U zNYm-IjH z5A;eEFFu6lsw?biNFC&?{zflDXEwdGe7zhUJPUq5V@R&UmidLeV1qFSkRDs(n{tYYXM#aA1JQ8 zs}c*}gAWVL)gXj6&H~R9Ir)I6oR0x_rO*#q0Q>_KD#*YvLxT3Vaej0%HxzG9GC*Mg zy)uy~sg&>$RvogAQ0SC2yst9%6DgZgkDc=C`cn&FmMZx-*I={wGO}8_T68s?!c6_= zoS=XpEbYW<>Gj^8`3)-ZHy2{fzgwft?m?8z{sS71?mQEFQ=m;K!ieMn8>QInwWu#& z0qTO)9#LAd56};RR+~;{E0##+TzKG|)1+^|U=4qiP%FeK5-GaKTPDj__R~!+fKy`A zc^10}?F^zWs6h@U@{R=ltO=}krXF^6xqs-HpW3AjfUnbeg|Z?&N{{%`UGi2<-=gQmdVcW+=7VKpO*FCgY1797Z?8>mE5 zrpMx{_qhO%fD+5CYjeXx29Zr53u;0LbBIy%={tu00>Ee$-&^<;>Usac14^*vg?}v! zDAC_VEq+80HDrANY}g!+V`*Gng$T(6xoCUrgzvMS$|aY-2fNkYr;{`f*`#6Uz47bs z9wbAD+9R2vFu()J&5HC15cu|W+C4p=gP`Q_7a%7IU=bMLA<#4EB14(4+=HM903<9o zk87#jI*7ht6?yr=7cQH~Y+ZqCPt2Y{ljT!w-!UgN#OmJzi|&PK>dO3qN8NQK%H`Ac zAUDbpjYm-|@m+n!iJ?)7z)sVM<;%YQ=-J@8E{pn3&tur5;V(R@a&YOYgDb~_nK=xD(%wxpjd=p4G9J$k>IyQWoSOKgPz(x$>fN$=-0hl z9KtUn(M=kYM4vJ(eq2*xlFn8+=3^*D&2J4!meS+UO2O3L32@RswAB*|;Z|8Oy8mgS&i`@}&?tDPE%R7kCt~ei zF5@!Bd;LB4#L?rwJGJo0NaQg@S#G!W$hZp5nByP?MqJf@Jp}7^MnR=V&?o&J4kF_@ zX!uXa?Sm@mJV>JaOb*xL;u8`ixK+fMLRUVR92|vQZ8>)UAq7nHNl>!TGK|L>*wwQA zS!H`WWM>XbwEpJbqT)*G7*$Kr;0G{#rG*kYAM!6U3WQhydn>$*!M(njFUzz&MFw?T z>MzT`VphZcYVkk=JR2;iHwcI~cmTVbX8(41nt=DL8h6Q}J1gj6vrk#6+1!NUvP2eC zYhsB{=F6aTYh=8}Q26;X#Nko#<3MZ2G7GV=j#02kt4lDD`eWFbg3o%5nA}n}hpG@r z%d;;(G9O_-61uPs2~u7;b2%!PiL!c|FGKd==$zAx!U z{BjwaE1_kZXlP(tOl@I#UWxLq<=pjyI`H-Cifm?C`^JI9 z2SElZ2T<4$`SG2%{{STf4--jJ&DgF1jsR6SnAXC7B628*M*P5eS#1ZcB(lg%Q+zDw zZIJ*hyh@MKtjm(!;7bBE@2M~_ny7W@F?tHA>Nw;F1SVQN@n_`(0~OhJ4Y@38RAr8v zYy|?94=iUPbm?e$?*@{^GYLSjh*51wPdj%Jef%kK^3$-@t!-`Nh_601s5F2=g6KEF zN8k4;CuU_D9!vW>>h~PA56Sjr+SPt_L}|-s>d((@cp%FMEVLGgLM>wwmhTGB>_vL5&umE(KI2r$aP zbKKweI_g9HR8brk_5L#6!y!l;eF_H#M-?d_3$8nG+Z6ZND0RmX++uCO)Bj)9TId%|6Oy}q$d_yV%JjO}oY4T%u(iHY^lNLT$iSk8Lr@-ZDMLs<8C z4ADCv3V+BvlYsP%9Bvi^#A^Ke4ZRs~`=LHSTI+>{i@+P0+mLJ|V4K~)L;{0=d1U)K zQqdrryr6Cd%GFASfHx&<;HyEtAF?}0z_YIL?U&WtFU^^~U^xi}l)rC~HVV`ga^L?1OLy(l> z=2Cd8=Vvedc~1`FKU!<1wq23&z-TW{f0b-cY;hE+bF)ocSH!rnqz)6 z^q}oiw0Jp_^(t7;o*Cfp5fno&A67s?4$%Z z@-SRQO4C6so&|wRyhqX{S*gfCn@pzNyy^Jpq;&t6M$T)T6Ol{8r6#kx#Nl%!dG$My z>rG!c@;KxO)Bj9}{}Xjsmh~@(hY+O|!*U{6=YSj{0OgRk>a|_ZCYx#VH~d2n2nt+a zmq3dM3mxxO>J_=RXS2)XO=;;w<_}E&Dz?DZ{ z%bp`I;nISt4{0}Le2Ph+YqP?foB8X7Yem! zAYU}Kvs*f{ObWm|Mg0%b4$7U&2_cwys2tw#!VC!RHXf*s4_4p~1+arBYbHN~&Ja-z z=oKA5npCqwef2>$*7ZiJ-%P@wb!4YaE^f^4cz6SaCNEk^9@a1Ngq!)VtrR? z$$u_yjg|2mZ*1{QYNhg6?@L#k7SU@z!4~xe93tHnc9HcqGuHYUvaz(dVLAnOk=3k~I&_j@!i|+Zx?62m0W$$KqVYU>U@5dgN z%l?8L7dbk5|2P5SFR`WA1k>@S@W;tmX^#Tm^{*VXLD%T~)e|tw?}-r2ps=9$wcT*0 zPv9yYsu6pQMv3D3PL+KcIT6DEZ=L`U{#H8dibKm`&r#MWwGFP1UowEz-M-u?NTcJD z@-)+Y_Ns>=iL=$oA8Q^-CS}!b{Ju^h6pT9tlI^|rhg0HCRWt9$^(NPMqNTti`L!W` zR(Fe=^mPDQOx~LreF7Y-*2ReArn_wQekA8}e>-3a0Duh_I@5;<59AR>mHS!jF?-jD zMGs@0&dw)ezNxzXU;6BZ;cW5E&IMqNNG(@5iS`#*{f4pJ&W>H(%>joF43CUuzJ7+j zjmP=o*5yKrA?^Tjve^XJP#n{&v{`sLOziPgLk7YPtSADFnGrA9=H5XS5yMAHC7R1} za$(S!fGwJSj@6vpsw@o7(w`du+Yn}vbV|@P1L+O;uP^{3lh5bYrc=t^y$$Rwh(q!P zFygx`2IM$+oBxP58gG)+gxm#KfdJz{q`~8lYuzCgbCv>h9)^BUd^Ci#17iQ+sk*_; zUKOVE3Io;Xo-FJrfFjTP>s*ZBzNWG0=n8Kb|D8iz|DrES^W?_!-0XV= z_f1bE-wiS$s?)hO<-BQBF1M42p1_pl_N;kZn?ZoSLKzB(C`mg-7X|Ml@?@D*N5c$`4p-ZUl^Xw3IcDqP%e&Pzgnt#xBdbwU zmbu?`m)usBDSj21d-QM#B0YftaHcL1eT|dnFv`b9rfta9GCTtoxh|T9Z^LVWbPjS* zn1H~k0;w zlFJap!#f%eZPvA$7Ncj(=*{SAze0MLRL!CtQ0MKObspWTqO4iJERpH#*c9z&d#bZ} zW6zt!k@H5Hno_{&yXDXLb||HIH|hw+Mu6Qx zMU^R_K*JDcoS`kG$vu2IwY?sTCixzJCSr;EY6~X@sTBiTU5p5y&&d;*rsBWp8zq?s zoKFY{GjHDFE_+Wfq!X!ZaxKL+E@i~?0?=mOS`s8rgqL*%;?wA?arJJz}$&z zCyj6VjHRNw!bDBLB|uLC^xD~THtZ)Ue#l&(J{4F7@G?LUumuA{3tUBz$ie-CR15?s z5?3gzs8`;o!T*~zc)NpIfkqf;6!-!nc@$NRlhKvQOw*Nkh2Oj{VndmypUgIJRz&>3 z)p|+B&a{n-qVbqtesAWVWKVD!MtupTkb^n5`Xv&^ zaf^|&I~2-#5M&gl~XbsnCrd!BfuHaCmcIc6}9wTx3}o3qZN;cBszrX4<|tkA zujf|@(2=C&VxL^k>$ANFn-tv^3h?>X?W{oTPMmlAH#&INvrTk1MV-(6AK|f7f)PK0G?^)n?l7`&ktzjU1?I|(;?`4A zV)Z`dQGDsWT}iU;PkkQ~=zSW^Expg-CCpv1q+;H&v}D z#@})CW@Ze*lh(A^{oX@G9LLy^+GnKd9Wk8K^28F%R#^3g5mH9l_p0>g{GvU-YfACx zEMQbjvznuiUvHysIB2!@3%ZI@m*Xxi6yKsXh8w!6rgyZ)j~;ibJuZ8Vll|QH6kt@t z_uS%|p{)Pm2g^T!7e*6o_CDE+fk}lN?fSCy`*%1gjO6j8mM~coRZmkIg&OUF6w9-< zyRhBnDCemuY}@RcDEZbc@AWH0QG+A2xBER!4ljXU8qG6JeGac-j0(5erPQeX*3wmP zxk-;n7hooyugrAbfXWx3rbfKWkZwO7S{7gqB48mH6W|XI_Eup`M+R%!8vIGfp|@%^ zTrGXHEcZWm9(bSxqrYrlZFrrttH_USU=7T2zI#$w=n)eMuE<8EJICz33>ja`WFcj= zt0W6J6OWV>Km(NB&JkGuPuT!KZi&YBt2UlYFIW`X=xrHzX?7)?{}@>uQF_P3s?+96 z91Gc3%JujTO;&+PFl{EHx(?8f`R)MT!VPG(n4; zzd!pYIlrLM7TW$^Qys+OJhf^+`)=IJA;mH+d3JbPzm7V^gg*}8T1WyIBIS3@@=`t2 z4ORWwQ{ui!PIcM?HyfRuXi+K-*VA~CWzh4OS~un{OwIYR2&2nQ!PbVS)>sY0HVYhc zdV9vbEv2>-sDDog(GFtX)qlCTSLYs=+A^;~9&M=Xg;Po6&J!3b40;B`n-azoSI@gw z49d|C4$R~B1gI2)%7=1dNbzYY~0h!Q@Av1-``QBPz z?H=uqf=iC=j+)zOvW{#tA9L=y{-)&UzRJwQEWQbsUgJ_bi958t>k=(a?w4fgqc|}N zin7%^PpFAUfV`1H=wNJKeQZPzjSm9B1Jn@$T%(2tCFz}sD8v>GAv8gx>~K<@e)qpv z;rU;y{C_F?&rP5EgEfyGaeu4T9=joN&3(rN)SlNk>F5F2@ga3O(pX=N6qEpHS>Wh)sc$9(~x|({eNV=1ys~) z_dPx{jFfpsL?twaN0A!c%opKJMoAECM2bRBGB52}{p5@K~f zB~5m^a>kafwD|q0#vnDZ0=TQ4tYb;bT2;$S@|UR2@nk)~~#DwPCr||K=Id2c-FL(XID<9(-IZ zE8hY#p~btw9L@z$JOKNjz`YZUvvNR&^M!cV7tD@Wh$|UC4ru2T{6oq7=K#DTXm)wX zTqVvH@)5)%@Xi+IL_ptTyc62k&_IhiPb$h9MGAJM6xavgatN@np298~S_KH^**`wA9M7hNQDNX01V9D-%+eMm>a)^qIAJ`toZH zq;IwQFQIXD;bf#ag&_|)XKj2DO-il~Y3#slQ`~xO!a_JfWK~DVPJDA`6KIrntF))j4P8=BTa@ITD8+zX z^2PLro~<|yL8-fw+A7e4LG+#E+`m8eth*=t)?Z^4i2*^si#hJS;UmU*J?ZCGgwhS^ zq0w4=8D^8_=aZo=bY9tt@ftAu1kBsU+%E2N;O^wIwiDI?e#&)3JNtXW(6zGY8MH9^ z`3Y``k1QUJbFfGF>nWV!`I|7=vB_g%;U?5Nxx1LK@@H3Nyko2FkWAT}?Nb<`R!BKD zY2((kN=k>F7sf~ zX6D}R`uaN22L~`XV5Jd-r%`H5s1XAU<1g`?Y(O)h@K~lNEjs-+ahaOJAiF6zxSK~q zyIN3&+zOlS@<`eE)3yE+aruZPG4qBstX$|9`VS=?XbK>-3^+*K3{oc@m@A95MOzCG zhx7C(b1%rX{F(6S*=^do%zOz+GXdGkT!JfETeM|Ngq;Pa99=FKgo9}*SJTD5VEP9d4Ls}@s4Dq2?hpH+FWq3w(RUbh zZ&LUpPWT?KCZ`u28YW2Z=4x7*;p3R1d%cLC!k#?QG4JF)XAD7RdNjU#oyVBlDuGjT zE6MMf`!!mpE5d&MQ|{Qz_0wW47JMe4#P~*qko^xAV2z`Pn!i{>qnmrXB+OV};w^Vt z{JzO2gOD#8t2gR}_8X+1y#8KBWYleFM3+d;9^fxP7NkX!3evq6 zy~$%@w^nsYId$oLf|<;C60#DX({>|T*2Iopvo)c{SPhYg^iX(H>2$a4BDCd3g|CeT zErprQfvx?Zu54(@dL8!R{!dx%A*b;Vadz)7K{1oEy|vG);7k)Xn<`hUr6D(crk$p` zty-sHt@xid|+aOv%*TEYlXw=;u_m-xPojV+2e2^=WM-r&W`8k_-m5-WB_X}_7Zr9O zmtYn?UO)Ab6L@Rn?P71!b@_jismKIss8rwmFEQZfaW$~6YO;Khdj&?kpQ&vzSAY#) zN_v_kmTIxL^xHV!f(4l9FsPG8qwRUG$003ArFh4ar%bsFlNqIwbm^;8;KI79eILBH zmI@BSeVUf$gSsX-!{86PC$QE?dleZ{mwlq(_zFM~fZM9$TvO1BR(6so>D)?mtlPC! z8G4aciPk;M4>Zp)rX`8VXcIQA8WZ$YdQzyBlf9|C*4w>X&1=J6)_MZbHQ0TQ!*YM_ za9mva3}A%VbEYqmt|(2?`sv|blP`Tvo(-AN1u(=1`r{rSTNZ0fz)YHp3HYZ%moCbW z8K9;4AYWzN*`W04T5eF8iR&V(1>=wy8%@U{Ym{p9P5ue8qZ$8_I(n4mY||MPan>2P zXrAH8!RMUD{a@o^Uv7WseXZ+e-LiQ_BPqeypl26$a*f>a%p|`%m71`s7gDN0t7m#! z<`l2k^yMv%xPU}U35vdt@?qCLWUk${?ULRu(Y|qhq99FeKutxKf&(~N!2NxF&Pc*b z;_9>le?u2xeMb7X6pdV0=*m8yIL`uIxW&W6nNQkvt}-df3CB|qhzhB@|q!_m`7 z`n2~898>`i9lF=lH z_@d{+apP(-rQXyjq`K8@h=%P0!y59G?3Y?7-7nmxSH7H{+v9%7qcmL#)($YwwP7`= z{=?zsNaPx}gx?G^HfBKUP$l-da`)QMpM@?GtsEO7%GPFDY?CHlFwOVsy>>5O?u-ad?Tb?ARglzRW_ zD`tsOh2#V1baT|XiSu}tR}@1nn0UZTUD@)+#R(ln)BP*kbl2!0kGopY(YX2NxZgmT z-Svyc|CVZz$CW1O-k|8`%Q2dk4qHoOicayrMQge)x?jbYuICVeQ5)!@+21{D5#!IN z?M60;|By-IkmR5EheINa06ex9=_EnP*6_78pYxe*J(tf7@o^>in}U;hg?}!9{!nO* zTbJGe$q-CiDtk#ogEfu|bXlJPumg&9bq*% zK$zVuj4|aCufm*qEclVB80J=+kC;-8io!+7 zVu8l-Y{qzr+IYu!;FlFvFqWZ>*FCJWLoO6P@@G%}=hbUKLg$FixDbxCJV< z;5&Gas2b(mt5%#zxDSO?sUTVfYBH(`EcVb(ml&-mYz@eVUm+4dmzoN)4AQdf7C+3}InR#n3UtWM3RsJD0y~gv*#4z}Lzq zgfszY;i=Lv^#@E*iI;SR!W+r#rNM^Fb?%wKJ4onU;;W{cdk~L^X!M~V$)1c8yol0R zCPN8?^gsxK%rMGB&XpyY)CLFlL7k{P51yvD?N6MoY8AdRN%}T$PdrRSNy8ZA60-mj zHCWL7GG|wA2YDneUm7M!me+3I2dz3$C=5_yqq+H3GFqbN&y}~W1bSRX!2Nxz8gjp> z_15}a^j%MC*^Hqj&kp0k=&PDwHD^hJC-3(TP&iR}ib66)FqXjJDFQwjvCB#_T+>NR zm7lHldE0-xtIK@13J_#9*C^pKg|>_v|lrT{oeq}&%wCddxrV9H0Yn|xZTj9^li;5)0XBB z-Sw=#K>CCtf6+*aDt3)S#QUN_O-rAd_AYLHz_V*z``#VN$lyL;F2L>p=n#l17K*hU zm~}Lu5Fp-z3W-fV%n^tlWCp=VwRui?hM#uglMb)^Iy~RQYhJ@JM0bf=Na>DSaSh}Pa8(Js z8}geld~fY20{wwLyG6RRn3oVnSQXt>RQ@7EG0Gzs-+6yGNb8H|KMye4OF-`5Na)_k zzcTw*L|MV5ZwNuNHbgE}xQP54jG?;PDU#$hdD5O;ZW9z7;dMFK0|olHbuWPYvsyh& zz>cP~l7e|WQ8=o>9+ZEeaE46_zP>WY(lXjy10-Pn6^a?UOq>1>rPe^aXEt`y!+(s- z1^o`VNF=nGPon$P?($#MpvTmhT)lxFcc~MpUM1(R84(2UQ_q#rD2VhhsDk-E%tai2 zl_2@kF>%OhszuQqof3fwQUl{2A5u2b41gPFudIIcP+e^kcdRLuS_Ul!KvK}b7npRC zEx49u_EiaTu3lXDOE>@H(v=9NZD9jW%@XzTFJ+-&X<+2(>iT0N z*wJc8I?-)JqompJ8D{m5)ZAICR*g?;%N{933GS!{B~fW1%-El*uZOF5xs^}hBFdM^ z4F}H5{pGH;9GYI&P`U7hugEnwa>^!6C|bT(g#frK)=MTI3Lw`=Y8f=OlL9#YW?FqbtG*0 z`v`^JlFkNmi{r>;GcWw`NdUYU9gMsM!&lN;z|mpR#EGMI z#UmmQ_*Xku@3wSwC~;8+aHiDq4MDjIbDR8B=Y+-M&?=q4gTaeO{?6&%zKYx0J6@n2Qn@BfvdZ;BJB+en$IrT`S@_ zhU=SaBuuOpHuc9N^CjQ^d>2e9QpZ7v)xD&m)|rp7hj}S+Bv&y@GbwJ>A@t?qTq^fD z!e83Q!Y6r=^z5&DT$?4nr-ox*f1t)Rwa7dukZ-Oc7{v-_uB*oKPgqF26wj9n=3W+> zBae4dOnLp>{ya>+*rfGp`3X;#xUXC9PrJ)Nti2A7P#t^m!m*ZT*|9yBw6ne@y!Oo8 zNzE6fxSTT?9e{|=7S)O4nf8xg=Nz#>J2X7U)NC=K$bXWH?<#6k8{{n9$*|8G{)bs> zSExl&`tSVRRTzDnJn;V~V@v-Z8QV^+@&_Q7pN7Guk1j6HLD^0V6@xWtBJgSk7&@dZ{J38Qeay^}qgTA>o`RMbX6E0O;>$ zIrl@W4tW_T&78O@iAF@|I;gU~-M>7Y%1w)+xgr)q@x>&i+EB)}(u;ZA#_!jmZyn9J zdQ`=P%flkQ$6UPvi6EQx_>?^QJb$;+Y4+jSKCY}dTdKL#H~WwA7Ew|ZVY7p0zgie+ zQj{d0Pw1i?`XgXKC&HWM??kuveVgYONp#hHxw#3p3fAwm zee|M5@mxa>Wo==$logAgJdo;gAi;~^x$un0i-ZE=n0(SuMz!+<@;ugBz*AZ%dXl;1 zd^!&FW$RXhcT@PDFU504W+nKkg%~Vr6@3G>6siO5hIV078*m!`euSPAE;~B^69XHh{yxfksR6Zmz+NK#=fYkx$g}U3kexEB!kWs z>;eKf`qwP7l9g3+rQ~jXb4_#eK?-+9Y25FAS;S0Qn8WO!SnlfJ_2Wk$OyK4)tG_H` zxHRY;AfBA2GS%5`bYF7drb3txtERP$eM(k{jmwt=-LPvi>@k>tTdbF3!%bz8UIOk+ z55?Lyp+TYHIi0|NF6-qJ{QUMlpEbXMU=Q7u9X{l-36urMB~=)&J&!tyi=MoP?mJ@`0Li6iYoBk9lUGY|tV#1WrWQQ1 z!FRu2i0QIhW~UgF$}`Rjn>KD5=GT64uGg$}qtf9e#&p2UDppv#|H-63!*EN&lVN^z zSC~D9a-FU7BtiMpv!$#nAI4T*Zk{tx928$9H*}OL`oBgTcmBXFL=%`LMh3AC|0{88 z7ymiPfSoGkr?<3)XBhH{l;V# z*(O*+#h>Pa@?0K%0y^=E+UZL>KxTOYMk1YF^$bMEc@PG;PQSR#A-_F03G`Sc!|kfOSzZ z7AQ;91;NEP2U3$a_)!y6gWP({4fdPBntVzz3nDfsBI5%W9%jwm=|yR>+sh004}s2} zG+Q{UPQOqPk)Ji+3u6S3)We#?W{*|vt9i}q0x8uOVVHY4C>PuA*-eKQW)3Pl)KuCs z%q;By{sUAINsPeVq-tSy*R51A;B5g{{~$xRACl%cf{5B8h$=3wc}tKa8Kruw>*WF6an*+&V_zwH9(pMqA74=8Z45y6_d=L+s9<7 zhVUrlC7+KYxKdeZsw<4mN=+tf-R3GbILFvt4gS4=b|9jq&RP4a4k+S1Iy}4&0YryF zSR=SiT(?2@Ep8)em=*1gHg>oGrIQ*Iz=gbhJUej$tU1T^s{eXB*3TS;!iShi#=j`0 z*v&R@gWfhN@BcHCqin=8^6bN5dFnXyX`-3c`6}4MvEg<=_xOTxY7Er$L|VSW(QX%5 zLe&CQ8+X?x{SlGz3|z$%VBR2D3tCNFhvZl!P||3PrMyoBOXj}K#PeegyL?C-YV?jL1*p{6I`|iY$l0s2J9}_ zy@rYFV!_>SIAD8(FMWczmhLtP+q{7f>N=N`bRQJY`Kg9#y&ztKK@N!D6l!-noJkQx zSslnpj)GxqG=7V-=K_(mp`m~8cJ zG}OMAKE@TDV!mIJ(r8T@2?hh_-})CU`SSUGaw^SZiTJ6F-!Y8y$ac_4y+GPW@z&w{ z!-|0-iwy_fMlusc&>+{U@iSYX_P>ewQq7CLU=3YFi-$>wlyknK;tDHx38Ilx6wl|Z zEMEdeqx>sRg84mitHq5>jLzC|#i`p}zgf^~wN@S;cp??FvI zu|uyvkoDMIm!GYe*UVjT*6#NnIG8DMR54XbB!_<-T1plFZkPZxDX6txcqTSHEs0$3 z@@QSJ`b3e$-VYpH+Z*8P7Z9vLgf`!mznc`l0|L>1Qsmy! zLmlN0(8`~CT2fMiB~k>p1B^k6)D=NGGZ&f!b{j!XWRRi3pv+_e2d6P^LhdJ9%RWG=DDpOBIv3FP%i@CPDBk zM|_=~wWQCHps5^^q9rP4k3McMUrrpe2{_tMlirqgA4(Z1Sn}xCaCCO);TxyrPYw$& zb9$_;5^Q!;kQW)(t@!S380C{wH}mbY|2}_gF3wqXUf}V}Yf{5Vit7}8vTwVar(R1X z8sLJz4w$TTwpWck=v;~ESP)%V9}unixKLWhs_1N6{*mDSIdg@uSN^wl=0MKg-u~TB zyS>IUe;fNql?6}*Xr&YH;`#OF;XU^S?K>aoD6WzyX8rLdZa-Biyrng^EgWk}22|L_eoklzHg6-FW=D$f}#n zW51Q7-arzClV=H<4>J(&G8&2xK|Eb?v zJBNAq?c28m8d~$K@2>THMk;uBq0aO0J{D%9=@swcpv}&RCy_+0%gV~yiLta)T{Y(z z7fILsx#Ve+rkO#*@SRlb)h))@fC1O-)U81sH=bwa4cT#V5?TczN9hh2p{Mh&+vBi^z_o#6&Qj z?~#H0AP+QZidtlcw`6ya0!clzy46+Rr1a(}!i^JFH0E&C69rjM^qghhjSkU|&we6PYv+I3)ZJ_1vZfBj?OCPZGp@nEuz z29guAAcFkp>FJ39$?|-mbHMvikfY?9cM-KBm%t0zufM;)&#oM*J%dzPJy}nX>)Ok4 z!2X=Msg`(f3Eca_RG;&Yu` zn~Ht{$K58dH#1dL%BYB!j?>%DH1H4jTJBy|bSWHvjWR`OAnrqp+CtYfR%wc$RATfh7gpFK{rdYZoUE3g z>cXFgmU0=N!N1IV*1(ry1m~lO*~?NNN4d>l32TdCr2&Pmqq8&rIaDQxZf&U$G)j?8 z$Mz^Ixp}RN@mgJ9r+XbF3<5-px2HVvhVQ}~@6B+1h-N0ah2Ta;wku+(I4jG_vQ3L6 zNz7H>+<0g3J#Y~tbNRY#1cl0{a|^;OE8DZC5E_VvO9G<#CvKf%?5QnT?lBFJ^1Ar@Eo%&pf~Dq7RHjD$ zUASXW(rHd*)0R^yk>9u&#>x4aJ=P^8C3^>ZaJ9>u63{<%bvp?SK zg(~ilj6iKr4FW*Hq0jeA-x5V!dpTx%ydd^1e(BfI+#J6A`6zHC=;%PkYdMW0=&$R+ zeDUEszW67BTQ)(r;vVRWYA~V9^+5R&%+=o#&+ma__nIY=fHwy5^|#D+TW@c~9R5($ zbo>m`_U_Mnw~sW7eLC!E`b=kCrjWLJ+gmF6cP^TuAGp?-Jdq<0sFHcmrAkKesZ;Bt z_pfzrT7P?cEl6(2{0 z;eM3r8^#2iI`Y@I-~U8MlY6eSM>Cjb%DT=fZsKN7Y|jV`41YtVHI5v6i(2*`)JQWO zmSv-1SVV;(@?1U(Z^2~CJfw*}0)Y)TEl$F=@9p`b#L{(bNKFymzxJ0;O}Vq(L`VcH zi5&ii3t;DQS%EVWKM5l*+o0!eblwx3$M2A~Lql*{<29zQbj_)WR7puI3N&o6jq9w6{e*@%RW zyy_>mQt7l8#fQ%JrP{$jxX>LGOV{~hWPE92esPyg!f|=H@vJ(emzdzDuNyOXGSeqQG{>G>itGLu>|gn4~ZRj2)1X=ZoAWj~tPE#rf2&VPrz zjl%pdCVq-)=li-Vp58Z$P{DtOleg7<<;2{|LEYy(Vn%~XQ^s>KIq+yZ$n4&|dr5U( z78c4-BPJ20QnO%D^3%&7=k-vIW5Fws;03XL1FWsJ;T)#w=E(%?mBHT7ci^(3Z{q0S zV7zr2jww;wz6nL;)rwKy_Yx8kFc02b0M%bL=uS5(4*SP61*n~2p=@Ds@d8*i)EzDa z9Tc}{aB2{B!kd|gy+J*_dWwah9W)7opV-JOy zXPy5>eSV$>grzIaf$J|fi63oRD5#1UH{qh|f%<>1Xk||@V5lNsC^&84I9O%Qy+ytjF z8*1#+P}|e_Hscna2clBl9(Q`RwY7wI&0soFXU={ zmu1-S)(v7Sr*s()%||NA@87?d3H)2Bn%Qh0H=(GaTXpEs0l}Nbo1U2Z8WNv zJ`I(Xm*+^<&FNHwVMZ@=;4&dl_aM-0VPRpfS+f2W1HbMpr~-rR2q2N|eL1?p7cj+r z<_FYoNH`|^dBe)E*%i}vsbY5KrE|a8-*0BKu+CU-48GDi{-8Df%?qE`F8EHej=fE) zTeJqj@}6uEVP&>2-(ap9))R&LLJho0R1xmguk0(-f!|_}-a(%pd*z8&&we^cn9T~x ztqcwf{22IXvk5oBgxG~)4*%|=Lrm9G@w3n>1$L&9lId)gpP^bax?9HIk?V}{Ce3a* zHhm!VSZ*gMCtr}_4k4gpI{F0IRF>7(2VU!1-kYUid2mu6~G zVdH!EUZyZC^IMO8`J#fli>1P{a#B~MW}}U3W3Y3U{O**Xebl* zU7jZ9c8|I6^_mgg{4+>(DUz2R59~acn&7^q zzC{x7DbknsWzn+z^dMjMl+X4!22(=5VI2i!7Z^FBvcTvnUDRvsG9fJoUbHi>=KEWA z9LLt4`?5OK|CNPsFsn^(?gW_y-j_+y7K29;eT>i?|AcRhiar|0Aiw#uc)osrx#n#! zkYcTt31mNpMzs^;n{CEAMAfwneqG$SdG(T@wWw_zIq#uWW;View)7UvZfUOGv6 zYy^CBh>`v9aO`LwE=iyJpdM<*^q!qa3Xd?M(L|$#PBj*mI`Ah4ljNHgcLkiXr8|*& zihjpUnrzga*Z7PQe@`p>Rq1nIgQo@Vr+8(ZTh~R%X9`77#q}7KN^DRwqsbApRWHBe zTiI<9lvzx+w;r=Ry~ldeR5|KmJE&(ERM)|H6=eg90A zZ0x}kZWoS4k8SoYlv4G_54Ya)R?Z119>_PI$>?IPN<5Heqk$#`?47gRstSPL){s2mq`Z&JNvvS z&0q{PooZ(S41@kK1-HjSsax5$?Z!<-EonB9FQf0GJ5+1Zj$I4{L&}=7SCX)EcJKaekdZ17U4lMO%?pxMJeos;# zni{k(ysh%1Fc;>CVVIp5goYJe0TtH#(DHH-$U@*xxV^coSZ?IVH_b~M!idFQ&X8xO z(og-;V)dH%{1Wn-CYc1iN!?GR{TVb@;xz{e^>t_(@Wjvg@T<%XTqmBC)_Zxl$`Id) zd{aX%{U$QKsblzYLwFuQy~-=SLTsaUjJ zlIyM77;OwL2FXBHUx?eow^fbLq zD47Z#V4|;wVI#n)2P2>Ny*9%oYb~0exZiQ1MJNplrLj~sJ=t)Bvhdh2ICj6YRPU~U z>I1)!g9(UxFwazFa8@s!&jf2*ndnkXMH-4eF??)IMfR^T`aAN@?Kt|r^s~3QLpJ&z z-VeZ%WV`a*(eu5^W-Dc-zM>j?hI70#37E;_u~)j``-K)C{z}0-+He+Q$?u(m0gA1w z>kTLZ2Y>xi&qwp-h!G1`=_f7%KB*0Gw$c@Y0&|^4zI+LRNBGVLm#Xe3T=CP6cRL3E z8QL*o=jT*uRG6rL;e#3yDwP6@LvIB<-cB6Ew&g=hQzD=tq}W5&CF_l|*#z(1?wvD) z&XPhKWsC^fc#;s^pj~8r0vhg=Juj%P(mlp%4n>#TbZSO!K{Txx(sBQ79_#bqh~$Y2 zoy_C=0dmt^SaK#VC~Is5A@`zehjGKwoR)#V;tS|XD8|3}kLPZblC%QF9Rjjgigu5@ z)U~#0xB26QNHe~MM>G4~NYT~dkrX25I%2zac?&i8o{|!3t7_!{rrb_s|Eye3g$~>UQJ=FJ6QJMMrjMb|<~=g~3J7 znihG|zfHTx7|)8o&Yl85q>Mr=R*d8XAm$+_Gx`B=kqkcDkk%xl9|eCld!rf=1~CAj zD0rA(9lr+DK`7|l(p(x z%MVbxAI2a>hqRdXI*75%4Oh9tR|?!MiavEsTPb7!q6*BsvQ9gRD5W;JrrGt?Sn4FZ zZ=IsegJxQO!8{@m^($aZ_TqZAaamU?su^JlU+B-Z-$^{`KffOooLKn)wH>^}r6orl zK8BwQn|%^A3ZI!=2%ByGk=fQ$>4Z-8nNIuPNMUx*sw)hS=Y;8IJH|4a#s24Zy}CZ@ zdrRrV_1V}2{O301YiI_c$70UYZa#d;(e|N?R_IWQR4u=JD&8FPqqQ|R%6|H*{K?=y z{;D^S_K9K2`V_6eQF~D5ex{k1GTIB&x zfta7uv~C!Rpkuq%G$EXGYP!17JXVRiq;$loONnQ`3rc-kh>rM$IjGcHro-M-Ds>Fp zFLL28RWOZ@`m+mJU4vgQqi<{L6JSFOeUoxX%U=d*lE&r@%2`>(;ziQN85xOmQflc^ z&AbA2SJe0C1XUsw>WPlhaLoqIGU8~j6Xwj=zf|vc2Vd%1P4$Fc7T!I))s`x?r&@t2 z*n`+SO`d}b0WOmE8GAho?~urmISmt8uPmPqv5ciTfsu(*|9LodcWzeNuMplUpM>AR z7oV-BqhyaGf4J|wXLcf$tZb(0)mF`|9;(Q=Y{0;J2I;;NoUgtU*L%_|ioJ+_lplJv zq;_cOolzn2SMOYVb|8;+W*$+<3iU=y>7*_FK~(;Hfmrw0^ zJF@eyROY$N?0kg4H7|KIIy!m_j$Dp@itBm(<5aW_EU=!Qh?Rmd6&@q=bAJ9EvFhMn zI5vAfGLqGW&`n;!dXPQCv~VRrh>W%!X&%03(m+37g-m(-zL{D5_MH2P9iw~qwAQIz zzz9Bi@3@?1Cmk7z`8m(}v!Ga3|zRour3r)+lq?yiGxK1H-&wffd${6lw6 z0fC#T1q}LRx(p;F_U?2dX*+BjsKO~STi|So|d-fd7b?LV=(z0@nEMHEC zx<9KIy=R{YMM`wx83Z195tG|JpUM8Z2{$gX#R+LDZd607kd&nw(-Pdkp&u@(FbLQ0JGIi{Ctd5{3s;E~u~LE=_e)oZe6!_s;Q* zU)=|hhB6r$VNiukdHE8IZ*bi;h-pnY<=p*dxq-26U!< zGc&mmUpv!fiCrZ;lyqr#)zC&IKqnzU0RW%B4D9j{Vyo@BArPdnSt-b0Ts{+PF}htz zKt%aa=U=$->UuYZANhTBf*8gCiuR3!AH=60CsAzxAGofWylIwx-15(#&-Ao4ASaAj zGtQ_l+3wu4+SgfZXq49=bQyD^1M5`d$+F~MoDIf=9MF8N#4nIt{+yjD3m`6(jHihg z9wwP^u>~sSSfVz-acf@7Y%h-JOq(v{dNx>WudK52ZB!KXi06>w?PG;@cnj{}gC6K1u0fIH=;)Xa<`LBv3W8}W%L%{Tn^9lQGp|3Rakz$+{b>hmKkMB1vAj6^ll#Ur*2%2R4av1#k5ssRhLgwuDk^pacr-CR z_xC446VP+#?aH^0a?@||E3fskHLQY4B{f7J-zx*9E=w4+9LTF)lqj2>)3NP$5wyEP zY$Y_6%sw{bkFA7ygl0}v@-HDx$(l_=yOfzTNkn~|peA#Yn~x)cIS-1#6bvvL!Jmql zibN8#;qWxkQMJl1e@)afXZiEZT+g8z-ZoZ#{P<=P7t^(PiR|Oz&H57%#TS$jMK&bm zGb60y;QsQjuwH$5l4u2E@`8LGEKs07*YF#U6!S-aqu9~E{bbw;yj|vSxxI6dq2y%b zOTJikNj#u)nr9?AVqkpR2NS+n7D>ur+calf%o+Tpis9F9)MD&BJjAOW!L$bOhp7|A&|pEw9_m-1HT>T9=_r-T*8F(tUTw_ z4~^D!X01Y&!F7^G{i6#^Dckn|6~|F0aDb{K7@=6yAbTCViRzn*H)u zRL1V%u~U0e5T+kwz0Y)2v`6S1b{tN`)SNuR{&+j~QaG zDzVmYE9H>g+IBxQ*7O-G61$m=pWzY)clxrDk}L=rjI=n7kY{0>imR|L)y~?Q*Cd7n z#jGk^2X!@8!Xw;8;pDS#r(=C}6 zDt;HA!kl6G%jvqrnDo)6%Pt_m1mZneDvr2gr?1LSP){iNc-{%5eX-7?{m0^eN*DPf zE^ahUu#P|RfHGa6Qa6j^Hl4t4z|ul6Jeh9X|;dnWZ_+d@?73UuM9tmP?-0NxxK za2rquNdDgyuk=*WOBiz#C+aLQI2dU|jZ87Vdb)hoWeOvcUUmd!oF;`)F&;dkq4wkv z2=0f^kA49UZGOx}O1t|wfhXt=_ZH_mq3BFQY>h+}S;UF$M9rMC;=1tD>!naGxOcix zmqwf7pSpMM6X(%>e)r(@({EW^5J^_;prsqAY&m}+@) ztwFljr^!Rmivm$JdmK42Jv~hlEHXa;C3N0pl)8&(B!FY>f4W?6B6fF9C#$5NM>XW> zW!@?``U#0TnYN=%SVui)5n<%N^c9D6To>JX}Z$@iTTG;cDrLovJ!1Ff@D14=Z_u-S)R`0P?vUif-h zdcAXH|AH@42vJJt%DfF3*e}{1`L@Aii_?Zwl5y1shLliML(eg1H1CLz0j)w8$7R+DKP3BWpv>LA=$BHpxh?BQpOl&RqJ4qES6;e)^7ApQq~d-X_(a=czLg%i`htG40g15b1x_*+XSia?9lU7__b5*|F3g%|=Nxp(wwgTA46Q@s^j!Y`A>{X>y;et@k$b3DU zwWv#$Mwy}c9?(BSGeoIf`8&^=bi~UVgxm|(B6=^TaUQN@s&?qJ-Fr!9%1a;m!Sf}4 z+kn3XxNkp~Jpl@3sPW5dYYT{IE|Z-3LQygRM5tOwOE5OH?c~W(`eP;XBSq8(!aOk{ z!Pw_#ao|m$h(JdOKY4G<`N*?w{$_C;hHKiS^iCg~I>74-3p)^(n;*|!SYNhXbEz7a zLTwSdZx4^n*BiFGhf+a@wUDFW;v29ivw2mq-%l;5T^o=}SiLic z*Z#u=aECgxkwobY-ZoA!yK5uWsy&#*+B_D&;wH)H_c#-2jb-U)d8=abG4OLSpl)b$ zzIY8y{49;s7PC?aCJ+Xc#QCYsi&9~JL?Kj1!*&^}^xGWe`3U27+3ngXUZIryrftw|U>&O(J7hCffpL-2VdyS(BTf?@)T?1Ej9Ho5e2@Z&q#`3DP1_T5WXQY5+=$B|gBzuHE<%s@7KU9Imj;xv7Zf^r z$Xz17VAGkVF@7KT896QXVl1MaNl@ivW1Jzu7v8#%Ln$`C2nNK9L51ur_s4@U#)1Ab#r_vR9Jj)gtMNw4Smqf| z;CGaeC78f`5*bvi7GB$b5}G3074`LAMPC-_ITgDan+zYm#uHlt0XB863qCT^{iJy` zN@NXJ3;D8`*PCTTx0jP&>6L}{M*eZTZU7u`Sh}FsKMVn%uSC+Zm zY1(x$|0YxQtUH*wM14?;mm=1cjOk!gEWvak`to?e=HU;aK@=a5H`*gV0}fp&GIDH& zfIXlLYa<{_rkxZOEKRF$$g?hygdH|%Ig-e|y+67Tjs$ehjkmvgc||Uw`S133gIg$d zWO3w^Pgq=SPyjnyTsSl+AL+UYC5@fR_RrXJX(&5sd{^YytunSqY>{0>@+X%E_oe4U z!~TV1$R9n$JOc>h38%cE&KBz1i~*!MBX8QbVY9n;Q;^<7H1K3b zcEXpau3$GJpkFxBcvZ6)Sd^-7UO|9BQ`QBhkj3TSP_5y}n&Hq_0Y*J^B~zwrKCa%s zm2ERXab+{i5BNE8kVG4a@vJoGf#4*b6PkTc+k6_Z93a3^OlkB~xf6P9q#Ss1d>o*7 zX;9a6iNPL;cFDyzU)^gUPQDB2vdOMr?uyelx^lQAAmLhtEQ0pWV{c;){S5JZBLb6% z?FSNJIc#fc7#kV63F%eY+nmv(fSG}YS&4PEtyjyJ(m;t4f0mPh=8c^7`R*rsw>K_- zZr(<9!Gc+BC;34j{sTY9_M$(HcJr}oV_3^L`a2IsU9(D6m)DTL5cCHlD*MYKlm4*c zoA`~1bN$Q=y+r2MF0ev68nK_V)V7d+*=z9<_VkLRmoe9P$`J~+qTc-5=D1SZpqta$ zt|hg}4xd?@wQ8zrBuKeJJS4pT`#<#Tb?hUc*`j~?xmf4u5d!uhQhJtKS zOzeJ%o_86F+zHGF^UAcTdVDK%~bUL z0(84;F^syWK3E=T1e5Z-1Y%Usp}(7dN&kAt|0C?p!=c{8|KS;A6b+T68cU^ULrJ!= zB}EHLrzBgcBxM^KjNOqIMJT(Wl$59_#xB{ijHQ|q#y-{=3udY+MDYk9ZyAndV~Ad{cxFVtd0@oCwfivIv~YV z;)>sk<0KD6^#l=7rYCwI5ha3j;`+sT-cya`PPdkuOSPk?%X$r>1BT=qEu}xY@!W=K zh8l!ER!A3Rh`d9OaS{8`Ka$zoUslPu_hE=V_*ku+%B?B(u{Mo3mE*{)pUsc(_g~o@ z(05VK%uSK6;psC<+KHK8w7WCJKaEtTZ~s9cseS2MIp4!+50NMMGPfdbMvHhus`7st z+Sx1Ly;n5=n{eeQz)yZdd+oK@$#hyW5`*v;p+$_^p^Kh)z~aBqU)q6?e8Aehv5%w~A!~>oYrW z(s0Gk<#|HS!j-yM^yQfYuiE-!e<=m*+B zP1D)gdEzz%E6s6vLOVj%1DK@y$JQ(Dhze$#>2QJt-A7lS4+Q}is!x?Of5 zWdx?U+2z}|AA-EML(aU+Gh%77tpKQ0(TkMRNxnp>Hz9;yTK(N6Cf zGEzhC-!eio6FdE|NgyZ*y^DP-W8I2n@1K0By=o0NX^9<@@4Ll7PK}))nB!mO**ie0 zA8#KT7{)b+8DjU!BrWzN0-&dfq^3pGQqinqjIf6?o+Sxo%Kcvz8WKYu&$QB+li3mCvb!*bJ0%izwhPt`Cg z-Hk8l3Q)F>KwVdf++K6#zwO&9`gVLx3~!Olry$sIH{{sR)D=iTU!8??_c0KglR=i5B$*9QIQZQp<=X|W`c-bY=4gRI}ktKfPM`aRY5Od z;t4Zpm@5md73qo*Xc7F1Ocg>-r|gIRMC;>gIpIhGO(a)^cphEo9%m8Mxb0sZNuL&w zL3}C@VG3NzESq%{`WJj^1a>wZPrKeM_#4YF)f2Bgb5=kKSVNE2V&VnYEEPhBeg5s! z%5A+JRVL6NwY@mL(-c;aHfcWRRfluv6(M@#&`e}ll=|g7NJzQi;c;McmHEce>{)5G z$_)nJdivEf~kD$+}{08P;qW@3D63fo?MO2^Br{R1f}+Ty0d#x?SR*Dx)yO66u`! zFtyxeI9ws3N?rRjY#VX7%?;zOr7%O#62IGa9ecKHe?(AVMVR7+o+$sEa{fZNU}pn2 zQD>`6|Dwu`)-=8@^#@~|!Ip+&`oi;*=#RmU7hW|scf6GEEG03}`N6=g`EL=pdD~t9 zJgfNG97Kfd)Yycs2fk>EnUJE(r_RVrz^KnUWB8 zGfs9~=K1aKle2mV7GIr&n$gn!tWWmUw<(O?aG%y0`Q ztRz(v2t2w0jNKcb=)4KmoV-ICmK{!+mof1)3#b^vZg-2|E^16Yp(eT!ZMEXOiUxUC zR($Rn?Z|BmiP2FYU=qSMM-*!HHdtyNWGR_jHmLdAc{;6|isBMp511LcsnPjxNS{s+ zmD|8(4b*4kSE!6!!gfItS^c(;)U}?PLj#SpubelW8pAI9LVV%CxK5tT1*}bg{Q_e# zt+DE5URG2%^@}OY2y@TH3tmOnVK2ldQE}-*w2x+J_<{d>O!TqhSMtB1cA3rN&sF?H z2$)%t-gIsm{VigcgH+(O0MKo91TCuYjR7KX3mCsNw?lts2h7PjV8+H@Ci5-%efrB7 z-T7aRP!9PuUg~)sG$pd#p&b<=safccK< zvV5u61ofbyL*fhPE>+B30`#YNx_0ZF`AUO+8-3+Z(53cOjCxQ@UgmN5EA$OM3kbQF zHxRTO<=y{vbs0$IXj%F^XYfZw$a&Cf{#95w>d!lBd-Q(|86E|EU3Vplmop zSj#P}?}(gYd}E$Zc&2D}KO)!}k0mc>LZ^#-=c#z#vw5WM@mU_IdoC1eW;BjLXxj~e z^J&k;P{Ym>!TYhR+*3?QA@$HqAA4~?@SMnS?D@uwbrP>&iVAmAW~*mbw4m}5;M^PV z>Gr{giMxiP?@QjxwDz*PnT_v-axa=wj#Tctyg5a zhWgR|^6Opt(`%}*?1vj#8A+_}hGB>M9;T#Rr3m|pDF2G70PGnn%k<5(qLcgWgXV?C z_e?@=;3)HM)#z9CU<-o;!R@sy^)mcv#W}Y0R^^@ahjxnJY-3i$TFjZ9({bT?vbo+$ zBbAZdqB_Q1wY5ba8c;JmYqT}eN>8MbaY+kXnh2YwwWx$v#`pxIgO(Ur)Ywcn*6Jc; zC6MEnyM}mdCwDS=6xZ%^DYA-_Q$hB}mazh#5u)|n(wy}%T`RIvoPVoN+FM5W>PeBe z21N`85PcHKY@FV3`t7v6Ega9lM|p;N4ED+-8JTVvZVaC2JgZ0N8vege5{R=Q^VvbU zm)y$!kz4M?SZ>LsuT0X-=DadRy&ISmhAgi$kCy~fmz7a{URE(=7yVUAMDZ7*=13JB z($Wfx9~c0sCFe`Je?my#Ysi;yTzVq6xNefk90QT!oATu$mGOKsF9)7KQlcP(5da1a zf?)-76Cg@5(7a+Xxgr~Z&x3e*{Fn9%;r6Y0%ir=wKn(l{N!7XuJSt=ne}W44pjZ6GiFyHdwrkX!nysFwkKa=?5(`3G261VXJeHYT;pOI{ZeOIH62rV@jagkORR z9>;}(L_$xH45?S9k8~?LiyxwhHs)oW#z^49PzPvJTFT1h;KZ@|1o|uFSVng25idAF zat|wCD9ZdDce!0wvL#V1ammNtmo>;Q zn_C>Dmpid3QxrCFv~)HU|M0^QH34Hz;KWnCv7bGQ{v9sMD?4q!gItZXp;Z5*uf_Vv z#5IR~WCy=w$>{%CB&F%E*fmg(!$oFmhOW;Iuw9e%G|OJpN^0quMPF_i`Gu6t-%D7tdD z#mlp2K3SLb`@-?~FSCqehlnd;GBry3)*@1&6?V`H)sOp!o{KDDgo_U#$U4)%6#Wud zzYoY8iapn<&K~kiYk6#Kg$)zQB%RPD{_9h$3dtLl((e6+mU$t^(tnHxq4%S3vi>T7 z9PlnfwL|xn*n;Xc2tn=P-KjK=-sm%8=qx^_UDVipHsRX}na+u^VU( zn_Jv6oyxzA)7&+>_qJbek1ak}e||UNgxtcuh^vc5xaEc7qUxxCF;qRLwE7g2u_b~! zOS^m{a4ql7NWXhSl`vrg6#s#s(%rfLweBZM0o;t4DanGl~;$RIr7gmZGL zdzY>0qSzDc`2d+27tiS0w5d-GG-c>{=Pgkm$1Tg1?e;1=TpX!+gSz$if({rTgG^M2 z=?X^7YRW)r{j;UzF|(9yRyOy}?FS_Cwn&!x|9ETn5>Qz$Dm-Wy=APJ(NjRcG_s@ru z4Cqm2Y4~gyo~!uxiCWv*{s8WAIyGp84Qx+M357r1-9NxrcxM?ymzB5(4C67-JUmkX zTLo4Ja!ktc+T{Mp>S#mM86Z%<0HQ_x48T{a6J9<1e(Nyc`EL}-{%4^f(k2W?!k1c1 z!S5}o5IM9ydZ*^@-RQN%dnPAF7x5OW{b!cWrlmEpIP$vL>yE!T6Ka5x?_J*_P83Fo z21^xvT4?DD)hF0ROTVs7(3Ln(R8iD$ zmH)7E1gR(+pB_n4CkhH|>V6WU)?Bs8(VO@PGnVLxk;D!Rhin!vD9Kka|A#@HDjN-s zB>4w@SWzq3?;IEbAZZJ%$W;A6) zM}>U$T!=T?M#JB$ESt#k_0GrHEG#o7L$Y|+Bc1w0iz<<`h$GTOKd_x<)ArTm`rSWmWh3wI=7O0EAJ z^#FWYwL*BDwuHz!D2f_o_UH_ip7J1CB@@9I>O{dyrA65e7Vn5oV-qY zlcl7m{`;!&lZ*L_g@Ve%4^g`8L_x(-0WZ*C!1Q5{O5?v&U*TSf_q8?xJ)S_= z1ol7j^B+tEYv-3sj_s=yC2zN?uzCmqj1Wvwqitip2L)Q`l;#`ixZr zSKWFSt|;TaXwIf9C$M%8KOxPav{l1co`or4T6`k55Z_JC+J7~r>3#{0kd>5Im^GTY zf5|Y}_ojZtMJ<#1s#n#U&B`!reqsZAKZ{Fx|*UT@{RU@gS)+iX3*i|5D8W)pSNy(vasx=$ZkOgwv*ILT%5}2R)E6IKD$}@g71x z0r}~0#k@SYyh~hbRa6h)KnSX zD0wAYHgKU&klFz>Or(6v3hrg-akK&;1H6q0L6dLWZj7vT^9fr)823vM_LT|zcjUO@ zbA$LS!9uxW?RAlLzJutlX&-#-WAS^vXdCm!1X}6#Rny zd0hh>fz4g(`jw-=K+{sck^3*{0ZYamSV9j&OCziLLP`#clnbB%mw3iQCTjVkpY4N?Ax7Br#XrYr8Q2G)yA+0ftU^-_PzJAEsWmOSsTUoEm-K z+OcK{w@B!^IKZVcYSH2RS-`sp$l2-cFwBMrT z$93o4QpaD`vPR7U$Xt9A;n7e48I!fF$1h}M`rs2u#{kVB zbgD=p@8&OI|wZbgoSSH$Mt5`1@sEawF2?n69iMx8Y6xu@90bK=wPvN z_C;GOI049(E&bTE;xxzwB_M!)vmxUC2K0qmjafvp0n}O zY8u$v3q2jv>uym63k#wie(kulWHa<$eA6?XdQV0a)e!J2APR+gr46^q_~hhaTDzO; zY!>l8!Ck2*SA4PFCbWi9ztb8KTbW{Bn8eJ)4{B7qw~dwu+A$bYU`J1ymkWw~bn?M+ zzjo_Iw%J;+Z4P4lyEfM>4RY_YW|Gd!ekU{b&CCX_&{wtG58FUILc!~1hwUV8@U`FU zg580;H^}IwzHiJJ#xEoowc+Nq9EKRBaw%(n9x_MQd#~7HeFJi5xXX#yd&^Gt`Vq&p zB-rBtfdR}Jj;UTem-mPElRL~Z3u2XY>}5IX6)qANwYge`*m`zZqCSmtL{D*1McK#R zKX;}anLin-i$|mXImV}7G(9_{FPpm9(`~AyBznA4^euj)qb499t(SKPBeV7JG?k4j z^muZD*{%(z@7yV1H`BL(kM0)pT}l2OyAQ~k&wjs9@dg=pJ{Jb@-4hB~?kK3c{tRm) zom)$a){D70ZPmJV1)r5gMKwG;@4@E+^&JN}T!@-K1AVQ1hk&gK34B1;-#IwtM@E)^oyVwT73d2!KRy9-e(Eq08RckjOT1M$4<(3XV3|Hw(YJt(j?k^t2>Z{p6K=ouB@!qOP^Zx@BFd zv4Ru07_A%A?0PNlx;^aZ>X$e%Ka#J$r}StL7tbx9)ti`-15V0p-C9Y)m)5bkPYSo}LZ$FZqxqiqUJ8&6UUDy|inJ}A#q4v-l zmdeu;m=k18b3`N0_*@7|-!><3E37V`gj$Mnn*yPRVycvLayLJ9imC3CdPqQD0es`Q z{?Zv;-fV{-Lx-LXWH7`=(5=f3T`}0RWGK;Pd)!x^9`Xg=PWhc6?mt6q3>#$Hq4q@` zd$D=sixq;XpBEx*<^u`3m@X6a{lZK^_-vR#g}pgB;gUHyF>8_#|G3(qTyddU-LCFF z3tuMFdjG@X%2aTP;Og2Vs^mbma$J4e-OSCHjgy0)UU@pi3ARo9>@yv`HH9N;`01)g zlxj(!zE9ggB`x+_96UoAI!m=hysn|g7GDFf6P_Beto*LNfy!#zTjd-=d~9C6phS>d zli-=ayu7u9K6XD>5fipZU&M3qek3iMhRXw`>fg{C`7PAm(gO?JFVqOBOuL$|7H8JtRN$*Yni;OqV4WUhkp#K0YWnUaCd-m1ucS6%zpV{PzDI5kP^!e_!Yqa@Vi$gHnjcqXm1F$`&x|7>foKs6Cew_kJC0OR?@t* zPs+0FpukW8%el+*LTu({jYlOCGQz&^B^i>ct=r-`Cp%BZGD0qj7lAPH;mx~4Sc#Q+ zd95l(Cdc76TvE`H_x@YHhzF(J_o!06O?>6wZc-K{s~1)!08>aU#Eoc=y6fNVSwC9& zowhsT!K{;Z>P<~tOOYM!oYvQdRO^*}ORL42E~l|R_+}5_ZcJ-9%R0*~_OL$@7e;O` zSs%DAKD8m8`o~LTggU1d%W14*wpQ2ah`%0;-XTZ8Mt4;)((7GDJW>U-yCw%vk95_< zEwryT)b;beb?7hYLF%#mZP}}hv^EBvoLIdjaQ<9K&rdutt)kJtWq7h1r_E^X{xj!v zf>imF7SyA?5ID2K#GGUY^pgm(-)Ec#*`otfoJM@_C;FCYrwZO6KMkYscYrl_EBHQL zXW$?=>Uj0FJCEuw{~k%^W3B#YpB77bH-A?Ul}Q7A!)yR!v($|C7gXXM% zl;fScw#!Pc+Jhq97&tpBt~<9qI7KC2jcNHTde6Ll%!K z@wwZ~F(cW)aOpE15R8N*dH67K9(A&&KfJ&%bA>G#X>+pEYFI$)kb=7W?R=@~K8qhW z|9N!Gv37be_dtdCP`2RalDvqZhz*f<2u_ldYIQm5c-LLKZX5F%p9au;-}I33eEaT4 zBNobXDnb4#nq5~x(Jt#BPYYs> z$5ty4Ticw13>4=9)tjaZ*4YRbK>weO+d|IUnD&LGXMQ4DR;^WG8dBjQYWAaQnf8PZsosupplU0rX_vp^W@b6<-Kf08uYZbbq&gIBZ_B_s^ z3FJVjEtzMVIyQOke|$jvoKDx1LxMkxsDdSS9b!s%acNo>eT>pw8_4T$Eiz(}Z$Ty- zJP2~fweHd7{kSiSHJ`9S2^yGa;9TA_Z5N0Snf ze^cVGw+PPYWnsm-_t*DavGtXrnPrjGdlE?PN4HldW5&95pBZH=)3u~$lB~-&vClzUClwH(-Uvt*utk#yW?4ME$7P* z|LuZK2Q8f0s5dvpkhyE~?b>kbKAY>*sNo-bV+CNi``<*)&gwt9uMio1+JD&4Uub#C zAiuX{XGXdJ)Yq}gftw82x4K?|y()ByWj2%hW}>f627baeq` zZ$r15&|3;wKUkj_1(h1op{9t(#OT}xGVDvIt71$C0x>*nGx7WZa9DUu5t{8YAfz8H z(-4pBctsUO`^|@7a(Oxt@dX2hfkB4@W&>giPd2M#G_+8Tt_wZeq$U>wiK>m|y>|0@ zoCN}Ic(CR0{M)E)m}7X7-E9N@0Ck4af{qs46`|rgR)st2p2wjxzFls?4^4gLT*F#L z8>Rb_s<^$;J0q+M23k94IuV9i4jz@ys4oQ@{9D*uoGdj=bERdr{NyH`8qXU{&SFUi zV-MZYm&`Ey)uojfc3R(lv20OAOP(Byt88=QyBP-B>qRXVdEQ8}-(d<%Y{*lKha3}- zlYkUpxjK`g&B}cTjnFMv^Z$DQN{d1CG!Y8&ma-!AhrH76G#N^wgj9RcUINdB{?$#D z8(q2aP(B}H2}%Tj1eUNj;xMD=o$brL?o8a}NX>kA>x@yaq_aB?Dwk);T4$d-F}j(Z zuFW3KU3>N%+^dIFeAnnL-OF#Wl~7&*;+i@R>m)FULZwGW#ZrbBDSNAFq4Q9_HCZ2Q zK@61+_(|wQ$jDwLn#5rm%G|KIxONZ)?b?*aiUr7Fpx%+X!V21q zU-U}u)Zt;n<3Z*0MxvIBKlFHdj-pcovm7ilQEw!Ay^i6FsnTRyP z(0zi;1h~ULZX7!I?tBN8YuE!NQ?Z>_>-WgBMa^lVtM>g5+1*z3KP?+dK(_u_oVUB9XCkyrfzFEP;q__p4L;Q0^Wg$slo zA?L1XShnn=w%i+pMh9E{pb4WQF2pN_^O?~Tlvs!HVj|u?od@lqh z@vIwW>(dk0Y6A|d)U(E)8ewazIB8p+kaQpY0czQzY-MkB@By6(4~`V6&DOqYE8A+H zR7ZKe;S-%2d@plqALcAxh4@udVd}Gt6zZH}tZ8ROn%M#Jc$aQ9HRZsPHg)YVNslNn zlnx$LhnZCLxpLNWVo%iaGNt4j`ZY(iH=+80Z@?@=v#W`rh#?mAv665(npOmZ0mr_w zf!l*Fqb|MF`U>{+0)<-Th&^(Vi(6t$Jt4{9hbK?uD}Uytcb2Lp8}*h3bpB>-+B7rQ z!g1H*1ncyKf7h`AhM>2iZxn?4{uuX0-fw>LvW4ZE9psy(Gl+%r=j3R($tRze#aC}0 z+ue1YngNHB-KjlYpE&GUeyKZ8k1sk6jrPxNhWw;RI?%)F6c7fpm$ncv^W9m|dojZcJ zPHdE4hgB7S#&Bfo*5YFPqU9;H0=7C)o)N5uIZ7ckT^6P-*a#evS>qE-&#=Qr`&Upd zDH3(H{HNv#5oS!h*ZUZw8k|6zqWN!z`%PJ!hLBjJEkUoctgh|T3)FKwJum3hQ(KxJ zTc{;&F_eC+lQ6yL%Yj}&?Hi{SKN3sb$`T@Dh_1tvL!?f$jKz)KA-JZj?r$`eqZ1?;lb%t9S7 z9VMl23Gx@`S|O5*RfjbW(|{`%JOZ+|;5i()ciCWgBN7X%d8!1&i9 zZkBVt3Bg87ymEkbz-rRZzF&AR_)LO->b6=^ver)BJp^!RIJVER-g*`;gau1U&C+(h3qcTJ;UIvVSO7IM_X z?E`YdE9+a4iQaG#g8lpn_OLS9Usfi!h_w1wg3&>uPZ3v4*S_=FRv{Tc5`UCSZbI3BK{2 zY=0Gom)pv1Lc3xMyS9C^S{Bn3@rutd`sN>5?&is{>~TwDIo1D}Rd3FCM?HzH=}N8F z?RlIvc2w^elM~3*i6v!U8*${2z72hZ_p!MpV;YRS&xMKBZRF+rxCzJ_5bOb5JNLor z9CWQ%xGQsDjs$VQvGYF};RmL%=sN%b%V>EjR1q=rvmUC_ujwpcnJM-{xKcamhvg1W zVf0VE3hZJCqB=u_=A%~+nz96#YvEkmlt2I0xt4*g6-cn9z;i3#xN&MPGF;1WG5@a? zMqhVk74mc?%qp$hPgN$Pa&Qu^#F{B79bu73vQzZjQ_e!56qfYj;T7{O6qqxr>tp!h?0qUKixaz&+cwc2jatS^>gDU5FFJ5OS@Au-x zChim3ETMOlwiGzGL|7?fsVxmqFSDlds}+BK9sjzBV?2J{WjezA#H-xSYoYz&yslQ9 z-%WZDkW`W7e>>PfQ$8S%#bhGX2aX79Ps_jL3V0;f^AU0ts5?R3)Vpyi#qSYw0XUv! zbg&ozRT(Jl6{PQ4!eaq{l~zC^GEOcjL3E)uY2}a0e-`Qa7D55_ zFmSbllapfAq0adLGL0?R^MPX;KE|}dP@41|Gt2{Dz1W4oER(x~e-pAAs}AlChWUBc z|DKp>-d+Pwj>}TUNOFE7+Yovf^|L6bR<@bf9B-wC^)m6>i;{Kj;rcbNRyPb9I=iWe zcabb~@DzDp}6xAkUSAIu!xy9DDJihc8?zvkJ zCPgWSV8?&Vk_jCe@V4qtkEUD;5{sygd$1qlxI7U;q(?M0-Z)fz!+zLxJI0t28|8w! zvslh?8glr?=(+ryZog1n}{CJgb|WH8jgP*>guv_-8faD~q9( zHvgS!koG*9s+ouV=zhBS51;uSHr1#uBxb-ygO2#@A8;Unni>5X&c{x~1!Hc--4z>Q zg!rVXsJIXaYA;=f(!dV@@w(Zw5uW7@(A!jz;eoXT!5#zQE>w9S@P!v!FXnPM8D9VY zI0HLh1cM?tUln%7Z{$8!ckI%vF>(6^p3_MLZ18*&r@z0yNkweIPWbBN#6+ftYEWr} z0+_EjgC{9yHYhc}1dD2Xhz#{VBbeNCdDj>N$ewKlQOR|G;8?8MS5i73cI|A@|FRk{ zWXeMx5FBUlZQNMY2kR%F5|a1h)roM4u&^G>aCMI97&)HyWm9 zCUO;CRw~myZUYfJULsedv&CgQWp5QaF3W+iuxnDQqI5X6A2*kME;~xXa&W-lc2sN>%K6^Ri(ROe94aw#+3 zz2a;JscYMZl0wf-DS{q@gkDmN6L+PtI}N4MD@+P^>T`c?CM6%alCK}E%2XaCI7sha z>EeNe?jI#d@EQVHB(h6kyTX%R(t%+sI1bmg-Tbt^a_)N=_8V#eoH9rC95yoF|M>AE zkt4~-1HZt9LG>@oyna^QU&+>xP&8N`f*r<9Q6+oO=4nGb%UhTZ!#);Ta!)=00zFOL zKULS^taeIdSMfSVy@bv3^FYgO?4tIcAG!QyG6+6rFH&sMLS_T!ONTFh@X26a#D?)I z?2&S((;oBAQHuF7%%vyAcu(zreASHBAA4p7p#W7Ns`kB~D)4HzbI{>8U9K!GwiohT zeYb`1QPaS4$l!)ul8$(spPbCCQ&}B@SPzZWRV1PYOw1ZD7 zwFpDeXbI!}@}b|DZ#=T(%+v$#R1Q=TnD%gGLfM~4^BraQuLN5GSTpRbu{ux?Bi#Xi zo~?gWRVErx3(&V+mtSL1X=_l2-aIb}32b5#DBhDqSdHoUGJ;#orv#d7Q1ldJ>+os}L<{xz81osK$`Mk}GHVZIy zc&uXD+0$djb#!(%MP$0_AB#TISzy9}7%h09evF8>RKYYFY(j8F-H?N^bIs(5)hqMtZ$X<(Lh5xw^fU8^HtkuCN8>-`RM0hzuyu>Sx8XT{I>`FaE}B2x zD9!x1_b2|iUFH=rTj~SJ2Y>72GS&auNc>!y(FXZPn3?Wv{i1ssAte53QBaJ**O_$kbWKUyE`cix!4f4o=LK#HoG4vyy|d)v$$jfh+LQ$%lvWF@mq*tK zWT5u)^AA+n=}1KU`a18$`M#+8ow6dgtAdpFW;D@RXTYbHZPVVHIHq07B8<87$BLN{ z>g2wL5iferN6f;#HGv}km~6V~`HaoI!P>*cX8Ju59#51tLzS!r!)@wKGg9?)HvN1t zu1a_~)wI*`1GawQRPIBHEpe$xBAzO2Q0tN7ua~#zpDQl{PEQapFLv03@uC;z@Na&M zeJgf66}+u-#}!tvrfVO>-e0Qzst9?5#%D4WOvNm~w^UFg*XR+orYir#hYT1%P5azB zkWutb`VYJy#H5haPg{l^KO^}&iT>vgn35Hm=r37^Uxu{J%tNR5ua_`^%NC~Z7i`=O za=~~67W~FSY1Q|?Z{-%HK#5)!bU67Rip^&eJ^5{BuM|urjh|2wfzG;SIj+U%%be2J zQ@b2>DMdfwfP-TWel5zzx%bOMZ7ikl-Z=(h!DRbdDMj#TJDb(F# z1{wB3AL9omS3$O$uBZ8p?bhWlvyuPLOHEDP#9KnxGzc9Ju@ko8J!Jbe2v`-NZs|%% zDAllkIu3P>?4cPOO>dw@j5E@$! zTubA}=Lht@sM>f~6`AGx>jj-j$rzXP$jIFK4W`nxpzD9k^qmA*~YrK0!rdFkYNxIy9^h{=VclX8% z_7HbzvMTNxWWZ>_={SCR=on7maM#>U003+3E+|QY3pwb0n`)jmT$QZ*z>{%5g13j& z^U3-jNa(#`r2k1?L@aZs>2t_V{&2_O#jV3{p@c0f(|zgu=E{c~?{d z9zkdkygbCng|6Q((hH8Rdr|SyjiB>{Pf~`>P;js%hwWPE!c;;jIGunj8uV1k2G?6o zkf|~hua5lRZWH`KjKYlZwEhQ(>vG!gRb)!wMJxfZIf~(MOk4 z%9;Y!eZ{CZMNiJR*913Cx(!L~$ApDES2~;YYEzYbPY};TPjuufmrcPRFK#{F7?3ia z89W~P#@k>>JIE$$tLx6fA}Xn5IucKQuE~ETExs=S*00&mZ8EA2lRpaVP7xh(-Lh7$ zRlm#3m?5;H_s!m()7lQ0>D!vuy6PZ(9-PsQ3jhWSBL=6)iy$QtI4B-Ey-_G+m`z#Y zo!gQw^*>yI@~UiAF;ER%`w--M)w;~i9<2l^?OmQnITTd>xjh%x$zH%R-vS>S&Mydd zO^-gpyLu4f`3|-A38Z+7q$u3q_$OAO&0nvO1U)5k7tV7yYx~#b7h3Iu!*wlogGvJR zuPo_|P>-i?IsH3)I;>FTcr}Mran+}Ve_iGa?DVn4)gk0;%Bv!kpPlexX%^r(@S?3g zcx@#Va-h6PED*tgl(e_uQxBm7hfJ;T|0mcK3+r6LZw>R~2lBk^_V_s|?fOXX7@6 z1Kwl?U$qu;;j*E_rr2!B6q;$%Uz<=vNq&_Le3fU7FAYDyigpq~i5m#F?mY42*AW|1 z<)z$d2ps@AdI2F;x5hWjNFqL&dkxc~&p9b*;I&;%t73#-r|nKPncq+Q*6Cgm9U>UR z?$XWgRykF)E(_0Gk?rMaYS_v%!PmrFdOv+7;UKxlHul2Okz7GrY=STGcb`{6`L!68 zG?H)GISOg~<=7L>c`qvF`CE7Ox7K`J_LcIKDs>9$K(k4Bl$*=U05_(EFSDrjwXxB~ zw&%WIz*uqURXaP{NB2KP@*-!H?hNEBY_@W*TJM0GGK!M#4K7$(8>Hda`oj-q6E&B6 zkBOX}6|Z(*<%L>-QaD7m&}nmeB|Wd{$saV*#FSGROIlgw0SoB0m!+*k^dCEp z|8w+1A)R$eMX}ZuM2*_1)`#RAF!v0<<64v+3`?duHi8rpuH)~Mcfd;iUDhw4KEkEken|b^UHC52NKCE0nY3|lu*Q3; zzNzkmoloDYy@MsZl##W@+e*)7+jyMTNIng)qo9YTn^no|$nz<)Q}Uiwx8bnCMx6Jj z)9GMimkYZCT=p}d*}Had^LV)NIr&Od0#v9uWa$rKu$Vk>;Ie?^BmB5|vB@#R!b1A) zgXbnt*KxVr&leEiIDb7i10m_gPDM|N8_*O0^1speN!2d-^#M&b#BEdHzw<{P!`#7K z&5?CMZGx*6%E`~Q_ag?i!B((pEA2@_!_`~+!3c{`1eF1-XSmHlX~7@|^=v=k@+qli zd$E(LgwTl&ubpNwWx;z_`@kguo+A@Wnj55}plX17_i5Ud$vc0p9Dd0*NGf~UeBGPb zrA1gRun|l+kG*I+5qBL|cOvHN{4!ALA07W>t*%t#4_;)1Q|n{v{RaF8POe2=l_khL zo4|0I1ceD^=DRik#Sk{a?_1X^)gjOHk}FG{Rx{3&n_o-a{OH(TF!-j6r*Lcp$6La0 zr3~5VIBaQ+xU^Qfamm{@pUIN@?|wJmgwA)9bkbGTNl~U1o|<7E%yY54AZSn~T_$NY z6#Cp-=8k^Z#h4!cbG`X%n`i}ggLWtA3;OL}6UishMaO$CwFS5pO$|XM>f`I{Yx@TT zd>4WAgTxmg=kNIh3X-_N*5|YLt{Q+;S*yP$;hK-yd zFUINvde@E!40ekMbc48HsgOTUAA^vkh%H%Q^T?m8ScwPn1;-h_6r$n!PdE6OwSWas zKzC(fV5$DN-t!7Rw}R%cM}vom@Ia9lQt@>y&E01sgOW1ctNe7xlhV$*8>+W1Ft_7= zD8pUzyT9HA$a4;^=1%*sNpuyHmCWL@R5-;#}d68qhT9TRk9YV{0Yseq|rrTj;I03y{ZpM)G3h=9cxfs4R?X zM8EEtaPV+|HV58;#!>T>F)y_vG|I(`6<%jkSod=93-$LcV8h?!h*)@WFJ&CbNC(>L zyRQWl+AdRIP6J`}pnD}A%u!(32_EdyY4fi{2WRa~xlp-7NWr1`0KXD4eB)kaQ_x}Z z@4x7_g#dyBMbo?UjXyg)Dc@lq+sdgz6yY!FbsrYKh^i<(b|j3hix3g<7}yZv=bV(Z zLjH`s#@vw1>&s=rbaoTc-?F-kVphj1aq%mNxaB!c4tM7g~9`sCT z;}mnae4v|~ymJXYfaLM6%QF4i3dJAJX5XOLSi7m$hEV$hP`7hjZ0_*_>C9_-WQ6kg zjlupeyXj6Yph)mz5k3l70pP3k6-9zR3fwy8f1{3T?208-cK=JdeP|0T4QPDf3WDFl zRt(bvTvjx3)?GWse^2&F-OYecO?A#qRy%DeIM#%2QA@GXq-tK$+TcO^a9!c|T))8! zR@1<<#%ku^M5zx(jO%Z5yhQw1ZrpR0cP7IVI(jk z%w@>WCvxGK!_IY&axXPQ>D@SfX@_`Ixz?i6vAhdsRfPR**BIDN&N<7EM7s<#Q!Jsj{Nh{H$$XaX3zDA1=IB}1Lr6{UauP{?1WxERL{*3g7~dt#HJAssud!-h zEWZl5pM{{>3N$i}8QB!rx5*31VahFGw*O_bk6Du2fiEULS}nKo{%&=K?Ek?ri}@?u zPgeV8C-SLd;DY%Rk@3K9Nf-3iolsw*CF0vbpIa@ipJN^{X1O#;U%3sUk1@o*ckX1x z?8zlL{y@+OshmNYtr8EkfCVSV{Z$7?D0H@SNY2T5AwHGAs6YO9?;(78zwt}-H;`Lp z^!sfK&j0vmTFzOSNlTq#5DLb?iCS$qL&aV zVK4I9eLxt>wvBJmyNY%}uTUu|6r%Od2wU(J^g_ZRjMeW(FgD3Y6)ZGs|1!X_VYUQCc4a|ND%f}>`nBKXrXbLeyW$TaE7rQ&o zp>`KNc4rL2cDboevWrnTKjJj$aT-b_8}A$z2o69Vvpc>KS+;zo(a?M+Og?1deCY zs|U|-taA6%dmj(9;5qybDejMaSao#;VaS6wF5H!U?nR!m5?g;w-T|Njo~W2X zzQ*XEnl7ho>lt_x2pyF&+yk)<(*8n&uqu*D9_V6=Rt>9ND8lZ1S6b^`4pgd# z>%3F*gH`6Mp&W(H^WFxsy89p~WnU+tLQ2rJ<#^h{5s+$D*MG&fPMO-5qTuIQrXn3g zlyOLTlCoH--eL}&ZGa6?jcGeyN?KXR8~NhADfC@XVi^6j9rBhJsl2Kw^T(GQ%=Jy< zs%Ik0Z%lei%Lx0+2pMNK=6%?@*`O?GFs(xK`vR+YYqJiuwA4;_X5B+t7D%2x+bF-Q z^aEic)Ca_JcIsa0ZmEZeycQ|u!6TyEmywFNP?MJ84$#iuyc6aYRwjRQ-Nb$SLQW#EX_iA1RR5cH)mfx z4=$^ya5KJSfMdo&Z;FWM>!0kv6enZ%+U%xBx<8efwR?1I;A37{mruE*L9Nx9%)s5A zef%N4y0Y>iPiK^Hy?n#-IpMGnW7B>;_@$k1RXieb<5=XbUIElac*su~#Q_SxJ2NIPABfGk$`wfg13FS(gPfXj=UsPIr~)xG{qY;|jj39}R3B)AYN|6cm^mCc2p zKZ}XwV-thAuFZ}LiU{2OGx>S$m!Q&#kBl0RTTYkXomZ2fmMh#E(GiU zA!8puY-)=?>hJur`G$Ez@M-;oq6_@V#G zfG_pTNFhN%pZmv%0W{*pa|vGMPA%}g+i3*v_UbsTak1%Vwq=&&-HbG!{?%~3f(g$l z#Pl1ya;=U~>C4GMFO(i2@k4*BHX@%% zx7}#r9u4ZQEsyT5fG(?{Un*#l7I@m8zeIyJMV(9qkbD+yph=ZR2B}Pw5|D~*|AD$1 za~`$NOv)5a@ZsF(Oc3|~K&^7P4T3!Dch>k9v^QPl*O zD+id|VRv9f&JRPu38D@#)t*Zc2rXWBx2PW0e&HU1XtaP;U!XweK<^&OHNY;LF9pz5 zUIYNm&xM5-Y_fAsFJ+^TCSn|R=N>8~+n3pa)&5;A>zx-*{0YuEI%##+oHMAQ#q~ z8A7+nQ;#?a%dsrCDR%BwOVA4cTe`4w87ZfXGs@qb4}#HFaFmMv*BZPoi%fdm879IR zU;4LNV>=hTvk6|o%j`Sz>>G%;1k||GNK}_K_kj1OzlEnQVn03SE zB4h}R1{VWqn8c?8vfr@>PU*-_S5?^vd5+OXcI$BYNhU|ZR7TlSMX_@gpYjK`&m?Y0 zl91K?I!rwp-jA+qqooXaHy$UqUZZo|$`~d09hNfOFU=F3Yyoi=R+T!vF2c)L5i%N& z6&{E@L&$PH+|wN<3TCxcHk~;}TzV7#9ZNpzGgO`yQAW4_OZ4$4?FW0u&-u>18k#Gq zqam>32k4$8qNJ+5e0`}Km5 zI)Jl&PdEiy{eEqY{pR7oF)Dm6hzN5(NN4Txc0T6MzWMW`c zYmD-_>C;Qczi>&6&oZuj?33N!n3kVxV2h7-zmLtP%?6h-^1G%s;+1C`_PkYE3k{=j zEdPbCik0^lO{|M6^7ErV{fK30m-${clN@CqAWsMi_txgttS)MfpA-4L$j+Q=!}QwI zmPn?Ge9LxSUuk4xeZ$tRw0Kpv3SgYfd@BZ8LZt2PL5g^NtuPk1VZ=2#DL_3o5!F2I$wg{CC=#Ne7c=s%OIGaXec@NgG@c9oX1xtc1q(0gwJze3k?rE=?q3<`pSI30t zL@KL`ZAW~oy>jnsQ)VqhR_Nqc^$K(QQd|B+@-&u)ikbk6)H$gUqS?m1-3+B(5&Pg* zYhIL8hJN8mD(iT|;r%;Jf~l?7Xaf_2a{yLAM~&_Vifg94s>DMJ?Ljy>nue(!70qMJ z#71YdIVk`>0%3e2fw|TM+F1afihW&OTPI3jttf1#fhj?F5@LoS*5&*8`=-5adZetQ z*EnO_EEHsCt3}y(l%8OTp=jB3#hgOyy$c`3McZO^_uN!C@^-1o#ggU)~FpK^Q;`DQfiRHXcP4;{eaSmn7c>3O-G2V8RvVLo_EJGcF2rN`Io+) zsV~oA^P9OyYWiNWIeix8a${$*MOEsY-?1;vuu9TqZio6Hm3o&TQ&idZOm!iblCpUO zMQkZvHnLhzM*=i!4(#nTJ?D?q%>WaCQUh6x)HVI}`R?{s)o=dL^le2v`}$HiU|ySc zWf55-jMTEoocBDS%xnsM&w&=Ac^vds3Y(R94` zNzI+)wSJlCD=(a&fkfG%p7XLS7|LRHlaA?Ow?lYP|eR2cq!7rQEb zQ3vc);{7_|{b%-Z5HeND|G{I2!mXWqv0-js4?8is)xFfBu+HtMp@T>3A2PjE;ya8n ze8Z=%b4T+K!v+8e-&zhj@Dt%s*U*c)I%lvq^(0 zA>?>MoHyMtpuIeQA~xgRpWBfUEfzS`visInQz!2!;`#ZKPd!8i6)sIf5e zbtpFQhzjiq`6IF-x{yA*VgGMksz*)BS!O_yx$#N7)zaU;e)74!r@kj=%G(V26;-z9 zFVbI%zPVNRXF?M*(Z6@tO(^Aj^}?Dxbs?IdEwq%zs0-CH@Y^{+DF@ zp?RE3CE2Zy6CYnUcA3_O6HaB#Z!^#S*Ww8n)2VFNf3c_M06+0M^>s#INHfdW*>B>9 z^KwsF^>VJ#+R}5az~Qm*-F=_{U~YHm#RDb)ydmfcqx<~i|JMes#BTA@q5f@x*#NIb zO6xdWgmmsNC!Vy!!$zoDx-pTjC%!``q-P{_*&z2hyWU6e-U2BV(hc_A*4kmdU20*0 z?VFgG&|6i8BHF!7dbE``{v9zpLmXQy@5bcPlA|KrFY~+8HP^m!HLPplj@E+?#`q=H z5cWN=hz*O52tsionfRdmO8?qv54LV65A;yC16DZ|1rycv|9+i@fak7Gyr*fs8Vr`fLB2s z1mrDLbqNe*yYa6 z#$k&a!+zFTK0vezPQ(sj*xNU;;lR#GHju3b{tzmD0oREL@8ODt{$3+$eZ3%=Gd70R zKcN&|NS=>Y8F!vtKh%uM*;IC%pY^TTJf8Uu0YR>lX9WbE1`T}zB^Oy;R+{`}w{{*= z^Jp`o&r@krVvpxVd&2_IKLCWh`t1bqbo|G%+|5A_8?QL)>3+}PGyWzM&{1lDdD(i* z-}Ob?Q=Q|Wpvf}>SFlIz;baoa7>sy%_|t9aw68=8SP^vQ6n8o6A!L3r=Xh%8bbG~?iVvB(A^R4H zrU8SEXNP`R4Q=$K&R{EfmJxHslBFZ~1JvQ=QRwc?{P=}_$?0+t?umYZMvVJJRdJk0 zAUcb~7|Sbn;1Gioc#%CmcNENcCODwl>#20n%(l8M6SY~MhdR$yJw2pnUjbbD5nH z^5*tqlyyH9D4ZAQcO$})({w529?zgN(HP4i2oaZdFfu@3ayNc~bpX(`gJ$vZGx$vK zYr@90tdC*HV+w-zy&L^TFto&_$MZ1q(q0sXW5!GM+k1(y|EC3jGXQTkBP9KtK9Ch4 z2ckmwhSDAS^>%yxkD^_%z%GdL%89Y)Y_jBtt-{1tyEKCZ#%|<#%tNs*C|u%`dkxkrxf|leUu2C#7EF4Uw2c2tEl5&rz}~qhG|1tL&h$!AcUA7+#@Kot6qMnWVqC|Da5}>;@{?8SuT0dm!QPPN zi{s3b)sKE>vFoP(86R&r7^Fyez?CST6n+h& z*#2v?<@2lKyf$Q7c}g9x_0|svOUpM?O4|JIS|0&+Hg!o=>E>73yyut%+E7`KBmqq^ z)9_Y|nBP;A*A`mTK%KFdB& z%i`Qo*JM7OjBCXQBmrahA#;X~E%XkH5}Ke21(F7iUvU{;Mxg&w*t89=Ny6T55d56$ z5NJ}rO@39RvGfnO-GO0l<-N*BE+z%PHMbzTFCCiaY7}(GDNP)hJm{KA7^&(vFr&zC zw$Zl)9Np{*bDP<>!fV&Q^AEaZ)xrS6pN1ao?GAj=>S#q0jf1zZ#c^x=&m@$|-&IXuF$Xx??&+oe+TKjciGmhBAS6|WQ=q0YMtbnP-qxS2__936jTMJRjFZ(4F z%l7^`&A(x>fX`{vc0AhLucGXSwdBkgJOhx0!>>Cs#^rDr;?eYk&caSs`H1dy;iS4L zGR6b$kbse(v?x2}+Ik8RtnxgWM86*U#P?k6N$Yx_#Sf3me$keFD+vNYqXO zr&7t-Q|~7w7MBlQ1ymwX%R>$1?+7bYV0ZgTUJGzrgcH8%5Qms!fgla`qd;kvZ!l?n zzmU-C_eR*aQkqmNekT7MG-z#M2^AjLv~0kph71Co&vtD_+OEZ|`6DSDY75U@R`J#+zrUY0YqJGQVzqJnoDD%;DUecLwz)yj85@ zNjHR2u4&F%!!@^|mIeIEh1?R0Wp9R5VYa6iWd?FQ_IJQY$XxIK zF1s(jS$Yt#RcQW*8GE$tOrG16JZasx`oKzR(%Jn`ueT1?Fc)d-fx2$L{uP(TtOIuo zG^R`^FzP5<=xU%@0H&g91zGgRu?JC4J#K#%BA$Ejt`>zUScEM+D!0jx6RKXIv20FM zD^Efl2U#C7sLFXLBhIkr+|RxH^77S42Pe%4PVj@fDw7Jpj1O!E*32$*QNv%3IVOKc zW^1$*xH^yl5|diTp+||e6>RKbj4iK}h$>ut=)Ya~5MBbbrce_@jGg$G-d@v9h)L;<2USp)i$y%>SnTD~DKhvJ+}RZsWG$bI%*nDcKF9HjF8t&qB*X9_$i}gB zoQ1lkn3!p+s8-I1Xrq{>o&e37(S$LT4DXM;)XyK~sHmbYmv?V&^Am9g$I#_od6(Cd z(4sM`V;UY>7`hPO!rMK3)R{3Jxb|$4>`VZBnVvgp)?KS0TS7C^bm&4D@`gv@pr2BD zAyHQ`i`^J{*LMrHjrE8z6f7F2!IOi_0iU)jR5=YayzollJwZbX53imAJpe$IL{9Q7 zKMJ*j(6x*VB=qlJi|ffYy5pWd9GW;t4jRumavB1=*%1v&*BO!T$hy)%P@g;pryL$A z&!H2jJcH6NxLEpm1yX{hei924>T{^*7cbQ-d=H@ZgNP20{pe&8w$wk#>Gf$KTY;y{d=ycbCdw~rIv z3o_*d-4W*lWk=GTB`vz^WMhpo^N0TDb=yjNP-b-)25s;Zzs7mDkcJ>VAx$bh>3z0L zchI6}2WWU`8sndj__dHV2JlMBeHU1$ypFoqL#|){6w$9aXxw&l1K9J2@_x&`E~7QL zTN^10c<9-plR)^|oK%e52aBP2TBjTSp_}@* zJ1pdPZ~`RmsxbiEfW;MTWcY*%LOrW@uqPzf9RaZuUEWfnBTL9=A-x~ZD8nPCdBHpN z2R$8S)0OZENp3rDI^O;$1d&Cobhd0WML@2{dKIN-C%PDvaF}K9nWa4D`n5^{G;M|C zXkAgPw@T=dA71sWQbLl0%#oc~uMz=m8L36i7$j~~vh}65t$Hm2AZs&zC>{Fk{}8oz zY?cmiBpbI(_ZIN|q%9X(Ji$hGpZE??8ypjm6Cz?VxR!Hwfw-Ff_VN;9sHM$49Ey#O ztlh?assUvj`e)c)F4BNRgXF%l2YsEe!sqHYxaD8L^5}h8nRDPhk1Ug=MoR@gmPgpg zH$Mu2F?w$a(V;M$!0DVhpk>SGTI?U6tGN)V?B&tH zXtzquF?^#kQH?Fa zPeO+(+Cn5*;nhkSujuBB1^$H3T_j0~We&vmwyIwBT^#nL`+(j@_*k0iQ4L4mN@uA7 z)8^4h#=Fx$LpuO3%JN{WC&_6ubQOjKKQwG^SBDTNS06u{cmtZZen**{`diH+coS2u zbjkSA*s(hW;Z~2IL0JjV^apYD*`<4QpMg0LFrsiy0+8@#((Tr*^t|}MwmamGT4?q* zhe6K6umv#-wz4AC?@RtYAqW(JKjQyAR^3U1FqFjNM(`o9ZxQki-IW%76u76?`!G-X z?VyedVjeHy4M7^oGO69kenxliR{hk&r^nj?y0iOL;j?=}$_#YtyJ*u-?q*Bs3GW|a z$cJGVv%Nmi|J44758?m4n;y|K?C8?%XKr^ZU0xS;W4d-e-1UXS-(S zIihugt<4Vrs)D^*5Z>WTlP^mMe-$_AKI{OttFO}%PufAt-|NVg z`Vb33-0uLWuUg(dzVS#t4ww;#O^Ji%$CHzT>~;0dUPb#U>reTcNpQ{BOlSLi2^@!* z<)SAVkA?#=5gpWm80;y2RRNn^Cyrn>V(v#6zHO$fs*W~g0~Qu3ZUlz zkdPmOTmV@C#SAo}I+20DJ`40~yK@}|w|KNZ=0ooV)LxR%<|pshXvH-pTubafy8VpW zIdHA~_Y6<0gcCFU0Gz869M*Tbb>P6hwrQVANlL`YdzYA3kDBm^_rt72S>JpANlnY0 za_sabgD8Vo1)EIAOAr&d-g7x!#t1cdkCQ?vZTzZ5Ed?va5A-+^*rm=+ZstK=KKRI? z-_i=FFUESraz`oWKqtH+N!-KL^GUkV^`EP8D6Z?We^ocC2+uqjFz+J*ytIWK>(hW% zFVqT}t!9r$*Y@AhYj|>!ZH+jlA7W2Zua?uc)kKt4t@}iAT9AYU&NJ%C`TY+FX<9vk z1R2v`NRYY0rKcD5lB+gy2%g)-BhO7?a@8A&`xigvr*$Z89{W`(@6M$e!gAyBLFKbw zFN3ZX=q%WI2(=sN`QVQJ8=gRk0lh#c2BZv_Jld{(=3VOC+3IA7^Vk@^?hqFb)N<+&I2m9;#Q7}IO~Z@58#E&OL+ zpCZm?cgHVF_kt?#@bDu#9-sk;!Q{A$9ihr`AnkyLT*`)P_1G8h69@UFe*GhPpbYE; zXeqttNW*}UR}Pq+dUEnb#FPEhgMnjkLttJp))%IBroKVB33G^W0~~4k4%Zd<5t-P% z3Yai0ni2Uo8|szAw;AdE$)bW1Q~GNaV_Q6|fCXZ-WwsOs_;9!aRGo()9MnH!s!qcj^EQhC^}BAxSC)2A*jmI}0Mqh(r6v zZ*Y|?3Erk5YJP6oK$^6}Jid&T^amh$#mVo0m};z|4yp`vmx$@St|&=4j1s0F z_N#JdO9HS9l+e%gny-8PF`^3YXr^yi{*9ZW zr1ge+f=YSA28>9+m;n4r-4gV>fmWI#=;N{Ux672w5h1iL#I}jnKVRz?3Egt+xKt>I zcQIr(uQLi|0Urbe3@=o8l0S}Kv>*8Ei+59=k7##v8*niahS@!zKoUa_J!dow#!zWL zvaa>_?>+CU&SzET%;%0BRR`=2IPtTc;{T+0n7vhnh-DB8Y2u6~j_epS{EJW9p3>c6 zX-zOCGmJS8=UFfM4UfkucPN5j+uzseUUkDsYcuGj-qYv>A)H)&ca&&QQvsv}WOx78 zFjbJ*!k-LHabeUL&@?btl=jdK1Y9PbH7*IQ<1E#qaYc~RO}f2viz=7yuz7?FUx({# z%EfONJ+>y6(53n&+5!m*lClyoX2@89L=m z=~^8!J?g=|uQHCvs5@%B9b60iGh zKd>?5-#JySbYD0HQEl_8y4flq-$yeQPJ;hFLN0#pcFMK>(r7*D0vETnc!YrOnE>87 zMwUFe%31X>m55R4?0Ti`G35_a6vTBhsiQGycnl(LOZZ_SR zx=F0muuD=rh|kN?6r?d}NGI^@12@ZpD`EGqdz^^qzQh}_ul@Hdnh*0_gX(GXIymJDTUV<}=D9nB5K zqmps2pyLKP5Nh}YU4!9O!cj!HX!gj-_%n!cOj0y2^@}eA6klTZ6|visDlQst<6d~X zIDMV&TZL(wj3~hx=YIP=P{YVrI|ChYj7)<~Q~vexP-jaAop{*%V!*vm19g>;E{B7N z!Lo$f)f4t9gCWILDISoZF#IMxBnhoB5jBM4i)6DlKYA;(me*%C*G#8}zvAYb4Ly(I z*5HK_8oJS<%+pWp=4#1I-v%Ju^F64Te)gm-q{Xt;l{qYQ`ITcl!FbrjQEJ+|A&@L5 z;QOL4&wU`QZE#r1Tj*NhD_~j{B9^v^pPp0(S^5VYowZW>K-~@m#yHD! zqOe(Z-OmCz_M>d^!!-0d?C!J~pYnrEl?5SAnPy@_krUJzn6XsQo8w9`@ zk6mK#13d#kp*2GgfmQ-$BQ5Dg>?-wHxzH@ycYgE$aO6N~Zy*$$MYP{KmH$D=W+pJDm}=9+TyXu?m!IoySd z>%(5UcU5+|0DWWe%?9fFvIBv|YxsUEl9HI(0G~kg0%tevIscO1>oTFOM=2=d>EdWd=-ctEEFz{T14V>rG!J*i^}a_28u zDHG9Q@^OAaXwCx(MSXpJ46dY1lwl5g z6^He3{m17wZVrc^47-=~q7Jy_gk-|_BHlTf7BGHp%ncbpbgzTuGR3-L6@hE8SK*Iz zhhh%aU1j4DdSKo9Q#JZGIZko(y2{+Z@<;=%V)inLZ>)unC<29=nAG}MH6yWOj(_@d zs*Hu>%q=B_uZR$gdq}P`VAO}b5fbVl{IyG&CL?2gyMYd39TfK%ggfX13MzH$C!_Ek z9I`~J=7-Vz--@HZR!FCdb=m@17>yr4g9;4l_=#Vl8}WM;c-=Wb-1DS0^0cpJwrym8 zp3;6(8;JDq_k}*n%;1ktrQgaAXW$m$c7^1?UzL6XvLp55#7SfZ5jm=0=6$JbD5w%r zO7(o0?9|Ry_D&ugaK!K%@e$WPX6UoyUL#Oe-nPA8hruNW$Lc}}(Z&id${mbtQvqdZ za_3~bpqRE>n}ekdc*@o6&^-6y$`yrY=$Z==UC_O zcnOEy`0Ol{3n0}a8VG&MW`98%W1Iivmj$|7FVzVHrdksaP@Hha25xyQ468GT!U%Hb zu*6*0<}-vn5!tMx4{g&+!cLS&<~FVHn0hq{X_d_hZDy={2*x*~11K5EV&KxD7d46(O96o(HWK>pPjV}xFcKv7-!v)m_1`&Z2&peZTm}K+jc@I%pRgS<*5loS@Q0^#&_pUR!^runeSsDws<|!Km48!ossstYkjra93k)DONpeObY? ze>E_0kh)Yc6fhF@YGDDQ;QfAKM;P1%#vubs+kQ-9hJ!TOk%#C|E zWM5NTy5dHN$Ql|USP_9UGK~kOMA7CS*C(F9-{?J57$#^XmIYfNiBRCsU=_)gXYf%* zl(E#K|B_%MjBSA2L&^DyVB>@sF+>|c?5=2wG`pO=;Tg*T@3o8GiqAuEgBR z%%|p0*#M$c$6^o;B~)$IVCK+jrz*^5GHCR`%ri*g$=zy3Nh(A>U*GeuuOBNU{sD)( zBgf-%)d&$yvG<79jwps4)+aJE<5%a_iTt;~k}p1;S*M zHW}_4FcjG|{hOmQ5bxi3w{N0ei0^{5fF6Vh_Up)~+sD@t3Ptxy8K=C*6jH=>NOCc#+ ztX~Z2Ym9lJD|%9E4DZ?LmQ&*|Tt2Hv5*VBKtSs!i`2?MS^bGl}bWpmL)E=t|Fg9wQ zI}BwU@>O!XG@w5hI?ny20q*L34yCV^Ki|77#nb*t8=W!w!fM!e>^J@lN3O};gyeGT;Q^aL% zRg_`_>S{zu0a|_i+gz>%dl8&-{d2!cSk3r;~XUo=w`7$1jp=7 zQ~3OpVAukJ6fqkM<}by&=ubD3T>c$ar`)wpzG1&l*A%il%}0Nh*MKj>o{+0WJ!j`m z7*0G!AFuF?p40t~c0fHqiP?$EK#iUcM2P@`C7E=2y8+xmyHI~}EM=?;Y%l?$7M(f*4FjTdP48%1-lagNb9 zokad#9e%tSAb5r#*r$vP=41)PpZO+AW#_0PH@m{=Q^68My3`W<3uF(?wO7L`Bo;VM+ircK^BE>l)F#TM^2IJXDp~NM9FaJB}^!_YI7_h@}yJju7I=|6M zH&>G3Och-`wmc?V zp`1YEDCTc1%5N4KuY`G`Vy^fg#u^8~&TzY1O zzMF<4nx|8LGr#@66JtM|v)_M)QN5nBz`n9+*gq~Qit5!32>`nK_7p;9ub}gajhehS zfB}WkB6{uDqw}Bj;5C@xg^Mp?m1s?NMklhXul2v`+5&X zBZ!$N+rSp&J0g{$(lF>z4ND@b2Phkd((-Qcc5lMp^m3Q}G?N}?+@7>py4word|Z1n zN>fmGX8o>Pj|gWNKL>^knqZ`wx*HMcWXvbfe?`6FAjZsNPPx@%Xo37u#QhWY*O7qL z|EC2oY(v+J;Kb~rY5PJc83AAd19OlhbO)U(*_^^p?9?1pwRlJ>1Bo91Z6^MXjg2-z%GkQ7xcplr`dDL`DvxQ#|?$s?(f9yTD=3v#^$~qYh$Xl z_`PjJmFFmmdp?%>c@bilJN_G}7v=T^t?_=k!EuBoIwdg;=W@r$ZhBRypvY#bHpCK@&PO2mHFE9pIq< z6A&e)psYv*SfYr~ue~Gkqq5X-eP;|d!n@T;fkEPK+n+N16JjPTdw*4oLODqez`_qG z;aW!H3bWyuLCByjyKO5@%&Hzf{?%JrUJG}U*A1gRur4Z=u+HdKF)KV9y;sX{;=g>} z4D3DcrLr-Ve!4|=19}em@H&PHSK$}+Sze71H1zQ377T+R`VL~e+8ZeIb!)xDE8{y` zufJt@q+%Q4Q-@~A8F?S8U)%7+yS5zDFqJ*A(scMbXZgKe+u0!EQ)y%4hKDM|!xsjG zuPM6>(8e?fnV^ya+45&}6pS%IB3+K(6IEIIpqt)>sgCjIn2T3tQGk7@MEi2D?n(h| z@7UILjlb#>fkIN1!#(sL-Q5Z{g^^fO98d@Ot+fQiL|;LNmZa{n0yyi$yWgRKSyu%#41_b<7?>}U{8x)ba;}aNB3a!UK z0mO+Q^)q~Pm$8jZ4PAs!k4QCghm`?1_ld8Q=(+hmdC;DVOkkD29Ugg(sEzg9ys>aw zOe*pUSQH83lB{0DkM%ZmW;$*V09%e0cB&r8GMC}2=hR;k?)0XjT#rSG-4iXAe7L>` zJK|nvIi-5L-&MRKq4%6G>+o?W7Ie{)I-MMu?bvL1xmu1Zm!1zRE)nhkM@twHrPGiS z2(E6>jNFp$T8*JPzqJHNi0;r#Ez<9ofK!|6Fc}(Pc0CZLfo^0mir_mrsL={SIqd=P zZ9sA600(jFg51&B$3&qr3XFi0bXO=qNl~xnby=hflw;1J8+0!T9%V>(i)iLaO!weD=2hZptU@|mGytAp}&5XUe?+G z`MX+Do?s27lGqI@ETp71;l7cPCASv zt!(d6G;cx1S4-HiDurW-QzmQPdCL;7yKR}mF<)4m0ZmxFFTfw}ItoLT4D=))-C;5+ z%tmd%of<_`J_}{Y@(=?3AhYLWGB93Df@%h&qr(X_Hf`FDP55(n&Ptd)16q=hbOy(hcq(Ceh>2doWw5TN!xyi=}6IBWm%O zGQ6*dsee+T$A$P8qI(N_Q64t)(f&!&8hoQtfQ=TNG)ZG!g2}k<12ECle zfD=xTa&U39q89HmxnlF=+|g6M6dRK4D*7^dYhGo`AF4gwYlU}%lCV8vY`$D3`;>a2 zLMZFACK!RyM*H=*+@kbSji$d(^BMLmvhX!^LgZZ5Jlvf~7_Ny?-0Y9#@!E7ozaZVv zedNhddURm%!`Ep8)t&KBP+d|-R}MV{Xxhy+G|jw2a7Fk_?BJ~>ek%}Lc&SPnSD!e4 zD@eHy^&V$qcxn>o+3-D6hsrv2T3LyqJCnJ?LYNM_SREs|Eigjb9FjJw6~KL6)Ny^Etw3#&T(V;JMuu zU?9FZAZ|PbW0T#PzJo7CHcLgmstv6hYpnlzhz$OKH3tzG+kxPnZNEmf!KY^n{(7=M zrAkU{beJsV4@)#NMb$-fp10VQv4WBn8FK?;i2n_dpH0#(d+Xf!bF%{T*aYR{$S|#~ z|MYQ|>i^iP9NvT@yKs}_`Ab4tLH#+*dj5iExyX^XVbSM%*H87hrxhj=U>a4TD|+@S zVereUQ3cAPU-&F2*`O^NRNRXJMQ-#kSH0B+jG9)!kzJD|i%rR-5JZlLJT=6t%Rs zc$t!=H>2ATccF!m3|na(5J-rl`Jj1G`(D)cS9bYs#ZbxHOT9{5zsHnMxqQ|fTZXMt z;}xW@DDmNaH2N2#6%GCGEx<9!OOY4FP}XR}r6*Y$)+U)ljqPw`u~;=sN_+SQ?%wyC zhN|ptq^iP95IXqZlepwyLr9THo!sm%b;dhmH~F0pYyun4kD}{+|ouwLl3z5TFA-*FAQW=lK|O4}+_;$|{!si@47t;$w}@Eiy4&z^97J=QtMX z#hW6pk8=@>$Vj9)CkTu*&++sy6DgVyML+a_8vo!SY+8^;QT$2cekyBVe$n}s8$DyxC*d8T^6WW5P+g~ccZl0Y`Ko_ zfOo3qD!Fs|QufB9psDa61Cf98;join8JX-I2^Z->7J7n%fOB@B88Q`Cy;LBJ_^*IZ z46=uSTj+2%J#Jc!XR7mSiL|0c#ytp?4lF1;@aJg>E= zsO4D9Y-`}R9F0*g-fL(^iXF3nNXqoD92;Ty>&Z3Xc>d!cowVfqG^*)US~wO?#B-A9}B|eITrDd zOU^9}E`3gN3jD}t)!?g;-n%uTaJA-kzj;iR0R5R@&Dnb=(Sp5Db3k3PX7ci~RLg;~ zR=5}hIFu+HZ6Q^BR~5sbVM1)ph-iZ#3Hj>u^#7Vq$y~-&~3JS z!c!QYp<;(!SOhF7!k|94*7K8h{k-wG-#fJNEYoR5v!zGpzrBxoK_CM(g+1t5K_t5zX{H zU^F>!7v-c>kyPz2Gi($7v;2#P^r9Nwa0jo7NBx3-Gkq_`q~{SLA3Va|1mr5~$nnL6 zXvqG%U*>11T;xO50JqT~`2yBC7ci-2o&_wHH^k%{K+1#Y8sQR_e?7eLyF+d68{&|H zEPbp1&!a-zaw^uGazXa5oWc5YT5q*yn2Q6CRZ+oqn0iv*9=!50)cdJ-)K5)D3Jgs$DRJ4|&((<2 z@>3yG5>=eCfPVs&H1t^zz&Rf1T!)Foj00Iov3cgHu?l5N9XwqLn42>w zlq-peAF)2cQ;stNtVV43(dG}3uXhMj?SbupPR{K%IWbB1<>)Dgj`Cud8(EcufGfL5 zTv4!#D)q`!XdEjYkW9FyF8o9%dg^pT@ztW^EIKEjoELDM4#2`*yAR}?No)9@liG7K z9YV85qQvSE(9o>krp+5Z7Hm*_{#AZW=Y+&+)IFK(&L^%hJAt40{#FV%)%l}BexzoQ zDIOGgjp=| z*a==4JgMLPO0}<=)_Z07+f)DRe%C1ycDPf9f^ISNd-p#=ebVmbL5JUeD|#w~!j3Vd z*oi&rOx(XOqD~~j6c-X9N;suIFP4;z&iy#7n=oaxCaCh^fWP|Ja8;3tifWPC_Z!83 z+wSm{H4Z5H8|F<<7yD&x&s43r`&)YtNs{*EO@PQ|A*yNC*+6M=&*dy)7QiP9n@We@118{c539PHZs_NT;toc2l zvIM>xct{vKJz*1k{FM#~E+Uh^I%QA&El>J1v11bv896!Z8MM_+`2Vobw0df~TUSyn%<%29~Y%~lCS;1cb=GAd~oog{F_dVR7)#Ew8=-2Oe+q|aIddKRg>Yc z%sZIh6)vn= zz}jogmC|^_B;*)FC=I3}bLxma4N?$bGiSm*kBj2E1ZfgXYVevCB4>5N*}!)5H}E7~ zV9h>nr%eyl+KfZ3}8&;zu$x2qV{dXfe0z+N@0tHBFu zAea?Kz_6Bc4oCx0UGh<<))p1=BnC$zb(_TJBs6!-7%R#pVp5#K@@j~U0 zotRuG$^X! zM4Yya5PN>Lh@n3xd=TjS*_xeyuiGCQ7oUe+)3h>k@Q!pZJFJD0gU7NSp!vv&#EZgg zJ{&p>_0S(5wVs+EZVXd4d$K5Eo;-3Po@crRy~Z|S^aN5Fd-8!!jCvB+W(#+ChGH>_ zE+^pt%AORysz8T%df6f7pBu_>Me}#N-YeXW5(zd)wp&_z>X&x7H@AGWpKIAb2{qRO zuMevPE`dG#42y~_`Yxs7{ri*4o7?5=L`=>@E@uF|qX3~&%`~=%{hQIILdo=balI20*GbnIZGK_SUVn7!MXfUP59fgS(1rP+ ze}7zC$)D5iHgFxgh+kVUAW3mgT*|+*g)upL>}AWv|L^R|!`ZFeUg`7x^Pc(}OxfPB ziD(wqhO^TIhSv0#T2wB9^ODBqkIo+U;58kM?dc2D@8-5eppKFaUT+04RmD=bk@wV> zLx?FMWP_{L)~tMTPuf3gE}VnC5le4UtIh>4n+F%bVW0lnDoaJ0QY1V0)l1rNmQ>EX zXrlpns@0Ynh|h&ca>fk6*tmSoK8BtN$OWvzspe-{`G`P>{FVx|XO zG#C|^P?1jzT(wDp{lJ5Z4+vepObPcNKlrSYlI-g0+O@jZ!jRKnAssOh1`GL~jSW9i zDCk3AAAre~c^24Ynw|fUBlz02YaP{qf~PxlJxhn~W)X=s=J?yGq-k`Jg#$ona2-a zXt5Xe|0=!A$8N$(YO996u=Iob=I@kbsQD0v2d@T=Z%Dl=%3kS5W4u4?tSWv5?H?PV8po4W-;+tgrdr2(%?7FyteBeIb`iLL(^1v)Bt zLa=R6BIc`O6vj^`HQHg;PHwL^#pMLkl|5(0nM!)I(L5i6+sO=J#^z`{>g1SsFcc#= zx|z@Uch~go`JxqNWsJm`+qhmH3#HyX3EHsN1$bLq_G``XBdn?*?n03ax}vG`54z(< zlv^W6T&B>mL-pMG@*I$!FL7*aBn0#kq!)|wvJ=ob>%gM9Pd2cDMw+tskdQ=?u4HK z3T^l&;0rIxO=iz_Lv-z-QjvNjB?_V`ph;n;4^c2V1$}=Ww2M%}wInJ{?n4GEDk-7C z7I8K;6;vaX;jg|k+0n6}LeYBt*V#z5bBvx5cyy3Y<$%ehiN*C^Usy_o6Fx<1qmxVj z$k-x(y(biJzhj@xD2MS$5J$1?2+_Yz@Nqk5sWlN2*hC8yE*Dq1f0McC*KwVOslY$w zr<}P^tYH~*S~i_QhtHrW6y?Gr12X9g@CUpWq37zF>}vd6zD>t8!%pHqj_+wmCgP4y zQ2*!%{e8m=eI4v{kPu$4r3tmYAQ*?5sdUvdf5`?B{L+y-)4rD4+^O zHk&`G4K=*C4($Au-T7<33e|7L*5B6U?$qkbfMbD|US@I4KR?5Z&=f#9aUIG(uUQRb zxAqcL>BlxS3Ql*2iGXeF&MWsawdYb2sjaFW!#Et(;Renm+Aj$9!F8vUGEYUedIkE0`y%u8>_ z^co^5@Hh*BkJQ;U*X))!JW0BDO!=DR($9hLId|H{}EYuQw9&9cQg-@que(y6c zL_e0ePZy6Tl<~2#H;xf-QpJ`41PaI3rX&oyI$x#XWt14Xn-rs#U!1|C_w2zP`E~X< zmn$m2*=fHoM8Rv!XPhu@{>tsQ9j(Bn8Rg1%04o@xccfl#vMI^I^9MnxVUdvXBL%Ds$i2` zR|#xr(h7HGJf z!MWJGjJk=FzXXVNj7RWYjp=~4^DlNMW3;iD(V0?qb3SP?dht=NCf4* zIKu=LK=6*QlFR|qSKpT&Jy##k7_yb(>1@$lxV%8rS|vXJI0%&(^s$I->qW$23^~4_ zIuC@k3seL&v;8-28`Qfw)%<95bZ=BIsM?DiUrn6~CKZE3Gd!?67!EW5H4mGy6mC5i zF7^0l>?}EG?}&I2*GrWB!wrpSJByfwJAxd04Co}D^07x)+S*dVVwJ1jMb?Jy8u*sw zQu*gm%M4-D(27$Tfn8PO3V1;R8UjLF-j@p(ieMrQNHoCxE6S)(p9vc=zrd_%evx{k-9L{{Qgw-tkob@BjE2R<;}~Gf_uYDkAG3qQN1r$et-= zlkKRCjy+S^Ba+O7>|}%}70MpjviJI3r}yXkbL-Y0g>=s2`M9p@e%%L^uen%FT8g4@ zyWA*6Vk%s?itCN2;;(B@x6(WLr~9J{IoH^41g#!y z)}cf61LAkEcNvt;Ve6sVGhBPz0%>g{JzDU@x6K@P;%t6_3Xt?mW5+ReKQ;FW8py|JQ1dmAsR`U>91#InjS%C10<0 zE?lu5$iVBbwfwG;yn#uVjBrtn4j6R>yh%t%SiATU<0FY()``FB_lTNWm7V+^vBW_f zdtWnQ{2GIXw*7{JEar=l=B+_8#*7~s2ym9teXWbaAsM}EO)wGM3qS$KM|(;1@BN{r zcwCGd7#^nQlutLy{r;5adcTei0my|J(SUwx=Ye>T)IsuG!NdstwRqmTW!ko2ls4-n)rv>v) zAkj6MtU*tx{VA6KbU_pklAvilroNJbl5%SJPi1(o-8`o0WV{N!A|j(xsMjm+za-A# z38}zNI`RPG-yV7qP|G3D1lmq=5n1`zWNSY+>-oDab7sdABC};)YFDVbu`u^pi?Z!0BWEiWq#hBlEsevfqMtcX7ddDt zO2m31bNKzJ1{OUKzirD;+)hZ%?A z^C@=LqWt8LLH)#3*HYA9I&fdjxaywh%-8UJwV}|IQ@2Y~kFH<84pzRf_HuTJMt3sL zEAdo+jFeof4S&?L*H)#PJ#gy$l3YmInYxhAw^HYId4or{*t^v=U#Z88e~ch&)5-3y zm#AJTjBD7VdGpy{f;3>0s^>V9MR&jG-)H&;20a5KhaR;Di;fVK7HbiuS~2hwSem4P zxBZ01H-<0^0md(j7^E;X$^d)o@&#oVv$(o528{r9rpiRBP+x^E=yw*(XDq)fDk_@V zJ0COx&<<6h(6)T{T!#W5!%|k#Vq!onYS=ujWev?gcsyoBTY9<{6CpHut*50$O+QXM zDYuW!!>b_-CZUZDcTyRLDG|7A2mXqqBRS7Z@`Vd4m0|GK{+jlWkBwx&Kgp-d;oYc_XSGiZll(ypRZU)=Ei zM%kWlGS3*Vu-olbq@sBAQqpN7vFOw&aelkMOeCzztxf7ggz^F94GK9p>jVXuXm!mS zWL>_GrK8C(J`F4(HhCbG>E*hC3_o|3ps)9LNAA3y5vO#MUtq7p+ZiX8ZPd9H6Z7z< zy{E|YgrC?t#M7D(-^mSN4`zMC?)o5I`b``Bd+D4$?Ir0=vEJ+Q-{7&+S6(&n_OAL6 zR&M-`ne3vu<+ao`b9BoS1L9H{8-%1KTgrvJ`ySS@gckYO<#GSMP}hwvrA?}I8ngC3 zqqx+E;Y=M`dS%YN-{NRTsgi6QE8PVV5nR^3lP7(G`<&iimnG_UT~m0{Fb}r1z(Gel zWf@FxkrhfjTu^OEfQyAj7#|Z6FrV@7@Jt5^8qD3=+`jVnm#k^`;nKvV$p6=Vox1wS z3N9oae9|QI4&eKwwge+Cbk;(=qOOjo*^ij&ARGLL^R^)-yktYg`OjH|E>)qG%O6Tx ziV&?><&#P!teoQ1AB;L^vQ5sBA9o5kx^$M!;=u#aANqxa^w7xm0$45%Ib3CWv9|(R zYpf*p#zSap&E`Ct1EBwZd>3usmSMWlbHJj$ zcTsucW33k?aOD|^u^qI`gay0MZLsn^@}g)#MiD}D(bl=tsjW(nvkAasmUnp~QAx*x zi07}$*5};is`75zyF@A$KY6>!e8>Hb`jiTU%LIfvO7RTHETdYoco+S#gF03pX^k`H zEWL421mmJo4 z)xU8a`&ypdmB3<-RIS!>dw7({zSyb53J28Xyd8Caz3qobb-50 zY>v9~m?{e1Wuv4O&n={qLYQp*&wsTOX#l>HL%766>|wUO9WUXg`y!efZJE7-)o%6ftn!Lz?Y zXgXI7IZ&QMqkx$L10!HyS4uvBnW(ijr1k#y%+$Xsb@N>=P_OSparqFXe9@MN*x!FI zv)@(Kq^K`0TfZ7wi$o8sGu90PenA1Xy%UJ0R2F@7mcqKzV(d^irh6L7-jr@|tcCF% z$BNrzI*fxON*qhMo?=2~)a{sb#W#o-< z1llf0?*0G(nI)`wh7BvE8(CPlnyND?`<3!fLN=mD?$WuJdu1N*Kb@j`c|A2n=3#o{ z@QO)@oG?Co$NeX-E9D@cR^ZR%>ytm-E=R~OP^)1Q*6URyLmy;6=A8bQu5{r2A$8Q%ij#Jqq_|N@LQ0o<>j<|IMZAfcM9RP+PEhQiF!gE=QW7s zQ{@Y$l!2416KHmqNVEpzr>{3!`U2Ll+u>XfZ=4S>3a2f*mkZ#|+GMa>>KijMe)nzi zF?aH@efshJ<=RxZH4eCsMZzN!wVf&x9R$d3FlXsP&XP@}v(NXsVl}a!rq;aRH6~RL*vSFp zLOr(5)wCI51KxYu>`NZi$P>`uLYGRqvp<2Yo`I?9vupwxphpH!2Z7p5n%1N&_U+x> z|9kW1O^E^w_89_}eo1F^{Q>)h>tR>k+&c7pIKLl+qyX#z3&5;xt&_VAfoSAxb{uOY z^vYoI0G%%&S1(?k>IJ~J>lfSV;P6Peay8|VN0{Q2gG5E~>1=lTK^fyCQA*_cBbV}1 zG6YfHhR%fhh+}40kBCVyx*^rY$@7*Td)h6tjInZj#p2BraVwDJ1K*JXheOWfUuvK~ zE0msLH~_|}a5^hJ>PMnV&O7`)Mp#pL1YIuSrQ2~e6mQA!#GSyg!gSZ|Cf+W-ANL9! z&<<;~Lks)UlXlg(9e@`|p{Dc}c5BcmG9k9UMB~#Dvo`4WM^h{lI?J}qkpR@tJ zA1-U_ESW>~W#Av$UMKE5y}Yu?I8Eorc@XaY(=O{9)yCZ_Bk;ir^P>1$a!KX_1T^%a0574aW6P}O>{A*XnoG-KAelf&*baT$Ru-NWWQNs9mDA{LdZ*p)EkN!)_ zMzA$t()A$zQ`qBH&3dK;{z^|%yi8A|MQhk6GF+yw12DX0NRoV ziH%JyjKWn338dKCCok>+0u2QnegRMqj|lPae#X5>$&>+A3)ibL-oV0zzQMawL)Ig> ze*!Y4!GlBwqX;ZQfFh~%KPGWpqRv;%VaG>(+~wz+7}js`ay+w2_7z!xN?o}e;_J_= zCz(l9(Vk2Uu3>Em_HGH}M0^qD$ccOJ-mi-?C7gWR$R{H1#gGp4P8gNR+(_rz*!U+* zm}t~;a^5SsA}$NCiNtf34AZ|Rv`?}Tzyjz~9Zv8$tcZ%l_$1GsS$gva&luXd$EAsE z{j4-aZp~roK5)(c5PvK~SNWF)01VQn2CpU9Tp_2ST4O*Ki<3|*46?ZMtuR+$D%PC4 zw2bnzSJ(N?WZ@D|ZjT}YpNQON%KMaq&L-~FLo2<3nRt+-uTR(hdF{V%X z{E&~k&$0+*hwLWY(W?+cT`9P7=avHD8)V8t@41KEGl}Z zDYq;D4aLoEx$D%3GMIE9Q!=Qf0b3iSun{sWEdcW+TDOVA4!A-C$8Xu-Nsh zfhjz#NGOyI;vDw;VDUllFNhIVfhG}0+sk~85@Rk>!?tlEV9?}?Qi$QZZ+jgH;q;vZ zg|Om~X=Hn8S{tt(7D*=9Twju9c?0W2z|@4e3r>5PxIpqLq)&Ffz2HMEL3PwTi_cCv zRY7f4UlOIwvy*CQRrhEP6(5`aqw5U*E{*e&dkS0WY*w(~lKrnGE z(-6_h@bk3mj7RdYY=rLwj~wS*E?oLvW41TbvI_#j-cEVLGS_}8NS)Rt1!gD2gxQPKL3$~{KJMhvj&u{-uKjfsPAOYv) zG>qsUx6dY2)g>gC54%RMfHU&-J1ymTr(Ic`Ver{}*oiE?h3Sav5r8)L0+zlfS7dQ* zh$h6mXPC^w$N7d3Pqq4d%J?_1!ota^b~@BtpB@PN6wvzZC9{4@QkRtfZRsTc`oBf$ z(SV#AQ&%W~p`UimX67j=lfv`qp(2a@Ip%`FqMYfF%Mwg?vNjNLmA;&v;ou4O9l9ht zE}AkrFrmbq5(3Q?sewC_Hd@myCj}yeRn- zo7U^g7QPJ#>Q#(?N%g!(bw;XlIct!q28@LOxJlGw-wUXkzx;Rr&P3$~ba}vK$_(IY zUi7b5v}v4qe;<_Y|CRj;M^(EWpTh4?DKN;dN0Wv#sJyV3YLy0A)#*45oN_uM8W}yE z=q<<4*Fw)&Im>E`LoeMYdy*N&LheDyHpyZtTSJcWQp8UEY7OI$NYgmOVntvbg>+>I zHm0SLf&{>&Eftx^XTO+J*&QpuC7>B+-7aU`&WgfN%Tn6WGX+vF@S3p`g*K15UJnqP zV%$^iqR~r0O1Hg)$A!>R_Yi4*7>=-;ir*kVEhAt~?<<&CplqTo^RsGpQMM`n4x^`O4idT$M#dMOVdTrXWZU%v#9e!3f5+c0m6- z42gTk@U2V7yEOC?oaxW|FRdhclkSZFt5U=1T6a*^#{}eV$6(xG3`&z`LHvF|^Ql#K z+xU_~(1#nB@5}qY+I~JZ%2w2~UBN@#N}1bb+glo`#YCNmCB?~9OTZ|#sXFMtxA40$&T%eb~rix;Z1%`b9E%()(vOZ5*Cn;)#Obi)rd^n1+dKu);gM*~n3?s(S)~ z##j)TMuQFAokfZDg`>dgG*|7P-^irukOm-PT?T>~;K4vngPNFhw!Vh1Xg{HdHfIR& zrsr#Qhc-oyfqc-TTHZ$Ms&fq<+xhxe@iQ`$h}H?L_d{r;p-7q(g*?d0P6~s|2->fS zhaH~)rUuBGapKccW+Xj-DIEI zp~N;CS7#fGnyHEnm1(7pp0-Ga5{w}CcnwXhnK?vUK;MQwE}@|JM1oqa-AxG)e`~v+n@EJrQz)C!Xfj832 zYS=hIO$;Pz0QkbbNcsXYggz5w`+yDlPSpAj13F_7KtUcwn!hV6o0Oi%6Wyc!6Trno zmtD(F-y(f9o!(DwTQXZeZ}e-bVL{hf(^X=is#U0{9?>KAX=hlxMEF`MtbX5CJ3ogL z=1V$Zxd*?1=L5J5+&Y*H?NzfFRi)~YrB*wvlTTwxW?_94N{Gln9A7sDQn9vKj??v( zxIS$o@@VNRI6oC8U7eZ$;1|JL{;i0nLp1gI$2nM)=b8LlWBFrV397EJIU$TXN<~@* z?p;JhYZKfX#%y_(rUmY63I@kU1l-D_kdo+wWfVrpVS37SjChhboOip1k|SsXc$9zs zSi{-_4@>V|8T0PYlo!Gq*g{_5#O!KwEBedX3&2j#s2+5)US2Z2kxRE2A8rRe5U`s& zcr|ECA4<&Zcq=!ncU7CWU*hE#{%38nE|2T9AoU#jdRJ=oDG0`WlF#T#!EP@9`NH3u zh2|%z@Bsd~y0)J{T}l#8e>C7^@%aq`}gr>x}dZ2t9YGnhSZ_s%RT0WOLQ8pc;fyPm&Kwd13qrrmF7C7aNd&9PxV8D zCqm7LcYD@#?wShj%$mB`vUdw0@0;fa)LOcv{df-KR%I-f5KPAu9gQT_9GoLBY!wV- zw#V94=SN+5J|B0AV1GZiUcj#TH>^Ob80g;(EXtU5RgJQ~!YOtsrOUfE50C!Z=Ki+m zF^%Ky+j5nJ;e1aR>mUAq;Eg&{`i-7C-GoKKatMYyGV$KLN*pZPI%F45?AP*&vv_E! zEhKben zh_o86bNt?pqMOYyH<6lRNfu&~M>V(n6Rg5@>X$f-h{ zsUo?gK?S2$D>hb0FxAWN5EPt5T80@ZA#2doAHaC|a$s?Z+*ODt4ZKmgvSr(uG`fa5*V#guF z(xFB(7B0AglLv3wIH|XWnTh3YxJkyRXuafg*vh1LQd=r*&PGj3#M#*Z7YFn!U65$#lIGKr#&778I>7ck(Z{kub>Z z)ha+CLG!mFS0G+XUP5OTnPllgM}E?8zD6;=>F!kXNh%-Oyh);TYC^fmyBVvuh>!GD zo(e6E@^=DE=6AjrlupaAv5gHto+M16ufE@3cbMeh8cyG~WI#MJe0w|jLb7#%yhj#{ z4lT$}@fg0JZ~3^*N}dfmBurZwd)5kjAZ-dOR~gQy?~?as^iOi3OII&<4MCw>8)Z#Q zMuy4%*al%s7xMO|0^vuu@9GoDDOwjZ^*YjJb999S@nlQ?m#tte#1ocuFcPwL|N6?d zszF$oco$W3Hd)K2e*E1n#R5kIgO_V;|7)G0PtWw!>gI!R17R~Z#wMCy*em!l{BrIn zkZ^KH1f?PhtMntyqCOgHu$)Lm%Oa#jkV7b@95fNB;p$fd+iu{BXXR1j5bXH%XC62@ zsbGL>NMri}g3g}0il;pYcu>^hh^Tj#W$H{PzBc;p9ULZGpJ0S>+rzaGaT4(ipsbD4n7J2A9{ zCY)|(7}W+I)2$HTu3(FA(dJHbZXq?(y|2(Uc_VoP)j(~Iqb%;t5NP%ZA!#|G-HIuq zciO3XEYuq{Z}zh)&*4-6G*6Sqww`(DrXxgME)x)*O=anx?letMge^+gugP{Xcb(l7-U81OiVRz;)Po(Q zY4WkW2Y&Ug^qDPj7q`qQD{QUyaTb5O-IK1i{94+Y)~!yyBga;|dpV`c=6&%=*gRVioh_bv===z``_pNqGw)`GBE=8Oq@v zP)TPGxaFB!&w*F@J?rW*|Og!5^)Bo!r97$zkA1gjSqogI7%KRVI1Zon`c-3#>b`RLl z;#qolZlWQ?-7Rn0tW|Ui@ffx?$bF-YD}|Lqrx7O_im3__55u3z!%;-vSeD0FIMibo z*YBe(T*b^{s44|7Awu?7{9WWu^_ly#{+C)vVIg0m$3Duy*Lnx-Id!>a*cH*t>h-al z3X%WjGa@sYZQ*8tILACG=;zrp^l2Bxx+w+3eH`nY=u}XZx)HNA z8#NwLz13*=E@fSQrgo{HnLha7IbQ#oPT8;IGE=KaIj!RB0!PxhY(8JT#1)U8KlTdA zB~99juyQ2PF{L&Q(@MiQk{3d3Mi?w>*iXIfm|)I*Y~Bz(6iKGH=?FK29gsQ8$lALM z1=JJyo5h-;hxPS_9kq~s4>t4`!Mz+k_TF<{*+meos%IiBw9sC|cx~(iR?V>phz8_` zBp{EC_Y5ELqs&1a9$PtX3C@WFixgLsKTp+G!zI4&9CSST%g>V-Q?|u+tclMOKlPtZ z2Fskv`5;F#a&imtyVdz>I-SppnAf5%--9e{zJeuF$}pe~vf}R1z4koq36aoqd_|f_6i*ZXaW#H{iC7 z-B51sf$64XeA6Y*Cdu%JWrJ|M{3LzVynG76qRTH*jhZ^$v*a@tL$$om zrc<{lC%90>vV+PT8uS1YxC!tQq6+oNzFughHxMAV=kEp@2UbYtI-zDz_F2c5l$62+ z{wQuaZ^v^ju-p1+E5W0f>&eYH*nNC@@zP|xUEWy z9?cwBy>QAU&_>m- zasZ|F_9ayvjBvku`M@GRtn%j&H1;sn)yeimen~d8%QysJ4!Sb!a{ngp_z80Q)5D?P??!kTR$fnCBGI)fLi6js_X{(5gg?UtLYH ze2ON>WG1|XBGDGxzksHQW16afp-@EmCrQ#2~?? z!Fl#pZ=#W9WThBu3?fA}hd;5ThV740{YaW&m?}G%NuwI{06=IiDbjXyzUw5OCLZDj z+BbTx3sLlH$oup;`WL$Nd#~u|hhAo!wx6V>xK=&a+xP9ikiuaLu{Klh&Z-E}d9*zj zErqibynr&-O(dpazXx+&mxsTelY`S?<%2Vd6LM}zozFiniPW{)u`0?nY~dfeNC`;7 zmEog^u*yB_bOx6Qh2z4%!XbVIB`dV)ovgvFmd#@()Fp_IOSrpr2JgWGXGZ=wi2~}s zKfyZ>Jne5RdPXZrgA>&w2Zb=RX0X-HsA_-JEb$pT_y|N^tXz#a!(6Ow`PuuFSUg`# zA|sW`SlXjA^Y2Sb&)dkV2V$b(%@@9WKR5Jxqi#>~0ju9*>|y3RrIN;aWBD<17mO@C z=g?$e_^|OX4EfgfKMsFX%a&GqiNt2LX5b4d3S{j(scJ%Okjs4&kR4ZS?&|8Q$)xN& zNV7`dqn?Gq0{D4w!(VoriN39;XPHuBpi-*_5lpAf-G$8-Ow6_1pqmN6?36^W^C%UF zd!eM|fgXsRVpYl$5xKiLsMsYrnFeG9$}t z@MA|i1=p&J`4q{ImJDcqcyRBvF40SfHLSf@{ILU{w{?_#^ZD4U%`Z1z;K?`Gz(BO+|I@JX?(Im$KFqu{k@9ZZZ&d{p8S$ z&%E5OjQ3F#^$v?tc>W6z)bZTvgnS@dv5m3=p6FA6Z2y!LA;=ealP)=pJ@> zBz~EKu`-tWXC#}r@lDmDv%`=1$$V5EWu9;NJjSkiZvi!X38rx6MRIB9w$=;UZtgS^ z)ITxr!P{VU$5&t8f>OQlKOO8fJi*gZL=Sv!>uduO4WC=m9D$LK~JC>4FFtn?Kc5 zO7hCTNj}N*wOy7QqbFQ0qrO@5H5M8FGgOEV+ zwJK~(n>$LM+j8xApdaYqfA<2f+@%Sdq0g3zmyBi9#Y*p{-ZJv}_A!QQY%3(d48^$g z_2meSZ^Org9HX#$`M!NG8F5kvdgwj2|=~0{7K*?^s(?dEkczQN=y3SXsiK_mkRg*X(fwP~Av_a{}URhH_$amSe zJaXPSasITo0Fat2macR?@YQTA5r4<8N9s;ZrLl25CU~F=13Gph48IVMvqusI8DlJp zJ_S+bZ&?Vad$2lph*r#yi+ctFt@2RS^k7a8(xLwuOp`e*1RzCnIBw?+>b8`;9*8Jd(K z@AGtY!<#F}}H9e`o{fm3`8QC+zyeBb=55{;8GeF7bKXJ)lMRE6A z6wq=vHi`m_Vao$d__*QK#0uEKsK-KN=b=*C_NO!Jq~K22ym=4Jo8IQed{% z(2=AhiVE1bByqz*LS04r+8H4&ulB!My9%_#IgGdQ7@>zk5`lXKSlCb!n*rtH#$@;8 z?Bca1>TnBb@?Bs5+$|OyK{?MbG9&wr?j1atYRuGozrr6MPZxoPC)w%G6GKh!u^0U1 z!Y>gQ^NfpmU322t-grq>gj?+cER7?-27`{O1Mw4%tY8H}K?ntAvsxAtfsQfO`Z;N> zey!nOBnF!+T#e}SRrxl+&VW*SCy`tPax{>~hgKuYO?>_N=o&)%GAZ07!&GD|^j(8a z+D)`$T~Pf&bZ4YOeWPlo++(M_Ic0p2ccleR8J%pE)ZUJ$KRX(h0GXG4M3cz;U^9>y6PcFiShl}}ge_K;OW`6G$sBp}l=IXvu z`6$k2qogG2&Lx)?bCGThp31Xd7Vig!_@BO@S8!_QdL44%z+U;wRRt0{v-C;e;nTW} z#t(%D-;cK972|ZYWdZ1m5<^(WZl>ff=;mi<>;9H?E?i6NUEC*A-Tk$2=$Bz7BaFRU z(wBAyTKM;rTbBQx0+JQQ1n*I$L(Phs-_hPkpO*hBGqhLYJsW+dMI@CHDW+Iq=d;!v z9IBtLscT#Z1N8?lhgTvWLW0CBoulXD;jOwYu-u)i2g-YSO-;cW`B@F`!?m;`l2xX2 zRJZ?T*)F8lzP3?Vd;a0?hxsX@TNDPk69Ma21F}tbb4+`36*h!G#{h~f zx=qOg;B%G#t=n@TB@u!u?wW7ANo?I(%F;|++J3e_kXH>M7dIfw=Wo?jQVO%cto)K! zl)$Xw;e?_aNoz$CppYV%NyZuf9u`n<3*&w_b74Zc)$rkDL=avP27rK@*(8P)dFbg&zpAl?h!&iFZ=lim?r_vwgSWvtaT}wxfPZDED_c)lS`vl9M^zWx~c@qVruQ?qAV-ZVfHJ%Nz=XESL8!j+P7Pd1d;f;|?Cv7G9a$n3VET zGZFcCMUlZvEltHGTz=jo(!WkTbw2#oZ>0OMY^2RK(0feq>I)~<7kjrKnQNxW-Go1J zpqRcE%$Uo8PoJYQ^&@+3cTSj~__H4W_)uR_gAU1mLi=%&;z-(!U*!M8g zeG9*}mm~i|?Ekq~-@G)G{idkS0QN6>#_kEE?7~@~yuKe^4!#7<`aDUf?>_&wVvad& z`w0+~*I)G2sEPZI(M;@OkK>v43rcGJN^^ezrSyN+*KgUy`>xg!%F|j&NzA5u<);7s zQFy!MCpfyl8V;|rl1v0vUYKqNnSPb*Gh%M;0$%oi|E$^}$T{E#JZ0@^UY%?P_+*L( zM4^DHL@&*D15(@yg~Z>{o}`r4?gv+BbG@m95Mr~%Ix@~XIY7Ra=cZ? z?48^h_8L!~nrOO=X}+FljWi|{(BB5i02sjnzOAoA5A1QG8;#QLVpV<{i)?Z?eKg+t z{N2^Bd-55TNa^%Mx1ZT6qAe8R=B6JEsL8Y62vya+A#jaK1UH&7T2d6RqyjiRv0-Pi z1@tycp8ar=A^lHV=avk!2_tlHX{tlXwYrindLQ<*0CqxOoUm_{d@I*E|1JhfEr$+u zvAqL!*}b$;o`Pe0F*57rqmRWV>FrufocC1qJY(zkQ>{}6U&U-?rcO4|4?A`}IOp|N z#ZuS$Fpx{n&_&Cn^;dKEFH;Q-m`Wyi;|2v!Tqn`rV#aGo{5SsQW)`2DpI6mwC4>S? zFl@I42AW%?jtj_kZ2yG7;i>>$1z&xDM{)YxhmE}Zfx~;lTP@u{o-QvfJ$_W!H}CyN z*z`3iQkZlMH)^Kk9lKm+zg>a!5K@Bi%)wGXePQJ|wMNf>dd4}Njy2k(*iECAzq+vh zS_hrl%yrYQytfS`)Af)l0N?b)v3T z5byQT{t;G;nc?>KLiiGH4_AbsWZs+7d$Yd%RT%)EbkG2@e-HuSp1>P0CnX+Py^ClI zCQ=1G7H%u%%8veWP_xDA+Tl*H{2x^A{9xB31A(T$5P%6ssz9lyr01e?f+N+>pUH~C zdWj1izA|O#j{3rjq(vJbX*g)`VbeSjY5)Qu4e|a62G+5RH`0LiIZE3)lWRe}X^}WvGN=L5d3PU!@U= zsos%!8|qr*XQm%_3dPo@$#qJ#d^?9N>C-Q!XsVFke)Dr`LGF&}sA6&ZSYg!9j7!~f ztcitR$;F&`r&`A@$V~YJt@S{0AM>kdYgKLN?nWFWYau?tvdVJI$h}&#!f{f@cxYBC zYq0yLcVU6`Qc13~9vH8@J&Am|uZfJ8nC_%O#B89I<2vf~}`h+t1uxuc(@;rprSlmq^y4V?-PC!>XG1SZs>5 zh`4y#>K+I%ff4ePWFZB2QW24V-hwtn<)85Ad+O#zQV{%ZBZGhXv)Tn~ZT+0$1tO7T zZUy*{mfzg1ZfP)I%)KsNs|$T|KrV25k9N|IzA^YOqy2zi2x_3j;hnCB*M4i4RNnka z(l{Htevu^6(E!eIs9lM0{4qE8>!5UCaM1Tkw1-3xn|)3k`JbE|h;$^G{*$=3lM18l zd*T@<()$@`oq|H&S=wD?sJ`|3EUOYHxp@Uw)(B&e0rd>V68xn>#YcY`eRM zHPKR!$4(I^5j1*ym9h8ac&;}77DeuGtbN)jKKLls{g%&oYz!a$=wa43u+Vw>NGiyJ z5EPXnL%xlW1I9%`Yi9Y0bm|1kcA?$ks^8?z?6zEHkANSNkxj70jwQJk(p(XIh+wFB zHYkjtHg`WGWJc>Xj({){DUVLbM4(HWu)Uyn&phmy(Zrs^#w;}#;nB3bs=v$UpAnsB z_BwoAs!n{_lguDnua)4UpSGtO`beLrVj^lli)w6p=BvQ#5w~9Cs>-;TmM5n@QPs>R z^T<1P2RxwQv;)~kqA2|HNm{$<6t}W@Su0KWQn>PYm5IlOX zOa4wiNy{mye;lC4@1nUX8(A~qAO2I6%2;B?Zk91srdjO!TE`fR5=&wrU467w=5CPwDc8KBoCH4ub z-!;G4>!v*yQdek6TKL;QAtHrP%R}SYORC=x463lk0oHW$LreY@bue_zE*%{%xqlXX zHq$O#6z`_<9Olw>Xl3>LOap2U!2|8q$ac%6^>?}Qi%chf0gHx|(mr2Ut@+Hv`?Xlr z;jU-o9Hao+dy+#cTuNU_;cpNee-Kw#HFctPQc(QcwBnJMvBxiK zZ}>U$AtL4f)cM}fu!_xEIllKTH1=b$4f_a1 zyZ?PZtl3V(HLWwZILww@ScUS8gSDEYgobw8D|O8yaP_;?*B3f|zj}y12M50iLWCID zz=xp}lvX&J*}AE$RzJRFOB1?R{fDbh<@4wqtN7un5vCDIg&+^%#oA-nvywsWV9u%k z=I6Vb8ZPQ{y61olI>mjCkigL%1}j3iZN4H1tp|Gt{+<5;+FkaG)^n-EWi5V5 zB>#r~!(P_@V~D20Z;j-AloZl8ta!Aeoa$k92D6)M&!UIr4H%MYO&kl;m~0Cg&CXFa z5Z>gaBhFzDUVWcUR-MVDbY?X-P}_kTm6kz8c_X_ip*Enfy0}J@7BE7FAEZuyY%7@0+~@;}S$ekVdp9 z|MjfcY)*$tC78o_cfW?L2Qv8Lph%O1&h7w>eA?3jpj~mVOz}JE$Am`DMs9+`yRUjU zr$emT{+W$i0EPUE85`AltQk?*fQwAK)1hJjBCw#}Lb5_PiMf0=OB-Vgzu~xu@77P8 zBIsk@4fTFqtS-h+DmWAcMGS!!i(f?b-qPz&`q<15%|jq#7``ocDW6@#we~$;6xn3- zKzZ!hxNJjMADRUczj(Z7PQncUz8?^|3d$W|n2}yhkeR)nEoLHnQt6&5Y{DKVth&E9 zY)Th;)ud9A)8m;*XD)m9f%bT@8X_2$zvLd>vL9)NfMbr}=WFltlX@9+JaSw%9mtQ( zTLdRiwBcyxu+&rZ)cS_K1w#%YEF+mLf=lkQmvLvKn|#iew2+p@-}ds6(K#upx9Kxx zcGL??yDQb|M;JCHA^17#Td2(GOM+is&m%a)$vfoJDewlDU%$6ZTdmd1y+GLlv@Y1Q zCqJT`nfIf+(*X}vcdJ*U2{KfI{zp8{cT@;^AF;dWXPJhY6wkf90ljleP9!$Ey7N zSXo~F6K)(@#8wN8vY*(pDvBjRX{^WMb1L!UMhW-XUS__%SZ&&OtzCYN3DL)a(BE|g zUYX89Lfg>6(Sg-_pnJTX)%~8vS`3~srwt8%Q&(q-4y}zGy@eb2uQ^*K$zzS=MdHl9 zI~)eM_CIHnJ9nP)|L8t}`Sw5R+tSf&+Tm=Ii6OY0gn9`A|h*$xmnDpu3Lg9q* zWXl>^vXkbr_43*=_xlDBXzpOD34@pQ9jPr^(#dvfqPs)_zKD?f3L*~~`3e6>yTU3p zFbi&Ns*AD(EDO$TPeMwp78HVORFhtB9)A)v_X#kCBIdHH48St=rDM>IJ)`D?Q z73%EPALb(rf%`5{+3_m~>zcNR55Zd~97zvbrS0p)t0$&S`zr6ow5PIlsi$n}>GSE%n6h&8tQT`(=9`_v>ead2E=h$? zqu0H#RDir4A9nDGYriT-%6$m80zbbmv|0ovI2k%wLs#lI)x_W_A9l z*C{|An{pMJYjB=w z77ISA@ZbG9_^bJ7r?*1)Y)U}{%XPs7e}g>{*08gfu(LX{J~foyCsh^F`oIwE$yIkc zg`Il#+)|?}l4_GKRRoj`wOPk&{5VN3Kd$Y=1RMLKI5InEVuKJ}(Ui%qBaImLqkFtuI%o^EFP0U7c6JKNb z@Z88Yf(1R!s7i1#&t;I<^LCkF082<$0(D0ju)~ z%l`YG4akOW2l zxj8vGGSctiH~`tV3Q@^dKllRwTYF08D@Rl-gkvHbxVS8aTIcckh)_=lj7LG)7Io7{ zr*rIA9Gs0SiUdZ4=FrCi8!-#U)L6Apg zMX?DF`G$9Gu~Nb9H=qh*7`UZyyP^aj5ZCun3)c$_%S2w@x_!A#@DhQ)-(l6@ek*@$ z{jrfg5+ZdCI8Nm%w+UO|skMg>K})nu$jqOM+)#uH z7!qCjgQoI#K&|el`u|<7K86jx{8dze`-jWj(lgxoVpDinM0kjIk+o+3Z;x4VO2oY0 zDWPT72vDtmiphn?>e2RTpXN=Ec3XX@yytGEc^kMJPy>(}JQrpmo6kph#^x_{Ijd(S z^9)f$LwmVU_bkapZsv5h_D81w#|22yjWWM8RUA}5M6IPmpeHsIj=JoL{bg9^uVLV@ zrPQNCZeW!`A{O$8m)v6N(_X0dsJkG(L|-@2T0+gft7e3wJ4E@hf&nZfK;4#s%2Z#H zPXz}L*iJ!Tj6RRNTim&JsBa?u@DFzpvKL9geqkQC=avrerr=K4Ga_FUDkxdE?INYQ z{iCmvBxHBfw@>oIMTlS=jmh>@(Dg!8{Yxld>%NkavUAmW;&!H7E4;`EMjYABcz3%= zx)TFVknQ<}A1VbGdILe*`VuULkY~3!4rT|H!N!QJ(`i7B@J0Y`IpB%RnCrnRb$)~Y zD#CVvb-^-D5K8v_H@8MeJA)ajS_d zi|W0t`gpA;`6jO&9i!VlReF~Qkq)=XHYOk%!>|c7_u{L6IA*Iubcm@@VT?XZZie^A`8l zlxtt+=5D11t*rV`_iONg%F|QctJP%PtFHgYq>zqW?~1z9jcX(e8_eFByO)Mp(r;W| z`;}<1#lN+XQY0?5R}TdhuAy-wk~q?a+tGJ|lXvOl!fbkUgnWXb-ipvZ6e`uJU-qoF zY{YiBOiRQG@&r&K=s;p7 zAdLw`;hI7Es7KO__}?X^Rtg9)Op?&lE#JQz-Vz>W9K|Sv3bGoMxz58ytsi3T9I`0& zRh~AxBAx;PMa@BLdJdarx@0Z*<;_F)iV&<0wn{&ny8XSW? z)APqb8||ZndBnSTi@@ygn5qFqJm-NETcYGkN1!4rZ=T*-8@8OpnpU4@#N8-PoTNf@ zXIx$*FBmiUY3ttgH+rR5!C{4Z@XFI!oR7BGH8D?zz2_gxxj!P}vbmd|Egg$buL-ev zxZE)hyt$@W*64PwZvmai^VD}z<9zl~Hxx|jY_?zSOsG(WH@~GkM)`Pu(XLkd5`8Au z*H!t|n6*%!W!a`JchDouKbV?67fs7@!jfOyn7gGGVdMKH`TW(vk&HK6mFwkh3D$5Y z@ECiJlzjgupw8}hL}Fh8aq{w;f8|D%c$H~(YsQkZ8ub~b&KEGXAOzeC7cVACplh*h-r8)%=t0P5L*fyt{fwyTV!TzI_A_beRTJA`#be9Jg_9&MO*K5& zc|z=LYYWs|IOGJ%Eqx9KN~AY|6*vdSq7*@q9gVpi)CorYN%Nf3?}OmET7`(>e9+S1u}@+<5^jYjq{$-w*fnsjzapR#|WwXp! z^b2=bJ|VUJM6mjwDG^MB&y8mqc~$}U1BBDYW{ySyWB$;HiPP3DTwE>)GBgK%T1q| zSS{lS4ZeBC?(^YVS$kU3Tb3%Zy(c5Whvt;&&!$m6F>5~B8=Xs(0S+OhBt&k@X`}zS zhweY}bbrx5mkpc#g+sTy00jTL_BXBMY}GwT)7Xdk!hwhqU^Empz3tBC#zF9ICZ0hA zu6P&~L&xicKVY9|o@R#VdLYHa2Pjl;=6=U|X1OT6os_c4>%hKP^-iZ&bZtKVl`t>D zI+l~dFA;SA<9`eo2lyXiO%Uhv?k5QsUR@daY1N55M-~m%^O=sU4QO|gzpHoc@LP%AX z03ko&v{#V(scZNUt5gQkI?KMwm=_VtMSj}Zw1JE7#f7I;S0w-RzUZOH-dPBnWzBW) zo5la$qVDe4uOxqs)+xAPoHA|0(Ec4j43Z-k9$ue+rIe!6*$3DA9wx{XM~CZ`(2(qb zhaIfgKRs{ba=D8v6;8Oe-?@nWOvlI9{g+p5)F!!p!K<6Q8%~B6^k zC?F)QpxX3%_dC_{%mBWoMxeY2b%}Pp*H3=ok_#K#`qmwU_2;|GRz{uOBxyW`?Rxf+ zV*i1zPlAofkSK(#0xl8r@`$>@2iah*iDp*z)0}2Ox~5I)uf1x z++&zB+nF7~h&Zl6&GK@<)}ri~(W*~Y|H}NWBua-LVEQuxsu+F8g`*nr<5hEhv3P!+ z|BtQjj;BKZ<37vGjI4}9N|Kdz?1O{`lCoDqC>`@;A0$F{AzP;q*|IsvC^JN49At%K z@96oS?(cd2dd}C(>MTw%b!~{gg~OVeHn_nC7&%NOxTGk@?+D zsd%gH?fX6cjJ@{dkfar%;WvBPFi*&DTE)%KhMD7U#(Jzb8R9skz3!xLVxizl9d|spv9dKnA(A|C0>xHVTnwo&n`Cb9VqK9#dOtMIo z;#}0U!Y?XkMuaV+q{?mxT#`y_aOsPs8$q?GS)qE&iP^I3T6dC2GY7CMr9EpHrWKV` z-ltZiDpj&?I6L#^SLlK`t~XG8KVYtstk_#}kaiH5eqDdUf2xl&?BlO9?h9y9u!^d_ zX}8uSXKwz5r?GN^^Z!FHj@3?hS3~f}f5u-9|B;_H$+YTOSj27PMAltU0jOI9E2mYw zT~~V?a@Z|OtoF***9Y)Htol=%guQBk?(eXo=jyjZZ@p!Y5YB<^a-5Bj)7e-lT2U7b zGKgp?G2_hn3T4tq&Bu6@<^2RIKx-x@kSE`rUs*!;z|xzM!ZVB}>ZPv)uaznlD7fI^+CiJq>*vcw~dsYE=sht6_Za$p?DImyIoln1c0XPx455FK>MHj+_ z+*1GKjIe!*iv-i4`MQ}18TB(X&on#}?NadRjdvT_e#!KGtuJfGWtx8UGIiG5bi9)C z>=K=Id%Z&aYgQ*TG6$|5Htr(4C=u>k%4cr(>tG>^+4FV5U$&rxf=uofMI7v6+3P&0 zKX)3Rc}F(Ovaa>n-K%VdUT|IpAw?pN$;ElNZNw8`(G)X{| z;zmRlB)u*8LxJ%>`;!QuS_E#oIaB}Hq^B=yQKVrWQanuXN;F|rYKVDhw!2}PC|rbk zi|m%lHUyTa44O&!#norD3>4u7ZS^rd+~b*! z_cByR!n&bn_V68SBbzlq;Aa@V{b@!4V%2^vqjrvm_7+t+LtM#yAcT%*?T2MOdvogP ztdstbW__{oWhY?fGZ_+k9;a!bB=tem=)5cN;NZa}>`YgJ=An0nId;zJq7jRvZq+xB zx_bnflKwsss_%`%MNc=&VRw-Y-%v*8XF89}`6C7Tk38l3`PtmVic>_W{t_;3hK^g` zLOFbqDOz2q>J#dt?*C;1bx~0%f+q_t;B3(1z2Z#^0(f^{a|n-fm-3$w&Rea0`BP28BKnlZ)3f8l>@|eZZCQ|OGPXUe96I-j~Z5*z6>scYZ*C8 zUZ9<~yz04r>i%xG9Hd0sEN6WW5 zH^f=(m>v1`2CXkD#NNf4%9igN{B!&Y#xe)U)&0K z2zii+b^CfZ+~w>dE`4po+=YL+p%EpwSVN`%%a3>*_2R(H@K&|~;@Z*CsL;hS^D`Zs zq=ok)9VNHU^O>i2jps~0h^|qYU1y|0rQPp6sL4zzvbGH@3#^GzJ!iXjOnjYO#JhXs zrn=eD0ZscwXa0wW%t9a3B1IZG{xM@bzKOYM@ULR4Cfb6*74$2<{4bLl;8WTCzk8fq zv@N7#N$n_b$+Np2tyV2ZE0R!ieHWh^q`li;{1nEjBWzyBgUlr65_N;vPsuw@+Q;Rn zQW%RH*M2;!d25o<1L6kQKA_jZNutk-*IuE-aScCVy?$(RT&X0|<`M?}SVfB%k=6|0 zEP^2>sL#yxE|PSDctdF$;`B?hFWWroPAE_*xp1|T;wh$$BP(`8v}pN$pA0ewznK2I zZ=to9(T)lET;AkzUb$BxG#2ixO1nw!2^($A&9Thgz_A2t+*ET3_)65MD;&_VQt;k) z2Wipp&(%D965nj*a?;PLV$bRg!(IVBM8wFZob5TRw~94=gjV~nuh-{QGyB3mFeKAI z+VPuXL_e>zZQ9rY5WYii8E{8|bFez2<=rTV+LrL@AlHj;#(7WMaYV?>51n~VKpN$h z<&Nu~iJdwA;&MrHIQRn)M8XFbA%NJE>=7FY06;i>i0F$=Z@Vd0~uK29?q602OVpqmFGCtYAyU)MD zuL+}UWODjX_q15Cn#{6(%DOih+gq}g`)+G4ekKlZh+X+9{+m!n-6$15r&dWG?yNn< z|8)T4$p5cSn$yel;zMx%;Skn1vqzvJCv&zU<^WT;@C0{@HS@L$gt?@8#(@6GL3>>^1SraWZQJ>nJvqf+Nz+KO9yc z03?F6q@rIrF`yUsHU5_Ad^2~jBp3c+o!f=EV@H_iZn1XiS}9LfSP$>AwoRIV5*r2$ zreq2Ze2d3Jc%C{HBVx%XV@3r(JO6_39{@FbT+iT#x6jl$>od-Kf6Mpg)m{(J9qfId z07E68lob2tt`APZU@c6P?>Zx|m4*wm*-0sIiAvd+tM_1 z!Kc;MWdynC)r2k2UCJZsAv+aXx3}G1FI=ARpHu}jmEwgI-iOxKpVscm$P6x|EqFKj zwjRrm_`5#|us`+z+2P9h=eG|0v?Hm*!7pqxK}Y|%fU_g5B!I(+v0ITElLxJbp;6(F zq`81K!S#5-AwX8=cFYJK2x4mfd#~Wk*y0`qQ$qW<39?x?J+!raA%5`&E;`nN$ml6%{L>wAUd+j6 zM((sn6_$^cpX|O5XF52lVbxlx4ph2WhNjj?^$@D>kw^K*qSz7D!qP3RQLN02<>2>S%Uh%mF z@TUx55o)kh1LNc7d94WI^f3rdAObY|)N&KR748*;9#hmqlZk2Z_|j5I5Oo7?S%@*{ zJ1>Pk7(Or(O9IXj21hSd6fb%j&-!vRfkqa10FrG0&FWusI79PVoJrewddt>RBZB_A z@q+l-2PY6$fLzSogPXgn64{m`WV+u>`(ZdbjtC-p7H>SS9>}M9s%|tE`wxTQZat`7 z7`Ed3GQN}&npEFzx$VxeCuG~(_=^tM`MnE-hE&96M4v{tbHZ+#(W=0@FgfzuGfLU3 zC%lhsdS8FwV?R?_y!-<8G1*e`68Hp{<^A`uD4_n516H4!?x<>ILYV0Ir#|D9Uvik zZuWB!y{?F*bERqXdBmUl+}b8uOemdrLyIakk=|JopkVVs{nMOC{|n=Wj5zl@H4 zUhy)crEhT4`>}+hr07{S*LH5>xqP7|EC9+oJ3GB%yO$AAWezRA@<$CaBpN!8Tt5A_ z32%a!HSb@qJzf_iY^x$BpgJMn`11R4)p(dRUUcBTg_yY%`U3X6&sQDd=}fx`MTyOd zNXrD_%swik3y$X;;YEVjt^KjyIX7q_G?aTBC|cIJhh_I{*C65Ee90@(vSC?KSYR6M z-VRl#( zecuUWrY>ZlSz)%#uNGrkYAG*nEK=CxRhRz3Y;p6@o*^OGxp+@ALUaCmpIMljpX^V$ zzb(&3a%}q)alP-SJ(E6+xNUhZESw@nOJc0Q^i}W)@%J-g)7Ri9C0^sV*#||hX}+tJ zny}TI54a6JzGV=*S|9a^rzig%?Z>&vP8&;io;|pITT#cawb8P8O(IKMA5_3kjN~E+ z7ni>H)YgD!{;AG%S|>`kYj0M4!j!~iTi+uv~X7dh7=@W z+y?q%)<^H9R;}VVvxbI-Y3Y4UYC&Jj#GUJ#T+I*0MbKR4{M9p<0VgiA1R=PBDIK&LZ{s^qtp&Ivh8~O$!}KS`tDsr0IQx3>&RlwGS)U0_@_ z|GKlZrT6Bp-s3mQB2UHKTPNN2=NzRSlj=4g+J$nvQqJMNN4!L3JR`DW?y3%BVCEyo8nI(iOMhE z1*#!0Ia!SmMurP~C*LZ5SH94;9RU{nC`TADTnum| zrTlN@aZEaI-n=mYM`>~KA!b3pil#*Ux?1o|^<7FTDve|QF!7At2k@T|}XYIHLBQCTbaT>w4}qB3|1On>~UB z-}y~O1_OgM%6nH65wA!O|RtY#6OdFBP{ox!7}-Xp4Z7gbQnL2 zp2kF0e)j26cn!YDIE17>yP%u<7K|9pp95LapPNlV^5~mrnW8IBRrGXpWDP&09A8pw zQaqaYraP!2nTxgmcQg`P5#L@8x?nG_dphxmSh(>t0q{oAhMR4%j>Zq;G6?yZRO3={99cCpjn0Xo=dawW5yi^Ykaf$l*^CzC#m4s(sK1Y zBt$mPZgm|Vtc$CoY%0Iq z1Hdi=lfPyq2(=?yP)L-8tg@izQ`g(icJAH=6D81w?dJpJ`NY3@( zENMtK5VU%`32`*rXI+T>GNCjI`IO6wU@f(Tlmik1ej5HBa{rG?yg_Alvb(u`_2==P z&r*=PlhU+2*x_+aUs9!mi9CceNW`1lB?D%t6aa@+Iw}eDt`iG3;GhLL8Me=8psdnQOZT;z# zWiDj4aVAf+GNdLe4#(A1<9by17*6)ff&xo}N)e`#mLLNJ|J!5F%xlt{vd<>n{mJ3N z0zA_}&nH3`o9_M7`@(X2pjT{HIlj#&2%P`23~i#9eEykt$|I7XwmVZj^0`pDoi;Q~ML+Qkd$W>?wZ>_$i+OB5K# zWe0Grx5Jk*?3u#gYfzr&VPSv(2Ev|NtK(n4G<4gJv#zUHEaUHtR_ts3(%BgfK%jd? z=J`QE&`Q&f5DVO;>a;QvXYe5+VqsySH5m{>h>1{HFie5SEwZ~WED62SG@@JnJYiGc zx9^QRn>SDFxpT+o_jSGEc88y5&TRNH^FBou)LKFaKaYq7NV9%x!PM02 zh{VLiZRUqx(%1lKZuOALeWh|7r#sZ&I@&r32DLxm<#Y4$GVD>!RI^Zburb-YxQJCF zf^dbR^Jz8f75?41eVRZ!y|ZMjQSrhPy0TM|wH>*W;W-Xf=j1c!_Zd^0bbr`6RlUZ2 z(@g~oZHG(-*Y@BmzuXIXu-;{j{+5f3TixS_%6|aaO!$uqX5?*%gp=qY`=w-&Ud;R} z*Y(6mhHVZrtd#=CyW+H|?w5fyg5Zr9V9_b&n6M>R1A3OeS1v{hgSsAkG71HdzVm1J zM^*4-{b19{PO;~Jj*zDIuJptE_tgQ36m*%@snpkM&1kjtFSCKS-e9SKS|Ne=B~GG0 z-{2lKi_ZV$0^}o}LLVR@*U_&JB@qq{BsQp{Bl8$DhN9@a&S}^eyd3$W2ahd;-Wc8Q z{q(7^PCWkiAk!ixHB=aaMBp0kaW3`OH@+DeCJ*2(i3Y9Tr)AvAba@UH6co5%ExHwrBu3+W0bM5^rV1^XJb&hYKH1OoS^p^>YO0vN|6neiI{!bKW=jK7* z&GNbyTuUM6F84x);+twl7qwollb+)V$#!LVjS2p1W}HSuxdru78Gz^WK7d^@D~36*q@GxUF94*P2xj4BJJqXFWW(WcwSL7En&PuVnRr zs4#4Hvx=iq+^Gils0MR0f>cVb^E*yw-89l$+3@_DlTn?~JLXdAVm{PZSbg#~XCNZ> z@+BuB8X+}6CC@4xedJ_qZPp+HtM?0;TE0DPDbU~T0Q57Uv!X7$Q`{AjjA#Hh$kgNU zq?f??UPkA-8gFp=c*5@Oj!42~9AMA98z6e)zTY7**Y6m*jH(U=x4es^C;0RT!PeCI%ANMFTuP-58&}pH=+B{k1Bae86lG-cFvf4YacBbRJHmH~w&Lv+J6-sQGIPJ8Fir7=q9^YBEbEouCU zTrUsR#&)QeH(v@1NLubvM#-g|+EsR*vUms{goxK>fsf>;w#Ns#naP(xok3cDsji73 z_zX=JEeiaUiHLo~S-U?I31W!TF+$<;EwQ{oSV4wsjA`D z?Cfkjo~+}rI@wGD*9tkiXi4%87w|DtUI#2fKt_HG^hW3L#|pDiQXbzl*&QD|xGL^D z+T{UMZh1df|3xW+xjdsE!N`CF&}!N?Tx>DHIm7LNeOFO}QiVF-Ffvrdy6RF_RNQ)hzb*_Q7yk zB=|;mT+WP(qj2*J3mTVH$0bmGd7+xfH=l@3v8=%r1TG{q^tOtWqT*TPO<*j$9)hk` z^s9ajDX!DR$>3A*dIR@O#e+NXr_VLKRTSX93Mq!rWehXso)SxVq@R|hAolj#x7z?V z09mmAG$%X6jAhV6^6`xTn?xa1q# z8;%uXReQoM7ax3dA%{OlM&J#umm7j^R@sHl- zMfCU`i2(*{Zv8KVYCdnSwYS=w>rW`{%eaBN+RKI(INn{}ug8}>SDq8F{k_a%P08W8 z_`4*cl=#O3oye20GTI_P@5n1}#nb6SdvBO8a6G%SiPLw!5cKp0iUamf82|3Nx7i4} zFFmHx-FyPc%p3(RZ(WY>Wzg|B?e%A*1^k0GF8$tMg^m`1=BKM4&Zv}?lEUe~5otBF zzh512IGFjnu)KEwNF(3wEQ8o6KwkeB$w`ju<_G9M)Tkd*$fT^@88+Jq;roNmP4{{uxCGQB`D8J1x_hsD z3{5BgF=jq}%`Z1&uYO@^EAwx?TTL41Ej@c=MxH&Xv+`Z7{71kiYm3*Ob|^}#sPMwp zUK;|vIRh7&Sb{L5jkcHGn@TP9S3 zXd1@PM^B$ZG8|wJ8!n{a4I{2YAkj+Jrd#T|BZiBQ<_jA0ch4cFnSJmv#ANWAI z%EXKI(N^|z+&>Q9EHr7&&(Euy-kpEtE5(p;E#5t$PXW273;;X1W+UkT!5zj zrzcBGH{tAex;0n3B9>JzUHVA<<#j$#5xr`j^IR$I_&pOTJ}jhqphMpBbj`oXx{oAt zw-*e`+x<*w3HT?0M?V!#_Gfp(0{6oJlIqjzp7EA!=y2FB*T}D9+7!@04g@Cm4)emDh070s{HOl`L`>Y#dvnADzmFMY}qEleXI-w!?5HZ!2*Ws-K_ zi=&M}?r(2b01%Hl0KTkUK2H*+Nm%b@6(XW#`-!mwA`TXW)wU6dCSE9}^5FQO+%s8urxAmXD)vqv{aDxYQ`Yxp)FgB{rYO> z4t{oYNGVxowN_%eq>6TRanS`Mi1PAsD0N)$poNrDq{_ToO-UvWgL*aYxx~Qzx%TU@ zhg+wBW1XjZrn08UteT>62tlRz&NW4C*Ds#iRC(P}k!|<)?}yfLGTjGDzd})cb##1Cp0uPb{^C7M#g7yDbfDI<>aJ<*TK|=U;(;Ok5pz@B1FgZnA z)HUWP95t*F;LY)5KKXM@4D>OCdEh>QO%7HflsehvjP;JaYw&edJyly&>kwrv+Rs3( zMlT%P2S!cj&Yc6(C>)}FC>vL&p`^*pzy=$vc;(=oNsTbN^oq%Nj}?n}n;%G-2sB+_ zKX9Er`?J>-{HmM=#Ek>8*9p7Y79i1&{aErCdL-M*l@$}d(bo11{-Wk47&BZKyd~89 zr2W-`@9O1W#8{+49}GdviDOH@$>5{(k(a6SPFEaTV&V(jjop{Ue8C$y$o%&pm@|jg z%L;mXA|0H%pFAAfWp$1`{<2f?N_PG7Ze<<&Qn}&>oIDPRotIpzXyXY4n~RQh{t z#RN&|9`ET$Pxq+6!IT2_sjqe;j!LKwM^E)1E`5CBs<>k zP#x}2*_8xLn5B9*zrZL#%BXQFazzM+)^L!i6AV3{1AZ?%~y%96XPM8I?byTS#EMPGHDnKsD(Bs z<@)B3_y-ikbN(2nTjZ9)eWnBfJA7ILqP! z;LS5~iqNli&R-mq8TY;W8-a>#W48i>`T;i8Y)C>_Wk_oue7S-T9isT$JArjz{+s1t z#JRXizyxghbA#4-@Xjza5(39@LclJ~&a}MYWN&`~!kQ%^(}oMHW;S6*UnR0`y)f=7 z#17M;UpU;jE}w>@U9rQec{hkB{$jUQs?R2`%ZAhT zOF8N-ca{Qj%L|(0Y6JD=WEm%zYl*7#`l+-w`CIZN)|d_PJef2))cJa?S1io+M$g%; zxvaFB*{IF!rf|~A_*Zu)1t12*I~IenJgs(Jpf30oSvqX)#h zBjj=!kRX5K$sJqm-;*QHZpjW1kVZDD8d_N?1RRxWA=De+Ds7AB%PsKVh+N4 z9$@D3f1g@ec|`41S7+ZAaRz$$XrfjIachExBGz^9jCBaIjOtO41MtYN@bvLf*w!-j zI9Htzgf7K1U2S95Bzk#y$quawOqc=FIco59otNpuJUa-WyeF}+a%w((k5fox)`geoz;^XPP<-oNVV%^e7sgdlFGl3Iq=UPq zAcK4C{X^-tfP?U*AJf^z*_uKm_VOflza6<^ zYwo(rpV8;c&Fe4tSDZ}kzuMDFRny31DBexpq zfLvbZ0m@FNrsLf~vc4`-to9<|tyG`VovKNng4&6q#y@l7|Jp3j{QM!l$?E+c2!{7Mbcq-lRU@4&BKOJk0HKF>9Iv%;W*b+;sBT;l&G@e>Zef zfIsc8$3IHcax(*Jdli;1gQgnf)hq!UovVu)@q&j0DwQnY7S&*CY}`K`##a<6-iR_+ z1*HKa$oM`4#ciHTRl&JvlsY+0*#qo!<#(kMW?)heyUBl1k0}``6fF!pMx-j=MT#Mb z5U9mKC3*U30b#6uI^NdaaLkJcq7h_?nzxKs|9GC;f}Cz!r}# z2V@=qY!y)q-9B|{5q{Cm#ROhydJCA7Z*6UnXRX>BKi2kS00d#J4Zc3e-I3W|=O=e0 z_!>}*=Nmrl=IQ^O&9)3d!`HI{k`>=W@-t);O7V?nS2vGpr9^e&6SvyZrFgA#UxPj- z8HfQ|-T?d_iejLrC!d|}az$jhZzz{hlsHKy!|Kv2*ysC<-x#p7&}%%;A@aCqICX4@ z{Esa|EQDd~yeQ0Z_amGROKaE6YCA)^IDG3TYd~#J}A37ZH7bdD}3+1VTa!rC#Z`sKD{!^7lHLg={-5F-GTRr+cNa zMQ#C@_ENqYD&N75S5xd2Y6jY?rk7r+H$lfHu~s)K+L|~B#^v@6F(-au*h1e79pCYT z_P)`h+H+Euob*O|uNQNKlz|O<6yc?nhbt(Y3Y5tBLWad|`z8t?e^!#Wun!16E(S7T zy;Rx90|31;m|AH9=3%^BW8hLIckv3#h2<5V%fn1c+fRr$ejjt38kiQuKb&}kKvw%-ux=)wcWDelAl$MtE$7E;oKOV2X zUF`F{fLyJDP6*InoMuZqcnkKL{vMNIDrpod@7uR;tA{1xr}otp(6I6odcWYT>bumW zI$zjgFiSYZGvDyKyaYI5po5{k#$WVyl2Og#x3)K7X!)f#WGwyW(0ⅆ$FjZ){(eN z{m@g*_hGY$S0J3=!>2RreS>@8I?-=>$?6Fl%E8+iC8PGYP$Rt73Kc6D8aVhG91q|< z0XC_@W?b26cE001kB8O7ahdQfcxQ((^lkDWIF4sT?mfg{BvWI?6ho>5qedc{`40k}>THwGom4W9QS)|BqUe zr3&>$bL+nc7N4Lig6MIhs@);O@dgZ6ajz8Vp!8@P1GnCuo=`(~2&|os3BgKn8SbEM zk>ol3lwR$Gei8mGzNpWJZuZn4OfG&+1M4UMIgWMy6#Ax>_Q7J2f=;vYTr3^+eDBA? zJHvx_7#J9yzwxhNVQ1Of*;#Z>m5S|?G6IcNJgb3At#6;jqe-#Dt}!nv-mT^n%)+}7 zq(&iM`?H-TNbeoaT6nZ1RigqEVsS>m?xibZ#FzK*5%kDcuh0t5ROU4Q@b!^$j* zslR040D8xOBI1PnLD825>dzf~k@BxtjZePxBOF{D9Qu`}Aa2RO+ZQkdfw?u$r;Spl zczSSt!TZ|vXs1!g$%IR0WlR)AUhEQVtJ;Hmoryya5Z=y{At7#QE_$8o{>zz! z>bk))238zx^TPeoY762|5M7~FlBzP33}e#1F0X)DWI_t9(^vCrPc83|u_=+;!;Nv{E?iy(n!S95|eY?@lGYypqbw7^rR zPC>nt{NAdh=CXDVQ*iO{(9hCBwBrT4tMEi07^$RP5R{p@ z12;}<1MW89iwIMHF*ZneiB=Jl)`NDALBa>FaeG2IRTzKmctLIfkwLuRx1k}!yjIE* zYf(BtUAt)>+j(KVC6>KC zakurlmOi%=9TKs>ScC|d2gc!-pDw6 zIi9ry_b_Q-;l@w&gaN4{@3C8W?8nuOLRWJ3#0bHLXlLsPLv43VjDp9;|NMO`~jGX z3Jb-Jn9lA51qH><_uYBts)yYJea}0ma(N<5MVnU5t~j3pBLeCzU8aleGS~hpucp>H zKs->H5c+BbAo$8#X!GYZ8a|^R;R&o}B>IK0uXSj*I>%>F_r-90N_BvE(e+xC-}53M z_xO{#q4A~mHA2oqHnhlB%B^o)q`8`>)tdnFz0bWSmwM~*Xqje=(xx_U5VZ6RXlO2T z-$F(_?9Z=&YSy5q8Sfdh=A8$fb>*dJ{f8mTy?0C%x@S&S(sgqa+_q}!5;i=w_-wn) zr`6q(%-IHNTI1ZI5+S~E8~1s>QL@_xzfJHcT;Xr;nU-IO&gJlU+H;W1<35Z5(pA8R zadhBOsreb{PwLf~7d7kac77_ay{WuBdv(fDeBrVK1lP;sQXM+V$FOdq5g;pNxk6(l zB1Y;k>Dk|s?-dHzm34hxn>rN4zHDUhd&Q3T&-lxTv4kCC+~xnuv0cBKf=61FUw6Hz z$fF&@A<{eJut$4_WXv1byjiXOzOceZ?kTGZQcKJtxug)?Vb7n#o+0&DN!&=N+QY`x zn1YBtpIR9RThP<2SAhk567$j0!App6;64q+IyegOE)2*%C5oNbX`Tp@`V8-ch%p}e z)M}uSCC?jKR`zO@f%obVx)lmT&dOlTnNUfr=0>;+||T7`^*U9u1POL`Bjy-w>3MYinAfuj68 zfU?Q&HG~zY>M$};1kjiRPmX(q#>|KG#x}~J^h&JzYLU?`MSNE4#;{@RY_i9{oa(%k zlxy+8(m$r;1XsTzNq}e01(2Aw3~>xMjTabZ@S4`w6rZwTk^*L;ZEsc2_WfL0I?&c! z+G;+usrR>%HwV9=@Y7ir?J*s`WGa=q`)v`ilY@gQZe9a&$d7C6di)@oz2(i$P@JC) zuHozCoQz)37xU?|?c=WwxE~cM?yYOhoU_O%3GzYO{M$%dnBlocT zrvsB#)FyB7?Z7K$eBz+G8H$FCx=kmu^3eRNXM%$ZF2A?-Q}@XsNWj|v&3lIp{xUK{ zM@etfVP631S|a7ba;8$t8Qe~Qe@A96=1);KD*l2XnD;$}sPc(`@{$*GUKlMM9FI7F zN(MYZ#YfwGE4m8IUxfvwpD zVdz>-bP*4pAryi&HV~WnfYdy1yD0o!TT{n6E%EtyBtbQQ=OIh8t)rt5EhcvRCGI+r zRu@T}B@baQTVh`j$+#?lQUE)Uyp9s{fFX<6ny@eifGQZ#xxXl9LbjN?5ocVa+vz)) z)B>cHl(+}_ri*4g*NW?YYX^4lLEy6#`tYw1Bu`81l{lmy@EQc?5+J%qxxiGEH5Cqr zXSa`cc537N0jU|92Q_*3*qWLE$}Wxp{<6Nss*!cLK#9Y?{4&D>KTK5|FUw+cKwEx0 zSEoANt{jHh`dM9=r|zNhFhwA+fLefPk)j^x!5%(M-z~91Ipf?2=d(nz`ufCoV{#YZ zEBfWkoh!>hnL#ho7}4@YR>sEE&Pf5Y()gxAY~a-31)nkXsk484^TmabS!TOwGs@TCjFT3nd7YJ`Y^{a%1Zh!gNkv3>FoKeRC5bDLuz-Za(gm2E72L~-{6unGVHwv@! z@|17gfR@b>B!&NXNf?U03YN@RP}KVNk{vt^J3mYZzHmcFUEbx=ebH4t_DBynTvB{1 z3aa4>aQ=ih1VasjEHx-gW|!8q%_#iVO;L#GgS1?X2U<`VAx>kuC69gM0fsYxvcs<} zvq)kM{(!Izazbd(l+6r(RbU!do|B2DrkzF3Oqpo6``6Di7so_JJsWZ*jt%{n&-Y(o}|^SaAHTM-`I+7VPzi+yU)yaa}21qKg{ow6gPn^V+z1e*B(5@ToF>b z-LUM4KE|F}K8@`3U!+>d%&h_BzdIG@(4V+b7c>{t$WK9rm|pV_9?-o4v4PPhOi9eu)qn|9-j|0$O!m$r)WdIJ;>T4UQpQj znbdQFSS*yNRg&z$g533SgzynKmkux^)3CS7-REK%E?y;M?0%ac9UYYj#8(#raoIYC z50|Zo!aRbGVCI=Qs3IT=I-(=XJFql>c2BEpXM^E%Y2PFkv>MgiJiMhDfL;cF1f&AM z3?5np@`WLe$~+f?d~-GEZhxjkDe z=nIp&?bKyROZ^&CuSL2FJL$5mE+=;CY~kHr(3PdRJ-Md2s`C|AmTXEMcsorEO_DA} z_7;&ZeT!nAcSec4s=k^-QlOV0v-&YPu};jLL1#Y?Qk_PhZ{t-92yPw7sUzI6oxUQl z!wEIOg(!+>-)?W9_A|Kid>5LaB$GCRI;X8`%|*C|P9+NWy+0nfpEbtgR$Whh8cuQW zb5Qw;7|_Ao2KFw1FXUN2&N)lEl!b`B5&s@M(~k4wuV9Z-Qd7y4&vzp5uhp}yHm68@ zS@cZzmxn*{chX}3+>5@Lb#4##bbaOE;6VT9<;=cZBE4E*d(sI+EJzt}(JB&Hqe#(E z${ADJ44wQ1;R)P3Tr%K>BPE*mfs7yvm)nMC#4*fwK!s+*QW+)CPRgH+S+azPG0xpV z49g`zf#T|Raloaj)$i$70|TxBtu#|hIl8AI+>iyg8p!@bKHD!S2`>{I9OsesIj#H? zr{1o3Nk>pz?l!z1%AR6Iq*UE{GBpy#iJY*|XbkjL*>m6nF^K(?zjx&e0pWq#bLNK- z3Fqm+XFEq2=sSg7KB(Ou!KHzx{IhDG=^pDV(zxiW>i|v%l>t=U=hEHczH4=;pD3!O z7`XEA`Di&y+nWHc;3#!@cy7UDxM4BcKqZrhh18+UqwmfO47d}!M8P}Hg1a2J^Ne-c zn0%HKKVe_#Y>Wq9i9m{xM;9L#d4F!P@|zeA=?+Ak5owV-q{%pq^B6hZY+tN67fsJN z>~N>P=50&UYUV9I?e+0&PUs_@Y*B=B5GTS&xhHF+7s^r76|!5S_^eO-4B`T0E&ogX z>y%c0EQ=kF1R{~s>TgP|DerpjD!Mx;=hM(?FmMRU*$&T_)gI5V?YxCBguF` zpvF-$%s@OqZc$&zFCYv6jb?V=kfLpr(sw*uS}&m^%}XKO@V9gZ;5k-;XC3pz$xCt% zopi6@Rj`ufjTf$2>4n0C-v&ENO8)1pgG*hh*h>cPc*bw`jpT&rWWlyN`H<(2LcDIn z`|muv0?5~R(!#8|({(D%dMbT_|7ZW2_643FU)+y589vku&oR*;sn^{)d$|Zp?fx9t z;n+-Q<9iNUY@1{>!*$@eiV63w)uI~8FnA>e*QYd|@fm9iu(pJljC#BVVD#Mes}d z&iq?MkT*-uM8^);lks?_b#TS;6KIwA!-a*bJu#^|w9US-Z=~)`>BopAn)VyCK}Hbz z<`c4}T2cc&&i_0_F}TR`+)Y!uSf8)rDznjy#d`C)mz$pBq*kenp$T~onnP!uWAFu6Ha%UW6%y8nF-#xCrKC#*n&>|y; zs{Ux7KJv?UlAE`TGFh?6j((FfD>(+*-|g(~Em~R_^0f&`B))7c6VHFypwF4mR`u$t>c|SU&iph1CoreW7S^hg4Bu1CzSHB$*8!H#Pf{FxZT0$h2=?8Qh41R z1?RMciWgpB7Lb9K9s|gZ;wjVx$2x@vCYmVnD7*5>DI=4nzeL`@iu?+7WZH(;OR&D~ z|E+JlhB%cmVkqAsB=rltv-%>48H5<&gA*z&(44v9x!2+24?;S~bXig62R#d0*W<6g zGjLR-3d;Su1t}hx7r@-i;?NJhp*!Y!Nsh7Q3MB)+T72pJ!RUm3MN%n*>zf#XL8cV5 zz^s4aWj0lX@^Ly|LTo(7wVguydO%jAuj^GV;e?h2b0%4j z?T+CB#=iCQ`6$Oa4bEchT(2;nUdF5~MIyqqG$ZJ8=bdEOdDkGQy*ESO{bLDP%hayr zWmn$PPf$^%Naqyy-Gq_YR*LpfwWfyXdu-$Vvb{7^w;FSgFT3yYI}eToRlSnpfGUp0 zkYMxmUmN?lc34vy*&mkIIUZQ3)s?Mx|D;s1d%Uhlk*rf^+=rs&xp1_9MH~z^>bRqo zGeoTQ7@uAHH@Z`jznJiv!Rz1OXxg1wj#)j3h>Hdaii@x)pg=&}op=nmM;gZ>*mqCg zXbiMXiy^6(abKNk*`zdfVYn{{a}Xj}l69@6DcM z*mtMX#={I@(#+D>AJfsNVN>|%)}_R*IrZ8qke&U3^B0B!HK%3=J7#EBx~O}6nJN;I z8Wb{ViG|%RC;}?Vk+aLsjsRy0bj369am6KLQNGCJ;GkMvd^oUNxhJnU)n2kxss(0`0CEV%DgzP<#3H-SWr{;-g1ELHNS#G8?@AHEVCmO3jy=>E&+=l$|~0K>=xe-MKMm z(UT)@`^xL2l-mTHdnSCMKnuUan$=xi*N5WcvDVUD)%_YQ*;ra*h)ekU;*|h*BpHHD zt&rk2%+^g|HMiTqYW^#cqgf|xeZvF+#4;fcu*(OXa6?F`f>mGf$@;gUj6U3j~~f^QjGaYo-kTBRD4w75D1<8^9KlO-vd+w09}}iY_y^M?PL|xiweG6 zCN!Zrysns<#FE(I|Eq`>YYm0cOm6weKIU7Fm6fR zlu@qj`|`xt=KcGC)f?bohHx}dOvlHv?7 z|63b1m;3EkFhAv`-?DKLBV{arN@V}a{~_uvprX$H|KXu~KtUL#6#)_HZUjL(6_hS1 z$)P(0q`O-|M7pHAkxuCtx*O^Lo&Elv^LX~?uAGIL&)oaYSFqG{@$FDd3jTH2cy|58 zH9a$v5Hf#Jb`fBD^rSSx&R_t{X_25nVG+^AhJ|mLjb1-Wn=4F1{RavyiCp?G2V5J+ zQyhFY^>CNYKowk++mv1VOpH|LKPH6AAC;eKpSH*l2N9<4m3}m7Ba<*^5$KAjgiYQ$ z-JVT}ZdsN9R|6zUO{oeDRO$oXk^^lERmb3e=XU^A_O@CYlAiVK#RI$VL|^It1;6ym z@~ZkcKlozAqDs~JfipW1(SQK7CMeGjt>=(4zdGj)Y%PDocH(WQHO6SKt8f+oRf3m4 z%tN^O@H2f?TD>t{?%dlN=YNk|Q0Sid9GtnrOwGxAI)v8`4FUTKq+E|K%2)fJ?GkB> z_&GQpLV~dd^Ci|1n{e^lR}h#!4&&-s(v4{`t!6l)PwjM>rz4n$mzOLVG?i3ehpvnh@d@WCH^;9ZqSkxT{*db~Sru)=j*extS zIpy9Td~rS)F}f!cI>?~^pje^!dwR`tU)DPeh;t)~l`DOw!90jgfZ{^3WB@I99J@(d zUC=&YVH}(Vss*F!S06qC)-+qfd9+j|lE}ASwQPn4@A5iS4{liBNEgK-OV3o(B_tZ5 z-bd&q=`T<)#U@NFXGy$WkF~R7sHk6oVU51LsvD}?{41LABXMXX0<=9&xlVCSbO7;V z`5(e(yVt_z*Z(2S;EzzI7jn~A=mc+1$1=x}itL?(E*|RR*4e;*OSWtSN{pHZO28UX zY|Xj~KmGE0-nRi*Su~|M4zxsaM6)|rH78OZ9ZDc14H*y3Pv;CIm!?sO2ATD>0n%S* z!!Z#%;kv@^PxSV1`e(4S%~yB+;Eajl)FKI@YgU{86qWo1O#@cICGX%=N@e=#vtK&NQ?_2tke!dI$t}ZeX3LEuHD6{(XTJmVtRt-miXLJeWSS zXF9u0|H<&MGUPEtb*9^G?Xr-PLgh5HY|lY}R+#p}G#xEdDBcv1N%(s-y?0+Im4T^= z|JcC1PRj;ZH_AG1Y@vFlqg{DK*6v_$5WwZ{KP>KYJCoXbB4OurscmDkt#yb+h|whR z)Z5T}B6BV9_qT9o7!W*j$yR>bdQ~_Z>nX~|mn6&Gvw%_l$r6k!_LXy~3t6vr6-D+( zKo2K66pF8)S*|1xDw@JLIRc~4`kp2j*!P_Dz&LsO8BD46ulZB9)F0>=L0psgLzaHE7=l5^Go7^Uq3pJG^k?rN7ep5 zusyRmCU!U%dkMv*AsBL`@h|Z6DV*}NPb38)nU)9&d!d6Cnw5VsrS=^q%eK?jMg(F0 zcz$5XoCb%@J!(p=bp)z(v~JXOCiZ&U45bx3Q{>EBmVcCR^piFx)mN!g8P&f0F1Ya5 zeM^WLN*Yj4$}ZVYK%r4R=xc?ETepPzb1D%4JS`FGRn3Patx-9*ZQitx&`Ov_8hroG zC>)~MFweJ4A-^(ta_O8HUXA7a$mmbSUxu20KCZhss%UOH0!q)Nbp*DH_|Y9To}8e& zya2ns@eybJq#?qcwlO0CA_Hd7w`eFucVA%`)>L%QreFv*?Nj=Z;bMRpUa1B|b62U@ zyy~Mt1WYc2_0^;+!e)?kJ?soM3FRN((#P#ZAId?#M8O%eXT>V(L3JTMYR)knfzu~_ ztyS$JHWI(BQ|e7GlbtH4C=H$J=hZ2BW_oVm#kM?O|u3Ld5$(qAGT$;UtqHRM^|&oFibBu)qU^~ ziJyv?i7wznEf>~%5Ci^;?m=k>0Vdbc)jM=y8F+%iyESNtZb_nSx3t)p+V2O92_&l6 zb)2{wJgl9#G4vZTIu35X1#AA_)Zs3!>1vt6^C8Is zGUKmlsIh5e0O}LPseEv5UP=o_c1IxAJ^>^o(Bi(86uQp@)khy;tfLSm`-9YeE(uUD zxvC=ood;6BkIs#O6`BJ;xAt*&!eRnB@c1uJ>eamt8UL{#by5aq6v{Dl ztq-~=*b)lf7vWmsZanpDo5xOafb{TzUObA0IFAYON5FpLg;C!OChCZkvwGRNuOT1X zhs0g-L5Q>C2-!LI9@?FYfbt~F^VutUQ{Lz!)YuvQJ3rh1 z<_(P5#*o+^f2e?2?}cD`1n?T5Huv(reWp*AUI+15*j$ z04Tv$0ctQYu-*J#j-rK{2o<;WS+b^aVSXhbh@Dht8MO2&bJ^7S7@|AJEgPHr1Imq^)13&#^fG##QuL!k$ zo}2atdStt(G8XEEc2^FE7=NP#1sD2_R#5^S2IK?Sfq-F(wbz8%Cw}&DVOqGQu6uZk!^F2>Zb%()8>Byhn##&7N*<5ZDn9ma^x+K z36XR7!H;5)`RFf6i;LH?Ay{ctT^4E8gmPr_>0c;~vV_<)F1i zG9Hk$u+u)kig;|jjMz!gvK|2%DW{j2`=6HyBF)T!oSYJaiuA=d^<(0Tz7M8Dhn&=0H zN4^?LJAgRPddyS5LYyMRvu`1Ex6rwelsC{RNf1ki(+c;Hm0{`l`3Geq(0B8+@p=aUG zBiMtiPuq0@@1CP5U2hMMjgcN>{oStWxY2E4qe(s>8)QB&_D1n>0?SuO45f=ei>Zf4 z10)F8U}z8VCpm_=Dez!jLbWc-{Yu<}{@h&$bGN0r&q4~o%0f-4i=STRYR~aV>-K*G zvoEi&Iv2fUp55IABl|hQM`JJd1!p#BrtQ@WCL9L&H#XDYgVPfV!887nM6>gJ&N&Ojz-=CA_II8wzVE?wmp*hEacP4vG4+D5a>s>4y6^ zC>FNV2i5K00CZ}J;^OehC+(rX!_FBy`lS;V=3xBo2BKS){hBPmjU#n$Xhc!q&i5!E zw$JK*O>8?sd}@seAXIb#RVZeL_~r~#OF6W#A&O zf47+rRN0DO?#rZzclD?1SEg=oIA@fP(56X{pF{WT^wa2MAWZuZ$FCjmO$k!nI=B^> z0s>4MDB%iuv))zDD)2)+GufRX@16HYcm^rg@%cJ49C{F98I|Rg4{ElRhtuIf-|(jen6pQXuvdW)&+T@K$~Uf=45CJXt`L|EMw|8PP{`tdJsG-?GRFp0F?^#-Ny)c=du9e z5}@5ut?Oh6MQ=(K1-9rK0k>|l6^oi##%(Nh0k{z4gSd^fvJpT6r|&K|EN`#QvI&rQ zKgU_C>a7l9rSa#9+A$W3fK01G>AqW5hlmh71-MpeKtU<-IxBG8uicQ10luU|n?7jJ zVL4#26ZPZh|7ZdL0L~~=ce$Q=rgVR*bOro%keI-VArURpbjO5qz`rsHADJxDItyU+ z5cj^F@-6~lj#!aT+{UGy+>dj=pL1v&Y|H`S0C=7V08bJfm*oHf(A_+j$-ElRbLe;= zy@~X{25H+MH(dx>?oj$)_N2RwyTZwK7LbW ztyOEq5Y#C#TxYGC?|w_1nbD+{OAZ1^5>P2Aw%-^lY7Lc~C!pccKx8Dv)zO1+xZIbL zcR(o&QXA1=W;h(mK*pVlR5SYy;Xtj~KQ|OASL8(<&v+jN5o~qxp)2)wBL1@PAkZqa z&OM&f*}~=P;@n+h8Khqw7Z|W#{zt&Pytn~SslcHJ7AcEf*Wk%~aWEB=m{}J0%+ktL zogREF6-D6;6?eqS3`@=H{yu4PnT?7R&r5A+$_kE3g3vW?E{i4yqq%{Uo_5F$GGM?Tr zS<@j#k#6Hhq#Q&QxEATarz|E1d0_u@ng*z8O=(KUI3AmYLL{0xB{Oqs+BCB$KmUd2 zf&1bZJo8#x$K$9Itc9<7q(#0VY20GvNPFHX=jLl2O4rqBq>EXK{cTqBWoq*XK(~78 zc%DtnRvq14A54LtmOrK>ssn1h^!EYl)taEet*&b z`=6C+ah_H2zna9G;*Yo!FizcrF7TVu*)MV%- z2$mMBb`RG9GNtq&33DLjwnnx5*ngkB|8E_)`2xwHzK#pbt6g|SiMaYs3u;A3x)bialGZJ3SD#^5}R9MdoAn7Kp!U#o7 z!1%f90#7agw&N34-@{!YeHR z4gmsVdY%k`69F(SP{u;RqR0XdtlN!6w4zTXkNE^?mF!vKg2cH00L;m?V+fqC)$c0Z(7KphECwFK`AY)0Ice6iZN z3tK^eMV@a%xKd`E-wi2(`$(l9fBAeGnB(9p2nO{Mu? zC+lk~4(<2*Jb>*50JiyYZvA-ftrv|`L&ui}1f{%4LI#-K{YS{Q0>1-#j3vmis&${@ z7st{iylhG|kO|eG9rHh}1u#C%ManyFzi!UUo1Go`c($W0==MsGM=m@*Qe!+LTQiY) zJJ^DMu|*q75xTgF1Vo3-P{#Y2B;HBRQ;Y6YA9S$7CI9RBLu{F4X9j4dk&mbyD#&~` z16Z4kGAU_kCh#NAlf5npEr7P zsy7~R1-#1hzDEeif~VemIbh>(e|rJov9G30v7Ed_OUNWYzEujw`iXk=pu;rnEiF*h zm2hMC>HPJspwfP=FN$-UGyDXVqafPU>!MGW`?V#Gfb&i%yYv1x-!=t`Z=(?oSE7fltKHTiq zjA43!t;rOBT4*XPha3(#4uP!A6d!_Az6dW>Nae}bW&uVTo4#07!|Ma7ReBNSLURdbM760@^^9&lUpEj)iUbQG`@Q#3fRg5T z1$?}TEi7vRzk6cO3C)M*u-bf#9*~MKmeiQyoi7egTavM zl+eWzb*5SI7{P-EHE?NbK!gULqHN=qg3V~{Mn*yWOAV3zlZ5Yp{{h4!LF+Nx^}lt% zVKSYJ1IT^>GnQZ$lvus{H#sG^uPRp?p&Z~v)u@a{71MLNENISyq>PP8a$}& zhk^-Y0mex3+MNQdW(s#Dr$f^jFp(7N#sxPp#XWZr%T4LPt{LYH(vX6 zC)}$`L1zb^3BS{?0d(pe9Du~Ozzu!}lq!IT2dFKFl9H20BE4^nKtKXKR8W6l=<~6$ z5pAa&?J|FM2qJeZDHjX5yl8?nP`aJC&WH#K7J!<0YikR_^c;h2hmB>23c-D!R!{dq z?}PJ8)1XZ8>77RUcfY;m%=6EXBDpr(!8z|ezO}Yv|KC|MMd_n6|2Kz)I4DBmtmefY zM7(*GJC7TKr1BsY7Jw^u$Wq~dzLvo8ZwoNko4kMqj-KA_wgxv~`Bqs@{rW#*=GEB_ z(5m`fXj=HOO7_-E52@whu$`Z`o#DPe0_Z}NlrBrYg1L}eJl#W7PhiMB^4K&DY$tx$ zcoo5)YnA=u10ZxFvnJ9HUOjJY1gsO01))rv9p(TWX zlamun*Hcnc$B@$sYz0 zK2RVFt@E5eC$K3PQ)rk(gCTiH9C_iQRji5~S_siSPA5DXw4_+*H>cCPTlIs&g z2jF9M2Tj)wi=G#`+5tj%c?oFQxnNQ7#yqhkKX>jO)Ii542Lu#K@0%lmwKz3YuJrVD zg(A4v?*o%8(mhAE#<pYlzQ|MK&rWzBIT^J+h1GHqL5Acl&RfkK{8WW9`3^T1=N5sNtm zar* z|J+`Y5)L3?AhoBE-^z6wvh#&laTsvpt&lei>!?k7=ZXs z0LQDjWbrb6aYSqJYSJVUAP>i_9l=qatk;dmHvPV$G|T8m-dUQI z#I2#7U|ys@!PQxwnwo%zwIc6(rfncWad}!9v3YiyK2gBU#+D@t3LH65`7JKmh~7Ha z7A~fyjjL$=-Xv~55&Wgamf=)787XqLxi=#UV#@V?y%Ip*fyxq4zd#gx;Zyp|HX3wk z6{er!z#mI}@gJjp`*X##xy1U}g6;mxYtLJ~i@9fO_I0(I<1AYk zIZ5bLf4-90HU#M{N{UzvOi0j5(P*OSqnuFPDWU)>03fBUHX!I>he10&Dq$!rZHLtOv9Tdt0eFC@_rC$r52Tx6#Fn6Y zm7?MGYEFi_^2ha_m4mkte3r5YFDW=s$^JBuUnfat~ z0eE+^gq#;<#wYPI!N28>haPE2aR;D->-5Q@v%AjAhLGcbz#Sbo0Waq_*i{!V2kq3y z)zrQisr(rMjTur$EYbTi@d_As!-WB5{$rz?v@C|&M*G11xdzHNGgRJ_S095@H^vA3>+RUV9*@T{N zk(jyX!leRSTsakk0&++XZ)AoA9Sk^)SN*C(Kr+Ft6;C${DMEGphn28(49uVapYrp? zt2-dB>bZnQJzT$V#sY$?xq|~&!^JY8w@dxC9?(Y<+=Y)HbAj&+j+e2%*!{t96ch+9 zYK(fnXJWb`jgi59LDbj;488I4iDjgxfFj72gJ0-Z{mQ9>r=8D^uS_)B)1Is4O*5zPRSa^=@cXQ!w7Q^h(e z_uFRzO!2sweh?t^&E4JlLm~Cs<=QbQ)=5^P(|sx2ROoD_v*dx@DSFwj2__(vi$1sJ zhQs>OlbGoF#w9F>aMd-|l`N^#fbjB3peMc@%>L-_*5Ma>?KFGT`BkBfxmXc9Etn>| z_82WuI~(A@wn#xnZUCE{k*lQ8ad5BOTD13sVTk!6kv2L|;im7T-B!CV3V~YI!Omob zN+hoC8=;*T7P`8IaAet0=|X^tGSt4}sHRLyUP9Hky1_|uMxkqOI^BK3m_tD+d_wp) zZ|axzr<}?1^keFA@Qt!V)`d^ra|RsA@-}5Lck>3e{c$;VzQ!^%7J6~AxwgaNSlmLH zih1m&gK3_>o~0{(&&@T-?1L$+Fj>$|Ig-~clCo&?tpFLg(5flN`T5_Ab`)IP+~L_( zKaQdfu7SeCzhwKkF9u(;bh}Fek2~h)rh;-On5Y;@4&8V{;n!ETH3taZ0MxsSu*YVU zuoidc-Iinf$M7~HFWAb0!;|~y0Ye1QKmG>Y?#x74z6w=wf)>0ju1OcFj9%kIwp!oO zEw1CLCwFxCcHn;ynCc8&)@SUHL(!%RG($U-f~_3vI2Ka*QD1scnOe_>I5(d@oRNLL z+heTkpi^jW9np#!XtH~Z(@q3@;9Tq&JE$P1SSU;eUuA2<)+3IIVL@~e#og^T*HoVD3e{HcS0BIV4Q5dONq1_sEXihw zZ?oH(Tpre`Kl~(zx35(S8FF-b8r!?{l2FL!)1ox?Qd&6qNaDcChBRdW11U4i<1XZl z$L8fmSz$eSHX>`i&c(VFbq?OozDfNns9Q132=YzaDMn5~j37voq=jxtQY?XDthQ-2 z5{f>KiyaNNFSDHyd2~yyw2!7=J$J-$vC|;~J4Mtc1K79P+Q)15;2&3XkC6z;^x2Rh zUQ~Ace4!!o<;l2fxP+xr*B9TIn@fR#<6T!~SO`0QJpWt!=G(iAW@&G4 z(T`eMDvTsgHx|Lv#c*w_{BcydL^w(sf)Ch5wZF(q^Gnoqdtsl0`ql8fR8tPI{F&ewOImVWB(<`u#hgEm z0T~+=XqLbteAE_U#jG)H&~-nkV1`7|QJ<})O8g0EckP0E^-hKfa%XK!qaYv0_$Z>O#&SCy~k zeLM9#rp2)KhuVGY+l{l@OLrVy7kbIv-c61FYGJCGzP}JK!yMy0( z2#w8!C8*-u4<)?9E_f$YqmOcR;wr@JEux#siAC+T_NZSrcX(leDu4q>xVpHPeFfLE zS@=|WZebx}OwXObwE2==*UBa+Rd(5OBhBBr@rr4?IMkg`l){z*-Qeps5z$qLjd!TR zrO@4FVTCeE)VXKFPB`!3)npMP?Y;n>9}THUNmUhh0>j9~ZIYm@Pf|@Nx~we~6AD}L z&QrnFP2!$f_=e)YCc-I4z~uh&;|INQ#dMOIj1NOQPcj@+5%u3{T8rwIUcUNk;P=j- z=wqPS9rb30`JiI@^J<3C6lu_TtOh2#HWZEHaUSwAS66>mXL>VSTv9^l>FKEgWy7>R zmbZhw&X-2Zp<_ty50Co;W&U6Tx`b9B@JNAY#aPS&&CBF44Of2Ks}y;)59JSr_&X@N#Vsu@Nmzz1JWokN|9)Wp2I9m0?D&^N3vP7}YH@+^ zL2YP!E&Qmyn8hLS591eFkM34PgulNT=K_Jm+y}<2Ax9Ot+{1#;r0=@LG5qt&$4?LTw102U{3tdjM?@~2N5TkcqUn2bPtt};{?S?txjQ(7B8e?MG zb`+EtiffP+XYvyZP8D}%2T|d6+u5!sn|{m7!vaxc!s3xuwRI=ZCo+MwNK?C_vsP6Z zoJD$v;bQXcr;;+a)a$wv+>g(MsDVE(`cncD1q4-kHdOl84r3#r+LhLnx{eeLF++rb z#;2ZNNa`Ydm6b~ngvt0`vAvMarx}hq4lY#dpQrsy<({9$|M}ZwN%jje*>wJqWLwck zqpX>FO%+F&weia<2_Lu>>|2u^VoB&BdH!ea8tlE>}7__O0bzHPRE~56=lOg zPjSK-OioObU)p88(y8P6mFF_dr-udfvkQLDQGgguv6aRQS71>(D3izn z0TsIs0?bCW+FdOz5U2gQ$9QVLmZQSR>lY;{q?EIwRySkPK7q$EKR>^@w--LAuKivl zGg4fBZ(P;_uf8EB&2CqKIID+7CdhQvXpWUdtz&N)aV$*dIikq(LL)03VuN$m<9Y_T zi~UtUeZN6lfmi5{%yaYz6!%Pb`E3re;gH@<*Kqt)nGY3D&c zV@sS~Tzs!+rXD&!%Vy1#9#j6>`I!fgHC>7}{xwS?c{HocRZ9w4U`=HSA%Ayk^I(#% z)ig6lJnnC+*}&prmdeQ;zS??n>4TYo18O^Tx75_-T-Cp&2526O-AEx6>~`-n;d;m9gV5KY_x~tBfN!_|9!?l4`YKcNUL8Y`1~pXTf`-)!`JUXJ>EVtov!+{JU%( zZV0KH%?XWYT#1IsQ9tSR!Or!|u|^tSFCB#u zh+#$VL+y|3tVL?y4|0}9Yd|l1p^W_WrQNwli@&YNudc2Phm|1FtJR?3W;ab(O&h9cOZv3^-AJcwB63 zK6?`6SHi-=BkN^iT#!wSr6~*S2hQOQHn(mLL9`+%e++~%dDBEm1Np+Xe+AMCv=hw+ ziJSyBfSix1>_p*F(Mah%IUB0cMkGpwdj>j5Xp1QYRx?$d9)-=x#*nmow$H-e?1)Oy zH)=7U?Ts$wf%@zz^qzj70+K`w4ox%lC0oY;CFR>%mcgyP&dJv(skj(i?+RR;op~2( zJq4|`E3sz_-Zgl(WA2`M-W1pJW4h4oW>h{BBk@zD&;v{=xCixoK1m(ZBO2@|ro`n$ z*`I_1c)zVXBP<@xUR@3A6l8TQ7xy075$Z|!#6 zc2oF+39h)9K3~qaaRws+_w&#FY5bgiv1yjF`q4F+kSt|J$&+UgN&EIK1pZs&!s#-4 z%es$6QbbDI(H`cIsG*JT{43@Bi;t>x)?-=|`wJ>1uDT3vSL2tz@ujSOB*=LT!_ibE z6gTxXjX|g!H*IluTWUd~D>)S)T0y$<_L}9_vacV~*W$)%fAomx4xIA;da{EerldsZ zwELI6Ej)qbhw3C+30`ebYucU2l1Sgb6!{-p*}?%vElsuEHM;O|8(7~fe;0vePhE{$s;&aXM(;MasB_W02sX3!|}2P zi3o_n*W9WngLo3^W(aNvf2iZ83KJ5N;<_-Wb`H8x zdY2gi3a}S$3zlsvV(G--YgL3l3q&EGMC71ObHi0LaR`yPx94)dKH#$X4>4ljLu)%( z(jD#T>B62a#aC&t&~y7Vbv^TME%AWC*Hi()vKO(f%kjAD|3t3F%)wP(o}(1B?Hf%0 zw^0i(BW;og<}A%6a#{~|2>w-#=?x*JnQ%$En31(R0?2M3zOKX0<{eZ)6EvLpgG z#iy_xKIr;TCUpQ0z8?)LvdZt{rC*ZWs4!%R591AjkyJl{#QiZL34K#j910Xe`3v|W z<6HP&==p?H5{ls)2ahSV5xy^YmosMmuPG9Mn9^hKI7x_2Kk}r8&tyq(P3}1UYofON z&i5#HF=K-k8x=VFB*}$jt7R*HT~m)0>4P&*$+&W`JfV{ny?ney(vQCb0541 z@n?u36S1M`Q~h-jetnuUvS)Zf;mrfeeKlf??wG!eLGln}WJ_kOMn zj<=sU!ehaTwK5t=!%>o-Fk8Yb9yP;t<`zf&*zk`KmnTQ9syK;Y z!2dm^H_J*NA}B<7mXH8jCE_Ivs)|*(sJOZw0R{Z{ofkw5v!zZO>di<(gpM+Ju;0}h zkK1%~1zbmVj)ZP(2h&=2f?lJ@vQ(?)bD_>qP@vare{*3FlwI*1twNZvyYUEfq28JjI^RS&@k*<-P`j%+ z-OCOAYxy)Y5Pke6B767i?#>IG|5iH+q4~+c&Sd<%_209@slEDeEpltnt~gjt``PFE z6;OM@fQIk*m%((wk% zQ(V#ZiZCxx-F-$h6aN`%BTJ5CD8<%+5_%CY9qwRiCUI3=9Lj);QE7NcyRcUG)|E=T z+gGgw@rTnCx?YT`3_e;7rT}Wyg`cX85ta}Sc6|0JyV7Tg?J*d5!`pSXC~+Rtyn`9x z_dOfz4ESXOcFGUm4lh#A!pQPsASBb0-iv-1heE8|c|Lid4I00`F0=1_h%D>;n`&!a z`4-2EbwKx@_rBnb4~AG=A}A4-qe0v7*AHXUR)++1;}}tdsK$X=9k-mHmJ%cUL16V_ z2@2Wy_OXB#9~FcEAps*ys!U-)QYk`-h(a(vyLY*sU3R6ym5BOPkdGs(Q$qwG>_rc^ zp)HiA8Nq^b&vV*{#MOu)G+HGH(?1Ez0T&Heie+Da8$PHn|DYad@0pA3wtb_*g4C-7 zkq9fHkeqT9n3GBG7lAl(rqGpHVgid<#WbvW24`7PXcH{oky{F@45#!}Wvx#}f7pAA zuN9-Mq$*PXL(*Qpz8$@7i_Pao_ceWp0}FRxD{2h-l7+cTr?up+bQ$KPt(zf#q>9z7Q^i5yV{gvUQkLTe9aoSBEj`%^a9=2Zb&Pzf{!(DH2>_WYaEi}PI>v!wlKJW(#rab^f2S8CDJ3$e zbz=XlfqO4B6ngb1brTh+Im^cB$#sEo4-Gady10*F*;jdbe~YS+rX~>(bd4)M^rvv+ zWo*1L*amY9aKRiF>?lZn+epLVoGAhV!!L(@^(AsugJ>1-_9|$dZsIB}(4a^2xQ|YSr{)9BK1E>S3HdQFWP>H- zy8^{iD&?|bD?dyo&LOVvuv_(8`;hiJ=Y=iXdC zK-uCfc)&Kg@i=hX(!~S)t!c$H?CqGcVzrz%?~$|mvyCUzv5vVV%XXj9dt;7EljVN| zj~V+Lok!{*KQaYV9L9Fa3L@Rp%3JZT$mAfkPQ|&W^uLl-hX2c{``+PFxD5&^D%UAJ zcTfy55pC-1u1BAyf_OVk+B4<_T9&#z(8B`7 z0>M)=0NoO7BbA=%)1D6LwiDG3Yw=f7dV>66~r_>;iuciz~R zc-{<=ivgo@(R-kNZv=0%mAHB}$fpncA|v|OH)qXN7hMaed3r2L^Q6A1)s_M#+z`sh zdTrJc4pz`0iW5m14I)_hJLxF0Pqik4oU(9AmxjMk2&jnVoxbau&t)%q_;0Kw`1z80 zpJLt^HkhAmtIW_Y$q$J1S(yK|aTpNy-v$c7MH zhYV1|F(=VI=+{VN&vE+!;hMl8g#uw3UV;$Wf?s9K$G;rHW5agL^)AQc)?d9|n_iBJ z^ALK$l@mA8qmVGJ0h%&z?#IhX;G8GR8%;R)G4C>=K^DE7K{Csyr9kT!{`AEAzoW16 zL~3imYGLV9($k0}@Kjt+)(tiW)1%R31mC(KL|)9LX{+U{8(wDceWpeesMXLmC@;$Z z-312{H~>n(z1iw+3KP&PQBqQxSzA*rQymEr=BrzLsqek;1Qj4Sy=OZ5T3}|ytey46 z!k8@5X`?iiDYiE&v5hI@nT$_ZSh&x_WGsk^aPf|mZS*V(4QdGL2#9j{Bt3k`ntkq2 z_=l3I??>RR0Po%hLICvm?6_1$4<^~`(xb^K`DmEYM{enHJD=UpGQ5!GAP9S4pa<(> zEV_r|9VdSmn^c6T{m%Dcfn|yA?ktUmnlW{BIds**C|Rd^SM8S_{~nukXNbMZ51qGj zQ$TGOQ=WW;X8mH!4zoSn!lxrEv|Zi)b~g%f?fN+;>)k`26~`7ao`lrMNz!`t>G+;0 zi=JIR#kl6;Xrr*Hqy%WT`61|UL=~L)KCyrSo-qgI*Of(+jfmDo3ttl-6wcUQ2mKdY zizxqvo;^;wda!`KxLSBu@O~LUuV<#{ljLJx?;ghx=q$V?s}5_y_hm1?WEKnN-FVZm z#X=M^Z?aqW01IFpBhn;h?79vx!oX=YYfqU4u%9pI=T7M2M0nAR+0>5i{5jMTg8Yf# zlXCB9q?^L7(U*qW{FAHiobJp%=@=jmG~g-*B4+GlnpGcx&qi(Xh;xMkGTi}p{LUj$0h0u6=8w0}5NZ(YMu*po(YKW!Zly^x;CFTo&!U-W9) z^1XMW-DaO85|o+Q>XzO1ZyIVz?yWRU*|lZPC-_YZCSCGB&{R}lU4nt$^$hJcC+acq zw!`bKRRON#ANAner!anctkX0>dbMVP`U6vXu(bGgZp$b-bTT|QM}dO9 zl}APF6v0;cpqemoAmR}fCyD~FiNn2SSjLWh-PQ~Hs)h;sq5`}MF#B@`nhv`4{l*8D zA5Zr_H=^@2WNXO^+;}}0T%k}*{I91)O)RMr4c3pwFdRvnSs6{~{N#73zjT_WeV8~+ zJ4vA2oE|^Rh5e>DC67vdwu@DdTig(X-m&7%-TC6m7eY$vdR>3rz0J|?X&DA6hdC=6 z2Z6~c%&a=W>C~U)(?3wDBG01~eD+GNrhWvs@mvuNY4iS29 zl*Wc#(_0HUL62RYw@#M*dO%@`j;%mH_V<3<{u}SoZixi4KsJ6ty1@+cD?TWkf0)1Y zH~JBr5TL~cra>~~XQ*8rl;0$Zf{iO`nwzNsheZP9LNL+f_jQrbK_ecd>?Gfam&E|c z87C`&bSa>R0U|c|9b~)O9y(_YP=MIju#Rpypnn5m0&!&hfCySKt!YgUQP~uI(4K;< zH{e~Vml2#vJ1TcUXPG? zfvX=~7K?bu5ko1W8W?6ygbvJDK&E+6GqTL-xft0Je=4VKyMiCb9#xhwoVF`Z;?t@h zKNTSMfPcu~tTL7{bEwX^TBTZ!1U_m@iH#R_-hJd4Bn*4U7Q6{g1u~vD8M6!*I|rBqZXblYuPVY~ zPva#r`lS+_-ww>O3VF?Us-kREymbo7B8F;D5|B$K3x7gqrZk zesRuQ<5I8zQ;^0Wc-;poQiU)7t4J5n6>+n>HeA}1c}GJ#p8|j(5xO}39b2IRFLsd4 zO=^+OvzgNgSNJpK6jw_2N#I_%WRTVNf?Pa2I{Gk`Z18BE zPm${r{t>K$J#0BwLa58#pjwfneOvg}Ym^n!BlQ@yj>(^Fwb@3t) zS+%wNeUS{e8)tnbstIDs`_jNM5LDK!icrg+v_HLu#DcDW?TnP>J&;6S(ND>Ik&Nc$ zWHN`Y$XT=QZn9^0Tc_*!N^}f=%;nVgBY|=ixF}xwZ__gUSKg<3Lxqf&U1E~ySo&L9C`H} z+2f4bDIT9Lh}bsY0?UE2DAV%f0Ws8;uLIV;H23afsWtmqmnwqDO=`)M-M~7TGR3bA zn+AtU@!N@y5Ax(r)UGby&+A6!1iivHXSu+7U?_sB8Qu9&BRefA00>fl8j`=;;u%dSq z>@G@$RKykU$FZySS?-GQdl<^VnD09*<^#B#Qg@_^an$9LD8$O zQB_?_vh|oIw{V!Ob%`}+wTf=+lEL=_;%KK|M^!RI1c~{yzx!DQJ94a!=e959Er!hY z)~;%VsK}|vM5+Z3xj&{OT!)%0o^EqdYR<$Chs2sl3}_o8KT?6HIP?yw>%B2+Jby6Q zHfOS^j0*7qpL)l(kH0b4#<&2Cr7a*{aDOotCt4Z+n_57!3Pl}H^;OrNH=&+BsgUL{Si)wvTjU&cIy5jT@(td^$SL52*yi#7z8i44K zKzJUTYAkJN6tz(={>#w(D_X1fTBC2~Vd?WJ>^URp#1>}E432Z~EIL=9HgI z?yuJ^a2q(9F(k{58}NLKsy4^7&r6LEvA}x5M)89Uhb|cAahzi0469c1FUWC?K3cg% zG}(*RG=E2-^|W?YWSb}Sv{r)0Y;l}Y>=GXRBWLCe&jVQ>lm+xH6kM_I!rMZ^-*^b$ zNAUWYoRiydB-6(-FD98YZGunONJUN#5AbYWYXklp@qC;LkePdbdVanVs(17B(_k9^ z$N>M+bH$gggfxB+1r8EEKLu^BnHYtp2}d&a!dD{<2#8xxtD~UV8+`uRn?9{X!5JH! z6lVV975=4?JWX0!THg;nQJr&ihfWN$#QTVN;{#u<2*o(n7L&)*?iri4cf(Xc2^aoS zFg>R2WqE3l!~#178c{$%99-2JEW}U-R^1-UK?NBPrG2tKJ5|Jf%_c#^!K7~R;^TVS ze4G+h?kdD5nlRT6A21-vWxiv+U5|3Zf9Tq8vat4qKoa(ZJuBAUr3rux?(Lp6RODUcqW1D=d3QeShQW9&fD~&FCAZz2^CGb(0kBXNAC_FLmyaTbD zyF0thf>4_0`7|R5ZVlk*AYf9AnK$!&6xiK>@q(IDF6Q>>MekxT;KoUrBO*y=}63DF~{bP6a9(y4&b zpoDY?B1#BIm&Ag^5-Q!@Al>h^=ls9FcgAtV!BwB2yV1T3ceF#u%@@%Km?!$z9Q3gg8_ zi~;vauhQWrP=-@D?#+_=9V!Bl3Gn*Z2n@>qbhP1&7F^1Mps@mwE5dKz$}f1h)GEp& zMHc85GoU`843&+c`!wF%jz{f5-Dc}Qx(2T?f0fvzw-BJYC4Sk6bfwAAg2)VBJf9H> zVhENS7vX+2kSDb&we@eTpsbDZd`4wVLq{%omlL3d~i09&xORQu6YSQBUpV7XZ+&K3+ zg9hKsii_`=<+ZeVZdK21y`|ZAJfkDgiHiAEpvd(%rGt+DIjwKcOh#-|@uOHNq@s{d z+PJ6mOX=^@%F?_@XB4X3Hk{rOStv%F<<4*@c_wY$o~uw0Z2p&L^970ExH7MmU{GGp zHr~EpGW$+q;=Z959OH0W3p3EH$HbI@hkbfYR3TKfVY{0au{B+ck{e?Jdf%Hc=nZl~ zamx>HKRk?H16D7&UDf=JF{jSki7?+a^q9YnIkc2U-U5gzAn2liW9W~Ooe+oD+V}hS zYmB3kGPn%kQR@5COSw(yHXL6Ei2_yl79)9>xF z=_unaB)Gn|U%-WW#dtbJAP&Ba+ff&XQ5aI-R(X*RaU)YBZ9yTpMU8>U*&(ou-_Y7s z-dvzT_>+21;Zy=E3W3m)Jz}Zf{m5rB{o^%MKGYaanla{NLZjQ)-yi5y6<)JZ%^m28 zAyjU~rJv$rpfgI82CrJfC{?DhH6mC|_S|tkh*bqlcU!MhnGulNb9Kt-xG_8W@*6um zsMVwEQU-H9EJUegci`s9Giz(=&lkkkF2C06Va1miqg!e#b zCJWzNL`N_!rP&y5j2rQDTFb1Fq(!Po0W|2p*6E{;0vT>ebVY7{LH-&82FMv_E%{8# zDa@MVdme3T_6vSn;|0<>^q9bvMt&aJuRc)xloj<~>=%2R<>u!g@jAe9W^?LzwFs3W z;fz42C-An;Cm1ojSQrCK8cdLJ1l}AVJ}Yc#{i*9x@i{Nn49VSZ zGQBNYjCh$(D}T*RJF+8Ja*=+(WO@jXHCkT&fsQ6))#Oes)k88ucITV6`oMe4ksr68zxlw&JuQTZP+8iG27B4{rdf8ttMCTz8e$ zm=KAJzcbaT(}}OO(#xa2>n(>4al=-lo+&eD>R45YN?omXKYogCiDYye?qBk`iu+ss zzHuRgt<1(4N!o0Vw^77MCrSlJo2GI}Fm8kmbwpRhZO3hd+W9=_!z>c$?pfzR_<$Uz zbbOvR`JOS)^2r-?3C(XQLw}G}HUlK|vllOv@*n;vD5|HKpQNy2y=V%swt4o&zf1JT zzr7HRoHd7N{N(VqlUB>$s0bZ~iVntOKP<=i4gsH3XqDE##*URP&h6TuM`x` zY&DZc(bt^*?ZiTiR@jFCOjf{5nMjb%ZOCNk`-`V@ZaFK6zyHGm=vBLLT6TZ9o@#Gx zt)QzrSXmBZ+7!TH^;w}Dd;9tV08b!Nn+H8-VGO{6Fsbjb=Vd)bDrqwr;NNHa>tQ{D zNvc4Vqn~h}C5F9s#-jqvoKt+aR}l*_sP9Z%za3!@p!q`tz;YwSX9!b3<=_xN{yQAc z)2-29c5b$D#qB!y))1;eg-y;&JnVfVPXq4Rmi?`X=!F9@#+N+2UMnw4_D{FU9$+CT z&-cYD&tA>KT%S4Q7b{veL`qANJW`16Q4IZ~{#@AYH<736h86Wym6e^`8{w5_#cXr} zsSe2yO@mjwO^Scq+$x*Z#Gyfulg&8g@F7i>gmVzRep_vy)tK%(54Ujq9cq ztUYL`ygccPjzIWpoy~9|8V@e!*bt2p7v7@%%P~_yHz|rPxnT=7zH=s`dt94VNlJr# z`CiO7VHOkZRy39raom`}7v=R?3Crk&Ik$HLGaep)FHRZkYgU$qb}Ba(5*&W9M}>bi z!mpA>(X|P1;^vj9S0tabZi+DdM!Pa2-s1|{g39-ls2 zUyS~Wn>1Q1W`lbKyJaXT0)dQ14FjOj?=KW}bt$3e z$-dBC+1OA9pbm^Gx=cjzgnu`4e-mCxzWf6A{cHmPd37D!-{rG4jXyj8u>Yv%QuAgrJ9{C0ZiV3uoj&1l;e4jyK)fr(Ks4q7;qjKL@83ls3_z_h znlk~QzLC*U=0#oEbo(W2oM5p{3HEM)Ay1vi-njjwY*bV-GU(5rKf#O1um%@>i^-ng z{DuuUxVCWW!#Q@jH(**vC}i0+^uovMb6Oe$rg8)_AGZUDc3@)wesAo3car-=AZ7i) zu!_9FF-!&iZ9SeUIP@0v!r za0u4r|8zZr({){&*8A*2QwERG`)`RJt(|@?;qq>zo~o>`sQG{dOu+7NsXY}hqBwY+ zYD{Ny-=DHZ!8}5M-#mmih|4X(f!6)h<*YUn4JH3Q1bO1zmaliJKMy`3wtCKF^=%zC zoSP`eEJ+BZVCb=Sn&<0y9ZqZg$%KNQ+wgb-NfSyp>$|D}wqK46HpQVcjI;iJ6!5or zZ9=8+6hD&4-(~5pwNQxsFKrzhF*~_~0Ic+1orSEyE}pZ7e=`i5u zd@g4|27Oeh|Hihc?gnt9-=_RCdA9M=5m=qmAnC$B0UmGDn4<5?<5GUVb8o2Dfya3n z#o)yQ=MeP})s-Yf9(>c#_sD|BsGe?hu;}0N5dNhRmtxm7+0(rR?P}IVYcI|=RiI%7 z*16&H$$FU)GO5{cp{-fQ3o1yzO^>Zo@z6UCn{@}bV6{IES~IePq(pY#-`I8?_<-0I zGbW`vf^#7j!me)b4+qOU{I%OEe!D8b>h}#eKR^Ezj_H`>j{Bl|p(2I)%xrJv_u;y| zpKbJWvHoeYfSBa;5!N4>W3i&2@!ARbqa(a{b!AIu)i!YaF|iJYc|VmN6cOClQz7;g zUwpTDa-XpM9vemKqGwJj4Iy%PB!b2D%~SSNO%$C1-H#~PrxM|wFLgTx+Z_9l;r3Zs zhxE*{E_(FjkYW=KU1~E!Pvh(b*NeANU4~lDIngO8;bNCU@hl?5!aRdhQ<1?QD@^iT zu73}UUc06wvA9Pq^&v8OC}60)BRez3@Whko>60f}n>QJ_&%5^c?=8@o=;!rVwatEY zURYjy*y0S8MKowDIK?5-7$`ZD8yIu+H)sz+iUwvsqiV_N)B_#Ou#m__;WBln9@eHp zme96XtDyATyhc&4d5xMC-8>@yr2D)--1pHyBALm3@BK%*z_$PKy*I4|6*{bt9; zaMn$XL6L%BPbm16--wbs7iaLwr$G5tUMwth}6&WBG2=3?g=|0~-rY0Pxyl^QR3mIe4Mp3Cd^qRfQZ()Z|%wWW?Pn0 zSTT$+FsZU~?OP`T0TU`#yV`AKeb42On9dG@P>=X5k-ih`AKWaulY|H`br(3sy`Jw( z$gZoS?@Zu}a{7SPxF~xd@x`!?20-wYhcjW0VE!6OZ48d?$V#A=76V%yh`F;sxNHQ^ zZGT|fBlPOMB_Ng7gLuIVxO|5B|FHu3A{m;3hU0>UAI+q4;ecGgXd?X^DKQxE^788# zw`~Xb?5vL;L17Y8MmGJO@5Caq-}gNpNLMa@(h7&P1bFp4hP6}}Vs!T31VE#M$sz&f zE6_~r9T|DsaN5~0mMzNgY(`^Fx$x@xL~kUukD;ikN9jLCs6y5Jr=o@)6uLD7E=%(C zchEbvggKytL6tHfuTe8T^uBE>VD$E0v9rd{8xCzpeL2tFBm{}(PECml&Ao?WTC~-1 z>RBkGQ>+dki+^wAy7V~LSqf=1Jl@K$_T$k{8JPGq{)(iRQr2fT12!KP(PG=`+FJOJ zCpMo(+FM!E@el&Wri9$HbJe^sS(PZsMrVjy0YzBF`4g`bo~yre~36eV=^1xawr%+QjpHZ_6}f*D-3))K?XTiHY5A z@sT@`;_*DWMdy1sjp_G#2M0r-IVDFpfWLWGO^wu(B3dy!x(5c3PzMAqhV;ZX|1JDH z3xr4PmmiK2k??tXM)}!h^G9Af>h#Yi=(=YgL8Po{lw{lGlF{+_B1HEG)L=GWgGaQ_ zQH#h(7V>lJLClZSu6~s8JkKG}9a+k;rFgDkoXf=}}?kB;RAC7HPZ|UuM zRaHr2D(T|v3^>X_%K_qROkA7mc>C){ZS^}sKidi_@49d(S|?PF&KY7UuDy+QdxOiN zdMJf*G&O4lMYZqso6Lmx^e*scnT<1hbZ-Qk{6e#cxA^B7GIlYuy8;mCncd~r*f0Pl zlD8~<40{t=XJdZK8}?38kwFPYzSL=pnZT7dSkwKUx{S_*=v-YtLk3rY$;)s!wmf~=%kA}=h6M8&`p8_OD?C7fr9S6ud z2vdMMnZ6-ml+tz4DfYE_no*7i-_SzeBMpiK=-32-8S?Qe_(;Fr*w|>#Z#PYdD@!-p zD;GSdjhsuVk2j)j6AOHV9HIBN#%)q|mJm6~)(r5ZWlI3f?rc|r2o?4(5l1waL z3prU~_D?qd7adW*JXWllx&U|NWE{}+S_90s{OnJR5~W`90=F;}j5_KzeMlQ1G2D^P(dM zGGE2srPS>1;+$#7b@dSri?zV@ge zTn^m?eX*JLj;{_Ao_&OMxUk-AyPI_wKE1AB1OaRW>7%@=dpk@|kI zW})fS#6cc(yW*EyaDvB?^_x)+6HC#F{dUU*g+Yp%qJc^@cSHj(>3kv@AP*^l2FMktPdO}&yIlOO({B!gYR~=%(o*dY zhy{uFY4ERqq%vlizdob!i)HE~y#Ud5s;gVdd`6wcoE;wVWjDWy#aHo4pbLc%0)$Nn zwUL&axOfQ1A-Rb!mi{cg$|KE8_Zx9>Nb?nYkP@C022QGP3e?gUt3A$z_200UALPD=Q@ei>_>TT(W$7g!cw)lU4^- z!=3ZDB?qDdQF_C)JjOiw|Y%z0q(_QFK=BH;IEtYN#3Wdk+z_6yZV4P4(e#;xk0{ARo^6m);9h(g*8S z*-oSvhbD^aZx;6l4ladLG=9EWn#L}R+F>=D5+{+pPfe716turUHD;s_wAJSr(KhQIE>Er;P(D4X~xSjukDCx-a?2PBYR=WUo=O7u)DwAFlWaoJ% zhV2&7f@Vut_F(7{A81zOLpKUg{uZ$P!vk^07-W!Prb6p)3H=7X^Fo&bpevxwR{Pj* zsHiY-_!IFj9qit05e|7I(oWDXrSsZ))TzY+K5afrqriu?3vyC@ktf_p+rUgJewhXw zja-=+49HK8!@5*obhLaRARyRnkbfz9mWY<-Mf;72sFth@tUt-mrYi8O$^!mF}so6HF(f8+K(k;g5nwQ%~X#x1t(m?{`IqI*oVeD@#kiedH=AgP5DnTs#A(W@U-CK}?ni&Xk46^N#J$T*wS{@5 zI|%E=@Vz=Ly0v9Qb*$2Nf$ML1y8ZV?&gcN<9bt%VAV3D3)Aj8qb~ZLNJA1h$9sl=& zawdD0iBJ<<>-NTOOdOYNqz@~CmY?<J`2OFN&vIaEEtot#8^uTXz%r3!t^HPpZ{u1d8C|=UK<}p3Q(as_W z95V-+d)-3s&@4O>Sx+U3hS&jnoq9E=DEd%`t}9~e2NxmFaJx26X2``CJI|O$oSEJP zv<3N%hCA1fMRn1aP8rn_C*dM)M9h~rdSQj{7X`5#2HejWIe%B?C9L`~qx)>a=4D1{ zrVx*{%v9rXJ)mJ9{Yxi^CE?2z)7V?!vM;_&M%JEb66SX0nR{-lyg~@Y?2bNu5C=XE zw(VUS8&!!l`TpekWUmejpZXyv1w&?dI!AmTYK%WiHenRO+)r1%QDi~MSDfE{o zzApUmml=zN^U2=fj=R%EY?{>hmqC-O?z2a6)wq^h$MdUr#U0*DZmi3nJws{7O$Z^j ze~S1`9w{orH}WPA^$t}vTA0{1kJ zC+OB|5s`CoRw1IQDsP*<;AZ;!N)kLn4L z`4PF}o&UQcd3|@dM=ZC`b)SdxVW*hQ&>ox%2XlPe#|_2`4Jh8q$_ua!Y19>$M9_w@ z4R}WSk8@1f^Hi1OmbR_@9sSDOm14p+P}#|p)FG_dZ*pxo_15Mvee={?u_x4Y+g`WV zr>6M5$8L~pvlkJ)uav13D9Q|bN6Lh6gG;v58|vw7bj)SS(V7vCMHR%)X%r$mr`tjM z(d24K(A+ooT9FJa{GB&%aF9PK8bS0>Iots7ZDY@!qQVe@^Zx)bLe8LLW&r4UR(low~!%EWBzHSwPXQK)T+nM5K5=8*Toz!gha>*JR zMy2yeQ$foDGHD;Qg5L<}Jz&&Vy#5MdgOC>AaPTcHDGR$9T^3~k@BLY?NdBoZD(;U) zf1R22$@$g6j;YYp#?#NuPBzOWz5HrvFV4*Z&u*V929y{UolxOo*7LP;A6_>8UjSpj z@|9}vyj}gf*o#ocXH))nzU_pIJU;geHBniJd|bIXe6>f0jS=fsfJtM0P;q`%Us@51 zzofc>r@6aB z#Hp@Fsx^7LnjzSVNVCjVWePteYnIGirwEb9QgJ0j-CUPi$|r};K+e9gv#s1;WSGp7 zgL&^#hKb$}vY3DmmDM?G(9Z<$yKNxbk(Zp?W-lS?H=7+(2-{UpfQzvZ)6A&$SlV8i zfykmf=yjBB#XJ3G=by>v{Z>`EF#|~Zjnx!)nw7uDG5g!z4jYmTPwNxXDLsOzfPoT& z>nKu&PxjS}n9yQf?aXt1_(YX^q-})l6biZwPQ29_3#0H&gGqF z7VN(T9$&}B`cq^i*Vmo+S5W?6Ak4sF`yKAc!irmSGijfuQ&_~&df8RI{@WqkH9;ng z+D5#R4#qp`s>V1Y1=-1vtBMLltfpjpw*>^iShdHFz@)HtlrqYslxO5zxN{HdT(a7m*n? zn}}!IT^jt3L{}g@rlXr3>3EKoecX?tCWCr<5YV*OxUIi!(?{1BVf7o*PxtD*85JPJ z7SHEexs-9QnKjt=*h|$GH>W7|63T%1Uy8xh$@!G`@1DC{XT71-yWIZdWKLgfaR0EW zA$q8g`m-qxTOcp7RP$F6d7NqfY0f;D4>)2(onJwgY29DLo2}Z z4Pl~h;~tr+)Tla$%P;txLCTg2zoYyKa=P~L$+}yNSEaWBC8OB^kyJSDWx~6?yb{FI zE{T%$%8P-fmB1^G82PjrS8|;)+KobBs+V6CfwNc>>oId);&m@dMv6)x5;&Y=WiYE+zZ zv7S^<_SXck$1rW%(`v0dDvPrMg!$<{gRU{?#rs_EgHN(YGRM87HB*{3i}+v?_4PVY za~13Zvb8ykQIYhZQK1A1KA%-@;CSG#df$uky4saw6P?#*9~f$~`*fUPpymI+1?P3b z2YO~2!L{c0@1LLN<+)u^A@+vW+~?hYaPbk>Ofes&nJLvk1t%Edrb;0}c!)CbSN6Cl zP3YF1Q~2m-vBBZ56hH-H7v4eyJIAmpkkH?V+NAVPoNF_azd2v*g%mv+F8RSLQ>EhM zXRV4d%V@r{A}|n{$kLnDgzOgpl!YOKk>M4|+U!OepSsj> zT=fxf+XvzS$@%}hz_l$jWcrU&Tf7g@hEB%AV$Vu`C`BB5q-LjJT=gt4$ zB*TYtkx@uo)J@}iEhu)lccl4YARPZOoy(X5#U`jjOSnU$I&xjfh!(H*(_S?4YpXdm zwae(_RlX1&BTxLn`#I;F5TSPYs69g+M{py1R;G zT&KY>WMnv3LFcOZyp?=L>Z`h6k<`TgRd$@ZjDtS2)zl+S2FUsCIzdqwmpl2hMo1M= zGtl0ac{H}b;?6=M@_6U(V8}#%I>Q5{Z#qL28oYIu` zhdaUIiY&pn*s4Rn+4dZgh@9Mmb;P%V9SZ{+~dJ34wLg95O8C9W8j*xl-s3}UAbf9Cz@ln&J1dmKe8R}s+$HY#5BUq&7*xn=~W zE3al@hMkvR|2Ti%Ulxn?FX1U^-vGaT-;hA3T?rnfVAB4>fBTth_VTtW511=%D6+3R zAOo?FW!*}P3y>8`ie$u{?xm8PL^L7uvpXXO&4ac}jr?~+JF8OHZuFapJtAx-VWVcQ z(hZp(*r>26m&8V_q?k%dXRcOn`N-kZ%uDtJu%9pD_T1|+_n{ynUA0?Oi$JH4oAhF6ctVHAg8fKrus9Kg0$RdR`yUCan0J_n(zN9 zYDBZBez{36XCE=g+vG_dKbgoB+K$ zJlKnYn6tdhJreaq+>e#xX^SQR4k+37be^Sczw!4|cI2H*1d7_l@y`|4hia^~uRI<$ z^UVE?$_zd{NcHuNt7k-A?%c;W6mi;1iY;fCFL_ju+0fu8SMkiV9Wgv)elz3W*7L*v z>p{&&jQ+dpLoc$$etI+~rb|2Ywf>oaxE2S0plw7F)ge)qoboIM8vfu5md z4mGEhZHYR3_YEo=p_0)6xd04$PTq2z7xnmjS&dHl^hD_MAY zCc++{aHbwXHcDmxP7b*--~EzA2F0YgG9&6RPE;mNm-VjW#oXUm`A1(L1uc3o)0xnH zh&U-sWl1@CyGrK3d{m1Yy&PkTwW(}jbQsR(Ky8QYxpejZ6PC65^a-PaL4fZRf&kiN1$8U5s&p3*#6yQ$76ll zet-7o!@g3yRyQz|bgOC_T7+-he*6u06Y$jz0O>Y9* zKzx}Bc3|KFK|JBT)BVP-Cx^^_SI9iN+j-&(LGaFVM?H}`fpnLK37$dYo0lB;!&L(v z8r!$rsu`@WGy?;aDLW?a)hN2Cn)Fz1Lklz|B9ec>!!?zd#La47s0&4XKyTMMMWiHr zb0?}K;!Q>=jdY-dGp6{%h)U+9gLq{UhfB*z zREl)e6sk`f)a(B+vzJA0MDrJb&F(C&4uzt2Mfhzzc6n}uY~zFNtUryl^sU24ABP1| z*8Ar!g!KM7r!6bLu*4nei{>Gkt(t9{;h8`F_yRxxH@?L#-ut<>vhoAOM2laHitg_2 zwk&8JXQc<^99PQl5D(HCSTW_5><%Td8P<%pml6Y?7GkY(0_GvlvHttO0q`gRhaOav zn_=#|g>eQVE`oD>ss3!;zTx%P5x*z!g{JiOU1`9;0owt|JP~cRtYPM8j@4|(Lp=0viGB^ZP ze_Rc475KAmOY;)3P#HT`DhKPpTyG>+GKk54(Sw}MIPZp3INZp&X!X1SfxM@&J8xNS z{Z0CxZM`|aOfD+X-o6d zz{W}R5#O#~x9U-|%KAc_EWh4@t_(Xe+En-x^K2Ca=x4;RAtg+CBYe$V0P)-PFV*tC z(}o1~DnQHugbe+)E7xqUvzEle1jHly5ARpwN)iqt5H#q=%vLEIHP+h475*1Xrk^iN zdLF)eF}Gf~#y5r`I^q)H2rl9xjKpsojtn#^QH=lh=^#QT1SL-go;CJeXf$iuO8)M0yZ%576?)1<;I0JpHLolifOusl??89FI zcby0fOcMh&6B*PG!hmsMzb>DtjX+2P-1`vZHls*=mK4PSFuT1wpfy`FdB)4&duReX z^R7ez9I#SZ8Y1|Mh@N=&i*~@9*nfzvyq@4$3VT>{i}e&ViHe|4w>#rja-uQPGPBR3 zfMplrCXVzInd{fQ74V?C+k~p^=UlflaUGTL8|L7XuVTA+mdFjkOEK*pwK-bA4-(y^ zRba^9tS6QWi|9MKkt&6)&rfwZ5V3b`oF){Ik9~8OO1%bVFASc`)1M+=(z`x-Clw~v zUd31|3YKNR`05`i3RC-aB!RObT~JRW<;`fuX42fi8&8{2Er=eUj_>V^@v0wKO~#YVOY zt!8!NQ*++8tuvuk37x&JrDpfrN_FxxU=W#?$IjK+X-W2wD`@buY#Dm#?hDJ?-!%^( z|CSfECUOs_k?1{?629~)BB4yk;YSRI*h*2stUsx`9Z8{ zLmW2j!3JJ+-r@NG+F743((A;czJ1|A*B6zdCr<8(=jH}T15c8@+2aj9jS*ih$KFXh%$ zw+U?s`TAWu7#OTymH7QzBS2M!x3!etYVk^7c5%TW+ zR~XI#E1$`wXeILs!3pU z_=D16^=rk^O#zj&eLLYGzZB;S486Y?n(NXKcV zB(toDvm=lSh3>9;r6 znc-Om$GpQhIB6C{Aw&b@*WG9c(IBZ`WG6J=ya`WWMixKY?YtB!<&}Xa} z_iDO!W$kJi+%?rDXxe}7>7>=GY&<35nReym*Zo71K3l)IjWcCjNV>Ija5?IwXtJwa z2^a+|{=9aOUnXP3CHX9w%TG8}ROcWd*tLH0ct__zmijiqReBPp*%NRz5fBs%v@Ct& zSr_@_>q39?@kA5%?Md%}#=+fPC{cg5k6~IWms7PoJ>mbxjB(5P@o=)1AW$`XET)Fo zRfH`sTVqgU7_%(Loo+Ec+E|Oy$1RR)fm>eyc9}i8K2rg$S^G8D>y?1xxD2!x-3qwKWI#- zNB8Bo9rHT&%n3DJhfMu12larfM#ctnS6*33)ymBic(;QhcB!Nl8pEZ{nlZ{(RU zS@2CzjxRu;pPi87V)=Ta=*15PeTiSQ)5R)~@#rOZHeyV@5RIju|6xG}o@^f5OV6%3 z>sa%M-2I&qwTP%GExQuB7~Un}i!VjJC;8iU-(fnE^!b+LK!y- zmaDY1^qDXXP+&J?elNT9+LYf==vDOilldK`Z?2L?bjo9d{}Xzk<-<7jlEaqz$90os z*TOK(x?ob8CpF8{;Eje0-`ZLF%|-y<6$1$l(TE{cy{ua`;MO@mJ(Wga7U4cc)YQ~X zLg`2M4qnosfS8_`mS*@zNESlSOwq-0(e}55IwBYd14z6HgQOG#^CgH8vg@N!D%oU)fc64oD+<};Y`FY+6 zxQ&OWQ4Ri`XdimbpXS=2F2!>L26_C#!mlzjZ%$1o7h87IghxisfX!*s)D#mWz`Oy4 z5W5>U@=s%Ghzb`}t1#X39TA=MFo5Qxa$oO)e3ug5OS!*#pa!=$R*R58pb{ zW$WZuqO(d$1fXnR8?PBGKM5D=k^iXEw7)*O4Z)ul=v@l%FJ7;hj0Af$7Uax`sI>H2 zo7cg{c;!i&*VfpgG=WLMYxsl|*FTRBhyJ+`J3malplm~-wx#PqJptWJ4+dwq z&ZmA{+1^3>;@kTUFy2C56)S}Q{ZP5BuFa&-GBdS$+D^akQ5WxBw|oKqcnNNwmSqkf zk}gGZSoYqUEpJ3mS9Ld(?|z8?>)n&>>u-?8$Mk*pIj@tLjd6EI@Mz0w{Ai}a`{2Ff z)6Ctyra~`4y8@8?(dS*Hb2XtdefErSc6Jty=#pCv{Hz+=5>Wc6VBUXN?bD>54U>(h zjVnK85>|Q{&pbwrA<6rjA1$V5Hy4x{7gYUDRJR~f)C9%W#=D)BuYmf0``!=C@l4QZ zGVWVV1dafJ^(?y7+$&K@q5|$PZ5SSCL1FdfxVShBcg|p>1*j-;1jSQqCyRdPR?=W> zcL+8oZ-7?XxGo_oE*{E)1lO3Tl9H0ev<1i<2HD*L3$`_Z9m~HbNYx2gD9c?S&8OmZvI6dTmsa%9;oWa#CY|YNxTv zhXghDSB%UzZ%_t=VBcV^(-%!{g(x~Bu6#`iSh>9P<3mGKhWpW)v}&{O4D9r0K3i2&9K{Tyr`MF=LK}dw+}QWVA*MG zXV4ycun-V{fPm6!+E<68C3oghAvXi97r&@zywfa3@EMdr;GILPXoJ%Hty9%n24hsi zL}z4XW?6y)H~JqerL|wUBsnT`PU+z|OU8|AL2SfXyD~iML<8vGBwBUx)PGjr<<(oA zq&TQob?&;#5^xubUthzVvlQdg6vg-AtA{cyD7??-rl=nYHkx_|3Isp6-@m1N#GocK z=d<8U!C>cgFN7V(Tq~kW1GB_KMLkK{3%z*p9_w44UfpCZMUtNsrN+qtm^eUr$sT0h z3C=$lg6H_;gR<`n7q6e%VyV0sfNw>1Z^SeeH@ z`=#lv7+bC9!{6{=-SOj!(cvBMo#aWEfENh&9_O?mwBPy8Ay^%T1E?4LNv^=VMEF}t z&r(-3)9pxOE!Ll=fk| zfb_qZ@T(%ttF@#USr-MjLTCLca=Ojz=CV01XiAx394#-z5)fwZ}SP4p?kAeVVkcwg0z#Zmzi$M}&Q0~tv zMk~SZatr#iy#Ddm;NtKxP{`}4!)CMCbW)Xb49g|JtV8SyIXd!K8!5lSN8kW(=otuV zjk8g5k&t?ij*gT#8HT^IcqP8!4pSJ$xQH#9QyeCM*+d8e0X;pru?z%#}u2~j~0{ea^AO58kQLt1ZJcUHPe5?iQR&C zn9|Vxe8GO}c(8#1ur`qTG5YGhs};W7uH7iveF1L_iy6~BsPolb^E(Xj3za)5m2+M! zsz0{z{u`IxLjQ6s07E?m19#fO>J?zVVVokwYNv@Y=g_hBx-Juu;unJ&w^q8RR})Xq zCNF#-a9}FXD4BgKOn2?QX2$3|2t{Zu7&@bjPFszPp@B7{q|3a6sHIut+~ z9s;pXt;h{4-OkOin!8S#srI3=^2M^muL&Vt4iQ+Ne!xzB=w^f2W!7#8QDDtD?+nKs=S{)PU4rakH3m<{uzgHgApE&ft zVZU{HgzmE`=NA!qO~BwuW|dZgm*lmfP&9}+Z=Q7wVBqv%nbX23hh&I5J&9W2o_FBFH$=Ms9{~)YTd)iqrcy0w4!mF+sP*{93 zWmoX~P62%J+jC}9)J^s;Az=ExfAYs1Q+sd&_r?3i@3`Cw%}|loqo!8lgP0nzEo#NM z9oGT@wdDwCs=b1;yP2f7CF48Hi+#^LF~9GEf*ZKMF&+liPDG@nUJXrt#nnCV+TuEl z&CPQ*E6$?+F@Rg=o%R@3<+suhz}LzWQK_vcwa$9@tRUk9R;dH zJ%Jtl?kt&QowE6kTgcv(1zW2pMT5?fT*y5Ri&EOxgI5m15UOst$jic-*V!$88vcVJ ztYM~Ci%he>6211<6l%uXpnL!!jaZf@Fr5vA7RWb1CEBw3pm%$F!!RYUUzn!%8id|E=i!LFg=YZAHhcKFDRd2CjlwnJ7T)G|m+$?uRr8Cl>R;W17!8HB z0J!JUM9o*X#5;F8mAzvo5=Xp}xNR$!mq)5&eLy+6Ng+2#aCSsLCB-*y>z-F+wBnoY zjd+-DbXjxHdF2g00fFOoE2WvKDK;{83M2r3fK-FynV((r=*7~a9UU|l7zqbsOH2G3 z#*-^|w?}ozq~G4Em>hRvu}%c?I+x7mz}HzHw2*pfrQnl7TJ-S%CeGgO@EX@2)+!Pl zObc7EWm}(oh$%$rcaGcq&M31uK!}tuo3M|fWCLm^V#QZl&nwI{zbWk7g=m3N40?}f(izHE8c zW{EB9zZIMej5gGdw(&Ye60eDOWCX49EMH>uT)GMJZuc}aK4SMMkX8EB&_sYPfc{Sr zl(DA&D@4&@03Or36v;~n@se7s#ydZom9wXrp7JKBOMI{7^C)5--c+wR_%+7qUUsUz za=0)(p#8TC$1T=T?x(kDXw%-*(Jg1aND&%hf|kp#1J#R$Y|8cDs%{7^vmcEwyJ&}- z39qGW2)|v6_SBL#I(}vHF_^x-ibJkm;?p$Mrh1$F-~pY4 zFF*bBb-uiCUt`qEq7B+{Wkz|kybp$>XK9(8zil5YIvJ&}dhV)o7nDD2=ond)HFl&K zZN6VR+yeH&mw- zfCB&a)4iE?V(a0fzA_@Dq^R*WgG^(inQel>X-^?vYU5n;#+k-E@W zG(jb7HjbzdBK)u9FnoFtcqeme!$SA!V8DZsH&^ape;dQUbWcdt)R@iUrxnS{WtZ4h zSGn&`ZZG1lQXVD6B{!gZ)1&K#!6rxJI51ZZRu%SrI zn4{IhnU*SP^tX$CnLyJZ$!CU^VvXyaTYH)djf+~64oM9a-nFf?+ zE{O)UBqGh8^jA<40z(ZYp!N>CxbGQ^eI=Ms2xX}ZbB3LfSkcwGHDT>|ff&!Dg&fi` z!rk5Vr@3;gw%$O{=s|f$Bh`&&ovrBCXgrFxDg_*7&KD2fZH|}yVlXGl^C9`@OSWw6 zfK=RT#xs>=MFyryy)=dDn3JCrfvI7jW)*dXf zc@c3_?0F>b7M&ZPB(S5v<=pvH^^EPpR!*6ZTA^Z86K|cG5HkOw>CFEBN7Q$RQ~kgH zAC4S_L#2$YN+B~N$2v%|3TY_2kWtxtOKFfjl9`MoBPp9Bd*s;4&geLfy|>?e`g}g$ z-*xrJ`|9d#oY(7lKkxgo?k}yufqOEWtpv<8K2&5RIE2I0(~d`)*OmwUqjjZ(bC-@< zLf04ah`;`J2CqUs@EnhS6;MFQCPO%v5?~?(4B~FNYc6x5=;x#1H0;0Pv~W{(bUnh`0Me754RyPYH#?tV%A%G=g1eqqTWQ|p%* zDX0B5%2kW&QG+F%o=LDF!+5d+cQsja$W9j}ueCdc$P4uD6KzFNGEn zxX7{;bnmq-lt7Fy;#Z}Y6nP8)I>f5eyJt?8W!C(VQn-c#DX>Dn|6BDGpR>DGV;a%x2aZWaP3Q_)F2DT{N31z zS*>x$Nn?{Sy-;!Qarv($c2gyCVaTN}bd~DN>2N`qk-Lf9|ACT2L!r5ovAoR^l!s2l zMv?f@;uI#7-|J3f)GuDyRvSor&s2M*$|R5Zg?hC^XN|k-cl#8pk{@%?%ah_^fpW@7 zbhcOZBlqh~YhA*u;@LN0q@HrjmQnYJoR191z~BBz(1w=j;ySHfwRonscCIAnqvVM> zO_`TfPPnOt#YU8qbBNq*7vU=9rhGMsV@xBpKUasqd|nE(SY|=i7{0- zJ3aB@4JIKChU^sllfzFD8`^RR1jfha>!}HokONA~pLQ;5QA~+lZgZL^|0=E;UYvrrmdc(NH}Ua#(v_F$tN5lha#T*wqkVg(phsFbs{bNh$s@%Y*D&{B zEzk(d{W0G}*gM*3FHiohcYo6tQBQ$^+_0?ni`?BNj(79i=a!g{T=B#(`Z4HEp`*ja_b8`6MdQTBA}@(On_27Hxqi59?0d5$ z`0-cQIdvFg=#lY2`g3-c-Nh^%?psaIt#L+qI1{YNEU z)0XZIODfZAo-kAb4)Jn=g&}EQGi29(^Hu5amCZR`?mwEcG}TG2G!*t;SzC&6Az!H7 z4E6Sk=XpyTP*@Kv@k=kFO^SDwg-B?T-?a@Nr8G6KT6}9GB^cLiZyd)@V8{~M3*893 z+x5v-kpMnzMI z-X+gAsvrNSFOt!&Et!xM9NJ6M3?$@<#7e6&A#ns)GELK>(!49^+CzU zy<;yM>j_7?%o<#JoUWjz)`q$O;zj%5N>XIi$1DJpBttYnX#vX2-L|>uek9tV+9Bo9 zOAaauAPmV8>YAFG=S6SJ{el1nM~%X`T4l0Jku2!~3iuj%KpjD>v1>TJZ1>l27cU4CJZu#3)w# zv$^`7IC99j98&8~02B(H7&{xxGr*0hN2U(W$^1I|VC=MCus4O_{;cMy#>K0sG}cW~ zT!dmJrpuYppj^OP$$LM7=@lJiiO8W_FxC?$|9n?xbhoiN0%$i#+Uz^Dwhd8Vz9E$Z zd98D(xv`4bH*ahYo!X-$ve}5*ciF0>3~H_Gt*l9-HdNR)!HCYI9yy~r(%3?j$@2hg^w4UvA?E#+L*U2W%Fykk0EoV@up{0-v;)c@Dq}6Cr?VAUM^(}(~A$D)jLaEQ68pkHznI7IanPJ zu-K&x)W53)p3!x(yzxXNm9q4-K%=w{KgIT)oEQzM^Bc>>WJko7Ru(J{2m$CBKx0ET zx?CQsIofdKeyZR??YU#&+-tAWKIRK36&omo-H#M86{=?aVa1o3AF8rvMQ-d zRjNIz#m`T`3}+Y;0*mEb6FG0vY zzk{UO5ZuckMqK+N+rEZ1y!$uM*wD`8l=)|G(;1!gQStb;fXdU~K6Dk2xX2iooI*2m z!%dN0>kvah-Abkb_4p~wUu?tW-+lIXclZ7ivZ$ha>7O&`NOsEEmw{o&CaK4s&e5s3 zFK|+`Qufx}KHq-Pb$l~@_~h=rL_ryM0er0EH_gk2_l|}1dYNx=zsozWEP(#;T3l`2 zAc`bykDn5MIi4yk+d{R9z$Fd(207VnN)~hJ11Jjc?SV&)+u{aD4q)i0G;So*s*M-P znV)eFwGH(QndylvidOwWXqm53TBt7>zEu)#GH){4M5v#$J1?ME&$;K3ewuycxH9`J zlDoo{%5iv8YJt>Xf34W4_M(Zs0u3e85ppJ|o>qpgdam?VC6oEw8oK1@A;Gq`wsb{` z^ZtNpzV9cMN|tPg-u~q_A{?@BRi}iJVm9tl**$lG<613n+=k1dkP+*7M3U!c; zMY?$-G?mMy)V4MAHI2AN%kN|b$wyo6BsV@Wn{FoQjhJ~e^hXV*Rr{Oj>z_3B^sLJh z+xL?0DhLT9yCtosEc|DiV!gN0w{r5xYggcs@h4}J3-F}eRP>L+7-8xYX7BS5q&wP_ zmO);?qdrtgcRTh7;?YI#2u1mY>iW>rt~`sCi86GHS&QSAD{FLNu)vA)0bd#^HLzT! z1COU18@met*1G0G-Ii3+3(+=Mjwk4-drp0PNSKbulkpoi-WE8(R>oa|f}2+@@nYQe z=8$pO9((HgPcBX*k(ooSzsAK!tCpAkoJmr$N?IqR? z-;O*k2?Grj(%SRQHV;2GgPv`c=)$vdB|k=)!hCoC?x&He!nG3OM(9FfhJj)Dq0LZ1 z4%;JFx#=6|-jWZ`&9na%#m9%9C$9#%qsAU`G7jb6BegWej#{PwETYtD{7!_Tbe8U< z&ujnv08@H-%+C*0lhQ9qfgJ2SQ>HmVGT058lsG({G6s=<6L0O7xGEra-#?w_%1c2n(iWKGe$0iFTn5y(j_RCV>rwLHY8!XxH2X}5YCGgxwVKVaZ@t)T z)`&hyv`c0-jP1E8+v7Y6__oYle$x54Rw0`NL%e-czbdq5hZypF`6ORR&FY77-=(tx z$oZ--Cd4@ZMGNiUn;T5kCiW}0+2bhN#NrPr3OE@ndPMTr(pk_q?RJ=AAgV8}wRG>W z6y$|T8E$ZGHZoV!06Nh`AS^bX(!N?eSbyOAn0druJV@oyjTxrKFOQ;DPs{Fk^Ydhc zvQ@1bEbPwzk<4zqjg&IEhb?Jci6EUZJ3k{8cX!)oU_qv;>edCa5D0Nn*B+wM2+O^; zca4L~I9dZdtJb#=aaEysk_c+?U6+eA)0lfjtD$+d4Eb5!P%zEJ|2uYD|F!x>5v{tT zg3RNLTz}sm-N}@yJPf0cSK)2Z_)wZx6KcLxY83XO&ykV2cW8kQ&Cu!*KA{zy5%4S) z{h+X0xn*j{+dqUNMnqKP0U|BTx?j5*_X+)x2Wr1)dkfWNkCwYh9gN#n;24b_*V((zPWj%)dw z>}>vGV+stSc}44Qw6}T<;iFNW1kHNxAKwElQPICu9ZsQy7ZhUM5qZ2(Pa`tkzb$Pe z-)tQg|MB>o@9z9~!Xa{RGLTE|^A5Js60adQVlHzAjs&}ZxWubth9PN9a{}jeLT++w zQ>H_TTE;;)g|2Zn6C!I;_scMK_znvJ_BS4^?#X z%T0O8yLyfm0<6xX&Zu%Ujn7e-FXe0aecED8ywa##-(FL{*z{O+X;^yFIL~qSGi#w~ zR!5(We|I_%`wT7l+js9A{rX8Rpxp;Sh9ZQa*OqHT{-MXBQUxjcdiJ(``6S2LiIc!j zFbIg6EJ$V6gakcc^Iuw7z3b@b)N-A^XZxpue5_}?x<{AR-iOwuy}p%uzLsC_(b3c2 zH#et(rWxXqrW}7~*!G4hvc|!b*azwWh?XzN#?sI zPlzF7b?-L}Pwm4EX1J@RS#kqdHBsM7lROW2QU;Y#rCXlay!MEa#J%3H_ISIYH@W>u zWZm7)LNyl%ffTA|tCw~cungd0paZy+0s$fs(7`oMPNtLW0%*Fj*yin1XqbAR^qIBW zYYgcK20iUs7;rgbA8?u;N$G*ky4SszP4U7t!TuEMgH_K;m3b@{A8_Eavrbl7UIl0` zr&ojG4D}_tD|Np=-sWRsH~+icnyl~HZZq~{<+Z{J#wPrSsA|~rRo1K{7K?&AFY6sb zFrlC@GL)rKYj$t_>Rk{z97H)zL6-EB`&H0~096g(EQ!k>8AUmbSxfIpIi2Hw34xvg zMruPY04tZ}O-k&JT;3h?$l1}<475v5@O-nfJ6Y{gxyshDa6Coe4Z%P9p5V!)$hZnB za!}kq4Rr}%o<=QwfY}0L4})KqjfT+&KF4e!9}_Li+euE3#?6tbDl@jcrSj*4ymRw< z-}!|!zqwDU*NS0XOO`3bPq{%WFT;&ASItiwFgv1`Q~S@ddQqlTa3R`1T@v?tLwT>iB)*Wwaxk;)R&JEIwE!}MoQ3Q1q}lxB=WkA_lHHYpCnI2N{KqDVN=p;{ky!_tS^Wly z>jlHM<@@G$Gm$F;MBet}S~sVi@D4_kb|x|!oK9L>*@5FjmYQ?YnF}!NU>e)6X}1*jH}Lvj{y^U_J6+hL?aV+&}TP~8$NJ)$9m zG_7p@DI2TiP=WYvF*iVmkvxf^4)*q<-+13se;lZ3s-AKOegcXDq$_FG{+e@L>U`lg z{)G3lN`C+KIhVJvqOj57!a1I>L$yorJt5f-M2vjC8T( zjr-837APNt@$`9qzr;#@+AS_;l2KopQwV z;XK)rrXNmG_(89**m6bB=;*((&9`3W!RdRzLOv-T4k8n?V8P_t?syUFGOF#jeUr>m zgB;p@O2Fh5?Dz2Mlmzd@!87vlD8>5-8?UA@=Q{UZZ_Lij%>Y?dw@e|1 z6&_QfoZsUm?3B+Nj{F?{?33U;>y%07pe-s zB|HmLXSLiNBxaj#9uM!`4MyZzx;{wxmKMILRzv69Alb&r(Ap$N}u-_;s{AcAgC@`7Usp-M~s zLZgdOdJ<*2_evAW)@R(IkCa5X4E?!?-Ue_G9&d1 z*#GNWA98#NpZ({*fQ=oLgfy-irSy7wOLZG2X_l zt=T(f)BN*%ReA{aKtV3zD3wY^SxyatVz$|}K4#i^An%G4=@Q=u4XBXPcE4f7z1gm;s$X}SGM(LGX6Z(LN!?cVg@xE zL7N&gn3?1^JNYV&1_U*whV4pd2alz)PDaBG&|$d`9)5Il{@e3yE|v*sfKsDoBkBvT zCSD&fYH$kOxf56geKu78XZNQ~=@sGvn3OL8Hx}zLvg|$X>U6NY4crYt&caFWqnn+s zv`j>YReh^1(DMuMCmaoX74(p8e|sdp^#*$*=)IId76LbQwvR=X6{dADto!2(wqqgM z_rMiYhoA0<34O?T0BB2N;Qu|hKIb~6Lb5_?6P{B5026=6?j{OE!lfraAoP_L;7M}i zbt8GH#RCw$f)=g>Lavuc@E3rk7)B5let$)oYyrjA{C6X zZu50sBP*QVTdgJyRU4Hhf8RYS@H_C`?c~}!ng@EY1*xLzjd9-gM4fuvZ3GY$(6zi`aQCpG9Oa#L-5b+sd6BP<=>T_!S@ z2K_NqhzrGYAk&RR=)zbYE`Rf+v-zff!G{lTr^T8@5kK#w{)E@(7tvXF$ILohU>r+W z>Rzz5uEsWOG}#4wLWqirjy1drI23p;sBd`w@<1mh6u>0dc?><%*WZS#*QgEH>{}&= zRLkZlpG``S^Oz|P&bb_kMc^X$v&UOk&P;5%OsbRWRey3-uO&A z%WS?G-F(AK-@@rNd(j)T=cQL$agK@>m z-9E46tz;34!i2#0%*8jdx>jn=MQHUlJPBU`rqyZoe1yMaB+uK#L~`p>28uQec^3{N zRr{OqKt50JKyG^q&pg_&6C1gB^|aG(F<~qhw*JP7046oHAARew=a3}Jc(t@nyR9Pq z#Yws18-b!AQ&$-2|4H~2A^%=&)0O&V zT(7va>b^7bVms-=lgCd~qqvk6l?=8R1WM zjlE4uswW$~$a-V40mETq*v$-bNXTmErInNe_HX(>%QxbQn@lJ(ABwsusuR*Qq`~~` z(Y5VFDxxIKpVVCZlZF~?ietLTJ;6rCbRv@#a;m7DZ#ggSAId82_SdZa=!-@fX;tt4 zy#$m9z()^yKi!7X=)}*P)B7oq=K1B*-&7-`YZjj;UBceYxVcW`7Dwf{e3H;g$vmCL z=|`S{?*JRcIFD=1Nr=;?LB zZL}}dFk5TFy!Oq<)D&04^n2ws!RqVpD^SEi7R=sgD@1cGvg|NBT`eR0)Kj;R1vD&T za)dADFV9ac$&C5_kW-`(M_*r zdf-3%>t>HvTh*=^K);z2`tSmfvOtCpP|nhl1M}xY{*ZTQ2Hj3ZnWxyhl$1ss4gqGf z;V&>lxRCn(z!DnReO(Vdn*&7IkMHj+G?I)rWXP5fxF+$wAXQ&oxvpAVWT1rd-};KK zctk{O=(Zmf?$!&!W+7|FhyJ9B2eOq)y*>liEPPk}-0yrJNjXu}DrG;*xJqo{ai~(E ztOJk%`sfhxTQev{=Yv*p&&ubOg<3L19`Iy=WEe~XGQ8Ba^rbJ}->B|+PWf&UOMOL= zje5}qIQUx^POBe-rcc%_65|(3d49aF^MOoG9A8j-3{y1b6)pf zl?#SWF#S6I@yCjK@;R4q&lwjo){H_KZ7UKD=qEgcNNxffuc$Mydg=3;^o45`>y_oK zuZbI}dAxY~(zt3|Y9pREuY9O+E!txU<`}Gs6oUN z-Mck19x!cDMo_oIp^rG91lw^O7qHzCStE8MuiCy5(mWP5|1FA@dFaxkSO`}v`PC+^ z-O{mM7^wscle&+%-BF5-_RK5OANGWF5o1@ZUt97>?8B+VX<>4tctVg6e!u{Im8A@@o8z z3lbZ`+UC1PzA6zyoUCMUzHoWoZP>U9!-a;`LVAC^$o5# zTZJ?Ll%VtrQ=VnN68qhW!&&DpwsqyVLq?Jm0=RzNyfZ1vnzGl^IT5yc&YY!=dt1=%Gc1*0BJ%VeUB4} zM>L-_wJX?0VJgY$yg%ykvqKS858_V3r-&_7jdfMC=H*g87j$mufG+VDvEB?qr$^XPmf|*1jhYjy}7kQn`PBaPsR~;9#H0=Q;%;M3u)ws?DG`7tmy@_&l`0U zgm>2(Kim;JVFuf!9(I6sNWQml_4PkXU3{n%hePoYM^T|*`yTXBYqW5z1zkLzIh5LI$2P&QZ z=bfvYyW+a4<0ci6)lm6v?c>3%zBl|)}Cv5b4@e8;R#dYQCS>MQoL=TYt1yb zG-?*$(V9mN&!%P6zvE9lgq1$UJSW%q!PaL z>jb4_5qQGRhCR1?bEM50#8T@to0CkjiRUACqFc=|{2j1?R(A3I&BIOyj)N>G#jltx zW;BjS*?D+R7Jp`NU_UHqW*Mu<7hrvZsg!Hpk2+$PeK@X=+S1aJY)b`r4@A6R`-kI} z2GWA<&{0bqg{Z)S$-JMDCAAA1!s$1qT)k1_!fkr=}v>OUrQ3^G(BTHxiP=ONQiAkeH2$#=_8M^+q(8Nx_eDQgsB>m=YPZst$ zq#=U!?bWMSOeJJ|8}^u--PiyNPN%YUGLeND#rdsU9ra8a_xU}|qwGD~$+x?6v@@jb zSD3egq0AJtmB#o(A7zu!8X1wA4h=Q#rFyB)@fYT!*V@=_b}1O_gTO)>s{` za{8n;T0-Lt6TC2H#O7P#j)tzl>%h>#HpL&P*Y0f+jN=Fyd)(exm&J@H6Qgors~+gx z9b7njce_xjNxA*1;k^sL@Z23z_>zOQ650yWv9$Yd`T%kR&e^a z$I>)b)#uaBFCNGZfg$!BN!y=XYI(M}oec@XR_7=~KYEVUA|mQTXbsRdsAH-*|yY39@X+Bf@enP7kkVrMm3 zUf@PsAyj8Lp)1ibDZm0=h)Mj=V6Go3kxq%m=xBicD4em+c^c(q{h;u%IAbV%%pHWF-kRRi_hKHTWTL6q#z)+u<0vt|oTrJj#` zy^h)}m2-$V{3~4ST$3QheSQOWN13MF?prODyTz^_7wuRLMh&|rgwPj9UAj(Y7thPO zGByu&q~cMg-qt%MPduxZ?yj9ea;5)~+4_s@&$*LBarc*$=K6=|y=tCb3-(5zVQVo} z2pxFPLNDalfr(btq2OG(cpS*i?)?E1%*$eGSvam&}p`n2>=snT`stbVGvn^1Y9wBaZ$@uA=1szt@8Y8;$o>{h8A7Zl%{lrWok4YR%BhIz9*Nm zy19z9kYmUQ+hlb#X8-Q^CWN7U*IB;AWcw8fhwnyPLuTP!0CN|1HJbd%XdrvMR~ywY z;~etClc`!uKmB{H-=zB38nD%et(y*|b0}_C1RXn575nF<>+>cbcF_ewVubVkaheDj z0Qzn%-b!T-JPHo*Twq@zqylkb;a**;^2Uo@p@4N?(`TePTE?BHJ6KC3${h|L1c-jR zwl(zl608j}Jq04~;_vx*q$d`JHo<+hQf-(vwK1p@%^piUZ$% z6hzh}RkfoAO2SG-ym2ac7i*JhA3O_VfkC~LAIKx&4_y2p=KvEM*o)ym{(%RsXhkCt zlNou|Q**PEm&9o9W9k+oH>A7sF412`q~q8|4f6YklP$?~ERzZg8{1{}Mrbu{-z;rz zrhZ~*nep<@)?VAw_cUs)dhEcS)mNQNn~2rTW1g<#=MH#Y*?~wOIY&8IR|zuKq(K+B zmdSn{K)}O*9fOhU)`b`q#fZ_UDv!pwW7d|x>guQf=me-Q)G6MJF4X+-lr&qibwTsW zo1Hg!5^1%>@stG}te3g4mM)jzmoAqq;5jnw7FzQKS?C{WUAlZIF-61vUtQ(6HXu*U z@?UGGv-iwP&0;Gtj@)Hw?d?*j*s>P~52Yx>T^S3!+YuZuV|<=t)I@4L^5W8kqZIRT z^sW!h0S`DrAP|yHX)2y7Hrik)zm@JI^J_rFG=C?0M-#^t_nrjWN_df_dJ}eyF2sD&SlC+H_rL1|p%QcJyv0pH?px$Ne-YOu zz?mO;Fd@O?MhI#eX+pQnl-E_VRsOm z8%aSfx|xRg8&@Wzo7Un?6_h{uiiVMd#&3m}$wwOJ>*uEFW@GO1a4RPBk6oFc`c^A? zJC&k8p5mej#J`fVcJ$Wg#|h#z5z@_Go?F~TKyicT8iYqdK|$omArRZeIYv^<>vpYZ z)T+}zaQBmRm9^&Pb1}8Q&>uXg+au;@mjvZUw=h5e`llupMk zikX;^{?A;Z-2^hy#_#k`atDu5=wE*6^ZFWd*Q8C#c(&`wjdT8bO=0vNte8|{&%IXE`0_+NOJGcIP~Kb~0dz2BJcL{parDL9!pjcSe+ z1F$e-KWaCJ``w>Bwe3Ob%iU~=%~{+)aw)L{y-i4P8hbO$%yz-ShzF5x#DzL#Qf173 zRX3Tc{m>B_?nP;nO-$|iDy@TDj!SGzOWra2rkjlud_HLb@9>o$0^+H$-hN;x0eu*` zVu{j`8$&EMlt&$$&+HOWMQ#8CYv$Wu1!+9 z(M%*1_xMsUSy=L2(U*8Uh{PrgxE~mULHP;*`_KotTe~x_^H1|xKa@^7Tg$)ImZyLf z-T*fO$jwnpRBv6%jW#}mkG0|5`#etM+?_dB=B^jZ-ZApWq+QbRk{=H$JIz|3gj)u8 z$8NMte39b*&YhCbrYrm|Sz~Rm|8YhDYXQrS_(0mQ*gW54lez9xUKQJhf)wVemDAN;$8`q5h>Zx{|8 zv>uw4UKA01^*)8_-OkU$=sV(!(Oh}V2ow+NN3{auL@xHG1=OH~_pzl>wg(q!##Ri` zqYFrLPqfwMc%Yb^)Mg1T?|QbEJ+Z%uEJM{q2?#dcK~M4DNq5eUBDCZeHcWFf7i zw3HtCs6z%6z)s`{5aaw0WY~Od50_b?$NCALUvbd?fr77|JX*pc z%b2S-2ijI@iyyktq3$#oo0sakv?)S zbMM&fYN=_gBeK~c#VIfaKYu2#dg1HtUqq!AGvCya=yA(0QR)4pjKs%uJpRuW?LKtk znwnlZF*(FT76;l_ebHbBb{0ePK_1CnUZwHHa7HGbn=N=yP_v?_tVkcc%1(jyKkn*l zudiO2#WE_=znywyv~hf^X^rM7_cy(_d0$^D1sCc4{m^z6a*HYRNT50YZae%MoD)DH zGq=TEjBtqZ5GK_7#59}3Nu3{3Tc!)5q?9juq*aGdZW(j6o^A`Rz=SfFYD~%G<*+~c zrk}kZ>v48D13OvOGck3FSzd3`I4SQ|?bi(d_taZu`RTK8*l^ci#K`sY6%K=VQI+>P zccUA0l@%#uy7V9e1N<57N$2Oq`0XHk2@EtKhX*9?Y9tS!a>0qka+XuUG|N!6uCX>k z!vj)ji03tPcV{6lnSaHb{1Vzbu+~0+3tK%hy^ktubW*xu0&Lt6BnYl>upK@F{U;1| zHs5CYUgjHD6~Y~A#BI?e6Fl)NS2F0KCntxtm{dGbt>Y$r+m%)d%S#K_GtcV98h4VF z&G6jE{-Ya`7#lOipzclSqu+^3OcY)jsN@OIRM+gYErzy5H+vAXIYYa@;Uu)kd3ReM z+t4nQ&0H(ZVHh`dDNw{ZimE!pFi&39pf0{EE8NHyIWNrc*V z=%Km+@7~AZJ8-0Zbsgm((W-iFyL06gAtcC<&CrIWyyqKR8S&y|>CnRPq=3l`x0VF; z@c5lbpH|G;X}o+qDN*KPT&uJtx4kLXMf%Py`AD9_19RU8^TF>(Htm3V2e=_HoC+aQ zVN(nwQmrO*9n5A%l@&v9ATOJOUNS$oy{9J|Fv(Zg8_@;LPAO}jE&tSu_+BK3p-xmE z>{N5e!TULH)RtP>O(cI6P#6_O{)g?z^Py`?ACWQ2XGmU=z1HsVPS3iy0?Deu8MYiC z21h+3i}vj+bZlm4YJ9V^c~h6bJG9FD!KL+jF0$H)MucVFN#!EXN@=h}#n|^F9Z^N@>`k%XTUMO) zC5O?{?Ov)EdraR(;|Uyc@$vB#1!Fz1K8%Hm90&rlHFp^+ajt{h<*A$t7SYcl&`dUfE3)_JtyBV6|V(+b)Ry{OCXyBL;yf><1H z%5TZc4AT36(_!EEQt%V$QCdH?*Jvq<;rW6-a)#GQo%=FmKkO`6i*`UGEhY7$e4*-8 z{R4;2-AT_Q+-7REdu`!iN<5>rsk+E>m1t@C}3dSCzB$mf5?)GJ>6nSjAnmgupg`#v{$Qc?_LUuKUS65qy{);wTdvQJx()f?4my2JSeY;#LKFNmu{OCpO zEM8npjMDUUD!)<()RzZerbB~^kZS$f%HdPqv8k2R(z@CJ3rbe`bU7C!)`V)kVNtnp zLFkMuH;kwkER6os>;nZxpezB>l&p=LA1-HDZT%V`J70qQk8~AM-oaW(i+EB?nM&p; z{;|Hon?iXJF#W-01<|x+w|u)sDQ(^9Fp57B%G;6oF{Txq+FJ%V`amJ#aq8D}`9HWps>LOzRB21f@It1Q;Qqx%W1odw|>_K7yy3#!!Y_TttrYphXQ zNoj->YP_yr5@i&rWzJG@TtFM|k&HBC7`7~IujfBcx>ml=@(d7iKn6kB;$IR{sa4%# z_LJM_Z~3hH-JD*sA&icW&J;MJN1GqND*aCj(4Pmg#M+)7CV(gs&a&BBim`$>4ih@; zJ>k-;}Y#346r7u_)I&uXq-- zyMH(=8jli?XZB{==TB_OzCHt^UrWr{j^NgZQq*xjcUaW*MNEvoIhg}31#n`3K+p;H z$0&d1gE5uOb`=v8LXJdYPVKZBTi5iXL|_P`_^a%rU-@+K{0AVm0~tepzd?~-1pa+( zfTvdd`Tj!ERlmQ{ue;*9w95<+H_-BpVUNEh1ZFzY2Xg;z4Q|xyYK1_G^p?o&=C{^& zb2#MbEXszTSC*4O@0;54y+2VzE(cn56L9x2+4m@FY%Au|rqpWo-z**wIM{O%G* zcxm%B)xucEc;bq{xqGyKg~j8O_1B!jDE@zcVEXSeNM)h1$Ngr09EWEQi8al{Ar6me zaNq1gI^wu6jDqt7bT{tGOiL(NtjJ=X5%;ksPBu2jwMfL?r`tKY#JOK5YHeAF0wZ75 zOlhJUm}?XP<7RcI`3!^SHovVTFk|uQ79RYs}2N-(4fek1Y#_AXXGh#Hcsu< zrD7Sr&{XV^)zVdmdAhlklX-D!ln3`&ATc0QF*xKK<^dS517(3=C$|sLQPQWUG!Hb7 z{NSb;+PyE8yqblJ{}+^FcyRT`GZ>q?t_R(JNq_1R7_Uk^H4>tDYVwTAb*)+JEqHy- zlle)Yx5{08eMfp#2OwcZhmWbic36fm9qAiEX!$mdIfgR*XQOjdIso*IDUp#eqn|2} z;-1t%O{12i)*HSK{d@&}y`jqpG6ntiVn~0M#&1auyua=>1a14K)5IB=HkALxg8BF z|9qI@K0u^98w+Fs0)VFE1W|HU67Tz>+ttAqLM^gq=#(p_RYZQsj&5m@BgDvg-TUiy z2Pa{#K)!)E*;D?bo`d(%y}utnODA&;U2+``4GSxGU~D=kEO$>fvgO8lklCUh`~qdb zy8*>G&v9;weSzFgTE*D4V`IkJhAc8OCKJ3gn@38m0SYbBE%a$7R}JTi7H(KWe7Q@D zmg7on(QTPA!GNCt2mv6Ay2PU>;B}53jrL3ubqx7Kr=TZ0@T>k$PCm6w;%n`v&5+BH zmE_9SF1K=R$ZMez07d?>dPb$EUj+|u&d3z<6nwtf?4VQGX+;hhg4qEEX042aiK-K7 zFh6kYvI0&41JVAu3L3=XxYH4`{E{rZL;091e1qGPI~>#U%i=sP8>C2g1s_1K4aBu@ z?*M#?V7Oj8`06$<>N@$`L%}EIwu{N|^-C{S?tZ2w#jvvk=@m{j1#!q+?yY9EZ{86d4nxoyM$^E)*U|q7!Mt&u+c{-TMF|p7=*%r)tK*#D_zty4&PLdGq<- zJmt~^B#rB+!G_6!rNiIddAHELNnVAe9j7qgYCmhmgG(g4gSqOxs&e~mCeB$`Sp&h7 zRYCd*heZqZb01$ykWTy%#7bPYAL+OxYFlbJ@Zd{98efGlM?ul23#aI)(IjxWziBjc z+mAQuNua!jaQXGf-_Vqm07=C%qCNcy*^(!U?BB@TOCTiqJiddn+V;M|Y<_%OvfIQa zMbvE$!Xi- zuS92?)~PP&ZQ*-*Z7#m|0U*iM)%A|k#`0s`;z@V8@6{U{`^kGGzrB2+>o<4ES;spY z2m7OgQls8x-~jsc>64P1uWg^}%}o{kt6eRH^KFM$5(%YY!35Ks-oj2RbHJolzPGi3 zNm=M5?dYJQ#JcMZCSRX-nfpVu@(e9MuAeN+DMMq*U!{7LwEEsHLnFL;ebzqd%o)uX zJ>_rLSs?H}jB9HS{>zWhhZ^(z^81eGl+Y+keQY%i`~5uUGO`zU>ggNA`(azlm93%s zbV_=Z6(!f-aidEzl?a(DIYij|HJjZX*nhZvq}&bf3psuewz4tXDpFl^u%&R21uZIR zV~6u?pM>R+K?(T(OwlD=p&wn#pX~XLZtqnEW=dSo?I!+$Sg{Az?*`yQnQ{asp)RQQ zJ+cgliIQ0TH{4WXjCrtm){Tb?9!EG4{$9*>x=Gf*@e=zE^ zktFZ2T$iM-asyL@Ol%`KCEy9MuzsG#=4ZvjnTpJJEghRySJai`uAB= z$DT0$^k}V+fSK^@{2E$%h~*RQwft(gh2&vq8%w2|Rx17urH{V1JfaF~=6Zu?-Wjd$ z=kN_#a3zo2X2TEeey-%_a~ERVT#3^6%3ogSa8a6gl1ze%O@7n~x{8H5(?TDKe+TAV zIla#baq};&SbqHtqi%-A#zKh=)SFlQg=; z;f72~O4=F{i+jjSWO87-LDC#POEnqbVRvTe5sqP9{avOnzSqXW`kj8Pg`IPL$8#ob zsSIwkQS8W~7;&raRgm}$q@;d{H=5<*&MWIZ8T`DT_~}zijlm5j@;81#Oy{Xr0;FjU zY+3mkJp!-O`c959>v7~;zY%O-vdBJ_Ae`IUC2?W0QzCdk>-hR31DsfuDQ@!}E(mWu z^Aij*V@5X%mQ@b9Je4%E^;g^ek*J+@6LoX@@%){`Tkq#C7F^jG}e2A#dOk^4_io1P=xr6~W-OJ4tvr|*uZ!vFri*LEuuMY38} zLPlhdw`g2@XBDoMl})%vDkU1^;@W$!aP7R)u(@1&r0i8z2)}cCe?Pzf-g)=P<@Gw} zJfF|=Jm(cDa$)VZ6Tv&d!BIUuhLekHfa8PGME5#MihSM%-Aic7`6=Pr{oYFD`o>TR z`+cosxx;Ju!7F8z4N)s!gQ^7(-X^j}&EHAaBBYRg6e)p&&kkeh$#Kqj1NlWIwJHUZ zV&(+z302^GU8+2M-pa5NJ4#2Eg>IbiF`NrP<+Au5Z(sGUtz4v&pfsR+$3R0_TrbXc zRH#i1ZXiA>F>#Q*^%GW-!xKYxj9hYVJXveY@AJo8M!tOcc-S7iHDp)0O@DzgLKW`A zDj}e2{>y8=t$fSNbj~ZWaX-k? z<7{3_Pdf+u>UMyvoSY}=JOi+yAC;MIlt@BClytcr)AN0mG3mfg?K@GPuchyh7At@F zxj?oeXT`W%0l&WAxa@UdkA*FwoPm!;Tb!L_HdFLAWxa%Zn|O_*w4rc zgVb2?+Rb+Ba#jU063? zm)Wsu#H5&1zU;jydo|WMa|h@pzBd*s=$j|}-oJ{EGD`9`%eTbY9|WX&v~p>u&065ctka#Ln;qfBA!eP!_JirS|K7Sx|M#+?Gj3%A9_h-TLv zKmC_pxu5+lr2G`oRQLOlA+@0!w(N8A($a2K8gNsv`Gkwt(_`cx{_g${AV73Lwi{~< zo(S4V=N{_miGjV?K4EBHW~gBUtJ{U7MUz(-R)tco!Dgt&i4n`g#o)0rp(9PdXdDNI z2scUSZFL?lNZoZT(c$Cu7Bi!IbI3Ug|M@+jlMrgMA=v8=A1~&VXC)g&r!ggW*_zCB ziCMjPAL4t8f@E44+rnQSxe+Cut8tpn25=SB$NEzv4;6gasw|2N^8_I?KTFHm$IsS~ zE>CMQQ#@cy^f8I;ckG;xJGJ4Oq%{LA$ia#I+F;VbSmU10-;77DXoK8`KeYpY+ZMAw`|ZY6zL?ATjuKoB0k zUV0$Fe*}_UL{1ylq`Hm#gQ03~ii9P0c)L1YE^?f89$Q6k3MaXCy!TgB^h+1_N@^JU zE~oDJsW$)j>O1mL>}#|1ywIL|oG~%L_hj_wW2k99B9m5=t3Q43PyZZbU}Rh#uMgOQ zmnA-rS-=;fqN2z#0vT<}%~wGBY)NkO>UJvpWdnm6RjTakfV?^|)=&Z!B?E_RSJroS zYJT{w%y+Ed+(wv|XrDD`xXNC(o?BkbldN0vN{RizhIXp9DBkx{D3&~aqgGv}*`nC! zR!H^GeaEh9sD&fT1DsmYF~n3)H#e)6scvQcR~Hz*!}DO2qPrd3y|;eVlnFUmz1X$+ z6W=upkpe*1M2BT%k~+mbxdSu3%*DYm2nO5^+mGU?s<F5rII|%bNLUGKm}ke5 zmirbT9(Zl==5kV|jTL-2%}vG`+_=AykkM>4nVW;Pg!>4;^UG~wdp$3MY(9PZ1UkAr z^*8u^!wco2*g z9{Y`k+FxGYbY4^_0`m3{Uh~ z!bzr=o_)ZS$CH>TmvUuau)Iabk*Nh_mf~W=OWcc%f8q{%4|d?T!%qVAr0NiJIHmZ9 zc5iFMwFA~gnG`NkKhe#O&5|Y#TV{0HxUl$6ougWbHz|xdt@{Z#kbNOAP3EiHhNP2) zW6~|a`)`iO7b9!|ijRla7VPXsWFfIcth6cJ0yl73Uc(ucDhvjd~(?Hw1-i zeBKWKBnWW2ezO1rCqO#|IqC~X!d)~PK?!$Ngx95(=jJ{`wtV&ln3|2DO zkJ7CCdHTj+Roww+k$;Nl%;F}r(bAWX5G$WeW#4??F5K()>%hN$OU4H3L9c{YN&05j zT*L=9-BXTV6^5xhk#%l4KiM_;7t-B}c?;$t8+)(}T;bKdDCV-ToRpj#u<)@=$XOvd zA>MDSwWURsTYMX1F_)b6<)X8T4$Hu@_wwrDexoa}q#&?v4j%sIK5XHV^RraPk-h{>o{O4H=f6h z$$C~IY%!QU`29u4*US6F4=q2IEl#WY5$kUt>b+)p5If}56ybC1w8hNTfaHKF^uVvc zrqabZFY^bk!vm3?uRT0Zy45-_GLdht_S_6h%nsy^jpBp;#=QPN!!A{Zv6%)2Ka|ZJ z!(;CKwEb|FDde*cA4P9Q5m=AjPpmpunwprz0?nIgoW3B?);q9Rnf-RjQ)X)s#^bgo zo5M6*+5C$I+j={@x|~JX%yt!;=(SZ)LUI_RKw|&A!`aBRwSYc5M~^Gl!){c0ErZ#xz@>Qc47BO@zYzS?*=9^00=4-a~jYbosf3x72k{(v6`QwdC> zU4;SzC;)D_T$gr#upTtjaKJP$Cs=b{q2W98-_(Kqn>sE~+mJB;P`2k};`3II52v=D zQ!8Tl|&Z294eD*$YGz^Bp6To9Imz{2QU+Jd*{^&l| zeF1mw$GPoK0-2T!Fop%Sno`Q~ZcNtkC)bZjEFYO?>cEF^o84D(g>wf;xQEIKDIO@kKg_G&Vb^d5`j1rJG_?+u?bwZu(hhJ zPf5abg&u>S^KRio)?PLY@C(0?#nbk~-<)Z3+;QHOUJ_=x!ba@xn>@USN{>j`QF5br#lAPejxeDCt#tB&&8L;wU zY)yt?!@LX7u97b{_g;VbF8@;4(`d6yKM!sEc=4u_;S`OY(QyWKT{bf4kt-rCnmVdZ zima3XMAxSA4b3m0C%K7Ey-O=b)I)Tb#9qsxC~}|Cpr!xQ_fv3b!BghFY2hD>F&7fB zasbZ>Z2&k#i^g2`c3OXaOcYb_$_KSv68oU~Tt3m6K}fNJdpml+Nb+ zF*T#HY4pZ9HVin@s=i42aMrh{dh|>B7$Eh=&7>-`UBwJ$44Mjd#?AGmbcG+2b3COH z=pg(XVcK}|Ih1dR0ek}aiDdO*{#Wqf>R}~dzr!`|162Sg5WUA}D1jD*&<;Ax!drU5 z$t~c=gJrQCp)o2({WvigF=x` z#9i_IG{QD9=9EjB)N8`m@rna2{*BZ{=M3w*+f^4456#)KhB+QOo(VX$)_8f^ms#?Y zFDX?OTRM`nMn5S%bb^9s@!}9m<|Mp5$0?ynl z0_8e;{=4{+loj2iQ;nG^e5Y^Gr5k&Jzz*R<7x1GZgbKDnT>E(Mt{;AHH$EQtU1!OK z8)Pw}J=Nmm-bvq#k{26~5_d4pmuA?QK9=9;I@*nPdg(rZFj)$mWJtDkxt5N57US)! zHO1@<3b`RAmE@GM4$FbeTFm=r&u4Ci#b zw^QY7A$s{)cDq@kg;@L}&S7gTKu7PJwR%19!$df4rB_-;Ca-_e&q(IlwNhBBL!2k%w^7h^OIz$1dO$mzS2>IR$8GX`vR#v(-UB@}qq2mtg$x;NdQZl1wJT zB_%`mfl3TniI#vw4Vcwj0`34qt^EIzE&u(32ULp*S zH%~?fXTdEFfmIf>`O1po^$u>YRsQO}U6V1FDjFf;7nS7;=%MX2c74>Q8{5xu(Aq#r zgWofblGpQS!8PakI)`VlE#sFCRTIOkYCYUABarinAAmLge`SbpyL*9L+jUog3n3n%}0Y=F; zBc=A;@RE%7l8jROQcJ`=k-oN+AzRXDg+&Fv%8T*w_-+3c3s(IJ1FKU4tg3KBHqKt+ zG2!1hrKar;kpqbC!VN&$zTKxjg$9T$WETh+erRYY9+Jc! zjDr;l-2(9=t1p+fgf%jpvXD;;4{n7r0PHJlX54TOk`$CKC4%pymGf*JIVHHE122xU z6QK_fZc0_}u7N}#G{BV-d!nmgrTwfn1NK~sRtc9w%AK&q(brB`$_*{#sqMa9UDO0F zcd%mS4b31DgScXqGH?r+>Inf~ZG@U)O>&l>Udop}lo#9HLxtiOI*a^0B3>SX#yt{2 ze+sr!(5)$*(nZ$wbIgu185LJ!RchK6L@lNv!QwbE1O*uPhR%4x@66Y_cq1uWPQ z5L<*3-1r7khVV%zd)>F%C3f6aDrls+d)!v-^IEEBoJ2Ai?@N8>g@8yP2ZeNv0@MWOgF=SQjdnSo6hL!}<$515FriBvR%9 zWH_iz`m%6?hX5H;PC*C(SdX&|a%kM`F9tn=*y&w<_4K5F?U*Tk7O#1tx^>pK)A0`X zw?=f8nyJy;IfG(l@u)BpzTD+e zoE!E!KTlALF^A#&sAY8#;%NpYQASNo=Uu#ClQdcnc-YfwDE63mlgo7N{%%^Mrx20w zPTl+o`d(%_*Gf}KXuL|QM^dm+bZ*>AJramWc~CzTPI)txSxL=Yq=|Ju$x3dSU#{2l zzF8N+9nDPT5KQDuSN8N8w11{N-0SJH@LmN~x#5#^hlk3#KOlb(-Srw@(}sQBng2nu z)y{j0=^i(KM%_`3ISxlf9FtiywXV_^f61{hv*JDM7F*;1!rHm3v(vFjjYQWy@bJ_X z1y0KDPwk`VAx}iFYmkvut3s0jO*iNO_-C)2+@`#1&5JodvpFz!XE$kYvj=;=oK)$n zh{9T-w?F&;G(o@3MZ65`S>1NB)9oVNzq;<345}ZGT-QHA1NFUf;{MlLr%PX4KTmE3 z?88IAn|1>tK|hZK{P|r9jXBUwQd98x7jD4Cl2uUHntj$8r*KQ7irv3Q?S%&_VkYXLFwRoMSy>Tu=V^v=|%al+qIK$*wQmwZsHM`?>uGe_K|oT4cz4Mi)O@ ziLIw$bw7c$X>SL!`B?4P%8P#PJ}cQyb~9Z7KwrxW`Wq;?j!Tc-zY2$3%MCoxIQ&jq zJ20q)yHn2)sHq3dZ&eAZp$i+VtT$d=fQDbk&wpeQVicq%3W|?J=5HRvKRqlFn3>#h ziRE`$fArQ=m2g)i7QaZEYolD=LZEv0eT3PffV|a!oxE z$B7|D|748iyT-Or%)=u3Bo?7xvH{%oeWT3i?4-~rUS9*Hk^9*-*HQOQZaC!K7%P8> z_xQZ&hbOJ1PolSXY+Wu;zjkvk_gWVm0M=+3ITSJ z-t!q?CA6T1;k7b5z?^u6Ku37(Je+i;&)w}{^XMg^nNiV*RG;(5iV8)L7|d~vBjFYq zK2u@@7u-KAqM!-5ZDt9VV|IUx{BnJmVRn?jTqR}wnpL~j+IL;t8W7Wy+B z)aVK#5JNz(L}8#c47U$HsHuQ7T|}qra8m6qnH`YI1)hEAqlfwgq!V}teBh!>qh_`y z{%f4GBcNJLN?Iwy(%SA=b|utNmZJzRqQR%%9qo7TG)@$UoTq*c37aM?r0cS>8N~n; za{L1wC;BP&=F1rjyuJKlr+6qkPhz>1T~aa!C|brSu;=;F*m}?rn(z&xiXA)^L*Zv4 zembG9haSW!U!B<%lX|OiI{XQOj{4HV1*e8q1)a54E(aOBL{9O(%^y>#=Le2=aNn4o zq-g7zqtW)+`=kvYl$b_suE3cDulRQX;vT-(OL_FxCYL&k2?rIH!$z$Er|rMvvcj}E z|3NE#k_jQiL+T%k3))!=V#hV)XF0(wddY15bVCoFqC#QXTLAic+G|i7bY19m&eJUcR3;y z`6lu|=ynpI8{sUO`hgngd^Mp))d7kx(2xylAh*rU<--b8S8~(UCiN&=i8;A>d8Z~X zKDlkqN71t&bQV$Qf>1h+IFjr149lN8L>DzZ%F_g>YRmzN&?A|_HU>8JwZtY-O~ynq z>=j)fWCl4etbVA^RC-A%4ACrh zjO*HGlAH=92ByVm+iaPXlC0TFNC8)3X9jVd!UIR%kv!2o7UI;Yo$}VH$q0UG4Vfzc z@oSfGTd)0GL)FHDA8O93Gz)qZc%-anI_F+FayB? z(HzLXz!r3luI01~r<`h@g1#S8hv!}B$zxyhWS<2Tkeq0>Dw-=7PV`hngf*wo#1I|+ zi9T(tie;M(3#HmWGy8(3^yI-5qUC9paE@lSb<0#q?7gTRq(qF2P7-gEwD`J=8#@v6 z5SP`{?&y@pz%Xhpy*fv3CZ}AnHn7UV-ZuB4YVz7Y`A^QJr;{FimovN3$QPkX6ho*h z)rLvlh+bZM?YYce7QYUnFIqa?N|l6ejvlx?En}vJHvU|>P-e|_(kl0ow(>K=oM+L7 z{EYeCsLp-cXpOU+q=ko)oM@Q=%rP-e#{F-0;p4-G9&!uSeE|*=36)_+c&)J&Ey zuuqrAA-gcioAGHWTE&e=zy4%joOpC+cW3601W8}9ZDKT{JUdy9aB2Z7Uh5mwr@7vC z1b3j#d4E`>GmF9=%U3y6O|vb;V2Gy#K{v_1;JoFdZizIaPv72851?Iu-r!dkYwDwr zJYsq9!*ZBp8SI>$o!xb9q`kn=z->mS8(SJ{ji}*`Hd$gn8~wS1-HVfE%P!Sd|G}va^b6(OpHsHACMas!r5s z#W8%kS^C~q*#UHrW*ZPGUAkLmyJY2O36=?K#vyDZejA%r2ibOI=C%3t8^w1mq+gpB zw_woXf5x6TwCrtReUvF(`6o~cfv>MF0E?HOY?tfynM~g@C;byPN3}cu$xYfb4o_IB zj-yF%N1nKE=$2j?k4W8MWYchz2$y9ywi`EQZ0-6ZZe(f%awPCs5IPDcR`(7*_`&q< zeb5mA+!5}KvJMVAR^FH6l6}Mm&b{--*3=pcN+6~&FfafcnUI1&AQv*8u@}VAyryked&$-O6#XIo#lI<^F9pio?ulz!o z`d!7y;$~fOlPJ3M#&+IePjkDBkaF3B{oOg4uEVNY{OQ zcDs0&t*#11DzbB<7+i8cf0hD!13DVCnQu7+Kx}qT%F~B{}VsqYb+n=k>e}Qyy@n6{W)Zet&pU$H9HUp0rx1qK<=E)?=ag2~TSC@FMEaPWgmwb&>!f4fjh{Q`MW+O4^Zt%SVVs4Hs?L8&P_Li&T*o!VZ$KjrR! zklar=;BV>==%#Thwu|U;52}&cd$X8xH+L`oJ)msU+GIT6N{7>uROhX^m4&>NJIq}C z{{(P8S<8w(rna`)LR?&VxwsP1X7$d5oY*~U`wQ-PbJ`8ndcIZr`mxPx?at=JcJOY{ z?s0OWHzLd3bC3I}#OnsAbg-!U_w&-C<)%FPBYi0sC!b>#Lv*~1?G=gU*Sk;Ku@pmK z`LH_dDxej!ny^ZR1iagYNh`4HG2EGBbi;_URZo9iir0I(-Hxwu>Xq13QY2k6K7Eu% z;m`p$kYe@fLZzgbcw5<0%}(7>BEp7AiHg4x)YwYX9bcpTw~dMk9ZMi{Ch22lnADZ2 zMVZ;YN*WmW`AalK2I2jt)~l1}q!wx4>1d0xzaalbP`p7^@?itH7Rco+Q^d2PYm1$A z3kMiY@O=RX*r#|>BITAfKW^v~lZC$UHe2O2*&C(WFYx7e!t5(~#_Ah=8@jXX(X^9k zB{5z<>^don^ZOX2E|6fWw^lx?y>}grx?ZT3sd;Th-Lis)dz$PVHU%|{(inz8Sw)}Q zg;5A@m1WK9Rh`>P3glk#U851#I+FR#x?Wg-aVXIeSI)-JXs4Ew_?~o;Uh6cm~bU?!~#!OSZoy zbm8`mwA*%UZ=2Oltd5yz9IA5TEm+nFDCs&4rT0?DGR9c$t0Kpsu~Et^RmvbT9Cy6w zSh$LhIYJ<);pXZGga0XD|A)&Q2bQkX($P8X^HRK7prWvv{0+}3J*&ymQ`b9wLTNxL zcSyYIRA)$*s!9?9$Sj*=)2(6Q-8fs5jvJC346u>c$12mo5j-+u)Ywv>Xkdc2mk<+Q z_rHyne(<)o=(MPzPnb-FM1ST0iwe~gG9+$ZkneTTaZ-115Y4xD=1o=mL9SqNQM?7x zMTC_C7Q0Cy{Xm3TxVjt42}nW?IDbp9*e(QJq(d{q6 z?&seN2_57PJd!wK{n9~D5qo0VU|WzhKNzA;n2=1eS^pCws6Q5sI>7B6<;$hm=PjZA zeTfc;HbYnc#T<_UOKolYkH3voIi5T;O!6gUJ-?9@TszhYO_#1qE_&g?D4TvsZO-bV7`s@z56RMK?}R(j;acBSxDAWlx^cYYbc zM=Y+yBkn@+S0&{Wg^om@Bu965K3VMaRMmabJh9+%rQFm}8XcI4bnyE4&YW0qR`hw; zBc4*4?;)q5fZmNAC}C%aSV^1ru4Opy_8^xMbkW~|ZnN5pC|1^02eFl+%wQ21`m9)o=N}by&CxjMTZi z(_mLb`g2nU%na5fgm&#wrS@m)>h4kpK?S9&0hS?j>-katpkcW>FIsQnCE`t99*3xa zC{1XOR-s5H(-}6^VahZ}*C@&h7NEypWrCrzoDktYbc#<)qhjech}) zmKfGoGaw@8#%<<;IvA9#P~NN4lwG=%bjfS`iVtC6qiX&^-<6*h{GR4xET4V#1|M&^ zb|+UQom=DGkO_QvWtSI>Vmtk+JdnZ#mtv zpOX(u0q@Hs$vk>@n^%&y)0XhHu>X-!v7n=sfUhz5&pkcAEB~rO&S3dFSY8T-d&Xt{ zIsdu9iiY+R%rk7WN`8Rb37vDsI&q7pGbxc34-qIYUu}=@R zw~E@=VF_21lBV6D6zy}VaxOLgT|>)rMKRH7G!JDxSM@=2AbC3>I;KmMlxRNi((Ysz zKl*O2rJNPF{WB$9zg|oEJ>2^kzjNUQp{*`ePPQfkJg&?vlAH#F>(ZC|hdy$Ma-(|R zi4TO%Dq8DCT-m-_tAWnl6zn%S!lthdoxt^tXuyNqy&7V?c;}6{s}+ya2yO}UmsL}J z3P%tl7OW*>o?kz+&c8<#)8V0~+}*J#BfvIcxckv94-OV0RR3?y{l{N9{5CcZj5&~; zoJ4h01wj`DJ99IBJ^_Y!f&>xU#04S*nrwl?{E$ zSY~zlZB-Ke^Ap;_ZM|fS`)s4!RCb=w%klyM7GPmplP#6(0W{r{pS;RbycO`u2K3-Y zk5T<*V~9`)<_`W-N=cW}3rJo4>|#;TE6B<4?Zn5`rek%#|wKLYt+Q~P5*KA#9PD; ziu(vU(AwzTsNE>+brB#SbDk4CN^(cA0*3a2&#jog*@S%{jgYKN&eF40u%9Tf=(-hx z3Py-PTL79b*+z2EEd|dQsC!c}S*zBXSlfzQNiw?9-=0vKP1)#9s>&|i**b}(_BlPN zKNU-`F|iy=Zoj7J;XSy%>o-GZe`A6i6m0#b9+)nCAgY#lTw`Bh`I5(z^qBfKyUp?4 zKfU|u(>=4{@jHInKAd}ctHn_OP3)jWCRx%tPFp6RO_Fg+oP}!OqQBq!CYiT>6ZN2VP6V27z z*?N2HiiaLPXQ3v-M&z!g)jvs%dbfHuWt46$UN`Tr0<6DfkV-vC<3qECnDPcUH5bRK zrwnx60IkwS8jaoQ!^3~UKtt@7mbopoeBgh9YXIgbn1}9^54DHwAz*sR3G`i1QOWI) z+8dv~22owRO8+XjHD7g;d-eW7<0c01>2bKqU*0i&%v#W_dn?G<}t_(PuJ906gyc@PaGR|su}^h;pDtnFWGUvm;FBYanQx6NEbo1?<3mS zVmML42tjkW1?+_6)2%oDPb5)1_;ff(`3y(#!u30Iw1GO7&?%AmjzCSvwGK`Af*O5< z9hC;(>!-9T^!Ixe9M*81F{Ga6<`CM2b-5}q?vUqY$bJWy26BAKC0_;>T}a|Vf2O%d zVA$Z7nR$L(u8EYo)3;Fxwtzl~X!exrxFSaTkUL>}wk8-pKE4J^3rT|v3Z8K04EcWz z(pS`ai;&V@tEGo-5)@wT?Tg8Pk{h|!a9O#vA7P9vlkBXbCF-2t=kBJU9RzdiHhW+* zwVJtj3IgdLdib2On-XSTKA5XwW{QMnsIt?C#HBjGP5_D<03hAiSE%S9y~yVi?lKN2 zwE?<0WyRBtSsyYcOlu?c-{4NY+WBTT?3ASlep+ahE_=&D-}#5^37H8iu>2RURAT)@ zp^++K<$pA->iQl17NpJCZ@iMD6`_MVcV0J`Y;&>^1Bg1We2_Jr2RBrgcl;6E8}iT_ zWNIMgdmDXPoEnMA$s@3ixbX2%zJ?QLe81kvScXg5dxjK>>@FLzp9tx7SO+85)V0e` zWgBS8+nfB>)&Y8>TyrFLA4uMiu~x+wqN_eNcgyu9F%Kchb2^va?>Zbv zAJK9)KD&vDpDN><47EcC@pZ>U{5B-gJ=nZ_&5Y72cRKQlqqA_hI_lr~#?ZS1wee9p zdcd5XBwBaIgh~vUe99pGvZW7CuKR?~n0V+;Ny_c4r?~4y;NhzJpBLcIFTe1Pj*XhX zfeDFtJ9{z1vQ9wzRA&V_R0Hi%aPDK#2YRHdXitv1;)!gjQMiQ>Ax!H*)|-j-at1xuO}^cm9!XMc~cZad3ykwvy$Wa}Vf zwIUoYZBNKWf|h%5X%JKy@RDWcg24oeGuhLRp9N>OqvSeW2H8++s>mVr*S}h&{*vpO zQYwahmC_d6KoF2H+C;g%VIIPuDcTCTJo}V+p}_3Bijw$Xi)jVyEkr1x z0>QcDpgWAzC*HV;GBmSVF#W(;Wekswj(*Ipq>Jana_`gRTw+5O=^NNW+kf$858p85 z!DP3!#cA4HOLsnpk&QEM{hkIr3iCE0GK3&dMjJH2@sRuiRd~`6N!g!D|G8g3yh#Mh zrAQfvHChGJV9=$?QbSc)hG2|6+LL2 zAaQtCjCr=^UV83DoISCA%d&qgdqwSF!0Tf!2egIAY({&|d){`XsFtCcA!za2?0#}X zW6&e=ms|eMEFV@UXi{OxaSr_9{;RH$nJKOQrkJqCJ?;!0Iy>cBX{>gT+h~ z^f1nj00g6D= z>6X)po+SF$dk?nD%qJoehqz5wOX+(yhB^+cIFajEo#F0^!~*1+;g}l=akAlxE6zpy zzfTrg^h6VIaS{fo|oho_0enPO?uQ zJ}!*u?{Aapx2;6o>~J^xBrM(s)ioFkIhIJE^=L6fw)53R^K)*oh|3x}5gys#+A}bK zAm;eBW@=zS_6o2=tz4{j>D8ei|nL+|4X_?S{bVY`jXa%vE zn4AAB*OlzhBcI~gUtE{uiy9{nK$3kr36fOplbw`g1XdhRM&UgfqDQKcZ+iB6 z)q^Yw4HbAhKY;~sKU=d3FaY??Vr?1ZG~}OPLr`B~o#HC1SLqcJHlUS}zt4_6KqJ|p z`ZLyB$;e8tabmj$;c|sR;mA>H1}F;K|CVOu9-XgJ&>G?f>E_%?t1@nQOG&CwKDVT( zZ@!w60g=gYy;XzzwA8jbR-;H~mP_efWv|5B=lLegdd25CGiCl|JK~gwg&_c~0QSGZ z2jC}=z`!qFF1suUGBSi+7TIb?IE(xuQGarUDYUjus|k;twnc;^gqy9=epw_Zc|nS4 z9L0)3=sT)A9qmahRCOW#n3>M#ygVR}WY>ELfw|p+yQ#h)naaO7R9|E7SKfB_dwMRX zujRbjzRbuI6*Hre|JGSZHkztO`d=?N9T4Vk%)XJm5*>dnr$>Uk!#FRmERA38D#BPPjk70pc6;y>N6@*JPafDhxtWEP!QrDf(>*Mm8Si@4=D2A z`RG1-h1VW4UicRZ>{-sh*=x_lPo!v=qPH#v;6wzq)jQh%#NQ4mI63V)um@8)7;6xCyGWY4yu9{P^4^kgYVsvQDOk%lM(69cbT-pH2 z?(plXn)Yw!2})!<7P-*Nv-Z#=7{N|*k8#+Q*p~~oj1_ymML%3+dKm~!tQgZf7)+Bv z!>@VU0St+d0h#E!5q0OnEnyz1=tdtAHUfaf#QzZMf>0Z#(10U|I16*DeF|m48c6zg z%iDY7eBp9R%qwjNBo=q<=}zhrw3GOh_q~H$$&VJa1NJg1tvQ=*2u#yu>JzxM<7-(_ zvIBf=Vm^UL8{$do`*w}Ue7E1A6DMaDD;?uu?6$5kgWV6aAw%MmakDk?{Z1wVR;ls> zT}vOrKbrJNB+4DKy$qFU{a2yS)DFj`x0o6qPYSnQMralsA&CWf6_*Cd1^dyI2eZ(K zy{s!LlGzg0Ec^?a{chguty>R8H$wxfz|wxrzx^)eM_e$ zK9?25Zk@2Z1s-6naoVpZuk)eOun@G0Pk5-J)!C3d1}<@^<3+ zPJ)SipkNo}j7sy(Slgh-A(r4wfZ?4W(CNwJ576`m$g=%b!6#=q%kBAgvO?g(x_pu* zjGF}ret>0;w*|2ni_?tT>B$AD1H+Uq?z~vD_K+d9uj-w&*ofJ4dkJ3CK}{xD+}5qV zPHBhNk^^sW4^2Y+C{^-a-!``){_YJZa}B96O}{neY7)y(_xl`0$#eM+T!G?q+OZ zN)$thN~pnvVmD!A*;I#xA+h?gzm9={eB3#hwk6Z2s~Ts>=q^StE|MmVK2OTYSV#Pp z-v03m7YF~O5$-5TAk*O+ac(f(Z@gU{?^aNE+f)jrp@OtOW#~~Gv;+pufjw;=m3-IUGZ7DdbCl5 zUANagTDy#+-xV^HGdfwA>hlDX&#dIT=uW=O8kw$~p0?H!(a2L8NP`^`P^NQkB%m}- zU+Oxyl`*8|XzcZNVU{?Rt#n#@@HVSPfb<~CQDpRQ6)b^%Xuau{nHK7~G2iZuWCzt` zzg^qMGdr#W=F@nrYOAWFT0;)DJSNDgUT*8m+AC8p?B#(|#si-3&#rU~@mul zyiJJnZCzV^9R+?761k|6PsOEioQD5M$tiN#V^sT_9CgL3k0Sb-va*)XDLHw^v_3~< z(73thFiGFDjii6`YQZz_DOi!oh7_bEA|FNOb;@zFYnsFn#* z|86$Y)w~5P-GKPWWxU`j#2{`1x)N`9{pv!I>aK21D?j^dgJLTQ$k!APfO(d3jH|!Q2f2zQtw5-y( z;Sb9HIxXC!%o9k|F;;1;C`x(XwrVPJ8+n2BDoRT)rI(vpY6(5YXVx~_*9y26^fh4p zFiQ)bZ1@!LE#L_k_L2|v*|;E4=8U zR;QYJr|8E6lUteLiz<{=RARZ7s@)Uqa{NwP1;WuXrvN^-91q1&c>&huDKV+X51=)i zkoBmC0Y-$c%hwSJh*Fx$3H{;6G8%4=_}38C_p9!}usefob!^ksZvL)yTma=~glNm@ z&^sCZjrq9zE7xkh+5_w;bYRkP*=+qI22fT_fTF+G- zDZ1G!eWc(AcmrV4WFMLiZ&)O6cyfe)+6U0dqU0h)`Lj4p@;B7DhS2 zx5UR00Q$go=!bt=kwVS6t#t)3jeLGxP0=k1*(xEK63UtAfe@bwkmG_SComW1lq(!x zg>n1`%h{<>L_LTxF{E^mCPjx%VQ#97J}{##Ie+o|exHn0!Er>=PZ;6=$#CnmxfV7Z z&)oS;fm9K7T2pSnmr5yVhbaE3QT!oZ{Nt|US6wr^7{|Y;0`TDq{kxA{aRMCo$YHgc zD)65h44(Ot*PyQ!6$j%26d+Q4kCiym%#3mYceej+{52&c0cN3j`(gN>XU^7Nue#r} zW|X&{U%M@UYMOq@(L6;e=EF6#DqS^yTQ8U+xM1!9)aK}Kr&>-{jJXu@qsY1zw^B8*hbWE(KIA>DZ~GnQXo2o-zf3%9GOc}L zQqnb^W-z`!l_gZG!~Bi$g_McaZE)rIgihHb&r$Nn!vpZk+6;r(b+sO3<|rI33b#hN>i`b`1Nl;w6k>8{f8Q9mV(LLKVQJj*HZevNZ{>qncck4itm z3WLgu`~IWv^Ica4lV z;N(23s5k;*))xsWLfF4+p%ke8Q_0xP+Slt08)%R9J!<1)VP-F@-~FqK9hRB;rF;${S94$9asfH-qVd%GHjE$V*9kvSm~7 zD1DonO05mWG9s9Iul4d#dlT99qk9)OIUXS~_Kb5`D*}nvi6v>y*r!>0!23r&ym+Ll zrFWJ0hHiosx{I!4#HEV7yeay5kiDr=Q!HL~l4m`w>#Dd1Q$dt0B5J^>ujcOI;+~Qa zzMRN6%@|OZCkVnfj6F>cpS}hf#Y=_V&k8%=nL)28s!=!@H81~89DVjn04j5Xox`tb zyx-B_)_RWD7vI*Bm)Lh3A(FlRR_!O3o$fq8nbW#k$}K6ME;GwQwZ7V8YpK+|@oI|q zFDD}_)cz*V{xzbuih1xi4q?`j?2>;abB(uN0`Q3hh z<#u#C&Uro_kLz*2uIqlkUkX3ec7k)y4Vu{akTaa2#8-*)irGL}G@e@63@C{T@wCfD z{5~Z3Vpk-f0e=B9cBqI05*(oGUmJ6p>xly-(tW*hF7VXC1=~vCvD<^ZXifD%fdLL= z*;S~!EVwQ9oJ)T-+`w_EST2v&(k0a+ZH{iUxJRX%+55CJPV(wAsnBw22s({oj6BZ-?NHFs^tpNAiW|o&6)h`1L%1=i-cXU?r?XQ9_ z6)XUdeH`Mc8o4PS?ZD(1PbYx-Ow%?5)p)0z(O?oKNo%)6V1~vfxaq!jZl8cD_Pd{tOyn< z{9Uwh6#4{^LQV~V?a3u;F2`*2djxArEEG^+slnOn3EgBxt-g8{>8L>-Q-O?U%uRZV zxtG#A)gN-j3_7xM|8St$6{x^6rlViOQI=WmUk)ZN4PgetXfZiL|AN>=g*&(8_cn=IAX zzf;hF5cw0QfrTJf4ok9P=cS?-2)YO85CABLW&_2r-sxyBO(AML7bRz`;8G!NgbjVn z*%W$cOn`xg^KY~kG-1F;j{J$*!_cMR#@Zla%X16#LsTk-O(PEsi*6~M5j5o?oIT}G zWEDOb_AYi)V@b8(o!@P!b(A(7{{U>#GbzRx+hN{fFUgcNLiCwkP5X;d0ObmerBFoX z*>YsRbX1FGDBzQ@ag)V;~y;ao;iYl8;d( zP+!W{&dOa1TdL7sk|}689e^j9_5LhnP!BwL|`8i=rTJb`O^Bo)x2!|XaJ zX5|ZQ53RfblX}H;nN9p&0=Ao2X!%%?%)`u(?b`T=7s3Qyh*lGS&9v8zmVOx9!rUv? zb%&pTvFRj9^vHxGO6u39!oB^BxkMBs{@(QK`P$M)=R)Zx=_$XjVUMEl1(F4Y_nRiV zSna6-y}C%SB9%#sakj+%ONS``u`DDtn!?UP=t;r!ombx0D zc{9T%s*oChpmNV=b)lCu*RhwGB(e7Mpn8R=;E`;KG0rKkQlKc%K#N=T#?{7F;CF;} z0W$5g`(;VrsKl10&@gO@5B`Obmj0kCr9U|O1hl$PAJ{`bhu%F>K%$xK-w3cZ0#Tqb zJLd9iz!g--`c)@shdbq})eZRkt9kx2CXRk8Z=#Dc5~T+F-o-0q05v#0roIdWw%rJE zyGL?q2Px3P4h_v-BM824Y?#~ui4X|Tv5wAX%6A~+04AJsW&t&x6w+PHjCZ?|ma9-B z{8N!=lrM4my%Km_v8wtJ6`}JaM;C5!A6Yt8lcbZUw;zj(hCarrUT!W$ZHyvJ`GRK> zi_o=d=e|hg#xTbymRR}o8Cf5Ry~-PwRYbnAe<7sLLkrwaJ#^NB$$SEXykl-b@b&~p zs`tP250XAbA$-%Rv$z|zH?;U4Iac99)f?wVN-rFpprNbDJfn8(gPQT{s-*O?lFb9r0KgO{SVUM8)gfXunO9YsO>lCREJCQ(D16(<4yl6UnCi+O_GlLa9$!L7_x$lIA2%gbskP96T7Wv_{Dm@AI#<1=F!KlUysfh?Dbn4VF#}TJ%TU~hvs(!;1A?>)YIQDbdUh7h) zsGgZ^_I|dI&8)5N(nmaeyr}@Elz+Xj&s1^ z?(3m~{+B31*&*Y`xp8G@{WW(Q{D5Bf6e-CF_^Kd`8V)*yt;zL5{S1rgZNf~ts9vs^ zi?a=2@$eaJf1VsML043}Q)5?s`T z>jtX(P`=GGZavi|GwtLstUTxzh(KGiSw_}cCsj~6=atBGpOUY{?)r)(dL%~??dD)y zB}2#TI* zd4F~Z;-@VB!2iBp0}0_ZG=4!TepwQ>w)hcP;T#jb#XIwjQBLg*3*#WyrEz#$U~Unm z@1K~M<6lDq(C1{Y2e$IbwZAVm(#*xW8?;IFPX9Vtm) zn?(AukcWy(#Mb@I#m$DS_GMQ0Gnh&&o-}}1456y-O+GJw)3m!SZ&S+4QA~Bh9qHeuTsh*+F7`Xk_FDnDW5a`Z>oqNphe) z79c~Ce?UmqR7DzQ{YFfg^Wl;lVKr}S-)7GG84v3nvgc&P1UR$iHRx$Q8CrRKkfI;a zQ#9~O?!{wWeNOzugaNM4BjBF}E{~8k37mz(r##mARk>4_RE)eI#>@KfZ2(z*!2;RP zt2|0t$*#niIvx{yBAfql0gUd+y^}S!lDGS!ZFbu1k(Nd0kM$&J!9)pk;-b%d0|D}p z_?vk`R7$2iam6w z`8MZ@t4blAGYVc@RDW&~Q7`b-fp>^S-fx+gP`yfZ(rC#Ok1L@^;A@@XSzZaaCjLTh zFNAmHh=-SC`ow(^6o&S4fOoI|q#77HT=`)shZ?p|l4~zUcMsa%e@qp}tq{8ue$**P za<*WmZTZ~&U7T567Z~+|oz^>uOOCNwWLPFaA-165SD^A@Ika6ZU~T_iU`Aw_!SWNV zOO8a6zxfF9a^BTkBo_UMa45bSr|KyB%%O6jo6sc@T3|c;_Lt8kOV_@Or**vEFdsQg zWyQ)D&@b%~Ad(V_(Cc^5OC}G>eAew;)Cl3(mO>VQ`^zV zqdvD^eL}VlWsI-jPya=#PLR>x{Bk;4fK!78@dG9+&9r^QC>H^fT>vn`ZWB@vNX#UMDM*y z0&9@>8MqxYCL>i>hH%f8O<9p+cMdHXi_dkB1Ga)V3@JfDEQe$~vm9)$dk7ZOKu z0*w{gU25Dqm{x>80i_9(l$bZz(wW8fsA0nUhO8w~sjEL5LmI&j`{b!r%9O_^Y4xrn z&p5Akzf-=|CvA#3yOP~fEO4`;H$jeEC$QizH0Ul=`Ny4oSDelRVOl}D$|C0d!uGn%OC zlA5Y!LxCs<2EF&`xihj)-{sM4;&I`BG2)+AkD~i!AIol;y2CqA@yujcs|mT90*M7g zvDLM;6>w_fUcV=o_HpJ++p$3aZOKjAws28(jnX!~2VEK({r3HDYVc1F?zR39HdjdG zny(^biD7CdEYr{9m@~-ZD2v-hOc!Joo0tA{sgdEe$cxi`BhfnEW3elSVS}k}m-l7#didss@$iif2Id>BcS`RN!x%keEJ9`38r{xIs~5(QasI$$ zCa00lPwqPVo2v(DvKdQ3w9X4Zl=B#{*?!tsmEaf|8oI)Q%qIfJc~(=>RC*#;%wBt> z1PLDf30x(L&g;J2QE3sjU2s#!MP$43FF^A{#YyjI}24YCx=(lxc>fTB0u})&DBJ5*BiyHKYjhKTO7?&);oyTJaX3)Lrc9VtUD&fVfirxHVsEvT8A@VW@Hou66R8Qn&!@Dg5ltiVb{+p2QFS>AEaUWVdEh}i@P^3r>DQzOwinMvUvb>==P!BW^*vLP)(^CMZ-0ilRo0?dTI772?MvF0i>9eUc z()1xFwO5eN=u!u!ZK*78U5q*Qj*Nd@%<2Nnv;DhJ6ly1biqiZ~XhaX*72k_D)x@nH z_U5Thy#m{Q`J(~(H;ptm_IMk0=OTkbz+{V_o*rhAIDxEYb#)c$?t7(hss+W+2)sw{ zI9VH`v$?__n4UwPbrziB67hDEe)h|TWl@3P0p58xr$x?wCCQw#=PYj0rhYcW(5>V3 zD#@TiU%iSZ=%-WOP`}5j&@5%;DT3fQDp0d?>`(B>x6+~MZZ%>Sq`Jb(GhG+9d0AWQ z>5>e>J?XPy2L&a`!ak*=mk95>h*kRbW|NJi7`k5Dop}MiCzi-6w^8K4U|ZJO24l=6 zIaa*0-ULP&aT@Fd-U>}tIe(1e^}k-@%MQ<3pygWdp>tSdT+(^-x|uE}(o!r{$6KRq zqu{jmnyXxqwhWOn>IkigB9GDt%qk&jSn}jJj1ZJEAa0@!i;q^tWADijDa$D_3b>Wx zE&%2Tlo^TR9UBbHR)nq_qQZ}<5HuQZ2)vD_GGfXF{2H80smd11_b(!41-qsGE`b5x zcFRzB%kra>pHE@j6g>X5?0;uu;&^33rb)X~mTh>$!|ij6EiDVUyg*?b4C$8X8+Jop zZ*bt9krWY?m+0mvVhxa}?7063c04yh07-sU&Z2WA-kZT^1YIrGw`fDI79!|PURGgsq{yXIqfNaI3rDE7VmvxGyY+MqNHz*+E!^ zFVlGICasMPcgJ(fS>KYk>dyB%Bps`MaFdHNH^f9r@~m?ZmrFdmZh(HtD`^>H?adqX znlzJvW=@|($BmULubQi_WG>Q@%Dz*5$DR< z-Zw?dPO#B?plU^(aSmJbDKG90M!fy@m@cDhG%DB{$?~nMskYq=BZz;kJ12m*xmkpP zzNd6%IMqgawZgR>v*l{NMBAZHyeMYFcs}~pIkHPvue2*$L{4hV>#`OH}1k4qz>0R0Q7;kwf*kNnjhI{$Qorm3+Z(Gwu;B4ymL30aE_NqtE<6pJN zg4kzyXJ`1ucy$SF@UwL=gog69_6;v(_wZ(f*EAxOXFFdu`JK$0W}cO)tem0vufM}- zG@4#>?Sa+<46cNj^8?zuv>T&ip0GShsvbVp`ew8FqTiFVV^6}BSkAuRxT$Z-*_o7t z^B#F!Zk)>4BgRLF8!`>?o%|XCl`4w{5$fAUvzit&K8tbq-!H59>B-SlckI=S>sueV z6_+=>hpRTjBke$UOr<;}+x*3b zikc>w8!K;cbPV6{^^StFU=Nqlcs#CBeZFP|-`V-Os{6Tq=FA>m(G@*^ z;YR4<2PZ-oBDso#!U|g()9(>FW;Lfnn*b$72<;rtbw)gvPNA zsA*5+2IFQbiPa#h!Q1aV}2bfghEQUMi4+d>MXay(dJ2eXm=rz#agmk zEd1e)QLgrwSU|$e#=Nc;dr)n9fD62nua=Fg)AM=8C6APdgqeuzNz2yD$SJksMO2+i zikqxd9{#t4lwnTsP434@nse@G|AnfdYq@Fqz0J}NdNL(BiF^BYG7Kc%AyTb94)@Yf zi;U}^t}B?)jL9b@%rUjz!g8Sa378r0jGdUUXj_r3M|!K^<;AdH4;uYpCx%0H2I!b}{&FxVd>p0b!?(+SSij8@>!OgbsqW+ZwM?HI0t!d`^ z@*S=^X`)oeZLSNxS=h7QH#(^2&IMYYo79s?j$uD$xqIszu3wf06}L`hhC9S-936#f;aSXJQErb&hj zj{KxW1VY^F_E(I zw3DsbQcJmOya5AC^K$(R&JP5lbGs`@8{)V+zamtb6x|Bu=cYX_G){{vkd*Th*mZ>- z9xMyLPZnmv_(|9HD>|FK|p(gphuQ|W6IC@k z8}6PEk=_jL^6J+YWcoKm{6bPug0&47ocp}xVxk!wqz0 zN@Q89vOhxFwY6`JHS`gxz4~=nwp)EBucuz*d!cJ@&w_2*57$1r;18uU?xTq9+$W1m4*Y?eIU2eeHs~Q4JP9{);I6EJho54$4g}2xV>Z>fM1uyzpUH z>cjP*3QT}YiYiSJ=gE+`@?P_LZudt|_ z&gQe!Q}Hp%X7osw?Ig~?Az1@ro6PfZ6GPVw4V^TbVr!=^xaoz`loBvW=@{e7;7e$w zs_N!-E+_o5SvFPFm}rxdztt?*En8dir4jGqpF!o0Ptk&k^||p+fBismh?gK;W{xq` z30^((DT5(-lZJsLuHiA)LWEJWVpougvb!P9$eNCfep+@zpk^;=icP+x8iK@pt#agJgYQk!OU1E}z!Ekf}n5 z?(es6hf8X6}b;DChgsCxlg8!bA4@1qQ`^c9Lutri!h%-<>3I zsY;4TXuo#Xeiw7@uEm1M)z`u6z%xJ z565P+ucK5J(G+}7oRE#QYWCFf(zlE(%(%M?u#wjTL_FGzIA|^X*(PthA%wZcFm>(K zblU4C!5Ou)R1WjUv6RYdMIsopb6Yp#+D&I9-E?@IRcq7Exf6<5V;|IM6Kea&m3+J| zIZRfdFW&w^Aa{9vU5mOF8StN zzIHbJ{tE9?#ek*OV_m8^FpydT3C4@oD*U&k%#^2WeJ${AY7Q>#;RP)IxLMtnz`@y9 z6|Q@Org?F__kKeRM|02oZkX)Ag_swTiAnhOUzI z!xyG_#;=m}Xh~&;CvGP$4_7zmyZdFSu9=RiQU$BnWomKTwWpg*=+i5D=@ytA1_@Yh=Nz52rKo5o|7r~ZH~rCWz)=jDSaXSHke zPC{BPu9vjl6+O{xvLICC+|N2tq3JZ$r+dTQ6}vlcf{)xDr8?v-3)=)=Ms9ERATso> za+%umq<;54`^?Q=PgTt8>%_AbZw+-Uoq~y|hE=MwJMdcE-oA_CT%tAeq#}QHEsd06 zIyGuCD4|GE8*3@^_~TgWC`~>YTl?;UU++v6r&-F!5_MyyA?1$I%p&!SJ0tt;&(lmq zbmrQnmr&MhoI#c)1xp!Ad0169(}h~FSqcm9F_dj6A?VP%S57wG*3*IAavvWMBI0Qs z+K87uy~QNWJ=Wm$O+<};ZG%+gD^sa(yR_|5!DaavWvo$M&-Npge@TtO;wEMz?c4i} zk2kHImv6^Zd~1NvJYnIx|A}XZ(ff;i{9l;uAA-C5dN{SB3L^v4%D1LrA`@Fq$vLfA z$LsqZGAnplg2@Rfw{-jL#JZN>`Ge7+G;bw|%=D30y3f z`XuTe5Ow|8?$wzlGu3ly)XhI^)k^bDJ)A@c4^T&y*O{MVi(I8P`&yAu^yCSaV>$fy zURc5P-~__hxxtNBfzrd8O-WombPy+{ZA0{}S6`Dx(>@iZAgZtZ#Q3oyyP-LT6tU%A zuR49CN6bpc&`~3rwtMc4V=yp_R_nYMHz;bbWceR%H1{P z{po0u87o!zajQVig3+5ft6jkFsZj>$hiw_JQl+xIGNkPTH#3KGZ6cFnkeFwL( z744!yO{8CUnPs-Xl)=N|!nW!PFR2SLYe~=79_=3+&LV{gv9M#QZ zeNZolx-l)X@wpzg?Oi~dRp{Je^p6gVvFIuF)+wdKhLs3e#iVn^OADNrN6qevxSNmc z&!aD74`Qe54QE;UeW?$&UtOcKbToZU`ukp#mCqL@HL4#vweYEQ+ekox>U%Yfi82uT|7{Z5vsktCdN+zE|}aB@SF_mu?r1;rL&8 z@Lb&Ou{qRf@UJ^**ttEi-Pqu}eACdYTmIzN@4vA5`0J}UfmdE!%Jj%?f=kcxOI1Uo zxvT^E${$g5I;1nK!I%_xZ@Wyhuk=Z>_=EwkrHzulr@<&W_qDspMEs3i2ZHaOS z1D$MQOX$#<&+Levqv~QPB1f+iq3RLo%{{njAw=L}%014HO#8-?MrS=2(RdT}A@DJG^|y%a9pgHV z?-AV!(JhaHN>GAc-Mibs84-i>FWNyDp6m0sJ$P8A5pUn|es(f+?6F>Dci{HGIp z<>XKM@x;lle5??nWAGMNqkx70ZgVeUul+59(3XX9O7`BZH%}h1^1q;UznxQ1_Y@lp zzSp7Nj#gTf$Xw=PED>B4Z z-cE!Z#TVKs6T(EVo(@;uVBW~c62;)x#X=i46N{gEzqcRh6F<7}S@4MoQ)#-`j`pBS zj&-`gs(*;@1W~3kWdZhHiiYV`+4m0~6-K_?T(A43!C>;#u%qyz{77DPD3qqfleHkp z(1|D3`Y#{xHUD8ao-lGp)Eja4%*Tpv6Q=(C-peOPu_yZEeSSpkF((fU%SkK^_d@?T zGN0`0WB%0_PZGZ@s{r_mP&XUZT{OCu#1_+OgN|#<7F{E_No$Al)AC93{c%Ut+t7YQ zfte!QTx)P(E^o{!O|mMXDBg!K36C(-$_kn{Cn75n*)s!#m0S@EI=KpJZ)nN|m^S;W zRjYGO`DwM%=xAk%sxVh_&FLBLawHS`pEqYh^PboK%upTa<8`@J|l-)rzu;Fu?!Y6laj}RydE=B zFf8XSNaUuR%U}YxKM8o;6~h!8D7&j<-Gwa-;i1apEq9>f{~ZlI0tK5#EEY5hJFzDR z{y!`Zzl}2b@9-<^e30MEZoN=aK0(;Tce1|Zop@2{Zzk!=|2N`CtTLkIpFQBbS)3OA zdmR3b94|U|jveo`t`tiw_bQ22gsY&a>#mZz%JclimyPw=r_ke=`#je4HK|;?fx5^d zXLtK%Gn&pQ-gYi&KH4r`wJ1b*&yqJ&QDgJ6a1#sj<;A*QE3u4{)hpA@GPG9;95tqt zf;EsQsV>JaUp4;{ttF=7i(8IK3vay6Zl0L=v$*SR7FOxpgRmvq9;&!ZYvYpzA znGICQMyj4&`}mwx&Jx4j^i_09kn}`_@RAI=RQYy#t=iW~{n3w9hVeDCU)nR%qA|K3 zOrr?aTuT=>mDxe^`vK||2r`CYJ2B`{?a`mZtwW#P?gZX6#!gIz<<*Tgd4fYdwi0im z#`cK}l`Ir>$A5K_L5kb{+j$Rvem`uo-of71!LL}$oH(0#@xL_Q;BTPPduzDa%GG#- z2DEfvU$i1We;MUXq8#QdNR;|~q0dW3?qvf=h*AxPvjsb~wS4rsG+y-D%${;7DX?Zm zMF6D$Y6wtakzXi!XI?5_!-ZIO_7K?2ckbpQcN2X+6&7thOuLg$OWeA#V2IBD`=ow&?uEnp$GKiwXl;dbH*S-cU`VBkE5~0vz;!jN?4Cd0kIh&n` zR8d{1OVgw1wZ)^e9rUH=F}$l7kzF+(&v72h;iK#xX3?vGU@|ubREQ@xR_?&Wytn41 zR~vyS045bjQY=lzVCfv7yl0krSF)|E>p+9AEOJILqB$Z{l6R({H%+hpe`%?~(eCj3 zR}$~{k{v58q`IAxWp9}X|Gm#ANG@_}H>KM(Ys86Nj z;vq&|`q+w+yTR_Y9W$;$8!ocZs)Tmd8s!~Vww5R%P{5o%7$V|s+F*&dIP#ePW% zWK5f{?T4#~24h&7v!+_TXFySzXZiMeHR-CD+`hR?gYL|2^(k$zeNEd8Ol*A8!oS7ijj+*4gHXz(nVV6TQC43@4XC7Li1fdtD-u3Hf{SammB7+Uu+iH0O2OKg?^hRZ z^cz*`&|YajwiafwNt1qb;ePMZJOc-*!R;HyGH517i4bE{{q{bpr?sXmmX<|1tQCbi z0eDpR&OILAA|%eMI8~87cGY$IdtgJKUMaKVm32ufQHMHgcF zCeRbD=xGn4k5n&J@>1JhEnT+p?dDM%_I`Te_UKm8t+lTq=U-QZ)Rn}Y?o}oWxS_xo zVEopw5=gyOCM(%K?DfmEoFXKt%yk_{U6l#8CF3M7ZKAXyp_kAQ!%|1P!=L*r$WPVZN;nbtWI0GH$D6$iaMEn5$Mws(_->nLFq-G1iZxq(r%D*fF)U)dte_mK1w3;-XOq0(9EqKA$FgjHKH4&?L*-9yGC-@(q2g z(V=PZMd4IoLn^K^)-ChFs+*E@W^bqvi%Br^4oP{=dqjL@JSR7e z>D89`I%;GhcM~JG(-x_qHJ9mqb0%{$R{JffkC@HICeL+w%Zlp?mncrTO^hPg}BLKw|hM8S!-+=qIR}RP6wV5o4)wfU6nLeq>{x3`Oll)=G;uTY% zNX7Tt)uyyDqQuFm{Z_b=VdRaYSr;>@xdxk6oM z6C0=WmEYxUg`Vl6im-RENfHAFdrzc}Cqm~-*)yYC*aR-KL|Z~`ua$~FPg6v>Mu+a^ z<*D8vYm+Wi*{ifFCRCz4Y~drVdCM)jRi(tHQmcJGld7& zr$U=0l%yob2#`#fS)8d^WK7C)$;~&=3w9|ep2g}xyqr0G1QXU{R0#Qu&W6vq-*LYB z!WQAAod7MVsGLF?K9gAyX~(+{cSgVR#3*7P1t-+L=CCw~D=y_Xy&1-c$C6{5_;H6; zKc60Z-nF%lcCE9zR5CRFoPn}ko0N0=V`=8lF&`K%^yV=1>tEUx6bE6rkaqX!Y=d=Z z_V|?Qx39ze8XzA+MkOzgB4Q$VR{a4~?vMn4DuWvniA}yPjEZ{tDlBv%l)R?uS5`Pu$2=lpCDoHS4+HU4`@aOkVgxd#OAPH!H*!QRX5_a`NUXOcc zbGWa6?I~9YdSy=n6}BpIqf&Vt9JDckOYMFZ)@hM*y}S8OVmD=p-qI>9cquuz$!6qC z4HnQ^!LnhLJJNkO!?MP`QJTnVU1R&}L=lXYq^G1lJxF7Z-qiPg>B@I`+LS74(fsE3 zBF9Wj|5EFL!c6|4 zmTx1|YUz!fX(yvbV*pc5AH4BpYFK)j0K@``8isNKXCHWlX-!dY9Q!O#l_R?;Qm>_( z8R#9qRf`QHb)mOP;oH3NBUB)sNK5T+#R#gNdyyx}@5=Qp>F|czyWa22x(mKGBE~RwJn~x+KGpJf zwU}Fzq5wg+jAucoljtU=tJ^wH z{)O^RDG=FR6?pe6>pD4g+1KBHe$^!f4{`E^?^oQfYbH}5A}6aHXe|#qGkaE}zF_cT zPE4c+Gm#JSs&gS8?@(3tWPnv7KY48a{4BeDsk35}t-!~#O~{RK%8)7o1>WyrmZ$9} zsy*J4s?w$^rDqC@ou98H2f%f()I_>+zUt6HQ}d2a9}gV0e*z!r)d$n5dAAJ-*QzU> zt$05d8nSx1;RW+BL;uDydL%)b-2bIsuocYzF;oS zwb8G@D!9vtrL($!X6qcZS`S@cD#}3GFk?8!=zXtpq?#l807;T2jm=Dsa)ey+8_Ti?$TZccDpc`8zi7Gw+3l1#KFYCc@KL~4{lCEvMTtA z*@A*+x?%hV{3VZ|c%`CdMk2~ZU7n={ed2Rl3`F;B@=lp*-Pn92*CHvlci!w;dFbtt zxv!HfR(%z5UEwp5v0VFfv}H>XVACGR-JS3_3r}Qd;D# zbI>cSLgcg|YTbQNv=UN@{wF#Z18>O;kq?~Y*&eHsFlctQEXey-U}4Fbh9V8I9pvEB zLh6urzzm&%W4Kz(6t~qN7Ed1@0}VaHZ+yt!@nLKNiv^n61@7+cPFKPYMu*LT?ePaew&{NMaO9C} zDDyrYva-U99BBDPdWtO#vepQH*ECAe5Y+zi>|Tk*We}Pkk3+%=^i52xpgxmJU5}30 zM~{a8U1)L^c%K(LJ~W6k9X#}YdXem3KQr`iNjF>mct-xQno7{~U^nQafzt?#*vfwN z4URu#V7-yS7t`JX$WPRK0HeKu69`)}jj-dNhiJp2ej_AkHQT?T}kuMii+Z*O;bqX3uTb`0lPZ!4?5=p5v8dVAOUX zNEMqINUt^1+m!*BIpzqj8*>`_-BkUpi#a`dBu7bZ!ux|OIi`4_Vwlm=7cZP;WsmKpu+&0^|?oolayTkLVJbrjDPB+ zp>-E%5z{V$VF9E~u}>0&ZNFR)c?uyIXvUmQrmVJn2k06(PeVV9#Ktfj+`o5zD>4xJ$$J^5%9e9t~^UDU>_Nk@;;V_C)*EIBI5>*5$kF=~IQ1rPamvQ7 zF7JbPCYN9lK}s~nt0Ds1UlU9PSzcZ32Ec*U5fK%VRj;Ul3EQO?EfG#B zK!_BS85NL_kRT^^&S?E(-^e!V*LY3Tm1GL|@X*=>M%||maIrvgPx7Yqo=D=Z$vSK2 zQYH`XEenSVVYh;g5k~!j$tw&WG%PT9AjT+VipK_On}*bGAa{8&EpW6Q6RJ5MO*!Kf z51?5X8yf>PO(kwx0(>f9PdALi!+0%Zk=l4|Cl?=#Kz~yT1QASYJm4@uWb@pg!D{EZ z;*V5+T9uDU1D{|ZJ04KIei=kn39hm*{#YbY(qmRsf!oV|YWW^H(Bs)@4x%^gjFl=$ zJ}cU{f?H;2OB2w|9@Lv(z2CN1V42iIQ2yN;!HPD75r1_Y-J+>?B;(#au*=cgu%$T= zDd8aJUUdzT3Q!ylbENVQpy^fBuy;rkJeqEX>Dqt76l!6vYKLoaEmsW-oBCZ|OHpZ( zZ!FhjdxVb#*NI3%wq91=>Mdn6*ZBFT4L@WOisauxe^91X+T&YXBJxGsB~8?QILV*? zFlzPl|LQYy{0QSVz6QSV-LVX#<}%#NzN|0*mg(#LPsRgj!yVF*7wObRrpMW)B3r;r z1&lz-zzY_TOV1D#gy8r}DyjuJ?x~2nPTsX44^T^;Sriui*wFA{X2T8ye>4r8IS^)I zX-Mcxf?K90!~LI+g2DmLx|yk|B&|JIYcfVN<$}cmPN!R7z$7>Ijw6s_8UI~eIx`tD z&O$~cF{Qc;l8x9sm?2B94$;cY-24ZK6yS3JHT6Y127`GFql?!j8a{xRO=+@h?Jcld z{P+-@PwGkZ0do}<715{xHhTc`J;8>Af>lm(QV;WT#|Hl$f*(QqG736vFOn<9mM6EU`PdA;E%zf?dm0TjLWG zKR-salC~J22}V=*fkV_ zL#1rVosu(@;1t%K{Oo#jt~lmHg?ZHf${#%%SI_^HACdol;x&Clco+Bb z{-=MnS@5b&Wg>nVw@jRmFyZ-ay<>C*25$;+lj?$HvCR(RQ`d6qO4e^$7!;5ws~~)X z6`vLiWv4v!6v=4SrojkQHhNl6xWic?QY4FD;CSZ(^EFKrE zX#31Yxa%*FRFSX1ConTJt4SubBdNo?JnhHPC&NTOR)CUZ!V&SNT7Un}={SlM`n2v* z_Ov)OK9^7~QI>P6w6t_=8v`S*AgX2cmC*~C8|4j1@#c|)apF-7;!h&*zEi+GIVBLj zb-UEO=IWUb-3Qn;oDLY?4|b*Z!OmOo<{e3vc(nX2S>n^}fGQ9dz)^_qu(}HOVkQsd z=-!?3?cH^t9E3y==OCmPDAsuK(p+aMTpg<=*?9(pl#3!F-pl8~=D0rULcl4twmRPE z(1GwOl3$1qfuagRJDKfcT}&0_f{3f4u4)}M&IA?QU0qW{5E&qbPR1P=T|0##Bm{F1 z|9ZUw_zEahrpAytWQTpHR%3B9U3U$ReYnA^6xpkbciNi?L6p+O+rc2IDnM1}+Yu19 z7%)A4*?YN^h!FoN9#$%E2f-m%-9pQ-VIBNkG0MZy*ksIqG`3aoL~hbU*@r4n=uX+3 z8yWI*KoAv^L%4Cf#`4JP;+oo4+Hn-Ci|?Dtovs1B;{R`_{ru8$f-U-4f0T1n8vJjo zJ@{8au%|dDx;e4%)u3nyERQ~lh6Rg|(|-|i$Ycqnw(bL%bu}WUBkQ$Pb`-sDk)#mY zeK5CLS$X>;37{Il3pmkdLKR^ED@+#9xgqJGlMLz(KpcL1UoC#X>BL=Z(JFsOh=V%s z>Sb7%#Kaad>Yk{yia-SUjWWo^!D^VC9Dxtv6_3J-U_Jvj@H%-y-ce214E!bB6lQMg z(*WTuHa%pZDqab<%rB4v9)y)Va*eM-EDHry9P^hU>f54mW z_pFgW;?yRdz`O_QV>yZQk2pJ!tY9gv3GmWhuHI*LsHuYsqqhQp18gguM!Ifkukd=` zgW-&R51Gf#xRbECcbM&V-n(L8!KiWsAj2fedNt*AXl9~sKS`u3Zl-T3a)>9ZqrNj0 zj_dOP#7m`LhqV@X{97{wegy9WLR#a*FN_!SlMCDkqITcc$CE=`Y9(6#%oG>@X~364 zrr%FL>P&vKDQGLy?QdB|UT409%_}3G&#uP~il15rw^SHc%gnWDYAM)CuRzRn@8OoG zk|x4SMil`UYsj;x*N%(kh98(P_q${itD-nJIpdd&r;9J1HYV|n@867RAXwBUkSyYnKv^VfV?0E))LrPpy+Y` z3^HD!Hd0-fC%n3fTQL*%h2zz+tL}bpKy?Ram>U(Dxh`jiV17O;Sv6RblS3952H*vc zaE7aZ6%D}yBpBvTpZ#%>ESVoc`}#ht99hoB_QI96wB)#kdGf^RuQY4xlh(^Gts5<9 z81n18`AveHT>V0W*Y=m0;H9Vcz=2`NU-Y?%m6Gd)fihrrUMUS>@(+}FhKYOC%m;vcWHne9Qg6VEp{ zwdpWfn#A1v`p`xDc!mj~gf7FY`o4rrqh+4}h(*_e!xEUUpTpKl%|e>Cr= z{1A<)FYa!HBT_yq#WZ%eHTHYaL3GVb+{~Jmz}rp}(c6gfopFBGDAb$(gI9U`8!HQ^ zUwvuu-@EvC`}jWnS7&)gLG2v$Xl&+FQ~kARj}JfJNLo89#!+&y>#XI0V%KI?9Sf&R z-N2IJldzYDJZBR`-gTmpe~%P+t}Efk1uh{9_ToMsC3pcu4-cCajFstW1s2@ zM5DChg)}dD!Rb(q$W}?&rvTG|I(~BaH|sp@E(4e?b*nV%7rP~itvO5vzTc22)n!cq z5i`^fHz8D!ZvXx_n@XBpMWK%X&~URn;Rzi5`pycv<-q*J5r}`-LQqzZASbo%8E>PM@x(UO1Iye^-;r~`V=K7ITM(19rqady5GBpHzFfm|5Q zE4az5@xqp1{slk5wFjUG=Xn6gnLDv+EzukoCm?P>9YQCYAcXH#1i%m>0@Ztmuvwr- z0F%JG#REQXZ&x+o0_L@z8kAdtEN6ZdmN|gzHU@?T*Nw8yHEt`NT>e6;r;UQ52WTl> zXUGWm%ly@U5C{c?FII4@0`STpUw`6=%L#nsJ{%l)f2^t5Kvx6$gXEJLNUBhgotDSz_TZU2y!+R4RRO1RrwWpqIaz~bB|`fHw3V-F`+(IS3AdbNq%EF z$VbI)GO_RY#2mGxpuB}u6~OP*JJK6T|Dv1ba7qQ$396PSF0(R%xvB;0IJS>itk+vE98 zc)dNle`N>dVu2sM93t3P) z{TF3$|M*V)LoicZZ0zA5a}A3;7p_0g;H&_bV!*y6j$2C?GN4WVQ2LD*KJ({*pEhvZ z+uA|^_JWB6z!j)v;(Y8VtA4KFwvfHtbDT#g>=>a>yUk;gHnEoxb0lSNM;=JCHHzaE z*TRl~dcmXdy8p-4n}9>zNA2S?#;y>G$`&J(C8Wkq5kuLsB_V62WJq>K$dV;Xq=ZCD zBBX3%iO7;EL~88I5XMgS|CxGvuiyJ#|Lf|i=g~Bl&*yv2eeQFg`^;yHi%^a;#pp#P z!~qboewT0ds+==g1|~DTinWI9GN*x6c-PvhH(Rni^M1hc{ZG%6M96fI4x#2^od8fJ z`q`!QQA&D)=d;+o9HV6)+_bjp1U7?H@*!Q^_VlEBjt9=)v!TWyXz0U@@<1$qJ~;pz zS4x2JgaZbmU~8jhr;^~mM%{D*b$)qbSVxGob=8~-?eyB*P>ASqW4SZ%9Hs;>1)k~qX>XO))U2jE@am=Q%|wcQ?@9V0teR9u zdsxtpF|GE{C&kCTOy9p&TmHDn{(cV`tR`xac4C^3K0Arx=^{RrFL^aSo4Z>|d%N@T z*`WkQVi&HVgetR0p@sUSa(}RCgW=OhH2W!Do`v&aG_{)UL$g)IJ0yl8GTsw zb6e{;bO6IOe=!aZB-u7#>A9XVaELI7C%z!$Q5hE~jzFzbS*ZjqCW>p_nidC_a~D)6 zP{7UNG<`I!8~~&yE+8VI)bXwnO4C)B9S`2P+w*O&QF11D=bwP;Oizub=L_5zr9A5@ z?;$Kskc&WcbA$V1aO`oaXdY7M*NeaT_C?V0UzU!L&>}fj8w~kl@CiAfR zed7cOchpl$GsUaeeI|h+&^Q-)|357Nz;1&U^H-)*%f9KM=IVh0@3EpyS-MZu)B3JreW~owi)+r0gMBQ?Y;g>nA7lP6k%f9}8dF)&dM)0?rxof>+JkpEnpz)Kdc zCrO|0(I5sl>vFONL$hTv>B9G9d{edgaZ{&Gp9=`WE*YcKL7_q2 znL=F@U1U+lLhIZQaRL$^sFbX00%r(gVtugOU>c0GZew_>-Z~m_1@5keLB+RJ1ieM) zZycW5i!yok_W4Q>RZ+tqHv?@`J@a&cRi8h{G_iQsrK9NIsG`ZZoyl!SN!7s3iLu># z`QclHrH>R^6K~qGfR>k8?Gjf1 zo(b!+N|Bkr{&Z6qH^!66lHsi46RS1R;&HbOXTaGCC4Q-;0ammQKM{)k=e<8J>LVZCxg_a>UHfRkY7|`f0V6r~QpPsJ zElx~%q^c+zl=^?b$S*nbia!}=IrTpm40g?x;j9q9adxRf* z)J1n6;sQ8}nY}jSGyCend<=3ip$Dj1%ESwkBS0?cBlr!eWNsV*k~O+C8DB52Q7DP$ z4fqnc-kI?zl`0~DtPzevUjkz1l8p_OqJ}mBa5jm})QZ>b6u`oMf}b<6$UqxX`3~w3 zwpdhRf+Ll}{sLVtQQJ^!9jH$r6a{Sl{tCol3bQ{1cfh3#ig{ULRfPv|hkSPFG>Ah~ z%ZCmLU=he3YZa*TK=V~@BX&dF82SnpK?!jXiQr>|z^!%KVp4y}X+W^Uti6MO<3VQmI5#{N4l3K|?MNh>DEL|hoI584!vjjx|j!iim7(_AU1xz-|Z zgco_m_5H=!qfNdDv|AVA7(y4go>`HCx-_vGhPPk(&5KOXnVNb>uSKfj!wcv((uz}< z^}4=kO^Y$KR_$GANWa2-F#gm>;NnI0B40+QI@2{779{X!GKL*Bx-3HY%k95+DV#@)@`SUDp%Ho0-fRlX1IikR=f7+e~BJR<@UShd?JV& zVP%;RpD}&fs+M_se@KN;Ia`-!hB+2s~7&ZIGX#Qv)61jBN_U$ zar&!gQJxi!vX1mr{|RZ& z1#lBLxb_U%A@GCfQ-`{TDpUl6Ua*WMLY4cYDNbN!ef>w%9H0jbFZ2R#`}jJ)!FXx2Iop253C%s2JHOpkCGLe+N4tYT?lWOCq~Vm-b-ZAw<=mLyNEA zJzPm(pI7eLY<}PiT=GQe2QGgzhvq-k_Z)5$gav70kL!EFu0g1-sGfO#;i;)qKd!ex z&Z>Mv_`vmD8UK6`^cuGzhyjJY>SMeRvsE9Il9ECx6ApA@o1-qfr-C2FCzgPvfJFlL z%$1dyi&T7s!(FDn1CR(npHnQ;;4%$=WRa7r1cY|8W~;jgw(nX3=79wJ{grtkBwi{y z4*0bF%!EAEQ)rMDP|K6Bg}MILN-*=Td#a@@_;e}we<{xX^)Aok2&IvRAC-+afy+O{ ztbdTQmqMq@&cThR5j?B0SA-VH!p!X^$)VKG;7y~pG?3KaRUAWVQudqZ)!Ky=P|SsI zQDk4~vtqn2+*8=^f7gNGkal5((0OI${sK;FHTHtj+en$Nl8G;`smRbEx$ z$Z@$KYXtq8F)By4bn~eq?a>EOM3xsXx4u~Tg%#v8*j)dzeFG=ZWNkOiP3N)xs4>1= zrUy(){2tewvy3$!`M|vohPXS495?$)zIy(rf%qH8jw}b5o+>u^mD)AC`WoaiOXDAm z)U);?LR_L6PBz;K)&k^(ssZ?aAoE1YaZS%c#0SA21-DAyj#%F|d1VSg4LSw9T&XHc zp+dc9ZRB)WhxMPSb;Ax9K-y~DA}r$ZJa#1(2|;-lTr92+C`*t`^h zsx=550B{5}NW9o8qsjp8V4M;tTP^WBUQZO1>V_gV{{Rdd`WnxbWtn$ak z!sUkJ1`=gvd%GXP8qq^F<6>^-TJ|Qj{|}yde$f^g(0GAx1Z5cLGaX?VTy%^E%;c!6 zaG@d6_msh~s=E4wTnQw+jo_ z*K#u=2km!|dl9F~?vxpPXCa-(9~G3bzc)q~tYWDj>msgWEAiQ>^USlaku1B(F*G;v zJjXOzcW`kurfvL}Q6dL>J2xH9GDk;z3#?Hq-46$K~fkt^2zk@17YdD}fi70-9#ydCcEEZ6sZ&zYU)b?VQjvwzkj zL>{-CKD5Qht~Gs2?I^AAO0?d_OJrpkE3A@x#a!~%Jc}aS`0AMc)2E7Qr5RTKHhnj0 zWq2LZ4&w4DIsZ5wHq8s}e?+qxPyY^P>82PJ=xMO1v;YH=vM&vsZmqzd3-+J-owZv~ zjTLPPGK$jk8_Mr-Q43Gzdp6A%X*bA?U4^Aw;E*1uN-{5#2EGvJve^rCXTKKvqJwa# zt7~;o>pA4!3{1wZyDW|s8lTj#0VGSwvxC_G53oni`amdJqy)Fb~yk2Jt^Oz{DxwmYD%>^ zfns>kH*>q6(-nI2k5+wEe$KA)cfz9up#%^iTr$XuUM~Ru5gG&wfP8U+)R(wO-5qrk zf9Q`jUL>p*^Gn`RuR0KOSIHj#u69@2F;Y_=s0uhN5a%D5;g1SZ4l~A@vl2u?CaT-;*D*9rLgJ`p5eGZGQ=+>T&R5)SESV zu}LRk-~a5L7|eIo;IaIS#i`s5%XR)^zetDwpUE(xkBFB4>l+f$uEF ze1l`|Rt!9PO8ap;Z)z?8_75^%aIZR#2BzDWy`zZJ zwK6|j#-wxS?+rTtw&{_gG$)LJ{y+TBzg{Vg!(e7+(nH0B3HdX3c*);@0S2GXc0t`Y z&<_Ql@$^xK2slpZS)GAHnaoVv@Ki8;10IgaF-<7x7OfMa#4RzN{fxSLn&2-n!Kb?( z!rfk3U!F?Lh65^o_3CJ4Rn@Ht?NdI`W`Kts+Fk%_F<7w?%rC$qV6X!}TfJl;qrJTD ze=+|aQ6H))r_$@T0kl%$!Y#{j=)Y#52QItrj!Orv@8;YE>@{3il^M>Aq!PjR49teH2o-{ zz!lM$1QU`MS69A=Ux6VhrjHP9sKhd0a8PRlIjN85xUa>z^@B6kr#SqA@JecO{KyXk zJsqwg%)>=Z+*8|q*Tw;SCOaKZ@Z+<3-ZTezIQ{M|{&L=9Z-jVWYu?IRyjt4Ek55~C zQ?0JNQuyJ3%H2}ao+QOsn5;kw_}aX9yU9Psfzubab=rBuufCrS^W$jjvb|()>pER9 z)V0(nRj07W*1F;R<-NGk)aR~NBs1nG5q$b*3O=rjmpK+5#h9GjM?|j(l0RI2o^wjU z%&!w!dBIsy?qz|+aC2azIMYN2@x_R~UL!|_tn>b$fq$1k&Cs#=j|WVE)8GDro5tXA zA@Orrd)%~o8{nL@jJ$_A*t42jU^xIhctap0=t!3JQa{G4gEoQ+D?~8iHE=Od;=~zj zYz~GV!ksP0w1gv>-xkIuCyw~4e}IP+gs$+!0+hDQF)jlB52|_2cM#A4h(Jo%s8`!O z?S+FH2s+7dYh3=*HUN9FvM{D+a2K9z14R^VBvPG)J=dcl{tU+jK707*mjvLqr+dg? zBn|OF`D#HyJm4Hi1(flu<09A{DAd}7zJzbpDSn-bQ7Iaj<>T*|ja?QrDsY?=Q&Pwv z@{JH`*?UPTTYujm4PxJSrZOY%U3f#UU4^JD3vJzrA}8k4>{Hs!Dw#6(;}>aOBOd-R zzh637QY)DKhQ^SAi?$IlWViD=OU(bex@aaFMKbJVQQTg?mtU`VW6x(E9C5sfBNn|= zX1L&-b~DK@C+(SP>rx5cnxtQQVC7zF`FYbz_GPsg`r5|L(zr(}9uEAq=L(u!@JAb& z8jMA`4KMN8MI*hj{_>6abc1W&%IUT0yaD;*_J&vTR`KbHE(@fQ^7i#BOgfa^b`2I~ z{Hwc)hAaZj865skfn}81rvsxrz|?T2Lp7854bGqQE1V^0a74SYq21TyK}?lCZ7SOS z?b|o(Kps4XuEoHk%lYY;?b8~Hv}lj{88*5Cjhv87ICY4IK>kAw?Zp}|c%sB0O|7bs zbzkOQl^*!8(lZ@W;!=(ckD#;SlSipO1Ck_FC$=0C;zZIb+II*o2+UB-`@PgreKl4W zp~U3M(X3@uR&V#Ws{~^Mu@wMc;XVw}5~|;t@H5@YV7g+G0l75{39AW>k&N!OcM2k?b!8d;5nyq^sVWh zkX|X8t?T4*er?n5HY>~>JB+;eV<4Ky&amBmOy6@K%?f@l|0xZIZmR9l>K#RLgiZ7V zN`2Yvzb5zJj8c8`ZwL{)c%~yU8y#tv@Oe{P$imMVo@_7G2_I+;Ip15^94diR0_h|6 zgS8&i0dbF4I|Fd*U^(3Du_9!BCC8pjKHPM;9MD;bl460fn zqXCk%wE@~dmDLZq4bz}y*Z@pfQociSdkeS(Itm+&@jOkFs4gL+YAY#f6^C@7jGI?*V_(q85hvxdJvU`AcLu4}> zptxN z5};%Wk>W*Q8%J8&uiz5$R!0;`F zV=h#4lNh)n7w!Pyjwbxtldq=t4fifKg3TRALI zKu-n*JXkeTAbmY$jl3~v2oq$Wob&1iD_#bF2#ioVLv&G-UWDa&FjM*Z=S+GTUT4~) z0A3~S(tE8Gv|qgtH&QmEX)FOnQ^V2hy?JjahCb_AuK21@wPYzYjv25?%}YaQyrt}| zi3nj7e*^@!eBo{46?aY2!sW;0TW%LSP5W7eq1S?05LV;$Ds?I>*&oNWFVs#PLs`=7 zEjvLT=_glrY$4l>BAWcU%&rVb4eqf`@WVSZvue=&MqnxBvJlgj- zN}<&DYbiO;LwSDDDtr7M%bXY#Q(0fS$+8%UH*9_Ao*~1Q7V=~EY_MhM^)!Qzn9}L1 zq>cXveF8%~p#8T`1V7T&U?WQw!OZ*jLJN}l>Q#)OKb&u<8dI$eDmv?mcn%-+eZ1!} zPsJ*=GX&PXa4H-i_ zJ=Pov=~tv}s&AQ78DWqi6l4RD0XT3WREBjw#|r$2U2opJ0YXop-{2HM;s%@(6e0%0 zBiBD1(lRK9r?y=GOmDE|Wk6WzOX{9Z_-!qfLP;N4{@Xxq z6{a!3)6{}alVW=l6oiYchKQtNa@5c10&;IEiGn&agEcv<4vSKX0NY0Thbdy-;&;QB z`4*arYTNUFx(Kai#j~H=o^nlHb)sBzfG*SzzpFU4FNIMmh5Fo$rmxKa9&hwN*F3yR zHzpNK=ilA7Su%Y?&cmDWx}i=;NbK5#jG|2ojjZ-Ct5tWp2_j|!-BE;??Rwo<^{p-k zv@-TqY>cPMvD=@O@x+F68&yRoajM0E)7Tc*JeR0agb?y|8^6XA)$<4wD;A3vwYqxJ zvS%n76rV5^QY*%3%{};zxgF6Om3cKouA31<=Vt%1}2^0s_nb?5!-vJu@aaz(4DvO>y=SyUaAfW-~#aIygVJK zdk$VuS-|oUV6OC35)kR1oj|fc)l9;a27nyu5`&h^vv%;JI@>|YzQMgkc7%tsu}lS97)WDV62H5>rc@C`Z!*I708omh98rYdZ3r7Br=#=iqRhspOko3rmc^d-&1 zJ!1VB+%9s3p;T7r-_Y^AWIekgE_EynF>O<;1LHa`8ZbZ)DIE!J$!D5H#v;Yr4$jpD zWJ}2oK3_>5uC}LGjvH$*AJgGWv)tC7bq?c7OYy)N2+$>Ard_UWO021dnzwtdMUQZAE(RojPkS9>PEs?B3mOk3~DX?>KUfDK(+LNN9a+2sO$(?6= zRxgZWZ(Of8eXAV*G; zCmQ#P!b!SZCafb!BzwqFb(EB1Wd9f8d+0?Fmo)UN@UVGnHr5iXf7Jeob{2SUwmNgmx2Ed0&Wgl{>R z8Ap47+PAw`_U0}3z9un$1~D1eu!st^_+*xksry=2UOqcZ{J0#MsQB`@lx4ATUkFK{ zX!H=mu<#W{wDGAv#+uyQTs^$jDE}5MjKA+^ewl}Oqvgj!bu67=v)=&^6}D9lztaQG zH%BZQRT$cUQ{dOOE8IG^*WEq30RE2LvpgKIt!MbZnEHPW=Sh$}LT6;^ek8vwT6$8R z9xpfqLn|tiEW2oQUQ98hFtg){RGa~9Gl(|ruDCxKRfz;0$PH)+2k$Z_?~l!dICD(5 zPZC%~^64xX9qOfafO@`I)W(KY4Vh5o79b^F zSNqBkS9(74{9(b}?ff%|Ir@2GB%>oU40M@}amX`V#>b>qVp7-qeiRz$Nl{k);s_P1 zZ>NQ@0fU(z9>cYUm^FLR^Ya9`?8IUnA-h1z3a4)1Y5%MIJKMBU*a6!Qj|zv<+>wc zg|mtM;>?4)erJbrlCO7doPTOn(!1n&Xk1y~Vd4iF&$}<5#X6UMP*y(x@!-ZwJAq^L zcCBT>Hl)OLM-0aXioE`tiuxBiR?q!u6n0SY zqQN6nrkmPT1L1^6XkPeIQVs}foU4&Q@QBm`c!sl3X@f@!wL9Sl6;?cgEi&Q|VWGc( z9S}+rTsnmsG^}R*giy}3x(tG(Oqk}O_EX?g|LV7)s@e1hEVmJS^{QM+le-c&=L zzaGFDXuAw%%-*h4P0yvp9J(AQcSf&EMI^w+Pj4u*v-r-m+Fn9;8-Jf#nqJ-M3rvP| z3T2%UbeYMRj}Z0|4qZ9)c;l0?iiz+|F&%ee>(JZ%>1n~ynfS)77OPuZ`0}JkiKq`q z&J9%>wpvEN$ltG8BTBPOM0&pBkm(lMwo#`7Rc|_pZZ+~`R9q2$h>rc`CMQ=Dj(F^A z^HPuP_eVkwMPa7qxzx#(h(I5_Y*VsIuxdVG~LeZIiNX+@o8<#njcbGezhv9ps~ zJzdCRTG{drGp24VL=2k?HG58AYY%h1Rc(Pk6e%P(aH#({dz_i(|Da5esuff3$!vB- z0ZR3L^z}zhgS_?o?;dQ&LHi9 zeb$+zjBGdl`#eFuzQ#Y_4ZRb38eLDH=~iy_K{9-i)^-fLOeQ;j^W;-;6?=V~V7Y$y1pEJ*)8n{x~ z_sf@X7sVDn;8YSx3q8LQcwt`WB$tR(uPDdb#+K^(OKgWPA=cB^*Eh=jnz~}+x#8;B z4KW*U4DS*-Bj}fV`9y1qw9$d$ygd9vbQRcW1j5o+w?@PO-nxwG=KIIDD=#&4W&~}& z4BDEq0mPh_r(3hRaF67;XOJvGQsom?anzwSh5Z&>Wy6xp{^6OpY{#B!yU4oj0x zt72FeY~ADO>+Q|>CgRns8z%H8SQ2Qa>Zrdwt)1Dq>>ERvOV^jmq_;s{q|hG-NuTdW z#^5Du54V?B-W6N>gsCDvT1}_X$KGUbyPTd~mX4B}jU3zIP4iK}GN@7p7nU#YE@LCo zOz!UYiPWF%6d^1#*yp!}J0FNO>OZ|%CcOLmxoN3=_uPbsP3$GC?|yw^*#GLD#|f#X z2@k~a^7E~$r+qy_i^vT}9X0nadKdb$HMMIF2#*g2%)9+`58`b|LpG}R8wA}h%3bo} zO__J_FJt`2WxTwVNNt<^diJLx(O)O4?I=u~94TO|jTHT5kb54FOepM`lIQrmxvVPn z@a8}@-RRIGdj_sZhlFR=iqW)-^WM?LF=ZFgS_^zV3{3V|WR;sT5&`2lkUFBWB4{P_ zrSTU`O@00Sqd5Z0#PxF%f4t*cI-tbMI+R|U6TC6?^Zm{Bft@XzE#l5*9A&k#+J7yJ zm;s9`3D;@{reN=-A}{NDPtA7D^Q$JwW0|BwIV3!myr_^c*@n6gTTJ-{1mquoHt8va zx7N??6bz0#I!RR9=?bi2BQrL8%u08AURpW=hxY}9-OC%ZHSo^AK<5EpQI~spm)g#n z!4~ZBiAU^A71k`lS2C~;iUf6-6nwR_N!;nOD`ITo@hkZ`lOHgaW~xU;4P z?`UXh`t|2DTt9d_;850^)VBB3>aTyLJ0Vp$PLU1bV@K95E`;~LZ{@>Mq81){l+m}@ z@`>l_U_UlHa2OsqR#%4IRFarWw^7v}-yQ9CGA>)A7u%k@`h(`~ob}45L-#8Ks%*Xu zx$$7yF$WPU*bt(dq?Kl^dj`Xs=2l%dcPYDgZ;S3j z5!re@&gD%t;_z$^`OSBY6qLg3p~lh(`F^%E@*`H~NYU<(Ls^yEB-3$6=`GK6Hd4yN zTjT?UsH&=HVcXsKHY*GBS?v@2Bj0!ba@oZ*RyAMcp29Or_OluJFCYE)M_fKt1*tR% zGoCCwXF8rV2sImUJS}@!wJSa3P(o|R#Se+0A~jwo5llB!2UZEsJFhOS3SF-LIWt_k zvBghGdv`-b+?HGYPW6d?GQ+3ktqm`jwdr#`siLB?TUQNO2e*OC{HA zuj_@^Umm2-dOHA7&t)-iB{3nn?7hxP(Dvqq$Da>#%;96h!x=m;<&MnrMB=b8$r{3u zn7=xCi~0SJ`udPZ&y7q?;R`W(zUYRzQf`%(cLZMB=bD=(b_?R)@83L&Db~StFh9NY z`}d2Af@kDT2idRiuTu^nv=6K>E?R3Lm<`_O6~-!b-|4B6=C-ZX3#jmD(p%Xxiyp<< z78SC-{jKY-7v+KS9?qzYcax#XhiR6|n+R^}Blic^csDEBnu7&L7JQ0TVY%_>78!3j zvVE6T&L_rmyh>1dzG)jl3>ueRbPuUw^Xe|k7V_{|-LpY@_Ww;EXU zN-PQ!&ML8G*`VYy%$^uTsi2WnV6UfZDhZw6NaG35xMX)@*L(CwpUZ)p8MV%Yo2j#s z8D8%tM;!e5kEU_kbzFW}xc7cXUz(~~JBwSqif38V_CGg=zwNgG6Ds-Dk41apjJdS- zL}EFT(Kjm#?$!Jdoz$~SbjVq)nQxF)kJdb_&%KU^;$>nt{lvn;ZFsI*c+5=qGP$+L zxt@3&eEx-46kaz8n?0J9jnM6ni_~0)LLf<~;WF)XoeViP1`gl#C?X_99xz75z^oC) z$T$hN6zYDd2gDx`>W!pWxtR^^D*Nu9k4Z?Hj;}wG(B1ztLcX4^-WfDyalb@Tm2F#XVp;?~;ZI2_wFk~uvZwAB+7c6#D=rPk~TD_wuKBv5ns`uKb$ z6EjewNsjwRtP6YA7sl?j6!VsOm#MmiIw-QoI;e>-M9!}HtKw@h;Z?cmDbvE;;)itn zM>bKce#+jPJ)V4m4|wV(Ck8L?dR)%BSg&zHN`%4T(rdFlvoJ|y$ibend$94+%{0_F zMMQ<~THK)|rR4~@?Q)lJ+?zmq^T!#Y4BC|F#UdLiZpoBZ43QPz#6C4PCPMNp>6I9a zOfhq))-s|^yR1@nB7<*rXjnP=Dc{r}>(O+_d`WT!&bwDbnqkUObWO!3Qm#8p4Kw&C zpO3ho!7Tb-(bn~LyiZ215)qbO2yUyK=%XWx@ba~lw1a3>)vi*L>xIHkZ zMw%ngO%#FJ^gr0~-`*K*GpeNQ$?+%EE9b5~a{405(A4Fx8W(sxL1;}+`WOc(fxcO1 z_F03?HtIM@e#k8dV+5%By|mc4uHs55#gexeTId&$8f4 zX~N+?#hc~_FOA#2oKox#>%V;C=PyY4MNR0OsfySw`%4?uJ-&o)2qJ+X`oUjEKjMqV zL6j(CZDpv@z2%f$ZWW}0i(X+#_RVGI}|k^H<9mHOUvR?%0|Fh=+yW${$uN^58Dy17@tB(Yf=73&m&83GtQ{c zD=77Q#K^cAv>&QL{r-JnSb)gNP}(5No>)2-%^t2S?8CO;99GZYI2Eg67pb6Rv0xl( z9T-o3twew&n`KIb>7nnXF#>cUY(Kl{~!08{iH5Qr69!7y4c$l&(3z#dTJziPGg1wD2Ep{OH$$zkK<|5m2-Ad zvo+lNpJ0;wJSIvkBtG1@Q*T#f@ggrzCq3D5Kh`4i(W-a?SF;VrOdAtkCyUQ}+?MSV z-6qWu?9H(nvsd2)<5e?=!ZjR!ZJ!gs|CqUCEdBqy)+ zmyx!_wo5%%YX%tJT$ZR}V|bEMQGd>yODlR3o{tqejLrqU0=6`q?Xb#Z)vm*?nC?dw zIK(L4Rs!Y)`F}s+u+L}PsN3SRgI?PucUEte=GmM9i_;8P)^q||xQI#9;|VQ!`T^H+Y^^e)RA2-)Y)tA`zlt1I+tBC?+*+8#}KvC}c{_*yr z+Rpioi>YUQL(5-*9`xG#pI2p5uasJTO!vB!`_XQX2plIrVq9GFeyKA) z&B~XS)DXMsCe%-gL~Y*hx0RT?2jYtare2Z*??c*?e_vio5tyavkVS_hkK>%^bRDOiX1MhRvIO})R9=<(Z~;} zMEryBJ1Ix?r2g1khx{2t&|j#T1G|5e=pO7DT@hcqec>sm4^Mtx(>gWKheW4~?B;mL zD&xkZqO3e|OL5Yda0Z0+o%lUo1cXf0QXjCfOV>UupJ5Z9{H)cqs;-2m=~;01RHwzG zJQhO>mmW>fNf>^J@3>?C9{clM(d`>Q8|8!dBu$QNRrX2M3XN^xvFLm#97wQIQ`4Yy zE3mMB2)sRBbWUbxiGdp}L(b7uX-8412nHr(0DUOdaHO=>>1Ij0b=m9%(Jw2R=JcA8=3)00?A zWe1hs=4lN!)>95~*0H@|cIac8+s*roqN= zYOBewD&wHN*94IVPnh1nF&41z!p(4#?XwQM)YVpk)y}$EG%Plc)DeLxiH=?E8c8pm z_eO6c(yB5%$J1G7zcX~#KKWS1V4j_=QEn1mMDZT=Wz`l5n~GH%w6(I9?HCf2(NT6w z-}1Ttzb2fQjs6U;iVhXWTL&`^HYHZ&c8ZgD5@-&`zY&={XPjyrM0p{|q~EN;%ZDDq zp7OfHtsWh^?p|)vc|88NM5}D$IO_oeeUy#zh1r4wx@T#W-SW=mc6x6?v3g7K<&BF# z-oY<8!HR+)u~n^82ep%IN^V@F#{6@gv~7?|K_!1A>Qu+8*4!yY>WA-r6td#ahmjsW zbOe<5Ki+){+H4Ba@jd4@@(E6H=(xwH-_VQ}v$>F*1F|6q=jH+HOIN?xGhXrdLk?xb zAp<@e{MZviAkD50t>jHvLP_>YKlgmw!7IJ11b9oR)uve}gy&b6pk;aW#N$bUo!{Xn z9-o^&I%Po8W#&$3DhZ*tMpgJ;Rb;S1590WT^Ms$WT0P(jDB(?u);O5i)Y^l+d7s7W zX=N>-cLXi!2L2I@7Q)y7Qod?)*D(!dRml1HM1JmvY&`O1X0_kVK4iDc-lO zR4|gmr4Z8JlRz#)DS4$U%nheoCnuK7#5%8 z?p~)&O+y;y9b_W|tr7yoJamkIB-SL*=lraC+XFFYR0(?{p=arB)>{yD@0z<+Zk5#_ zuv#bC;9b=epJLt68+Md3G^BCk=e1JHmw*IF0<7T(P0VZFU4tgSDu6@5zWR1#91=4m zTlh7;=!4!Mr11uH{@x{cmm`9rp2)?1w?U5b(k5t2zOlwa;_c6wTQviyx1?Dw2n+BK zLo*nxbf{(B6k2>x4C~)=P`7YyWO5R_v1R@K=eZ2kfT)1_tEWF4jL;zs>TWDeCc>40 z&$V7{4i^~F^uVI06#h51$=+&XeqP2mdg#Zq4BmAw*ZV~t*EfB8Jdp~KDpu+U!kD{) zTNE~GA->}%?NiOeb4;sef4&Q`XeiYr9`$;IEGJzE@gV9&cRY*r0f&P2C;IlaG*(Lq zq5bAxhGLXzNH0f+t;#myy`L8H5t*b5nX58;9-KZQsF-tND|OJ34%wdom@SO~5r;aL z$#N`4zG;jsCFNBoBd~HOfcC|Fn!T&?4v$>V1*w$0DMfXT`+H9&R_@B}dF$deaeu>lx=Dod0=ektXFoOF4oGra!xtLl1N>Q?BK2m28+#YjGI`>_ zm4MAI8RNz?E;EF0ABnMG81y9){uNk%>#Vpxqo+!dqs1w6LXoiuM8b#C;G-cy=quv; z4--VbbKlci`s7XyQ7VEiCZ5aS9SsN2Zb>a3O$VCoy$*Y?DOQW7#+F=@O$|NG?EP`e zd*@nd$C^K@^MTrs`QzuFH9KT&1q!r_b4-?<^^e8~Ard=W?AF~dw2VjxnG`B&3#d(i z;6JsTmzQ_^iGKaec&vEKepOY~#wr-~$sGMY<{s&S{DIej3_eg31oK`jnewS;O-vuO z6h{}r2W_hTBS%jzrs@y)X2Xryf<4yAX#5pST7(+MJnJ#M7J^n9Mb4zFt+VXxY18|S zj0E=OQqQjnDLX1`fvW@%pJ3hOS(PnDIf_WhcH1-bVTu20ns~x?I%$>YmRx1Sz3Bc$ zZ#bjcKdG6P-)BIzJC)#kiSPOdp0=B&qH32wdu8Y3aWJOrP2}pCPYYD~RdMphZ{KI0a&!uVcXu!+xyV(URpjmsbmo-OW4 z6G6Z%XVK2m+QPznWj*8#%GvCsqXV1*)`|%}KFtQOpf8AZ9S@T-3`YH^m@V8YkISb= zIO|B6aXJTkHj$5y6tW$ytWtb%Z2eQ@&fpU`B6*Aae@;E`57iclmTo?ikdB_fX$)d; z@q@IASmquCleg8`va>p8JXB^6bsay4z6f^!FVV7yjdI7Km2k<3@MDck1Zhgpunxczn z5E+jZTlsuRy3M)BLbGZlU&xyDb&Q?v#pYyZE?y@8_3GOXl2pPC_eph)>9f;q%RtGen2mi^d0xnqhaXv0Gn8YwGZ!_0QYZem>PQEsNh!W(|al{ zU-=|1cAdYtpZ{@Lb@bC=uZSLbnG6l)A3d!L;e_EdX+C#4Z^Vp6F!g^FWA%s z^3}3VzV6{DTn#9kymerV=jXea?W?OBmw@`XrFc~}<5hvnB`NMph2~H6bMZ0hncx)w z)c50G75q!Dhvn4SW}n?w&G1x~ZbiNNrv=~#tOw~B6QpB@+DAweW<6eucI;~>gZ%JP z{@9S){cQXdbd|WI_RD5qxW_ny&Cxm1Dfb>dkIxq1_`zyoab9{+N0t}J4)DqOI@R{% zjMPe$rzc*sSin}puAfgd>BHu7k4@>otnkq6vF1bfLmbA35nt;>$5^*Wh8;;Bjh4Px z?KE5K^!qLdmU2;-8P>Ef;C&qB=S7SSum*m;VI9bN$)jeWNabe6p?{^dF7n3 zv&htGq{;_go#6y~e&yVUM-7t#y`~GZdF%&PQHD*k_+OjxwZxX?qW1uFY>QGZ-x8H{ zVGZZv50)tXf5Zw>3vd{?VS>tB>oYy;AqE^fM$lzX}oSPTX>mB*i!GUnowe zL@lYk6|5$Zazak0&sei^6`A=b_wYuQknt+vm#tMhGBhxAyvENHCH_1AKYw&-oBzj` z>BHo77I(sGzy}4xp3?01+j{6wmHC;mPMs?>LOKPi%F0x@zNV?$=5uFYr(=L~%f2b> zG~3nhs2HMQOZ3|PIbdVrmFe{3uLt<}7#VRPy{OH+WXCEHc8bg(%sN~Wpfa0qFNgOL z6UGjRFd)G`YwCgHewRj4US7w@$TJvdfNTsUxoW^Vdh&G;S1jwwGbpNL`7+hB()z71 z3OZIO(JKEeltlL)oimYVIf&@~^7L70*Q0py^%M6xVn*asfqG@_Bu^Ob8Ju+aI91kK zCC$U+6?YN4hi&Pj(7x|pwuk0tGIyt-T~1FAPkVR?7$V(HNw~$y7}~{@N%yQ+@T0C( zgGaptgENacyLzi$5XZB&Akw`Uj;z4vq`i#+yt=p>(y2_0!&UO<7DG^w6X@n}I*l77 zktWL+K4;KG@`u-|w$R6J*x=NxqFTp{9WT&dSs}Cfu}0X(5!il|NgtR()DC-kEfo{1 zPu8lBvP!nUsW)z{mrLwOWc7qbrNn%FMUi=}G{fh#lYvBXL@5vp#0xbkar>LnnnE*J zq?f0N!riV`cT@b>xi?36*B8FfS}E82u*`Clc%xB18A+` z_=ZYR9W2d;&Agw@0k7zITao6YR|m(D`GbdT+tROm3{yYV#m9#3717$S)Y9oglcF$x zfwa3Vv3z)8J|QlDcSede=g;u^LyhDD!S#ru70NAC6e84(I&E_9a3aDgfkxj-Dn;z- zq<-amg-%q%()APPFZIj^c1L+S&tQua2XhIE-6Id)oBoe=Rv|ci?UYNP5ZSP-My{iipLygNLwf9%`iqtH_9WSM)IOh(r(Ak7-3Qf&q7Ctb>4kv z8p9j@ff1(Ikm838!6-}Jv4#F3mwV)wr*AaU;#VvNEvw>uWL*b>1_d(6YiF$9hz9;! zEd9S5UCa!L*}<<`S~roXDu)BEv>c_Z(IiPa^+j11Omp^o%2VZWYGx4bJ0uOeTxSCbDGjf&Wryru?;W9FONG~qZZ!j*su?4@ zWCXhD4aErMt)$QOo>dO~bN7fyKeJb+`J$_rrE1UHc>u+G<0rmH)oGZI`*1+Xk9RSi zo;-~T$m?$7n3S?1Qtt)RZ)}db7wo%fElyRr(Ldx=zd9YUfGhtQ^V?3PitPYV6>xD$ z*s6ly;^HW|%?z%!c{#92B}yWI9-is8|N&&-hyzsUhlfQ0RdFN-p za%>cihTe@CY9`N1+ySXkS&U?+SOGy=k+DWc*~y;`+a;@*Mv{z9kW6=6VZO|l`o6Q% zqOk{R40=4jO5ZC-F_E5x=!GW4B@u4v)LB%ialiStaY{kVF{bZzW8fRgG+p7y`nj3*v~-EYKe$^|5I`$Mt-F_(CYC*-ZWd!u)m`6 zttUisuzjQpN-N^xxPF|XbO_n4rSEZCSYBQh@j-}4H{y#9QMF*E$H6LptIRnS<(lq- z;2s}pKZ;1s*dHV{A6T8+Ac|w;xn($MyQ}F?ZIecF{SSB~q826QH|E-qcjv9`(mibn zr2UONe23Q;ZLM76w+8*fOZW?|?yZ(pet(L&ACD2~j=*`1&igO_9`zXx+BNhg5m#w1 z^)J}2YpgMtQtRb)!N1WKu9-3JTqhV?v8A0%5Q^06*!%ynb>`tvzwP^^qYzQz=V!gGn@FAG_b(r|0<{$M$=X@d0whoGLtN zEZy1K8a!%;JJkuC@e^&XPs)_QCC;Www7QAx9;ukzAtG;kw{~8ZCiWo9qC~pxg)@H* zCf47$G~)BYEKM)(#?Zwxy~gZDE@0}(X_~Y0P}NyUV8Yxj2W1XM-C#O`Tq^E=^ZNDv zfoWM*s7@CweR?&7i!dcSFZ3Zj+RYioOt4d-Pz%iCwR@!fSgtp>u~v#QqNFYKPYy?s zf)~{94R<*gS`uaC#x4 z#c1;T1Q~U5@Qqs96@&J1kFfi>28;~F(lgiB5!(qmJSziB;`g&`B567cu5aTN*P3$u zXe>8_ru~hxWbxlOmb-F4WF1i%+s9AgtdvQqO58i!#JCrl=Y=Ib7=|s4U^nhxn6*5O8>$4F{ z5}n>BAwhcQ`7y?|M{?$?DGqFpCf+k4OSOn>)9ipA%KtEW1DPszctNL~?i_yo52#c$ z=PC|KsHe9;PtNMCk+z^}FqJwC`x$(B(Co?C3Vk;qa#SC%-B$_bC*TL$+}>D*XpIjv zRZzB$ceDbSX_`YgS`Q|+Ub@z3u$EwG1@|V!htnA|JN?_@wI?wrT%>oVYljP3WMN&j z(?HAmV%jZc4!;fHrAN<&)0&nmL3YmsPDX1x;q;4Q58Ys8$d!T*IcI^^`zdD=wVkCN zvDU-5U)6J^9OCD+MjlCsxG5&EsML)4SY6&tv+Nehtyt&<*zSXgXh|yW`moL&=8`kU$7T+7aj6(PBNk(h> zkp>5>NmQLA_|x!i=v-I4r-knS4c^NkL2#%Wc zQEWWOZm!aD@+seV>()q0nXS^(G_jtH>LS@g<9E`}v=o@AuVPWgw}wv@Ly2ZtTe_gR zQ$A?O{B0s)WkFg8KFoA7xWg>=ZsWm5`~JX*PcCn(i+X1Rz&HibsNZ)n#6Qu@7tWLA zS^H;jxwEO6b^J_kOy_)<;h%Z3yGud>R}k3f;hKo75Ian)d_Km%e6mmw%|zvfALCtF zc_9=3+hcze4@6CpL+!6PrJR1M^*~;qnB~ui22&l2nW6VL(CTQr-lO2n2B%DgJ;tiF zSPwDs_SRg-h{s3Av{C0S;9!3oG~wCzIEeKVE~1wIHKS*#{&XR8o&b8T==q|(AJ^m~ zP0ujGenavGg+YrU9)-jK6&TW{FGf`J>Dfnj+ZnFt2($AJ5l~L=R8X6>u-2akRo?TCr)=Y5m?7-y?`og3eOS)=^HD1Q%ocU$#xZ{A z){U^f-rn=54bZZHSyvh|z~yk=>UvYbRA~1jCQ)#FqA~#@X8o`LIPw4@2Cy^$ABvaU zsssu(lS;C(rLhS0*Dsig&ulfm%!^K8hoECM=6(?D6=$7ye;qgw- z%zL?j!BIZKf|@MEiuDjkQVSuRKi|B*Tj!RLb=frs9GQN28ER7~leurfI>8XQNA9)= z!j8~vr-xCs{;&td={3!eV+8wH=Y(Fe*4!`Ji^T}Ot!Uy#mK&sY2lu~a^Ik%X0$R3IIK2bLixq_YXt!9gq);Z zbDi(XZe0d|r?-X$u@hBh#^(EBNI`95d%F-!80+b>7@$$jRhy|Zm;V`N0^X~z`wAbs z51yFZx<-tpJ$1{SrL6uQ(gtbcK34@+Lk5EQsh7I{in$0O*DjscG8# zm&YPRFhNZ6#A$2mgNZVTz#BumXMOkwqdh4>_ z`UQNB!y?g#X7s@flivgq1Ln>s4b=W%u6^z6pUOD#e123kw1lO zT`9lVR1Q7cZM63c8VOfd&IwLnZT#h<@5(7TLx$3I_7$>R3l1wA)t4DQG>=Z4!-_+r zTMfNAjPWE9X?S>dUChf9_O9gIQlqWGPE#Bg&4{)$qx|n)=H=f>BFI5OwNDokcq@g? zszZuZ@Y~7g=i9mIpS_1J0z}7W*k)9bO`8cWHhi7P<|9q_Ji+v6={8&%!s&FJJ~8oD zJ9FitNOEf=;C1kpy+;8X=NCEqwpQ$OY*p~A2IAn2q1RrI6heQ>4nPdMHn6ClLHg}G zbVg`p0WcfCetkEzH@bU7B7E$PQm29k`#j`jNg}P!dq~R#;UhBBx!X-$hCn^++6M?M zAbXk1V0JyTg4uo1+A6Kr4J=^)1{Rm_(v&6druVw}6w3EVsmNgT%j8F&-PIw^=XPK5 zJA&|_@k%TIDXCK#`8XKw($cf9qCdy4pMzr!bG^Y(cMuY!<}@>Bfrzcl%2q>PPK3J( zX?qF;v7TMPy@uP>9+hwlusJZ^3_Sok=L-b&nMsR_D&-v_7++3n|n;M7{Ug!i#9y^^KX6Z$Uz^)im9RQRLje9R|5oth4*4cV}2 zpIP`$`R{`9zXk9wnZN8VQ%G_b>Bh0A7ry3oJ=v=;WOv>}#9Q({pp-c~`Fu&G*QS?3 z-u~R6L~hV~Sn7d#RkBzETE2qC+N0wG;gdZF9geS5GTo`X6kQCFRS{)7%Tn)W8RBtn zHw71r$|2}E_On8gMy zSrd2y6Fs~Q=mR2Y`_uU0A3#?LIP2SQ66;;T>>tbnH_xkaqeb#yJYWR`8|_$L%88c6 zFs#l2Mk^#yX;ScN)EsLilY{KZIFs48In5`C@Is=<{(d7afeM$#{m1ZH!N9JdHDAY?ntCHQY1*%|yJ+x^X?A1DXy0V4`8lJ)7zdE+H z%)j9u62^vN=$D7hJ3OwykCRrz8g}eveN-Jt@Sj2VL$_?4@y?O-8z--qub~1{NCQDT z|AjRE-lzWs@~3gavIh-xPA@&4QZsm`--IbUkY}P}LVyIx3K|+eEWT5y~z$XK} z{b$RL0eeWpSc~0ML1m>;!PksfhB9E-L3dsOQQ+q0{^9e1Sze?u78m!`d+A4Lj$fqZ z=fu>x%2%L&0MlBCxaF;+Q&y9Sn|S}0BT$}}!D+hxi{zSZeVwo>hd-BT#+TUN8yj{c zirOc~qKk@v>7Sd0+=*EQZQ}c(8<0b;Y?aNMA=?nhAaj;G`tY#lS8t;a;2bWR1M5?s z+K5iG$fx!b9}p)s5~>vTgXn7j84O(N%T^CGYKlZ z&gls+y_f}LG-7H(uNVe(2V#=8h&bUGn?TstmxwaRw(#2nAcDu1koK6yMFRVHbZ*og z8p{2QXSp59JW8ohroco;rS-sGh7pAo@n_zT+{_39$OxcJac|~Ub!pQERdI^23q&@; z2H?K(WXB&+Aqzz6uYgVa*Q)`#TrO`I9n9jors1wbd#FT*iVTq2@bS|Kmg8a`&Gb}LxX8!r{N50=Q^To1zPCh>K ziIQrE>#9^L1$PKwbj!T&fyc%PUzHi0VJ`FQbA6vrE&Dl|3r^bm!-l4D?0KXCD09O7 z`V)oB?4goT^n?C4QP2$6Gx;BuuH~RSPdmg;sqK8$7q-0hs4C3^M002=Jb~?Vb+(Hn zbi0Pd7Xn}Zl!JiBVnY_W8G_^YY$dT#;f{n7hY?TF{w)HkY%VhEMJ1our#lapUhqGvCU!Zy>m@q>Zl1GOP z-CXt?Um@>gHc}D4mLBEX!g_>C+iK%(v@0B%nSpCZSlXRcaqL)+m&jq=?ScyNa)9w& z$$Q8(n)c)F$*}Usu9SYrag%e#UE_rm#MZLeS8lSzcuBDgf~T zmuh2?hL`~JwUm|Vh*3T+^i&ZCy~gDDk0-*Ii?lii1ohcHYX%Z^9TviW; zMAB77-k|niw9K9m*0SU&pFw6|HgQHOHKw?nDUFV+h+_~=Vt>xnn*@|{f4lueJG2=B zt^@0pNl=h6D|`)fM7GSnWkZ4-kIF__itLvDqNV;qdA@@7J_VOE8#WI;DtGhytr7zr z_dZK-XbXgbkQKI)dlh)bgZ!wP*wx9db$Zxv7}>tua=xm?X)^O`y3?=Tk=qanSV4Ux z0o~X9ghjP)>p>M?+(yWtajY{$ewI{!eiR1g2wlG5dtC?obNp@y!39q$9d*(Qbg)R) zq$pX5fA92U8Z7GfMqlr{Yv5W7XzsPx4Imn_EVN$!h$`n*wqLvv6YP=M4ryR{1~O=Y)v-(%{aAOHR1o9RD^mf0+|l27)%`xB}`aF>e@B(@_} z>gb#uLFnij7X^9Lo$F4tu2V<8rYDp_P7OaWd1W|$pSi)$NFKtEao}wj#m6s(O33yR zzIr?T;EH8(TUiRCy>2O(vN*{534J1R@1J@4xt!9uYHZS3IigzXJits!KNPYi9-Luz z!D%PUKbWfqwB$EHia)avVyuFcYn}LrwHk%Hw%q7A`DR%z7rug>bwG)O+)~hA5C~xp zS7BKb$^I`m6OZ9Dd7=TsCGK9E9tgvhY7tCFWxTLrYhP385NHo{8IqQGYNb>T&6LNX zEY~;amK{Xl#&@S4bpEa z*-SFqNKp(?o|KRhc=>HDQgSYynNK@+rSH_|++MiC4&s0*`UF0*RGA{~v2uspZh6S^R~z4`axOm)i{qOE5HfhEE;Qex&~ zNLgQMhqv?LVQNP$*_8r7 zn03p^g+GipXn*v7$+o|9KGXYrWpFPu_r%m(IG>qIh%3=uc6vVF27j*iC^L+ufRwNO zA}Jl2I_mOJ9yRg=FfFH}9FUhVw8;z7Uo5@qfx67|iXIArJ7@Q>2< zTe8_|U9Q7xv8AYd=?7f?5vxsAK>rvAxr+eNyjY7jW~E3{}#gc)+1`!Y=nDf*lqvvlxDGnwvM-w23fo?7xuawcVC zz=sHEXQ*wv*~L!rkXLB@ciq#j38UOSVpehfElya=JvTOqdwRWyqZ<+!)bNs#h08EO zF_Na?gKo%GQ<2@E*W=gqZ@x;*l~Fb%+g&l*5vCHnr*Qve0U9j-dr$tOp=`eVJA5Dh z-V5L$8T^~%?Ujak2F?j-28HIdPW>RjEi*zSiv4&if&bLk+S+=h9QrAUm>G(7=KX+- z#l(T(CH5qEM=QDG11;yPMfXXvDj+w=s|sTA*v6FMh7lh?{zK_l>^YGnGLuFvXKwUy zdagT}Vws+qEg!uBT5<2{qo zi&&&9%h|N8`vZym%8F=7#;+|W;Bp0Xj8PD{!h8*6Z=MDkPI5-w^X(^ko&dM!Er3J; z)tDMjyyYOV-YyQTO#-+BsC#%r0Q6hzterDg^>V5VuCZbrigS+V$j zVNbBfJtzWtH^@RKXnHiF2UG*o+^U^huQ0wlGl)Aj)(1V?N!@iMa%4Ms5V=O$AweF{ zt}p8ZA2O#;&k*i!BwiNXYv&Q!r@L#^)<6|Dc35!g`$94j5B;B4tg)BD=6F!BDt@@~ zaRTpcTG~Ry>72&Eg{iZ~A#>!GEhsA>{=hGY*bSIJ5maS+k@heLFgR;NP z)*eleHd^K zVNTpKQS)3I$PTNl#bT?$w(BalRH5;~6Ap`E6Lsiru*8^INi_Em{b2iCp|EGq!~-Me zIA(KA3pqZpQ#L4ajB$=AzyquGa1Jg`kD9KgES137#jrXHmn~?or|@an2%{D|J=jI3 z#LtXo>Y1*M>Oa(&g<6j^Lq@!PX>3CuHPn@~Rn3>+Df)Tnm^8J8IzFDDk^a9fi+JL?u zB1D^>{*-U?A&CKdTKKp@(6-T5j2Fj6eB~B5(Zhy;js!KxPu7tI{3Y#1kDe)n#rrvE z6;`CbXBplI3d*L7x!{}$k~EMm0{H$v-mWUTK{4cFWzWDf&>$ys%9H;=$%K$gBM&G( z+ITK-;r`(S&-J9V*0+#>QxkYfR>LKfQS=5@!jwc_+}DU!2+stV8Ji1D`h*1q#gQQ% z3MrVcz^auxrT^JiJ@Y4+400`SUVu&ke<=D<**h~XHHF665yVS4Uu32ScqGIH1L^jApn*c9 zS)sab7FgeUB*(3luYYmZzqP2Qh!C4)5Nm}N>Pr*ytgoe!h5GJ$GdTnsqCN+rrNd?SAU1=c=+6)$AKCRCH=O6AKB~jN z5L(6wN|Fut8t(Z)6?ORL!~gYg{}V&v zd@HbeKxAmYl@IYwryXy7a{PF%dTb-t?AvXD=`rk7GWL1EC_s#Jj;$P;tgaPIPt_X` z(jMmyLTBn(z8mw=7E2-#v;fR&ZQT|$^qwnYvcvI{4$cV8u`E(!@#r~wBU)Wp`&@tE zwIQv>#w+DuS!7CnQz%pr7;T9ifB*%M8aNyNSPm*ZhIQif_M5^I58;iWJeGfq+~-k0 zZTkUoxU)!-*aXh(Nqf{Y;MRO$nJaCmoPG~*hiQikUz;Z-C7rWMjzN`jthXM6@wojS zzW-s2&U~e06ae#t13juLW3xUYQ}E+!_x#TNB1a`N=e~YDSqtf_gn68eigAe6;q^x= z)421Y4{?z$ET0oR36bRWpXoEo;*!#`(!uxDk|yZawR%J9#2d}m8c%HoCmF(4TeU-} zbuEzJZt031FtJJ1_i77FaHzQ$560J^tevpm&vJKBxPi_4=Xi(MWkTe*RKMpoT>nsN zM@UH32|Tu}PydA7sT>t}akxYrepj+FN}tS~bb>bR*+d;DUop~{ub@ZQ+>Tmxvw3|& zdyiC}qB;2^%+g_N^#9zr=HbSFUAAbMtg}wI&Zu~KYcVF&QLKWL7X)Fpo5a^my9F?Q zz}fGulZ?QqW(CxWzi)~bOy+-xsgnOO(l$=xYTQTgsB*ZI+A@(TKZ4OZC9>iotu`0l zYIYOgBH-zwv6weZ++pTdm4gu*={2kkR1(?@WE>%IWbN+e(jGu>CN8&OKgIEb^^H2kH+agB62M`{6 zEa^zQX>A!dYJeax+WGdzP}6X27ZOYA9GRGJI(E`wT$Sk>Ru1u~vZY;$eQsP?&cVA; z(NO!QG|=AHvq(nN>zpA77MysTNgwd>w~CiXbbTjl@wAUb6}AC!r@UjiYd{7s9Ab zO<4{2T9tnZaOeIJ;CR`ut1JWKREwBN*%}y6mL1S$D_+*Ylh)~V?=l&Ui^xNtVIPk- zC=zpP$s-)_R|-Rc0M*gWW-Gc?G>5Ev=s0EgRWvS{Ke>f|!miq{EO(LlKrO!nO^^6% z6!ymp=B$E=HZ*ZanleH+cM38cAz85Zy?gyy;Yf!*6bE6Vs|D1IJe{Hh=z>&&&x=7I zWdS%2xJ`K(?bd%J7_gljfd86jo`I1`9;m3mDCruY4Hp;B0e2BF7Fb$Z0#iNEg1*Rb z*sg6XQ-hp=3O{radYh+pWOR)@sUhN0$_io6*F;7j0ki48Q$ zB?E$`h@$FN=M<|q4JLabwWYwozu}p{j)r^#?%uWALP&A3IHvUh-I5_daU4KwsUGx15GZuQEw5p#alljP5Dli<2 zW!{M4HUjyeuZ@Z>%+_0l7|>1!xJ-K{&FQgF9%YH>4Gj^|`N$-Y922lGo_N?n2?v zof-h;U+Gk7Fdi$L#=Qdl@G=Wq*A)#=yI|Q;-g&-l2;UMgO7{?MbO(}qeqMqMyyV4; z7YgOGG`T)lT($jM@F@ZhIg$%{ph%)Ix`y_!)1%c2c-4r6R**W^3&QqwAquo)KHa`y+>m6Tbu4omoR5QqY&Q&Ob)2gJ(h!#^d19k_}z$)n^M-1 zz6Xr+kJ2<{cI%v<)C5D^;VuLMT6*oXSUgP*XUacE)`5K1fvnbBrCoGS%z{c*=(!8` zR^|#sA|Rap{o)OtSqYsK))!I@{`iB0PSX6`FApF%A<~?ugeS-(zbZ7oT<0u4{cSFH zLw)*#m7s|b{m0v2&lAa60N`f<0jrY+)P;RgDD-0?gvpQV@} z2^(MN`}#Ti-QMa$PdC?liGVY{osG}r(`BwTJE=b zg5T@YSX*oBb4$s7kgFgi8qApL!?)xxP?tEck6DFI(%R=`FCR~?6uM(2tY_Ji<`>LQt4TSdIs z0masjz`PGiQ=pM^)8wSZ4;|_l)%iRf1`+V{+SSwU2VebEc43TBN&_?~8A2SnFYC2n zU@(CQ_!6BEx`bd3nQV6dUALW=j+k-?aMXriR#H+&%~h)B?xUu3o%)h17=aT>(Df6{ zu^X)%{aBbl=rsAtB$vw^A+1XH-IR#Fwy+GvEqg#TVvU%QR^hIU`i?lQ7Y2L3p%Gi@ zGFBz;W3(5|33G$*7xw+1<(jdb3EfeqPDcie{bf=xyu=t~7gCcj;ntK2WS=TpI>&o! z?(63pY{t#m0G7i+s)gh|V8J^<`fT${>Q{l-4k|54n7>qfqTcb4xi7tp9Tz8vcq3l{ zhpY(`Xu6N-sLeDRV6HKn>Nkah&&L$xPFOASn;qYH8e@{F5t2KcNmV`wIrDc)k@ls= zsTef4;IXr|X3b~%xu_e;n(!n|f-XN%4|=J>8Bi8otJp83nr-nt(6LoeHP*dKek`5@ zhEaJ5PTs9Y4L(6Q;M@9eh;^+Kzey`6nqX)HDv%so0?P7dy2mTvv~%<1hFmFBX^dj2 zuTif%DmN_`)j8S#gxQlDrU=cI#U--dO5jx{BwI$Q)<2O_YV9-Ayt1t8YdaJ37!e3O z3k?s-|DgWz<3t=Ii^&T2K4S~??Ts#d$^JhVr$2w}f7FkyEB)Yv`;u!Kmg9Ml%$&!k zMt)Qh0e@m^*{*#PRduf$lxRr2w^U?bX)(pf9&7fKj@K4(9yvqG;fWM4zUuHJ*)uEs zy{ug3J<@l8w^M~Zqy2zRy(w!!ayB@*lle=z@?R6nzmYiXHc>U~X35o|cc%_xJVJu1 zm;uOkOacJ};yV2=zY17X(oZ4l4LZy%l`IR1`tnho1BasJ4>=r0+5e1`={ z)d?+>_{^C{3W}0N4I+Yql8%NDqztK$`=P-br`kUby3~Pa4k{N_KwfxHNZY#!EG8}8 zb^AEgzpAsORbFV@%WSmAW>p-|3g zxdV@BN0-IZX*k)O+L-(mw(G&%WU0QEk=X4V@}SmnUvv|!iBTEYrx--O8324qJc?c=FL?;YtY^Lhk{OUrZL1vWmGWIt1` zP*PTuQzhwFb>FoLt1-p_nRyAGTexsE)CuO|7fGD1WEUF+oIl1_GEI}MF*)wVJ1JQK zV61KhP8c|YSM}MAOPFHxuRqqwVQ^?RJ(@(V#MIaDizzT6-uY^l9a$rwzme~Bqp7-?`%^Z|!6Z3CgA8v0BvxS8`tI~+er88=PT2Og> z7;90PuJ?9$))Z065m)(iPZ0Z9NX8IV(`cLJvpr9iiMWYomAq0XHm_>hm&*t}Wb%ob zi9dX-QrWZVGVgLgCCfODgpj<>8IK6qSZ+EdO*WatZkz6dH`{`Z4e;p!QS%twky!h} z`1CH|Wf4yEp4#c^-CJmMbT+iXZ*1sbD=`l0F#H{lh!<5!l_oEm( zIG!N!Q#u9W80`5URNYqSH&xFGW|H1e>bOGhXm!xHtF?bCtrMx6 zEnQ`atGY21b%IkB^XfSLNbB}++k_8CW15~8Q1IsE(Q|*slrVmGiH5KZUdm-SA@22S zS8fO%wT0aZK1424q8JX}(V@DYruPltvfw4nEhrwE@pBk>gK$FKick4TK0TU z!#9#Ly^w7%xiMb=%nqd_qsaT31>as8S+*ytyN*!C`X2>P>_fgsy(!crhvNlxk;}_J zd-T@Ysq=)-xu$!xy_|oYtNH&>OC8y8x41T&EIC@9AC(P*f$gKMNXMU98Vp?v+E9WS z!{1?DbOxm24J-yGEix@$06Ze)C@dtU_W79LIE$L;Cq<(Bi*G{%N0_!3$>)`mSAl+0 z4TOTTQ+dqml!ZIU@|FGaAk3tZQ-uset`HN^+78NT^UPRPiM5>4v-T-5sFEAygE4&U zuuh<%^TstEX+KFE+43oscM9S16sqeQj&HVca#NZwkY5~>X*Y4!K#QWgqon-WjrtOI zy=gy~ek_av-O2+M#Rq@R;8wStKc2IZorl8nFz`=*6niElumud0^P1gA)agZ# zFUHJM^M)r@q@-2M0Cj7?bS)-u(a?RqfPR2{5Pt-kj|foXhLH+oTsULXTZCh637S2; zi)IO^j{wSwHt^(}=ackz`1Bbh(T$4g?F-LwI($I2HB`r@l_%HKNj)Va^=PFQUD)|C z3Ja5LzW{R-GjGO~UR-mJ4vv5#b7Kng*sv<-az&Dm8Ih{=WiVt+018@t#msFWiV9CYL z*(up^TT4p^y-G;YS)A{D{$(d8pA_P4f+)?BcWi=9nU}!3yt<2TW#RegcoKD$aG}v2 zZ^OhqXyp3+@|~KfN&x(W!~;<7f{{ik3?eZ~@&;$`Su1`U5$~Sr0~%SZ?Z4|P0Fe6V z`ImoUpnWvCQkCV3Y?sfV)DSj*9z(O(LV?7_|qXvAL8R|MrX zJhlarW98Hv8n##+jdyi-_)$#XisSBkPv4RlwuE~ij`}^UGfGcybGHyLh6g||ZRcnn zhsZ?wNauD|7D_dUrn|Eq#fe4st(SL@COr<01kNXF=Qy`!FnpGcZedm1?aOj^_W+Q- zQ@Fn8y&L&3^5I_k|Li@H_?wG#U={@Y<&}`H;_JqfDef{I4wgl!wrm$RoEJhf8#||Y z*?lD;b#cRvGl?uTI_50zCSgC`Y(a-UZG5~x+cK;#s$B@dgbG|&~m*W_8Y1OI{mfItu3>=$XdNq!&`*K+P|XiKwN4@_IUR;>1}IJ%5Fy*=g#!u>1kZB=`DU zX0-HpQsDF`;1L|KPB&93FB`V<)h*wBDufch_w@61Ee?`k^1}+sn{*@h;jAQ37oq6D zl2OQ<8ZmR%^}e0+BsVbbDMt!P%$W~Q8tP|T9LR+ncJ-MTce{V6W>)q7Du|wgiq#!a9L_qx`Nvcm5LYZejWf zMSMopGmc8~YJB7*ClwJ2Hkj%x$jt!P)Qm;_uW^uauPcJ;wlTdhJiu>xwPGGit_qCS; zOSMqpeK$O`1q(J(k%ZA?h~>x@=)Qy`Mi9nqW*@fs6-ANf1bQL#itJi^0LL2w*Arydb5$isI z_8QXa>AY4UQmEp;#QU%?y@8vD;%zc`261{gx^z;2W&eZ#CA{?{NQ3Y`1p62+rVj}e z%hNfE^AydcoQAYRkgX7k80l#=7v83-JfZw|f#RTs)7+M!c}$3oSx^1S#Yg00{GmTf zNRBTP;;jm^U|H4_Cp&SYN_m5#IweK#@g7x)dqy1kw8*u>D?a-8?F8tIemluCY5j6i z*a+gCj*yJp_O8?W&t%TfkL58HE=fW4>-sx7WT)jvH7&M$_-nkqyAiH!*$;LPs%HI9 z@dfIEuvm9qBU6{LamkJHcE1*)Sjy#H3_8v#| zmBvshom9m0;6vKH+m)Qd!pDw3G_HzPn_AYxaOap9tUY6aU2Mo{6ADfie57E6(GDgrG08wWRu^_RTKOhc_0TojAgm{ zL_Rq79tCqfK=!^q3}kWD#?ZJb?=PqJ4w$aEF&FurjPoY$wsK-WQXc1u-R%OezGLw_ zS%KPgSuB)#mU;cyY`q#wpiNr34AN)7e`a2}!q3j2M`|nTS#PIM*+uxSEgy~D-Lq~4 z+PN((NM_55bNcmQbv$(D)0~lF>aR$l@w~Ap2FlRxF?cmU)qX~nj8CJ3Z{i#!dWGCW zP6G>^#|q)-Xmw}PHPnBt zX8*j0zn=XkXUn*x=E)y1Ob$4vfw^IQvE0xQWG$7X*5-GK#E$@Uy-r7PeHR>`fb9_p z%V8;z_pd49_;7rTk+MF`a57Jc(JkU`pBqcf2((E`r%Eq!tG)#GJV(2SM#v_>H}6E) z0J55A!l&+UcFscMh&Wt$X9ogVyPaQ^Zc{Td8q#sDJ*ECKgbNdmdqiNaFEjn8Vdon4 z2Q1tG2=4~Iw5;>UZ*@kW0f|}M2*pg?Wfp*jEA*PWW~~$XY1~PVpL@9)h6zYA#pK2E z=LUy_>__j@f6B;AkEQH5xT$Bd#4+^hbN=0^&?q;SkA^Wbnc_(tQ+tHZx3J-is`y8f}#5~Aj^ zn^dGput6jD+_A3`KiS+R2fHda>$!Qx3lPwQwXh&a5SH+>M;-$mA7(YS%BXn0l7GSi zum$d?=Rt0A>2o*I{`f!@=b)OAZ%4cHRD{E)BW8F+84Z)0gcxx38Z4OI3H8-0GQAGH zCd6&9Xsby44MaJhey!aS0x@tv{0Vd<4JgdQ8kg%m3WIx(eu?ht9e6kgknt~4K+m@#-^dum)`kyOna3vijo>-wcFwFdPgcGIO@!-Kx# zN0vQ~WZYv888cc7nV+HL>~;yK8%{GoRoRHxOKBd+oDS7tyOjlvh!rI_iBkehGouah z`!=hD$$nw)t8&sEr>Z844A;JQVs#t;wNU3j0f!28RMoq!h4PfTn7s7v7CV{QSSKwC z&MqfUwh6G9Fbl3x5?ze{k3HTt;Wmq!3v+Bn`jT|h98G|ChGyvX=p^tuXPI_^(j;a4 zX1@S?u=xmP6RH3*6$swQaKE7xeLPjDu{l&TWnnen(7VHPq>g0BgwL0nvIW&(wuPD# zX5yCj&`roog;i5ag>klyz4tdjn#C$GvjE2nAcIOFg-=gQF0h-CB6Kn)8HInyg^cBa zsfbn@0EDcqQvzU<-vZx)St<4=kf=jVn{&%<)6|>lJ^;_!ZwRF89=$FG!6i zJ8+U|Y%3Gwi1)~DH44iZ))|SyW%`;)tOJmcs$PH$lQwZD!LSyn^=NC?=Ike+1dW0x)O!(k*_Ev^cJ9lmOx+-8o?h4zE@XT36l`gEz{@1_1U}=y9z1cU&@TtEpHDQ) zDCd&?auEFf6JZJy!ha?XHVVs{(P2g5KS{<_V;c@k;}-aD#N6)Vdkl4aQFqq57*7m& z`B5}Xl3cm{gmLafeR0~djMnfD9vr=V2D#*k*Pt%^L1!G`22llIh*}a95s`>{fX;cU z@bsHJdzj^Jxih@P77vNf)s|G3iF2h`sdf zNpgBzK*_9XLarUGr@;soW)$AAUEQj+2k`^k=YDgMO6Z_(Uq@3$wCXM@icwYGIgz0k zVyBp!OX8*`c|IrUk_XkMmT{>dv}}SJuQ5)RrBQn>&2%rfK{HQ8fF`kF3jJsdN<-9E z-%DNnKSj=i&Hp@?1S6y+2D0TmpOn4d$sF!^_k_G87v`)=_(|UWR8pf3*jX}*LHYX< z-y);M*q|VOmM2$C58m$4mLXUqyy*!B{j&kU*#+zH;B5qn;v)Md=1iM2`w4mkNM3UK zDK}*&^`0gvkG)F4cy|?9YEJ@?r2v5kDi18Vn8K5`wP7n1t2dev3epQIrE-9yvvLXI zIR7~PiKzT$-MfO~j=v17%l?;(qjqp&CAaFw%P>0d5Ph+HOAiI8gOH#%yXrFPsp&yC zw)$X1u&*JW4_Y55Jku5QlbLEE+B31dye#=1nrH|&_hy2Fy`O+m0DiTsBOrb6)lZ#v zPgF~*BH_xs>eIsKMtpG|5Z2Pkg^{g_sy7{>=8F%u`0%aI^uEQ(jPbct7C$o@+TLh0 zKn>BpQN$gFpwFUp$0%yZOez((Lz%8d`FEWvN-3NYfj6z|$6sxq*uhr5 z&=WO#ggaw7qwbU?NO9Mo2gdG$++pk*&5wj;c-S~n_wd$%jy@gG4fpZAfY|>bQ5v$mR3jzG5hzn?wlzW2w{M4uWUOLF#%HWA( zyUO$wDU}^ylYRcXqjiJP+Q$55&PcWe-fFh@`%Z*`rO}9EV9%g;aow7QXZWw0i?{Ly z2M6E(Q0(mfUe~LB$Wih7waC7mieKv2y`0}#e2NL?veDAk9y-f%m3-v#dATBO?Z@Gy zGJTh~Q=*(~H^#p2Z+a)wboQZC;lZ=7tjzVIw1U85Sdz7AQy=cuD&p(&>I;{fi(+&% zgI+_O-tuA~k3UOyYF&(Oa=BjB-raqMR=eEu9xOC6EU6f~xM^T*t!892mJ`}jrQDld zYQ^~Q`j|Vd?!vu-r6bfw5g15D-7obkUmspb@)+#RvUweYyMa4%{$NJ<&uc=Nl0|Go zfsrp_T-Y&REdz(YjZ3>Jjh%XM`R&oy2dx8ZXKW4&oLB2}Tq?O^r1=puw3P5N3R7g_ zNK~V!P#;E^B|kn~BU0F3AbkF|^&4OpUs|=l{h0CHL)yP?*>k}Djz-gYF6Q1l)rcEK zZf|GaobvA5Pg=2TKYm!D=G2)P-Gc0jr$_shuYGoQPG9b3TnoLnFT>L~hg>18`r88i zu+*`o0`V-zIcHXLytwm(IT48=B7Ym-asR4?G3gy1Ms#*|{#L)4nb&3P`EcRWQfRRA z+qG9u%;XICV%%K={QOEshF)3p^fU4&-`w%dgmjnLZ}`j6y;%WAp2cU~Hci$^y5N;> zseXBg&KNozQ)}oyy2;|Trj^bE%q)w4;9jxAv)Y?(ZqIi7 zU-y4~QG=(8b2M8uF zxAnn4@YynC9Ovp@8f1UJxf3xItK-!C>B6P%o}TxeH=owsC-3&&i9Af5t=U9;stPva~)bnytPgm@euGQfA`G!^ZsJKTDY6Z-6%h;Ea(2p zTDGJj!20cOhkN8}_^(~_ib(@0s_Uwhj^p3Lofz1)u zuD#xwx3_*U4pv@&*fQ`?ueYcMV8REf%RBQ*Z5ix4VOrOZc-bmGRj9`cd=jP3a2BB-JLY$T3w>W-GFW_>7&uf-+6Ek&u-XfWQB+F7H z`SvQBm7=_VQ_-Cx6?e<;sLa05$NwrT)@&>~7&j97F2Z2v{E7N^DvaZ_(k!>Ph2|39WZmW> zT-Zmhty(b#ADY)>;YU-c*0ch9gGX~Vbkd4PP8~b#SLMqGcQy)j4ZTgSZ)%fQS1#pH zM0e+1sW2chIXWDnwLw>`2FoY?@a#l?vUS zIHms3`tu$W^RquCpZ;+&u=(hBMRpbSL-vXuR*NYO#YIK$I|G{5cQ1^%xi6Jn6qK#} z6ysCxB=4nh?C~^oF2^)eiM9Rs>+0){a+mmWzFmtAGq6@QO+Z!f6@0xw5 zIF4QS+SRm@YhGUQ6%`fl?Uhq|TP8}lo>|2cKRs}WWw)P5acz;3Bgv+Yj^1|W$a}{s;)pxQnjD&JpgiRo( zGbU}eeC62Y(c-tKE{Ge1q=8l7@6DCJ$BiWG?quvQeW%uRto|Vx0q%*shX&p1Y!@$H z{DGD$?yPwG;A92vC`GB$^0}*WQ?Ox;@@%HzOG;g0uE@;v>PW!_Z_NuiFfW^tdx~!F zl}YJF)STj|>zfVAGM7l#Z+)*d?AOXoz1B1wJrcfN-I;tdJ+YfU^1A9}R6yO$D&^oC z?QZR6$0zKMrH9t%M835>y@hkWnV#QG{Z91`ck&#b7C&uf%S;tH{(PjuzBq9#AvR`~ zy=N(`v!Yw*6$5>Xl+Zy_FZ}0-#^~Lb%6xZ5J;hnE!ph4!o%Xu(rmX(!)WSfW_c6!7 z$Nz@VL-QOKGkCH8gQ9wZ8DXy%%Na|8e!*aZP2>)-=JWfI~#7A}TNfB2uJ-ZB(QwCG;kp03sNq zOH)S&K}86Jsx*@jLhpeH3MwTCgwP2hEtEuB=zIrt-kbORf%4Pj+;h)9d+)W^UiaKZ zKjF)AXU~2G(cosb{Z3*O~p4P+!qb{LyGmMF zg$(7?)a}hu*ue>92+s2ps^}CjYjk2wzEzlEkJdN7{Zngdm6`{;;x^Ls8uG>9E+!ez z5$6i6(21*)>!#7w8wKs_yOxl8A zlJ2lR3*|6G0IQ8A8};+%!_u8kRxg;nK2TD221UI=bCIoplvyg4cnqaOk{v$qwZ@4*@JnfY2;~P+w{gt z%S@)37UG|IpV_Y0mmZGePedCQj90+I$#f}dA^#mU(h$8m-tR0;;F;B>LEA3+)z&M$ zU|(4+kUp(o$SFa0AM|$!Wlac8t#^k>e(#(4$BJ-tMIDCN>dC!5i`dt^QTsSw?a78F zdbBmfuV9OL@*&B21c=if=$4J764h41j~r#m&W7LtmJXDp?r zYx(Wht#AQW78dTvoiC?7r2nABcuEqWmrs}7;J+bRuZT{Um-fa%v()U8XnOk$8lTtX zTjCzKW}ZqYBiP}&EA~7B*6O05PKK_>rlbfaA(4ZgnQ2R1UB<$?aF!=U#{i|!2uB9UZtJh zUR+%4GY(OHXTXxIg{nzdgz%b}A?at&ovWm$q^En!^m<-QVm?4FVjZt8yfiI0Fj5Iw zBwx&4fF^aSM8XGB{M!kvvGWay@HBXW|BT$WIs1ztv6mEJ2za>>e4i;!@=IUaDD>vU z2x$%X#$W(Rm7(kXCGK?=jk=fi<0T!@;>z9TCmK;4asrPf;fAnk@pU>=COWm+_B1t# z9<=zKp8C&AlJkX`DLRx2if^H{cM{z#jr;|_5u`?`uC889LG84LEHZ=fIbkbLq-w+w z4@7drXuKvlnY6%;Sp}Zis&@aggkL%LR0RxVsbp-`Sk zNNbGKDiWQLnZjtxIqS7=KSY|Z<~x(aKFEk$nD0=}1Z9y408E*qS)8?uJKqPFx0+*D zae+6e#Q>8U*7p)#cg2~;0=!n~XulzocsWIY^n)|{y+x+WIpqkTDlCUqAkI~o1~^v} zmP0V&z(!zKq*HAzEj{o?m?8)G`WLIQ;);sqv8E@34j!r^3Mwisjg6OUjrx66MGh)M zi=0!4F>1psClVdNH?=aaJmD!f3xb$oV;yjXivo$TG zvg=GHQme~z?bYaPP%n#`xZ8v3PiYV0tgkc)IZqBL!1!KB{f%|JC8|$X+f~?qBR1|pYlb13&%)ADF!eMp($o&TgC}7Kv5T?dza^z}?AWmuOsv9t zYnju0hscm0`o2JFUuhI;k|8R*x01;N=jaO8 zeTS#Gi-F*`?{*Sa&l+B}ugvToKw#dvrreUi>svO?jNM^NS6@%}=Nw>>PCTAcPw{7g33vjM!trZ02VC0LEX z5yZVk8CP)MENyK?2c>*~U*mYdE2h1D&5_-$>k@r7mX?m;;o-8UTa!DC;~;#qsvU@T zdSm46IX>z{G8T*VCMNwzXDE1+v~D4Xv6Pc77^VfTL(c+9YqZIaZ3uPce#9r)1XH$J zAjI4*C&48w>tQXIhgC4O1rB!R$eq@0(<=n4OEtg^ILp_!d?JuHi)BSohpQLDESQq5 zftW~F+mdtRK$dgKsM*ZcN_kNh&7U;G3=OzkJT$nz6e6r=2+)mVCik zHovAy?ql*&@hknGW}d&lS3H0I;3oM(F(vH)zUDPd@?X@i(^yUJ|i#!pY;`OFhku(hnJSA_JUt(ybuKr<535#LRmRgCGN3o!GVE>9-HTGC*f{Vzu7D z$<0(07k`C~_DDBy{G&F-aXK}%UE6HW02f~#sEP3k3X{Yv$%H(YNHg$79>6So540`B z$wACzuF}?YSDYFfgjT;NE8h?}#5u2w(Ua)iCe>`FAO>$of3(3btQ3xC+l|L0D`&lf zZWNVYHyv(4TN{`lv3e(NxA<>V!S3Z6c{U*E zisF_XTg=)*3)wR*^tL8#UJ*2F#kMp@g_%p^;wck7W%b3Ds`10!E`bQOd1dz4EtyJFCJTyu#IE zprsHM<9<{2H(Sf$l1b2K62vIn_LD^`hXOvy8fc#K&`o#tSc5{>D5Zp{@`1Ooo8&Jq zt%6?b_UTVjCXUa3zbh@qcR1(f8R*v(`OM7ByI8Nu$;kmsQf_W;u}haS*PEG83Xe+6$-3hJl3K?b%b@vzrDVGYJ)aIS%ioVmGq%W9$Ctyj#`ET7j|y!ox! zURZrJktv`l+*=RfKImy?jkaEMDdVb z&qT+84ElsQX1*lWeb_{LUeDc@z6+eRw|gY!NO>^a(eVwp6WpPqy85$&yt_=ZpN?zV zgjzz#2~v(vqSXKl`MSNTfNUUmOi*Wds%>&oQcq8BKFkuSTtHD9mwX={m0NSwJ#43k zDmO|Gx2w0$v@I{W;C&;Nrto|we%Z45=H=})BODKQ9M4%ld;(`JQCU%O0hX9n!RExY z!)@W-IIA4S>z(ZFEalu>sYZq5Znk|wV91E!XKKI8;ZL9(mK=^KFzk_Zj>2Vr&&do`AJ!LxppLETWHedm1^W=TvP-OLNyJ* z6%>>uFwi%#Q?GZ7B3?73HdlHuNkT`!(;s^&@BqH9LN4E;DMkHjhVFd_S^WaDiz)K> zsnn0EWMR^{F-$8%|N-eX!8$*35Amvg;VBZ68M|w>Vk~2!0I^4|w!-;} zCKPMTB9!;H5fZXaI9}SwhaH;S`Q(;oKMPmj@xMDE(w$#!EJrsIEBpnzv(Oc@ocGI1 zaF~`tet0>p2xdhNIWrah_Lk(>9q;QKC-hcw{glVm%%ULKioGS~4uxioYc)MixKEhv zQ1dW*_Sxl-9_b=0a`L@f(a8h()vFMG_}?Z-=K@m15Vm}=JPsc_7MxzI_b@NB^oYwq z7bp)&H(vDN>~Nchdna^et8h%j_M7NnqwhOL3_BTDc%NCOQ;-37>g;(MuXD~`;V~bS zyW5?#{N^`Ob_GZ|p(fN3cmJIZ!Je6oZq1UoF|$DDunuW=Hm-hr4IP0Y+oyatcw{`x zL>r!<5VM8r->-GuSC0LJw;H>RJ;~SgJq+~z>7R4%;X0ylkiMGl<{K3-w;p*ccnN!= zQp&PXr!le<+hRC6rHUT8QEsZOk(t;jJ@s;%ToQU`*x%jX-{0$8k*S(Q%#DbbPuJ8_ zG9W7)VlM;8)RM=#%Dy)O&6%Ayr!BBCFyMoY$hq5QP2Isb&ps0w&RGkz-l5)mcGzcK z3uUJ=m6ge|{mDys=+3aqcR!<^2|ei1wzjsSq9XaD72jvo0@&VhJoSKM4tGxl-Hpn% zx|E<@ICiPopxGoY!9N{^5}F+iwPQopsKB(buvjt)8zPWL7}h3jryeMc#V?y-X1jJF zCbNC`NY@Sm%)A#Gdtv(fC&jFl!N=ZY>Ydu>&CttIIA0vENt@%4C@+Ue;IKTyW&E1rcAMi6m-*RZ>)k|P{qx7 z5Nd=N4~UnsXfJO0riAH08e~<9TmPP($G-X~M3A-II8ZJ`2mccuQ>MoPI> zk=gmz#5~Sx)jUDA+>?9@WRlUoJKRC=tn?kUUUIJk8ph!wB3aNDW=ikpFhQtw3+#{rL9^xvs^GWDcgmkTou>7|p@`ECK`*!3hGmjHtP8z&G8iDm zbez(0zC|CeiFL6>f%8jx-ORQlV?)n|L6tiToMh;rn6%A+D<4Asr-m_Zdb{B4o!(~n z(GcfHg9-Iu{;4UmkycPBPSc&ypPWiAGW%FjQle1dWsQqLvs&QPZ}h!>x(upJ?hgvZ zDAGH^4Sg1N;HpX(F z+B9-$sE{2sN0wosBjtQ~u=A5!vmD{lt2DpVi-Q@lQ?V;C`ym2+6+M`=xoy);bX@tn zaita-toZcR&j>vtYO|E{Bf?K-v=z}dC7A{aU8k_H^!4@i3KHM4< zEtj>zH!9+CMX;P<>%mN}BYt-&A&T?(*3n*H)ooMy=0;olEVOZ|6z*V&jA^TCo24bs zz)Hwsy`NTI{IcQ9UL9&I^9Sw29d6;0SUX(v&0EIUvYLc#ho;^z-9qvbs>SaOvpk?EKb~%TW}Fo z!{O9eWQTt+)aALdo8((Z*MXHBoA}XLe${=Mz|dsj6>o(_Ko+(>G>P-NdHy}{1J>B>v`g( zlZy?7A?bvM)j2Qfkp0kwts~axcW8>{_HFhtA?+!YRFUqdL=tWF-be!8!#@t~|h^9(vML{0tw= zE6LKHIU8;=Q@ebx*<~SD2$nB4>;LCGnrzx%T4)DKiVkeJp(wukiNZBLTHZXwn-7DC z{wlOZc5{uhMryZFy13M?h2vY5B#+?rJ_lqTtUji=>SwoZm9bfVcHMuQHEJW82Vpa{ zGD84Hr>U(Say3^=Y40NQGwd{w=$F?>im|7%Nk}zi1>WdM?DwiBkghO=&;1B^Yf$?U6)&um|92s?Zoq- zTdT6#U+%}{E^`>3m9Y9<2#?1ritvE?(K|ZXG@P3=`ocy1KaHdD91sZFuT7truW%26 zC=a_E^*87d+WiwF1sN>Sbip0KI{Mhg$+Z-WU2eWvpGm8UG4Qyu@HIxSoR-HaRAlCo zOv37=_ByDyI!`V^1A04U63wbzXEMulyl+exH9K>&%qF*Qo6vv6NIi@A z^3+RWy|r56=;roLpT7nrpEDrHwRal=mmlQbHw(C+MHy0lEU8R<{2qXZW?liC`J8Wu z4-jMDTRjST`vMz&cDyj8a7FW{XTJKC7JF_+e!A+06KOU2;nt`KeSuIbsaplyC*WR- zYHHLgt_ya;s-3^7uo~L3$s{TuAWB*3Hu%;i7voyF(&Qqx3dz4_U&TT+6ws&_g`6;u zu;+JdA$naq>Sxl&zYCyUTkkz-8nd`~n}ju-%o9xoQB6;khcmh&>P#f8FZlGbiQe_|Cd=~wd5sTVp6^SBfE{f z3XMqXX7AySmm92COr%udE4OiNw8uW^ z7oRr$V{4w6<_LK^Iz|H547eQR=;$cx@aeQ~W1Xoy`M@Lfr#8sLdM94*pv}&$Cpz_b zCT#JPLF?t~r*3f%@SV&Fi+&IGLt#Q~`GI{E7!;p#9*Gsu>dhE~8t6J44)^YSHQR4n z;^Xa&n+N0s)mK&1@zZUjpWZEF8Q!HSp~J*AZCwcKk{U!_A<~{*HH&Zo5mX_B>CHXb zO+nMJ3De2~x@KmQJ8*u}sJBB05ka4<1QR-C=Jg(#*29>?dMpVNi+stwOYOx_>0Vl@ z&`ypR6b8z=%)}EpoQKO_l`h~D>ka-i$>c|GeX%Hfe~)0e9?LNRL6jVF!d<*MI$@U# z3N!XnE878Yr_0o3d+unyx(TcN=QHCq557HZd|h+Zp#u$rY?8AD0TJQ9{=^m$p7Qc!c`E*s$%j|K_ zi<3|?V*P{FncGd}HL>RDM7-IF6cHe(cm{%B3g)%!`^3&W;o%ve^>{%5+d4|tx<`wV zjy3uw^%}d`pMz6w`&11ay6laq?IgFrK{17|woD@ozf8HpTiCPHYd23IX(eT6N3qZb zv{fryA<|9;PP21?T=wsP9H4RB#}RM3SZhm(8*+0fzR7SAgqli*-spqjFIA#&oXX`S z+V|kf8nhf1c@K7_GsaB058X=V<&2(6A=tog^e|PP6ZV(m zmqVJvxdjz{{KDWaZc)#cgX~hD;e>MX8fITbMZb^O&3LwoF1M6?z8k=T#%~LLD2ToykMTz!TdMRO5Z}`ju!tvoN8mH{0nYzk zQ((?^I1AUKyZ>bvM&Tt&E6s1t$Kf{n8~vf)ESbom46Tp>VzylQ1;7By>Gp%7_Ss{r z3A5;@FZ6>W{n>xQ_;|mD+7`zZgjqSRwrafhD_?e zm>N<%zBpz24sbm2X8T;v81!L|>mE+PQ+&(h(3Vn+Hz^!+5Q_gyeY#k4&Z6*2a|g)m zS5T%Ad!+v+GFSai@0)!lEux)qDH}|o@3}_)8G;nZ(b=7cD`Dl_kPCbQ-*-MC(3uId zuOy`4(=RsjVe2eTA-WSHp1CHC$N{{vJhqiBFQP7WgdP$5|!@}p}(DB0zk zYC=o3T}o$%Uz{2eh?QU|LLo0mHNu8@K@eGAcbimoh6_sqe%#R(8(21JGku2uO$3ifMGLP(3*u zm674P$Ev9re@teb+-$lxeFbhm^yTTts?ZRy}v8f_tSgRxd5^y4)XVKcLqp1<;dineY{>D5{mRwG0>3 zcT$alvoJ{Y7hS3!GOrF-9s-jS-5iTt@CO~#=rP|L4WnXMyVfxK%v?cma9%}7!vwwB z-gCd@CO$;V0qa?yJ>_RtK1v&THmv<+w(I)J&OEF>&$isSM7a5P4E-r8LnkEkhhS>G zEOAsoqb4kln4WZgtH63$61`M!I{zI$jCsK!4Y{RoCPVrk{a3CtrTQn_*e*cV%1h29 zFd%a@zfcHek0_-<-%T*}y(k3aVhH9WUlu@*#Sm(Ztfh7~%-;EA{bR%oo+DmacFr&m z55nv`SF<$B63U7@Np}i>N!aR2FyVp-rlkXc*MsP`hY(%S^-<+j#g%QSy@k9KF2?Z&z&3wf~VH~r71M+ z+beZlI*>qP%hKxVe!Bz^{)=74_b9#z0e?9`8OYgM=J@jRed~1?-lO?1jFf*`Y}2xv zEobp#1<0-LRV)7F^XVr}dgGjGN6eL}9qW|MIRO1+L92WGtUdmcUIqlw*6Udtb6@$0 z-iuLO;FlosfdZlMUeB_cxjVKf{Nw(0D_fzmg2Y=rznRl`Sl*=ZLk; zs={N>!kY;rx#?S@u-*;%JQNpzow6b503 zb&iMU(HO{7rHWl}uKIq<&tslDH*v+Vi71reG1J|2og}EWZN6SkufH-T3Ll zJ#GQc=u5S)?HdXDe@bbh9ZjPCwtAVwkP5S7rrac(#91Q6=9rt_eJ`ZZbAzuBD{M-T zwIbt=YYl{J@rTchzIW(+%s0GUM~hke87G&$JCyYVT>0uaMLpaKLH1tgxtX`uPt@06 zdvW5;!h14EJW1?rYuMHsk{{l^9|o0apTcuAhc#%CV)OVsa~c%v6trjS1A$Q3$w_P8 z@FN8bOpn*6N{L|Kn@hj)>_lqojZ#=ncnVZhRP-Ky0P6mNSCV7)jcK6`kI!3<6v7A+ znj`?#-!6tU8?imJ`urMh8$FtAa_J5^n;cnmOE8(q>DQ!I4T8kDsF@Tm7?Z@vxCm z?xV9y=N*G_s@U-}6v6`C>>(rTF|r(k&oB{%Bk;uw=V@Umw_CQTlG-$QqBz&^RS+t@!sKo^Yfq4ND% z!x#CZ-FdN3IpQE^jroy367Ja`+1daX&gW2ASm+02Cwm|ywxobjG9^Kq-2tIY(eN9@EqQissBDa({8*oOE+ zqhwR|!ZIx$FX-snhRcz;l+&;YY3QyS z%6bph3)KM<{Y2vku%#8i!g9NuKoyaG5zl{SI9D9La{yo78U}jHuw-!dwcs=I@8k1 z%9A8+rV+R#Sw+!cRF(Ee}lHsV%cd+ldv@-x2Po{hztr#TodOf;}sD3}h zCHS!1UQx}SnP+WdBXZDTaVoahl;1V2hpF{pR2DSKQYwnhlq)02#*OcC8pKVfw zB0yg*(vT1je`L)4m**S0htp>hPv~UY%3OyFcjpN$klow}Nh^ev zb$fc^M%}wz!lxz4Df{SwWw!@{hCegvFMX#Z5K!U@KYzc|_;*du(ay)`%Dk@0d;WU&BqZW}=AC zwLcYk`neX32_jAaQFDLkBCV&H76ZGLfDFlb%W|hkE*)9lzR9QHYFvwXh;Q|h+<$Wg zChh8(Y|WI{b4c`TjCqFGBC|+MAxY`!=@X2xCZ{oTw%57255CgS@j{n#zDSO1=$+^d=>0+pH5|zFRm0=?Z7ul}C>I>v zao@1-uSO97ndX4*XkEDxkvjF)Kw^WGslomp(ZzmTgu!l)){5t!WQkyZk8RVwoO_rJE}RWsL|+< z4jeUO{A!DoLHAgKoCVS=-ASR5oQ*S^7OYNVx63nD?qFhhMAfhEVZk9iWoyY2sNMVsAr&Ah&Ql1%dYgo0BW^C}NoPKSwZ!Y4 z0!R3UdRSU6tACn4Mye+nh5GjCmWD>ikX@8=4kqL+S-TCdzUpaVDI-7Yp9M1^hZpK`PO9CO z3HD61z!_u6<`BB4vMDnqfu8%8zamLr|8UZQmIXqRG(~96HCEE1Z7DCV+lJ}GZ^A7O zm7G$Bn81DQ2JM+9pcD!Jr22(kz9>C@a{IQ-J5OZ`?&I+NsR7{8hRnAM^T!ZF6U=4Z z`O@GxDGX0L@9~~{16ogj8Yx>7N-M{Yi`$cyDo3){cbtwd3H+w>6!yAYp`*;O(VWyQ zMJh3p9dz}4o48f` zwj7t;Ax*yInNa$9Vs~V#;o{CFD~Y3C&;q=|S@qI?zBl#Gz(F)w{XJ8T?KroMuL^yX z<3dG)2ecC2#r>;mu{Vj;+9Q1j>yEGOH?TO0WaWy`bB`+VpkAOR5VPtQPEt9knGs`Q zqu&*Q?ET*v%^cdabV!tZ7sSFK5qH@}3{9#L5)87^C5lqfp*m>bDPJx|kW%Z3g*-^Z z1&^pAB+HZQErB8o7bWpN753d*al3aT@Is=SkxH!nwGlcT+PCeP_o=(AJIr_O#Vj`a zGzF^ydzv*O8aPKZHoU&_t9Oe=;1E44VzF!aP zO-lUEnOW%9!6(4!SFP7ZH4fBeN-l5EzHaIqnq#dO2xMd2KxJWJ?zs4!`k<(BG2yUt zcuV0h+~$Cjh*%n{=Keqd#sTVn1Jws-4gOw9%%*s;?cOkXRKX*{F>)Q+mi~+%b&(;@ zFvuR?KHt6=KluKp!oRyG2V(uE|DYFdXFdeSgQSb)q7`bz4Az#riKQOW9Y@_UjXZ1( z>Kogprw^w}+t0=i_&o>)i}7-?T-<=)2GbG8N}m^@8^+;pYNUu8TwKFPG~_^r4UcRL zLt+2fqK>6XV@H)7+y7G1I}k3SdKJoHdkyMf@O4gWRnY6KNndvVskzTY3VXv1lQ%16 z-R@VCJm#Lq-D71`=dX=uT$>Mf_ZZhkdE!&A;rny?_2x$cRShn#x)FD7Zyu#jxIIq% zU*B-++m3vwYhtOa2lZ`drRShKf;AXtiDF+(U)pkN9$gDVU8K#rC)sRq7?Asyr%B}- zbMKWlBhIq!-dU~|lNsG*OfyM>Va@zXdRp~_x=F?BnWg(RpGkhG^NV_^HVVmLN*cbu4d zEptf#MJw_lt{kC?XOC<0uh~-Bv&VOjGGcEFn|maghe8>>Uqf`1)bV`+L`YeOczbu6hHeWOkb6$H+t~|GY~#hY zt+M*_=K|tJ^vioCyh4V^9<7 zcG;-#2z+jT)ttzk-#UoBuNDrlYaXw9F>dna32P>oCgU_clZ%JN+_wW~6d0Et_dgf5 zddL+zK?vN{Vb!TO@K$TJ_|N6@2>aJ8sqv9aw%zA>Rx-!;Z^<*Xsq94I$aA#NT{EyE zVjLs9Tc?XE>n1}Y8aPH+ZNj6*8xF1UP|KAZ2aM9Ghz9mLuC)bdT2n4Dp7r5D8{Rse zz{~49@vKIicJdpsm24!{_fu&%#Mbsv(HHTd+ojj-A8wrq@6i1}^U#WtRNWAFU|l;( z-SmjcRi;)Gw>_eY`KeEdylf`KO!kKTLoA^hzDF!L>i@7f+p;D>BdyWCqRHaKsY{*b4 zk#|K24^ff=A;f8VE3q}wQLXtris-$>(W0ZiF;e_>iubzxZ2jt=EnIFaysU+6J2Jk1 zOI8KT7jB~~FN)mnOv$2FcPl+_}}4^+*e0xM61~Q3`!3NoO{!+G2g^oRJ{IQZz<#Ils%>T7gQ&~q*_t0dqh>xDkF9|G~IgYvDfW) zL#Qr9Xhef(`TVg69j+1In)G{ov)L6o8IvNF=x2u5%jV-wQ<)#KVnHxi#a+QDnn=J3=ZL|Bf8j@gOafJ#Y^YUgu%cIlmE>y+qjOz$?Yuz{A?02Q9*l9OF(CxbiFYcfgETcDQ}H z+tWT|M;fsmV_|m??c*9^v)O+rGJ68v62a{DIP>voF)euG)#(|zFkyM4((hxB zh@)(GIedU>r;`o|l7H5gitG+X z;&ajRn_g5H)s`s6x@%#_j3!DDGrKsv$?OqQteMwK1IMmMj%Kf;&qmzMT?a2&VlnUD zie70a?$!*Bc!bVOQy!(`cOi@oldafVAWPh{Nmu`OAu2X9pQW<94IF)6#l3b{X^C4* zYq_TI=bqc?7%jyU+x=phog7Z*a?k?U zF^ctd`&vHWImrl_mUFs{qg0PA$by~WQnytm*Onge5q@G5 zfHNxXeET0vDMmbe3n9mKa(LUn515zy_pWlZjsRFIjS}0x(A{Ra1!+(FG<-H)RfHgE zcIU44dw6}atKpb^XIr`rYp7_u=4Uno3jl@g4lQ*94Bs`Q%CXfxO*zu8L#vN+Rg2_} z+u3UT%2bJn@7!|w0RTaXOayOtL3P+c1K<15aUE8KVmlv4s)(4ZOLgQy_i(=1fv>X{ zH1L}&?M80%3!&R@h|tJmUpejwE9rbLN9IM%Z!7I~+GL>(H+!Z<>XRf7hqex{-YUJ{ zc-^D1{z+$n#?BL^HzNe_kkwBc<%DW5o-6qu%*8E}T`hvi{7VQ^nU?>tg5h6UnTnKj=CQa9f8B{SJOdPS&1EGh7dIvMGm(^JRXz)Xu=Mai(a+LwY0mJAsO>b5JmNp-`KS8=5RaK#Q{6U zO3HZ}Zuj6>%aDNRDKl3SVy@TxKLHBY>2IHx<~~o2J@=zZ7n;_derHn~0?_+~_UfIH zX@dR5(&a`%sn$OiejX2ylMo`(KJpC&)pthhIyXxbn+~civGzaR;%TR8flFkkz}L@H zMTt&QeR7~$^zYI}al7ZcN9B_8EE^dFCE>2{G*^$tnXh=g$a7pfq01Rk-KKB1CEB|l zH5@Ep$qW+mUOU~cv#}Z<_v2gyUh^X}+_R@c3VFc}Ky!lAGAiZ{vu8VUsw>9lZkDCp zBCFD7_HfAWn0DVj_&CE1cv~1iHe^e>YJX}6TZ6*JO0-f4z9G_8<|!TJoDGcGA#sew zDBE%=_*ve8+1<_<=UJjmE0Z_g?x9w@(FFrmUe541Nr6oz-}4486tP4nu%j1ax!f?F6) zlxtwK4zuraY}r$tl*W3zm0CrPzk$5pdF6_3-2BR6`XF{^M;CPfNBO$-ovc}u>Kb2a z9l@LAR2P?Uj-Z+aDJ$HU!s&62A&RT;m$g(?g zdVVH&WttM!^eg}7%rB36OtQfunVqu5Yl}}S+(T^GL$%s@Pc-aX3qlckzzW{y<&Jom zwSIm4NPEptv95`Dz_#wl?vJndklCcK`0jFD=(KGmw|DZP-?X!bhUT##*#dBg&5yikh4^zdjZ6A52;NK1LfZH&Fl*4XMU%jVPW&mm^gkcD}wPzDI{s{BN~7IYl064BQvx6CBKakjSMT)pg+W^2O~#0wUMr)Yb^#Pm-fOr z8a!$XMm;@qpTHM*lo3KqBwm*qKz-iyK@s{^+3#lcpZ9 zyAT8g<+A~i8Mjk^_wCue=^6fJC~{0zS^y5o%tNPjRf)GR{)1J@(T#ia@8J7)yf$nki6#7S;0*X2H0&Tli>S%4D%kr_m*u}Zpmy;IQJIKm zJ(uBY9Z*8)1aMN0nnKiwIG61H&)#ZWQJC?PS5$0bKh9v0t79}m!|726<@Q)EP1^1F zZ*TvRy90D#Q1{%uDQ2wyg*q|CP2@GGIy)70g=o$WID~w3=jO|&6~OAcQ)*y1*&;X6 z@#EXm*O#bVI)QVuK=AslOYhtS4U38(A3X#q} zsySAX2DjT6dK92)jmSzibAuwSJ(Ju8CV^hi(IL4YZJQ(6xhz0yU~>dWH>&1JS}m-t z$D4)ke&726%%n~D`h-pBkB?B#;=QrsHiM~~5wj6)dsD`UgRQff5O$Q|MqHBW-&1v^ z#{&T-WT4@pPJGy$Q}x=ne=M!7H5N9H*#(L-8+Ny=cQ$6L*C$g2d7iLyCBnN zCig<+cf*rEFNGtPTZ?yDw>H zJ}-Ud{!U2X+@+SP3I0lXMBuZ3>gP}TCa0+xMQiLViHZdE{*kAn-2RAE|6=_CX*4^2 z;PY;H_sr7h-6^r%?SP#hd%sL6cIW^rzNO51wR?w+#fqdRY=RP0h#{acp(Qpke-s5TaO$-N59sjW( zbgAg%rI}Dg;ACdzwjbX|b5*bOT1yR!q_h5q00uHL{TelO_Eq{QDHpsCxb%mn-}(d+ z$f>FpYGw_08XH)SvxV~8?B>mqu6Ex)NnvZ?+2S19T28HAf0a5Wn9uw}V}10ldf5ME zhQEN@R~!E#gLjq}@a;BG8J;Dn53l=yVBT>D9MN#_T-^&Ut?5f5nt?C&_P?yGY*7f) zheu4?>*5~3@_wSi0*J@Mf!#5KCsnVOstoOlZ11pA9TU9v7~Kvtps2H)i_=)3f*%JE zD276p+5!CyHZ!sa9Q&ZXS{!ds69oLBtAoi#MH6Krju};)p{+5Ayeydz8{W`%=hRbs z_#(db>`iDu!{%^&t6XjD6V319Kx6JZmHwb2_ru{Sf!(U-2a5I{HthPOO*JDviF~NhpEs=(s?5L=D_P80GgZF! z?$tLU)Qq1bV$M>laOCwa(-)#BU+eq9J6epB)E`8t$d+GGW1#p!n!vg7lh()oJG>LNtrT^b2nVNiS_xcdN$B;Xnxd|Zl6>S@h@-{#;{|Ma7vEJKE zrHQ{_!OYOoERoM<(Hp5>BY}E-mu*Lf`i2-1DI+;30xp^!_V3LnA-{5*)ZwVru7`Kw zzMdv<1oHSk1eNBL(XUuu`@131Av(&UDIBQGfJ1%$>EOA`R?ne&U`vc@Ejb{xH{f6Y z4*2*9yAEWJiUXE$L-MlmzOfAWaXs?i@ihJ&kNe>PSr$^-{VVrjLTvHuK5rpk>=gPZ z_Ylp%RO?va0md~H;ZsiS5Ha8fOQp`wM5UuY*MeWG0HQuC73@ZofS?fsfZ0(lvisnx$fWc}}l#;b`)Hl6Dx z>!-Xc#Tgc$BHl;T`(>QrC;u*J)2T=?_MK;WU#{1jvto}tX*a@ry6Y}pmFpM3} zF}T4pbO_t?Y$-4jl{Trs!ZT^VNniC%K-P*-Ln5R1cEY()$d+`wLMA=U*BUHA8SeL` z+$vjGN3WJH50i|5@pK3;{vTCW9Trvh{5ODwr4$yBMx~{@JEV7|OHrg-x|b4Zl?H(Y zL{=oE8?mzHw5BJQ>nKNh3%zVzV-;k$hx@z`UQg!nG zHM<9sh^Q(6)ZlLL)tw5QJHE;ZA`0}k>G&^awc~wgbvz6WOuK|%+ISuu3lJzS{cAK@ z{+En$DD8m^5uHNz7-t~ogrxhADw@a(7a^s#lN#+;};wsiW3Fq`s;;aTz7;& zXb2Yeu&Cm4jOBqN#ejabWKP-;0b)DdfCPM~3MhdP93^fWFoc({-2O*XpDARXybXR- z{7FK+#S$<@lsjU0L9Q8E;0t-Q|B7;Qu{0w56$$IhJbW&i6;w%3N%%iaasD6wDW>2Q zf)2NTHlON`4}pL=20BvBiNAgMnJ@oq6YBuEpa|gDSptTtg=>y1gk-?AZymi|@K@^| z{Y%uRY1pYLkWRD&$XJ~_y0Sx$J8{aO2tE6|&ipU9lhdY1=m#FxZMptgqM6~y4o`wB z7$NAoWbe(t`pdZ;C7D7275Akg9sUWl?%KrF$C+M!ipE;Aa?WflQ251Dbx5Ky4Lj?JnwWg^)9Rboi zGI&$819%+NdAn9}KJ-4T-j%asU}$G?;2ij1EXaTOlz3lk$IC|0Q{IznrxYg}K{>1G z25c2_g#P6td!JwI8}4FgF0ZG@JmZA*qW}5B=VAjdwOU5fRSeDhEd0{dQAkS6jXvqE zTQ^`<$#D3SQv{6~Dy7d$nXt zfzv!LpK0%8SO-K7eeyJ$AC#=oRU-%vhK`Tq8Xs^E#{^}$5wt|mDDl9Z>%p3kS~LUx z8iqORnw1CjP9PD>m<+KLg%m=HAU#fw&@496Jq6Mi5$yE=a6Pigbts-+{>;vv%zvg9 z`te2+W%lG(T1=Q72nO{aOjb9y5yv?xk-~Mwi`dLbdN-y>2`k_@MHFUjoJ^m7lq;(5 zD+BWF2{+yshrl!0gbIBOmmIYUS&BUF&XLEdFy2Z=<9AO-uOE)g4wG8IYC=!MlzzZsryyT{haVV`9IQ`6d0!oOMEBjJ=$~ zwLsnlx61uygC4IK5ng!yhm7lwo?iX~@c59Ni<)NdymV*9bdM5oWTmxg!V;jW9IBGzj)pAzh>i$I8AgoXq!Bc&t5`| zACgR90+EFD#L6%LgfW)NuWDe){`0$YGx@1p@GlSAc~O1Taa-|7mvM zXG8AkI{_62#5(fN|I~spD*>GX4TmOEUa~0?0+xa_$!$br0s82OXS>u(;Mt$<+PX zaM_n#Xe1Ya{h^rH6PK-Cq9hQ?tiF zFRp!XoL$Az47j8&jb6L(=atpoQ&GO`u zXruoTJ()a9I)-sgPX9&$u$El~9z~)rKjZrJKV7fd8p0Lg=pr;P2RKPVQN!-8AZ0Kc zK!XI;e~qRO?Z(14wDF~X$f@#x#DYs7%U`)1H>dx`%~Xc2=~}?GrW-SbS(DuU&>g-o zLBPJ$D*q>*_L*mZcskLdmwnOW4A8Gv&Mt@3_33{aBIwUNOwo4pQm}-TU{0uM%-?Rb z{_EzhKe!gz{NCuJt+43yls{S$B>FGgh~2j^n@j0Q)N!CiBT^$)aa~GuLL?K!Mvy=Z z$qJz2f<%f{8mm%=-yNgKNlh_#?B@yHN&UI)?R%?ScmG!lP_<(X_*$${p3%8~lIxVbsoRU(4chan;y<65N%>GQkKw2D9ILptk^ zkRf8Er~~+S?CYM?ku_1KyUY;$0tJI@(YzQ4;r3TBeY7!Om=foJjJ1b>%k%yo9q+OR5PG#5+RTJ(gs03^NMkx}aBt;|5?mNB0^*A;y6> z$)sD}675}8k1&J-jSNxY;S`%qD{2wd+6cJ>C=65pQec@0L+u14pbpOL(?UD14a8o~ z6~%vf%aVnDiIXMBileprP?&Ecj#aziII^gK55)V~&>I^|+YjXrJm=6^+1Qv-U9gU8 z=(PJ1q>eRq zjOf>>utc{{C%QiXR@C zm$Gz)dgSqoJBV`Lj97Oy@5gQ_#zlc+q+Mrn#w#w+FjzV0 zu3A^IoP|(Oeb_bQRyAd;^BfkM86h1{j+uuw&1WIktS{6OL|`{B4D5 zl@2T@DLz5}J?2{jDQbQA!Pq?{{YQrtOImBHbTbCZjVOpmpi$9Ya#$x7ZRD*Hi$(v4 zd(ptGsqJW?IRY~N8s<+oq5$(ff!|}>F~lF9HKhb%W1X3EB-N0ha`ci}eb-^$$_s^w z$#p0E2YgLEd#@v7%92Vc;ru~bl&CJD8BF-l8O4T$ znI+Mxa1vc8kn(?jiLxnWCj4~6(bS72eI*dw6#I<&saEm%!>X^vd`bD+@?ArwME6Re zrNx9*&D>HM1P!3|k*&SbsDkOJ=|tshJMR^KgFq+Gvx+DuU&mcnGTv`>`_*OmWwGC9 zZe+=JBis96{B+ay$1D3LX)#``Wg&L<5-(WEX*6VP`U}9(_`hZ^%28(R9xAq`Q(w8g?%`RTt`l{fujxfu$!s2TCxWQki~Dxq72a=RwCPwT(lmk|XVg*>?qud0!M-_}r06UX}4xa@3W2vf4Lx(~cy)iDkVtr^GZDteXf zBw-!2cFnWVew_s=ziZ5~VF~Aq`E& z;%$&`WODKVcWNMnmwATlG^xX*MhjA<+4cGkhS7~!t1$7fYp#40tqsqQ64_kfHdKg| zDE$$^S~$Q>0nvgVv8Sh-BCSKk*T1&Y0!b~_9g>+wz%~&5>msZdQzPf!v?H@S8t_L{ zW0LEy@h9$x9SgO2hNkXez7yN1h19OaM|kLp$3rl0_e22;uY_a1(x<#_HDOoL+F@~w z9%5V7E`+OiuhUDc)GV&|ccogc*IL9Qvk-(>!)Tiw+3^;4Z%fV-h^rlLeE4ymejVy& z6vQphF=~i?mhuGF(^GrKcZh($5HGfwJadE&YanjxVDK~7yY^F5e-=*RU8?!KhzQ@U zMJ`JV1cXt7J0a(4^UM0h)6pc7HGw}JRyR($cdi-*op|76|6vAP8*tYz;r2<$P0Z}xF9+=d@XrN5e*LdF3XY>wiT{V0t7w`B{>h5RO1QPpef z7QJ-EX}>FFHkc_&do2TWf;rseTeE8>B5c$~E}1fX@d+h5g6*)kdnb|La#5aZ+z7EU zqH`eRn)%BKs;6Q4#!5Eh^QiV@oztkvh1tedKNX!ifE%KP#<7Q=&F0r{B025u;|z!MzK#a0842Vxi&qI9Nt=Pdhx5WMWX2x z5kMUzFQ~~S2e=k_e@%j`(e0wVdd=ee`=ZE{*AjILEm!$1-Zw~_#05oHsF6}gZcpBy zCQj8zh-Zb(k+;G4<<74)!TIaLsM9ka;arE$sO(a#lb+uK)(mGBPcU3WPi@lRJqSs# z0v8bfMU)`{A{;YVzlLaPy0)U+^_EA86C4PYHF^e;YKOpWmET67^R_gM773#EOqpe$GSPCmx^PgKTP(G~t!;PA1Y zD3SWag4*bGQtjL9TJ*+gq9neDAXa=o%@?RND`g>(L_ph1<;zH`}^UP)Ini`bJ-hI1OTC;h}Ry7Pvp25B4()@ZBJ)y(X@ zJ2~=Y;Uh1OifzZ)C}k1Gsg6jI(F?lGD}fa0d#B=2nbwYg&l~f%({2;0FZ!~G{hwGR zyF@tl<%ka(B4kRSZME8}ogV}%Bt2Idy4+t#5Dch#P}L&0 zE6KTCHi8}-3KcGOFx=sKg;%S)j!P7a&*4M~&L*H(+uuZlL+%wBgl+?->|MfRc@W^f zimsDVE4q9 zfk+<~2IbRCAMJNV$kM3~P^y`WW8_CEp%*E0=TEyWCoAlHLd$gwglP^OT^)a0dul-n zRQ8{wD1V_7_z*5-Z(p1$`e(cJ_$3kk4Q>=iiW^6gyq^chLV?=LcVH1l`9TeHyDH@i z!9lpcl|7RUWuRAO;!Z*5LDuyp+a5u*`-01 z2QPwQ3IGiV(-zev0&e$|R4QOw`(1Azi|`8jUwI1siXkjl{Ep6=B*$5EtFKMte&Dm( ze^}u;ZFoGX<`5p;I5`_Z3>l%j3CI#@e*Xe|XaMb%QzXfXx}jkJ#9+^_d~Z5Pd>*T9 zBVL9*JbSBY+pWrA_nH-UdgbWGj)GDAF6oi{$9`9zzZ+XVAE4?UMOn>>q2Bz}K@=_} zIsH`xq1FLAl6y<(iNfAw5YdNL5`KkLb$hS^iUS(doE+99?D>wZvL{8xo_pG2HBCg} zS@MuN!tqtOdn!q?c=5((yWkaRGVz|`vDcEtYf4K{nlUa-rVuIBge8UTY@%E7;7j}vX)tv{zz1tUW!Rd zV&+@)W;=If2U)tM54zv)4S^7NLh`7C%#lps4bo3Tq-l_ZTgUdUXZf|$AeOvsiK3X5 z5BQE!h#`{AO#&WW5HXl)%#AdmtRot)(qPo(gy^7YzgFFQT%&Kg`FL5uD1_MU3Kj?p zg)5uej*FDdgWT0VDX|hL(C(SJUgJIBlVuqgnvedSVI5gxsTdzzl#`t#_jmn>`JRfU zQ=vMdo~n?Er>pNL`cZ)!k02esaT1u=>-yZFF!Mg4Cp_LDYu}QJpLo15F`gJM_a14` zuf@%lO4iW;yO?_du@g?4G?p_-hCJZsHalSRgz-8x6kn9S4?mgo`;bY&^5)1F0>|np zFA}D}oE=?5SgR+TaQwI%K4AkOMx<8HZ@fZjA)7S~99s{*fMfu*dlwozQYTQ`s2&UQ zMCEPS*LiXUU1>_~^or4tRF{!;ALe{jf;+e~?&d+jj#~MC>;aUnr+iQ%qmXXjgpXe(%rC4di9+6i8-?|wIF(~1F+W^j6k53qAEox%R zn_F8yfEvM=Jegd^^FJ;PjH07ZXb&oQq;VnJUD94+Cqg)G4r}yn6&Hlz3`it{m$@k^ z*YF93Cq2jNJ|YcryQ|by{}tabit@7}hqKv7R`rdn*O8b#5n0byQEvb4ty`4XVu+M} z|2;{sz~gu6#PLCdpMDYohh265XXG%^1|L9Wk-B; zCORkQQwJ{v({HUlsWy`}Hoo*klzRC&kv5xbHcW75H)U`+0**F@jZd@go68arPEcr8 zdDF{`(?vN65{%!Yn=z$(s;OMljfM_y7hko*(x8*^yOPEEZhfeXX@_f*cI>dO%@vMQ zA&TddY}&g%%N52D zr(a<;#ff7NmTn6tY__DPs>3o+@}Kv0_p4OB+xt33cPs4?@2XX*|v-H=e5O7kO{Wc%l%b8vj zb1VpM{GK;&e?LIdlfsj*Oe-MV(>3cN{Pem-iX}V*(j()_$O@FpZzTM-w+4rhI*3hR z>mc=s!Hj_HSv-w*d}ZLt?Id=OGr-~MTpPijY%~3?j(=m5z+NmU*ncC2cJo7_0<%j* z&xBV>(gNBEYjE4&Gn_QSY-gL^NTX~*^`T7fciw}e+aT1~^i2vm#LQL-mUAeXc4(O> zMe+KzZYd1sH63_Xq;tV+@@JVgHYeJSdxbHtJ&Haj@Z+jJE{65LCCwOsc0|m5J&!+0 znUok*4i#_!N#hfm%B$#|4UgT%BDdo_V;>a1=f&6IPagP9O5@g1p+6i(mZR@M6dz0s zXu1w*VFK?_ZFaemC0G3uE@9sq@kfOup3D*UtFaRIq3$ISl#Ser{f!yJWQP*%&rE=f z3az)Z@qT?#)9*)0Bb{&`@L`X-HhYShb4U=}E`*%L7)yo#P-qS}X71J^&WMe&pNIm+ zi_&WF0NH+8rmJ=}CtUUM;v0=Tfnk*rHmFhI)%th|o2#CrvJ^Yn=2CaKi+tF3wD7t) zx%2v_;|aKV^gYoZqtybMpOnq8MojdT*Bxqy8Nx{45;Q?8f^*GnWGvEj ziZCY3y~MIt2k;IU5Umoym*!8!EjCHq-Yz`6>P`Da52);7n3EL1OpGD?7$qZ7Udtwg zc-4GU-t>0wgT-B})BEcw#lTnM{-0%{9fJf<&d119CoL<)kdO&O2w{R+yw&^5`yztz?N)93&uTaO3Gv zgO3YuQSM=$%>qZw;B;q2dMW4^LjID&7kff)ukqg|+Z~Wo)u#%8c_L)|#|yoKDa*K@ zt1oZR4Ij(A8$ZdH^rtY013PP3ZnG9Ue@0LHny`&;G}f`RY5D&eonAPi>TCIX=mhT z8!y6}k`3Te9fg~T&PsVO7AGl1Y+nl^b;6yMUJl2mMuaKxR5DQ3ZM};^(1{k0TszrT z%rt&uQtdSQ3OrYkO>W(XEpN-1tig3_cxwMKras zsCmXJpX|+He(tzs#XkX}+DtxG+57QJU`-5W@Eca7=Ntz^KK!AD=fbL;B1M=7N+^gs zhA_kfP{;Aztr?pvrCjs5D{=?AHXe18HB@;$I>@*_U+!KbqK(+k^(`aPZ5&czbnqAa zpnTQk@yV{UO&Y6CxLdx}JG5f31g4|LfyjUMD%tL>l{05kZ63}M!`#SM)TzS?1wV(! zUb37?a}1B!^ZZVqjmiJq-nuhk-~9qG4HCa!Bye(g4_kC|U=ckH@$EyM$+TF7cuqn4 zn;KO7psgr{ESi(h0X5mp?~Y!c!tls?OnK%0uP~+C-!^zf8S_7Ldv7>&4V4z|`JO;c zq2rjtR=TKl0rgw-j3~VAH$3I44tHxigK<V-W~&pH3LE#^a(T-{XQi(hfrXA(y=F---d0iWxHHo|ge13> zZe4gNP8)OKZH=w_CWzDmBGx0{lkt!#novI8K1q5zHfGIjl}|x+w|_EOVAj-}Ru>&( zuCrRPsFHGBEE&_4KgYU#Vnl5?NP8+oiR{yd4XTlP1Q%OR*Z(@e@EugmvrV*Tk=9D$665Q3a_$O?=*#_i(R~Sd%O9hu>g9Y%CF>--X^F4y?)3jfLEp(~OjVd14DdCj-&^wwO0e4eW(w zgj3EKzlz7=f#OD05!r9>xK^9rH=exOe-lTb`l;ykUIv~6!mm75O#7XBRWC;{Hscj= zfcRz(Crvncg4eOvG(Ql$BsIVB%%(SuM>kg@DMVo?p5~TWqdRl9F6Ty}TTd+V-3pse z#w}HcG8vy&E#z*%G3_JzbSz@d!C47;nG0p z{u}(G>%XkNbeA!jc4vnb zoQ-eKKD_Lbm@$W`yf1v3TWnzDau;gL^-qSyZTHV&PG=9Vc?vO zGrJ*rF+=I&MM+HI4$G+c2cWeU8(q3WqvLht>--Y#Cx-}`WlbbUD*Z1LNojgQFXxD0 zdeNo3_Jbjb>Ivu7sXcQvJiq6%!h#o{Gkp4gNuh&jk}l|3Im6~E*2(`f0Q6N9C^ZvtHbCvJP_O^YabZ8!ENycGN$TB z%9n)uT#-y8IjW(9X(PFjF64Ao_v1hPki=Qg>(@^cR9_KfFcERUaA#V#t*|{S0($ZYi8uAawXK0}d{cnNHR_&oc}0Gh)9SB&DUkGRY0ed$*67G|pa=ldw#> z+5TlnVgrci(-y_Y!;_`H6TdPj81x>J*ObXy8djyW`zM-2ZucFvDmT)PehQ2r4LiR+ zWoQemV3ZleP7FSE4Lu?eUEM9oD-<_ilGJj>uJ$G_mHrXvCyC zYf_o85O3O!2vpH@h04b?c1#>_jLd)R`n83rQc0a;`h5YB3C%2w+X<-Kbe5a4%g{)j z;uKT0ihvA2$%KGINna4XD2Oy6*+ru(=aS#?sxWG|9CeZ6}7%Tw-Pl|D%Wa=d9J{LxS@Qv%ap<6lHpd=bmZ#LO)P{Y@rA zVW&T!VF&FgQu_J@d$Cwq{<{=uv#l+b{aa`XsC)=weCWo!VII3gOj%f8#E3>LE>b_~ zDc$%->Hy=7d=&hEUapBOY)2kAr4Vr{3wFCQ#VAE^rof3AI@GFrTSs)pQlMP0YB{p~ zifo`{ZCI@qk?vD4M^f|2nP ze2(tp-r;NLiu|G2k?nS7y|P^FwQ04Ypqoj}$3lMBU(~?0Kj-*;C8U&$np2#FXk&7t z&(of-7*rmW*0)c5A58Wgwj9Pl^vn|`J>D0|S@zI&MoB!JcngG!&7Zu|%hdpG(xFs1 zVsrUgUWnud3EA}`I1Tdq%Z%?!d{=;#{OpuCI_B|-oNG|{2IMXnd}=Pl$`og#8D7kT zW@^9e4=K^#KPjd@vqVq(3ne3X+f&tAll3+9WHO4eV|tFyP03_9zWtEwa#_P16CdqL z9X;Z2Gb3aU^l8v7#HmJe)5CSy^=}eV{fI+hlKy$~g8yDfb@o4|RNClU9#Q#m$Z6sc z2;u?qD@nxy<|QK>^)a(M+Qjj7%pT(5&0#~LXGz1g1YdePXgtK}`Spt%H@>lprS=u8 z|AXJ=r;57Gh~QKyzX~U@V;zPb^NN`#k4`HEQ00tiAU`Z7taQHcBn%DV� zrVaw}Cu+l%YXu`=h3TQqso&k5>$a|Vpr8A9LFu}n-oq5zTqB$>yIggJktAY=GBo_p zHxg)Vct=iOH^GN#tvU$?PIytDa06ZYlEv?HgM0>a5LQ+0Cz101s|A3&LETl}5I2gF z-Hf)En3;L}_2tmRG`o$dl?F27kXln znGHmQ&IiSkNu>m#ugJamUFptf`HS6@Xdqh?2k=9J%!)TcG{G?*FFhE`V77C=oDZwt zRGpdpoa=Zv4gM`V!K&Uyq57;WYGtE;bnY(r_@|9ELxy|Rsh>QYJ!8c3dMSG8^`a8B zk-v%^d0K|5*6Z{3VUqM)_xsO~9ZLQ*>gIOxUDmo9qjOU6vtK^TzMq8=4uAh;pT{w| zyZ4IR35Zj~urnlyczstZ8sSb#N_r?lf2m2)B-D3XHjddQcd_FWvcs(*`0Tdy`gl*_EztPsqfk~Y^-+5pEdJ7-4u$n}_ z6uGe97BW{|YfHnOJdwQQs|VmTHO+mgPXhUpmp-^zCRH`bI{XAB(?l-M?eSKPH1wDh ze?oe0yq+q3BB5TdKXFy=P$sCan(ki8_ni5FI^{B$qZ7K|1*HyU%rTd84gH;Z-do7$ zquZgnw{(NxoNb`=S>zbsU=qKvMiC~=JF z@X6UIcbM-_fw^ss;aop2&HZQC$3NFmlwThl=f#fXhE(%yZM~r8jA$&vOt>Jc>bYgE zSE+J+TwM9Vp!^23YV!gpD_9{56lMGlZo?M+ zcXW%?iyp+Ad0pMBa;)_dwZN9aKN!7;EnTfR6$O8>DW|M7jiP}Zs@PkJZ z6$QFyKg56e81LYzz2h?cQm3s9Tu+G}ZQ91Yt5J)z-TiIKa_hCFfq*qhvs87wM9l#8 zlX0yidg8Oc|8)K;&h+PS*$Y}$&X`D(^3-SkQP zbZ3;xL8mbOqdXUtTRB&IQN*si+gKf~l-;P|>0wc9R$a-ntCBG6h*ZAHq8$Zi8DS^{;=rWpna5={?5hX2@->RLZ$QSV}mIb|EDW)OP_p=s0|-U`TnXn^;(Nw9dPh~u?IKzIM&N^V=3ipT zTng@@$CZzsD3!OR>Uz6%Cew&;AmCTOFIqp8NVzHTDoRB_TftDJttQIV#kVtAIl`*t z#pg2qUvfZbdeqo*SKuyU z-Q@|hsg|*H-@@-Ezfgu2GY`fM`!ae6&3Mje46U&Fgv?hBNN`fH^s&Adbw-n zjqdP)frZsA{o%R0>gMJ-{FY@rh#P>|M6#)Rdt0>FTO1wD`sacbd&XXO2hd$+dQTS< zJKyf?#8^H0!omJIE^i*!UrxDHAXN|(EBKPn`osFgLC}GD!_c6|!$O@>YQDR2ne{HE zwXTz4MkWm-UrqD?DkjUnmT2p=uC82Dy)iqPBc!c0Y^R-jdA{?a12-NjBEo z@6R9BbudUPH665>bIG{#F>_~l&nfL)%WeNJNaN~fu7}s)&DW|wi>+3&FWO2z*I74f zYs;&wWYE54_;3#%md;_Z>R6y;9!NUrDm`*LfQ1}j9<(147 zEtJ-ISrHk3ASGXYZFW~`L?t5MEYVECz*k0(leSnU@0D0)v72i|esvzA#_Pr|-=tZZ zk+@os^m9g?xc4FtZBdWZo_wf51og&!2wF-0kkufgZRe2BZ)cbG<7ZuF#%J?8DgP1U(bQd(86Nkj){i3Ku_dr!{eTE zbGdu13xsu#KWHRdH$T5=QpL%bfJ)aNHMY=xiNpX@)z+o;Zn?KCXzy7+n~wcp#&6(2 zX>Yu$CX%-28b*=MQBn7B-O+)Julrfv+eUoe@Lsn+9n$ zj&z%suNL9LB58MMTd-B+{@Hj|T_*cgU2)nc16}*UJnyV-rW? z1D3VLN3xwYq9FRL!l*aexAVKzVuj`;_kw zo&vWRJ!*a-2~WBan%(J^-4=7A5X>sNJoE#9kF^b^=@2#WvvFkk%aX_awbv`(x)NAl z`fA@=FiBkSy%%gfp~`?d_;p&*97vn38(CJCl$Pf6d2CEc!cyOII)F`Ef%Q6VpW)q( zI5WP!Ea4=zV)_Twd~s@kU4rg>HeK%oF6f2FK(hNQJ0FYM_u~N+wBOTySA&+bgX!ZP zb=JqbJ-Elh!`|ci9)`gE4%Iy@I_m0#o12?;jg3Elq#E1-{0JxfY7G|_Qka$x?>CV zjCp}&D8*P2ABkCX?+uEnYc!_N?rGlCO&|ALHrz$2_D420N<-el(1kR)5#yVm z)K!u@cVKJRb$GSTzOj8$wc6W?N*w!oeyzdHk>3%VlRb@N^2C9Ce0_IMe-3T$g)%?- zcwO%NXd#s1c{5k`q>UC-@chk?>GtYs;hQ%Jp@*}XF{E@g0lN=?IfAXKg4y(C@V7c) zx`&WfpS8gA}kDo=CC>)C*#9|fA$u3-(EuQ45HU$pe9Q@(Eoeg5~n$`H8YC3b!(cxY%g$--~f`W zlv}nw@?4YFm#1&%&Y|!Wip^!6ykFk&% z!3y=kcj40mmmx~6LZr=Xi*F*UV!ke?s(}IJr-#ph36P>vh~IPU?)UvwSv{b-snQxD zE+rt$P%^R|>d<*YWD}m|b!35fC=Z;}O$4itq*L3v#CDJ1oo4M(DPkqelKf z|3Te+(P2+Gc-!{fuOvy)TIM7A9dW!0&~fc~D^v;*YNH6?8xoazpjFU0xNgX6T> z?kgtcS!qhjul;OD%EpY8=&f!cX$s%B{jSl35Pp7D2(sXT$5#+h5TCo<_$@9;cySJ~ zSeQ;MyKP*ULSgK9#zk$l-P{#$l@D>b<#gO%`;wNC@o1+D<~^(oyPDGD+eANg4+*A}IyX0<~KutCvNu-Q7;OOq9ptZK&yE*%!}#h~aIq-}S|N zfuiVq-dncD>V%!nu0O64ZEwmXl^wZOnLIu0Pr7?aCU?Qm&woe--v;eF_xARJZkLV% z+hfTBamJD`gw=CyDL=9uTf{;OQ&S+De~ya0UkBt=FlRXY$`NEr&&6KCf{BD*(dGIb z#)ylq?FgV0Ya|8vx{eg>atRF~4>iRcCg|a&y}qm~3qhOU#-o#r=~7k^ch@Wdh4~sy zvZnQQ;@W3!H?cUNP_1@EAhYk8eyNk2TSa(t>tn4Ho2QVoHX=(G-!CqPksL-N19ZoQE}C0QWQ4Q<(lI`xL(B`kwnYZ)|vt?Mg|s*b48}4={k#S_zBb{G54-DPVjQ1`lCu*JPp$xjFNV%-f&tcKnSh_PXy=d~}8VmC!49<<{ys zU_H@uHwDpA{1|jsde+zpVO6TXLKP*fEn553iue*b6sj!=RBBH7M^OA6V9V8 zT4o9R-wBqIQ~nWp(v?dfVQmDH^OF+`{GsF4yn`eLIL{mV`q&@ln+1U2##gbf8$YFh z@wAscV78H%yJj!J5DMF0R=9Sgz+0O|;j7j?C5NBKYA+h&oPauo@_T>faX*Z*UzvK0 z!pP25ct=*uYcmxV$*2H7b?|gJiw7>Pim{>Cxn%?ORQfCL?L#FX`~}RAZfTq$E^sAk zPi(9eN3_w-?d^JFN4ReLtE-gPC2-9(+F3)maskbXk-;Bg>e02ogSZ?ppQ&Su_o$)H z0RUdvv_WfZoXi(8MXG5}|e#O|XRk;1#-g;e&6vwBc*(P^4PNIkB3C26R? zzg)0Vg?iB-7EqFDHvs|@kO$ZuazNxx;;VM^AAi)h>`t&KGS|EI+aG{pE$Rkg$W<&j zELmIlE?GHbi!%9)PAD{3@-7Jz=_%D_Lo4HUgLrM>LMg70doSGbk66Ch5%P+M-31VB zwaS@FjITS$%V7tE0&t**4{kty@JE{=U`Zw`|J32QB3j6#-~rU|scuvLph4MRJf%oG-^ljeKa81n=YSr{E%?_>Jkp#h|8_voGj^Pl^%I^Gv`GSs7@IeG9`XgN*Ub#* zrYrI562Wscmrw>*wId?< zb87-CdZ0?U{34kk3^E3}plrH6^DU8`9P4WT{ zw+`vop28s>4;XKRK_S}QdZ(U#A9)van)j^!e&f;1Jlb!H8J&NR93BErE5_eP5F%=o zNQ0~;V2YU_Acq#{i))QwL0APt+QY^-o=tD-tW6j{%m%mtc-%UySy0%Er-}efRS}6;TcAgOIQ|`vHGYDUY|Sf*|F0M3kln z!H1uFxJhjrXgddMtj>o?udc-bZcA51#A!}+ruZEf5_+Hrmi&YFWHbjB(LsVR)=MdQ2oO{%ElSQMDk8{>7DgN#O%|Cp27E-wWDK^KNssC&|$v`IKPNI;<$QOgd0;YQps9}Us&L#5Py-|T*L#gn-A zN-n_*G~_|*$kGA@{uWLpZBcw;((8~Y(?+j+86dfcTLVpDvSBlDHKfO0$)y4{{;hZ;8cOH(U1Q{S9*dp) zwH>8XU8YARMPv6cFVTV`FX@4Mf$AbrD{5!MsSX7o30TPOJ+WXZIN>%YG`6r*f+t|Z z4?m7I`T>m|<=V){KUWewZbeJroqq+6xV}49{8g~cf1mOl;KY=(0%xLl@07irMEa5b z#vBD3O}--B}zQ5gP5? z-^MSG7qU%pA&-x}xXoykzevQ-E2jJo*vGJab{*SxArm6qC(J#&m~7n^dfoRXX<>eo z^ohW26aknt;R(9>iVKx2{NOPIp>0C^2dY*`#)NP@))B#nK|M2#z*eg(5k8fqq#kRLecJqX?_d*ie_qA6B|#mlB$IU(Bo zlmb-%%@J^ZIiJ>w7r|TMP101QSZ57l@ns@?Y{et!PK6`bbbmk9vIPFcgq;!|D7xR& zD1v5R{3y+ypk)mmCaam)$r3yfrmlmN&!+pa;x2lqx&|9N&vk=IJn{1ubNo7GKH1nn^e(9_39 zDU?Dw#=uL!LwTS}c#i%JP9~5kO4NH%VIJ5ZQGvQqL4$-Ey*nR(gte~>eHwh#(=dIx z^Xj-)edD}~^OFspP^@Lu!p6bK$vz_^2m}8T*OY?I&gSS*#np0aNr-v!**jGdOI;oC z-->PtMifWIOJiMnPA3+beYhXx=|MT6!5B$t{ipB0n6GU9=ECOmlZYfxab22MJ}+(5 zoEL!4AEr*$QCC_(bwmb9WsU z*t5-C3~j5ysrqNDXS9o+8y@|3b-^rQj4;(#LX& z$Ax+6=SNb&p+y|yx9iYrT6s(BIqCyt+ST)zdzrLKH*E;la2Nh#RzDUktj0UIwY-G@ zq}$_NTF?G0Rw|T z(j|f0RK6+lCPra};6icNMqX4@rvnCnT-}LdiIU&*#UP3&jl-2TsV(0r+>Nm}PlDbp z^wX-o7sTP$Og50A0L>DoqTN7gUC8cXS>TkCd?A+I>DZCJhc*Sc>a3U_?0^D$4E)8=jz3S{jw^?oI)vTSS_n2SGr343JhzDH%XQ zLRuO|5s;GZ8bC@xK~fO>4iC@st>2&Df8V>-doLEsnz`@$#NOAw&ffd%Lm5aY%{oO; zzgtfoAh1L8ZPMYzDAg2cw)#(KNYt86Tf7xC^hqr706(E-E@k@lKX1V2EUmQOiIn#7 z4y=7DF3i4$cRq#Z{+QYoY{()fVIkfkIh}hoNctE}DUIJif0b%|HZ~(Rf-izzTE%(o zvKf;GXdI5-*BYgJ!`I+3X=lTkQ?U_uBNpsBMD8?m89IOBI=YchkWH(Em(Ao&l#*|} zsewq-Hm)_lizkl11|8pcbJA{4CsxzY#BlIVku^uKI?g;UY>r%G+-_j#I}*2)%Dy7^ z>sT|p-P)c37HNAmB*aDRWNRqx@#4d%HVkvIVUI|IjCQCsZWdt+0TaD6ZH)=`vT2Lb zST(GOA4#PG(qZV?_0_;JuU%CW%lF|Rg(mEWG`1cSy3zPibmjo_1CgLDQ;GBHS<|ls z{I&Dt@3APs4U=GfTVgDA?T2L2TPpLzU0m1v#bP65HV8L`q_v&tzXzFUkKuBBqRo@B ztr`CA`us)6Bs2=DpZmeF+&nyReANVNEWX!Y{?*-k{8X9ibHABy5>S@@kFSWga6#6N z>=x-h5rg3yYn+hy!;nG<{*s_-8jNUo7+U~pdw1ItjF^YWqIk%cyq0$7H2r`vvgGGEx%73Q_;1)l}oQSnS(h>IBVi+q=K4q5)L!&!334ZZ6^)?zQ65+F!olmHO4ZG zW$ePl&wqVm4MP~rfrn8=;1=(HY!iM@-E*=Voi*l*!ic@Sq_lmh7`9K8Y5-jvkCNig>{#y(lb4~_PgR`$d4)OG9|=HlkxweBjf(d1#k#|%_>e* zBP+vViVTNlMLNgL!)i5ps#A<`iIi3YwQ`3lC^ZOzc_eLNW1f#r7J02ghZ9EWw`$031S#bJe$ry zb}T7z^M9=+W0qzZxC?3vpu*?+%Mv1?&2VNleEauaoe0i#>y#_A)|?2{B^`$ly@RFmG;Tgb<fgMoG9pZJs`v+6t6l^`DFyr zBJmYHy`1Zia+UNmC@I}*8kliR_>j>z0~3kEfU!3#;@^~x#CSAw!C~NeqC0p^%pBcq zYGS(hl7Dzdzr+`7cX*_*?NQEpoL$27nBNtU+kJRUx$xmul94TbZF&eEPsq%eX!mW9 z5ap!c>Y|Uev?X&JZ-NDq)|qWZcg4KP+r^||(lPc}?y(p**pQ;FwR76?8d_p=Iu|aI ztZN9JNJPvpFf`DuW*(|&C#3{1%ewl~`H%+kRub=ALy`r>C-%NScVQ&y4&#`RL;Ho2Q6O&ow%9Km;lIWLn*kL|$UeEb-}AeE%7=AL;XWk-O9a>K zTQNCi_d2fDqWrI)*n|;>L{f$;z`LBBdA5RVDHNydRH$KeFz?(?-MGpwV}!LrmCPkc zdYNx-hMV}G69p~4gtVegQI8Ex#|@(!(^Cv^T8Oru#QX|+3S_$cYa|&4ppr+cW?q2! zVE$;cOJ0C%8qy_y;OBS4=A=E;u*!|iocF!UTf0(gy@3E#M{fge$%8xfgC<_rJNeR&`1A@ro$&8dIUI?)X z?60autD1Jc@wW#CM1Kfrp2^s2hQgc57*K>{5B9f=T6m7$kmTGf?JrDP{Wx zuq`5axHZ%dhWCVoTehoH@Gnk+T9Ks?jtv=oN#XCvnL zkOuh)$${lOSKOvrDWK*cB{rwv>xfQTi3meXeBj0|Vp!Gi95>$*q;j^!@u|W$2X2xFTV%x zN{#6q^0gK@d2yytdDYX(=87P{m@ck){?j2#Oelcg+Gwe^ufBVD2j~TY9^mFw?|njW#h-=*P2mSoavK( zSWqslW@$-}Tg1}wYBztijjDF_9aVh$w}8r$4ji1x9=fplZ7eg`vZnCM(YCU<_&wSR zNwEkc3ax>r!lLrjgzp*zuSPx6Gzkth6!|W>fla1zbS7Q@hd>k*%^FlxrXidy2Z5$) z(=*&SaIuBT5}YWeOF?ES(d3m%Gba3mj5;ZQn2!mvQ^FtvGBU)+Y>o!52nJqf#jAB_ z1>k9HV61ZnGucR=3MD0DepV23eP7n+#twrp{1`9ZM3HiUx*0Y_JN1-+y>r43h7@r# z57NV0ObFvJU(I+_@`o1EadTcx_y`gJ)g4}9mU0q~CBL+eq4Da|8JZi}1L-RH(OHCG z6D#w^wFbIC#wj^RgS43+njP6Kxv!{Ohpnr8hvwp)k86G8Z)p?_hR23w>8qI5kw=pB z_9y)`#j2r|-ZtlZ5!UctJ0#z4GJu6dQ(g^^4?V|E5tgH3E|lg!Jb01GSjWd}_m^Qx z3d!$o7{mKpPd#zf4if_v&jEY z{d}3J(WQad^$pknSs5|IsApQo4^+3_OilJ{Zd0AY8Zil&*BjPD?MaMYZkrJKNS)d+ zI>{8$^e1E=wxVtNg7bRIg@!Y}`F(6@tFRiaQ*m!{fPJz}+x%B$&58Wfe|mhu6(ncW zGa<#Zf*-+~b7{pA^W$-28(w2_hUBY#P!2uF?BTWfVa(MrE1z4RBd*(u&KSs%W&c_r z<>-6enH@18x^N4th$S!)aB!`F>qN%E7jWA&Xyl~w-10+Gem2r@d?Fh5J!{**PQ7`f zmGzOxus)GLg^iDxQO`3K{ndp6N$93OPm|r9^|a(Ot9taPI_JPU{4jMT7jlTePR190 z!^`IO`>@F_JfzuC$68$9V)83K5%HVZB@MyI{$kOze4H$~|8(NYnSqa|>DJ#wGWuIM zw^fDIT8B9&6pMqf#(qR|gkm)$2QFw>DvhO;EVPay=c#ibndS`>^SsINng}Iy)?mWM z?+{_VXP!fWevf{rj`$yglZviw$gj0+v`mIz9aBD?;4wdc$kIT)F@c$t!wqCUzV06? zW*EFK#t_)*{64HP7Y@o;i^Z0%7!IB~7^HP&{!&TFlk%<4Uz#j};6pkbSZfIABYO$; zNtkasH#61|oIs>WUolE%-8_9hE~G%0M}-Z}eOVxbIV$cwTzs?rIye1n1Q(-*K~HrW zE$|fU6pIX{jSmi%b``Zz3fA`T@LK&n;BsgpxD|ibY?`XIU503ifx~PNYL#1unZ&qk z)Sdf|z4u8~wdG5Je1FC}o{=vzxCs53&pww?@8TQ{7NOvBdQCMvd}fTQD#lH~6(OD? zZ;fV(#7k#|&OIS}X%#t3Bh5(af0bD}jl}fH%*g{4{QyPREUU;*f*JrElx%CJy4#@l zBVG=3PI1diec|_vS6*!{%1@&F=~49N%;5f(atc!>Y0Kj;Q@^jp=GztT|M13quFPd0 z`8u_lF|`;wocjuHaQa;kV}~(UHa6M37ny`u{G@0WNo2SV_s%2QcS$;Ael^W|x&C)% zz~NVc<0wL!@Z&juapp&1Rc#?iA=w8Hp$pVs5FNu+(<^HDN$Dr~R6pZUdl9*I9aRV1 z8siR$-RCxOynX&^nRWOODYQ`#T1lNfvTayoR_^tjn)Z%$0ljH}LSx>^~;zZ53 z2K)IRI7R(KVEA*rl;J_|p@kP5}1E<+iIcVNahmc2CjAFT5`y4$T8_mgEZ^0 zoNPo8%fi0C`?jGgR$ZQr?+c4Y&nhmrkEkd@JdL{mk=0i@wRohSc-n^HES3&Z9HKmC zsPj0%Q78%{ZNcro?e*FDeW5SP)9@pgI|^# z9*wRRpCD;7Ui=a=`TDEk>l05}fr8@o#ZXKiCd{s*#{|yH+klh(I1@e>Kk*_>ebiuc z!5fv10-?52u1kru;zU=+oeot#%KjMXpkz+O6uTyPH(D|xQ6)Q8=i^hSIv+U0v5!K@ zL~YP_d=hoS1WK%#-_2Q%(B2`B8g2LA*4Jc1D&=||>a|ko_#!wFiF={7jq-f-A2KvP zNSpk6$js|5%jF@R{`FN15nk9Ik#b(Xhxp9JzrH(ya3kFdrCgN^AkMs(>uYCiDW;7? zyrvcwY1%ubA_$x5l`17J*h}D{nkW@Q;?A%&$|Ct)ORhE$52P`mlISKOa?9~b?hT?? zdaONG87)>K+|1BQ;uW1#lN>RPsO{h6HgtC;MT!Mc{)`eGonY(4Fk&7%IhFPIE|;~) zAAYJxR*@%VA|ipZfS#vY!Y_q2&z1e#fG81j?xF-j{5{#ryv8H_JU6gmes9-qJY|IH zK4&vQD&`tuo?=3;U$Y-iq=#$3@#dxKZM^UVqtE`LAHli;Hb2JEi=kWO9W92%38qK`aT*jn zKta9TO9zj}B%=0lsDN0Ow(KrxgS{*WK$ZutuCigUGW^S_!pGo;1=@2ysjhp@CE?KY0IaNJP9nv}1>+NLs zd7DrrSBZR|X7rL52(OUoqu8D8l+lXD|xjA^NTsl9Fb^q*4|pYop|>re(}Ky z$$s$qqJ*xyQ`zg;eR1CDT2fi6fz>kg>=CUl#RYK_Wy4AQgY8f{X&&Gha`w4&HcoFV zGZt@}tM#BMt4~~>CVZaArxS(@cxODObnbYpNo^>Uhw?e=X*hqWFnn#(rdZWOvA1YZ zUvmvM@Xcxb=f|?Cf_E_y@3^Zbs5k~<9Kt1`=Mh$E?;RhAmcuL}lH7a^f=7NDaLnjn z%cs@{j7G$<@>ovsj?J;kr8iA>8zf(vi*0+Ne_>=HgSj~?ukF-C#A2oXQSg3<;G;54 z%arq~l(}Z#rQ;#!^a%-WSMJfbdh~DoaAF3-Px6Ew_`cQ=VCi^x`;2aiP`go!7% zDH1}&?z9_;zb3T(DBD(e)%3MzVv=KX{-Z21;Pv{#J$=YrVss~l5^-Dc&-0Nj59Mtp zy4=Ge)~KRSP!k=^D+EGCdBeoTryglWt;K{gVOLhlB&8m|oSS`_UUqt*I%`#mZt1A^YOe8@EG!%Wk8kk)F+&aOZ>*;KJ-o=uQz%rDfAL*bs?8CF;O|*d1rSRo5;;-^3GwM9EgeJS9UBbrV7JuTT!{>_+AB+ zjC|s4Fm!XdkjrgzjBxvO|C8^J{*eKpJBo)>_QYX-cC`RJpOjVzsA`v7x1}4Ksp8Oi zZVtJV|8+tYEu!Nlpb}kHVV_f~JdV&E;(veNw18rx1=r$&31#d9Yyhx2w_fJS9owPrO&Kh&;$bOk zt3r7MStMc~8JVr$NK(-A8AyvMT|Rb_n`|`*Zk!(u+rNc{j-8B)-lUiH6D2fF-DZ-^ z8ahEc9n}}FJdBK&y?sv#ZHypCZ?&ddM)v-@B-WWB3?#pb(oG)u#D=vW%UkaR^yM{_ zJ5&5c+|B0_LVui<6x>k{|h^%ou5_Fbt zl#ufp;B$R8(oq^?@Vk!Gn=$~AuS-W=%>x;F1WufK=nMYUc{1zAvUCGvOuAhS6i&&a zZ`8ei{<^REC97wG`)yOeMnr%AgdMx=v5(@846kGcS<9o60e(0Mt_?W*AnS^B8pK~i zAW=7B`}YH<0^DjoS?*){%6lNP)}MsAl=KJbPZzGP!3RMI#LbhPH)Mw76_aGjz7(v1 z#EB`9gh`i)1oFe8_E~iqKbfYssaTE45e^cf^Nn0<1?8n&zG;I`Mo5>@siuUzv7a|4 z;=$cB1`VXKAY^*dU0o2Tx)1i!O(|V~miF>Lq<;G3mPTm8A>M`8%FR<+)@hL?yQw}X zkYu}85x#YyP=S!EB>e*etNnV}b64PuEm3uwZvBsHyV1Sef_{KVJLCCaf`t=T4dwzD z7+y*tITFpNn8c57sixj#8X{~UQWAEi<+&8k@vhX30sHW=nt_pz1meCSd}AZsl4v<$ z{IG8tub_`-a-jaOcep{I+x`3$ny_q;U$Cnzm%<+mD0Ncq;%(7L)0Wmz6g#ZFE`A(W-jR-RSH6KoTwuVb zj^GWScEYPyr9nwf^~|Rw&h={1&lYoIve%K-{GKGr6`l3)X1oLr=m{KDT*rw7;fV<( zIgLT9i#_=7$!&$LOLQw6!}7>b`a(xE|b^LM|^o zK;!owJZ$go&wE2n1Cvq>UThs2J@Iw?^sJ{pfIR~@)z0$G7lh;ne+qvMwU5*gV*`0P z?m++be?hj1TO+!f2Eq2MAbttMhUR<6eX1R7;*69QCN#bIg_Ob2x&_Yj?ydv466Xga*0;?|0_-zwR{0jKKr@txcNeU6xi8`Gn;Y+r zxorS88dGJFO`@S;Ja157_yzy1x4SFrAAVurai=xddlK*0_|kd$+eS1ow?4lDruW7r&CgBmob zmq@g}eXS^ODI*cqiE?m_po(b27;oIEq826+h`a|+Aij7V5%Qm9O<9{ByfFX#EDB8C zH%D=uH(N$`2YgvWKXFP(uoaNP%whjlS+ z8xbFlFzJY&EtG-8fh-M#(y&#;H?f#H0@D(j^4-5?`0MaK?b$6OEkA@4@3(I*JXjX& z)v*8xcnS4D|ME4df8tWkuG_YLy+=@6R$J#OWZ9u6{3$Lj$-TxTb6&np4b8ZflRDK} zwFlxuM1ds7Ak??~!_rni<%khv5{lLMiAwlGIjYE1_j;S)v!BlYGNS1#`41mtf)Ymq zhW7=Cr??M)7b+{3Sh>@j*55{zNGKk13|&85PekZ#NXvhFQ0|~bSTtN3mfZife`@kd&%dVNgv41e7cIeMGbT&x#-s~#LRmEI#B;t8fze0SV<%c zJa`I2WUF!;SC7gfL^v?9#huHY4V?f))Kc;cOWhOh2&fa*cqzLBPsO8{Oi4Tj5FT|} zBThlwiJ){@%%2>)9dUoGx7cUP_YQ2f>pWDc*1MgD*DL+m;V)gPJ0M2j^L1U! ze^sY2KeRXrBO-BAA8VCTd6%q(JWDGh+}K@;K^g*5H^Jsu%G|gd^GuFjdQ8H`oS_Sr z5;&0sv>Uc-ksQ1|vW!kwgQG}Y)Ij|@t-crH+tlfnpom4GA&3||zo&iukIK`Mlfwpc zKQPk)i2Ak_pT!gejU6tu9>na9^(|lmZHX%3-+acRN%#`)cuH5&%_z5CL@Avogpc6i znx4#q>OwB3xgr@tOM6<7Ke&NJbw^`Vm zu`hiMBUd$TCok0IwyMk*esM-8z)8jy3=#M~{5mP5s;!k@R5>8@8}hYKDT;w>Am^ih zR|qZSHX6t!+i+j1mzbGV_+1L}deG7=?eVjeX0;&LQLd$L6zIc{(7+OgU|$hbk)P!VEk>GjC9MjCX&`#1z^QXqLgs;$mvZGYAA=HgarXiAN!G`{xvH& zO_!iZ_ON`jplr31S=mbz@@wo>k4T0Bgh2!XOjU6%8;LXxF zrAleIcMXH|0T9o-6xPmJX{^oIgrhLa=jSCSA7hl>*{;14d&^xCF&Pnn3P!uVqZBm; zn$fva)LLj?D>9DDoVq}8OghAT%qOgLSQX9fdPq6b@Am9E@MbC3x*m|tT#K9P>aN)! z?eB5)tIA4GFYg$r>br(uS#`p=nwo|f7=3&I{$Ukwf|xmx3#kX_2$@yf?nU7$OYB^* zP_^<`rKm1tW510e$P}Ih;aA9Sj1gMGiZPV9C3-@78l&oGQN;XJJW|2xgZV5bb5^bM z+J?pnUo8tu`cN=t!jD5IOHj+btLL9?(p`3wuxzy{xT_5*WgB3tWwLsJ%Nrhq=V{Wa zyj?9HYPeiZGeqzzVTNCG=gFZ0x8*|-(m@#@S3#Lqn)h+e(^5OV>4cnBO=<4svCpii zRngQM?NDmO@M?{A5US4oXh(L~oN-xvv#Z5K-$4>+Mv4#!%FGrDtstG3-W zjyp-9g(v29m;iFZ1;V`-9_>Cv6r9;$_4!kuYb6*47(d<@<>_~s?ni@MpWfwBxeKw} zsSw55VcD?t+^+tLvW90OCBolv_8|!x<572@IpBEIQEVrMHQM7**_8%zWs}BM~B^E#`&UY#KXP)rZyzM?B=gK;_V0a zwOumoyCRyZ-ecwVa^jVP7q&jghvUMVZF&8+23$-~S*=!|lu_@EH4)R`Hhl6)DMMI(=Fv2{vi$g!;uhg zw7;05OlF{YzJE-q-stPZNN4fN#SvSq<=COOZO6M_H`l9`#7M^1YJdVhID#PAz6JiF z!xGw>o1hh_j#+oEx%CA~@-Do8&`cix;7q7wtkgHjhoq8c=Q@ME*`w;0W>VgHB`rP5 zbRba(X5LmEH(#+J$cn`qT8#5YzJ9iNJL?f|rr-w+RP-SinpK#g zf$zeR1c;LIda6~f;Ac8$4y@0xZB2BH@VD+51yUR&d}WpYx+?qqfZX;d(q>wu_)`Us z&a3R9A-=e0t%ih)lHA(<${_usU-aoEW$qD$Ofen1Y$%KND`VYLs81nI=3$Aw&ndA6 ze!u>hiPtVHSBS~JRiyK@&PY%19OXCJ2q!4jiu{q7c7+P%J?v26+k3dcBFQ9HbL(=IV_AJmqcyB4?;**A@XP$W z?_yCELtYcCLy$e3S<+Yd@`;qPwD-v2jBtFATF~Er-GMgfOa_`==Nd=p@)ELITsnUh zODsNFcJCP*JdioQh2fEvezz%MhUp;%Qb2acvHg%5Nh+&Q%UBxq1BjOOC23E)6#(;w zc2j20rv`qHO7P2x@-HXTd|aB;U}u2G1QmyCa{P3@vE((Tv7st&-vP3otW13-s1W%3 zxC<&3#`O?g1E0ayxv*Q6E~o@V%XiY~mRvOe=fn}gR1ei$3&CQhuJ8|e#-bUmC>yZE zmu@J_YUcRDPI6q?C!`$Ze#)&0?{M!M&^qDU8ofg57<}(c!=wmbbIe-6$bfTF@-JAZ z*l9skF|t(w$tg@GO*SBu`6LOEZhzfseNHFI`SGD9jd3Ynj>ddCCKFSLu|y<*ax@%I zE~oPv6S)VD{1w^f;v!eJC$=J-;~&6T$QdZm168PvC%+poRd1TFr%1gu#6-MADZz8{QEWVt74|p`5|hka^rB$37H78 zs3lWU#>hQMwoo%a{;+V9UL6dYi$KTyJvP1}!p2YT}QC#EKLpg-x~#ny8@+`@e5EwHxG z<`BxGET_Tv7q8xmVSMuIbrkdnC!W1^A5T!Fr|Q~26XafOl(N!DJ%wYMdO%EXATUqD z6uYbd=v+j#Up+KjnfYqWBh6%sfV_T32XTTQVBz^HT_gVAJ~88mL>0Da-NjE4pCcY{ z{~jT!Iiemu#=I^*#`Afi;>y`nI0+LoSOtjH1Tw^1iG-8RX}BfkGDnb=wP?iDDYOyS z&3WO5Jn7vR)xKsWeNOQTQmgLSHPFxh_L4Uems4-w{DVjO=vfI>gj58~FXeX}V2$QV zfb(8M{Aenll}7Vqtl9%8aqTsj+^8RdX1H`j)|jp5<4m_3NQCq@lA9)nlFMrZrL2x? zdSlyxZxJ)K2;M+&Ir~N*aIjXk-q=T&swcuE2fx!%l7wARq(!-Ap~O+J4tRG`2@A|0 zDyS)T2TZ@{I0}(o&&Nxxlllck2M^b}VM|WP)E9IctZy4JcMbf#EwK>{2sWh9OsWFj zRfY?oD8BSi@SBpTm*Yh}f4J>9QE(+YZ#z*^`A|(xf*#ABaw-oG1gW}j*RH4B454XI zxM17PJ;GNSnBuLn<79QB#39*z8IRKL@l;UPt%Sh=g|uD!oSu85r1|=o#FA?5k9oyI zAZ)m+7oHbO2G`m50(ZO`oyyz%r>mX#@4V;#Kw&wT9pNk($N3@pC=j0aD1}+X#P0C@D=x#?7(Pr7``>3id49?Yhh%tN$!*;)zi(cz zrI<)ZaQ1e=%ZEAdYG15N`;9)n*f{VBPtoPk8}jT28zJ(&k5u-CMZ2Og63TQ~S6hoI zWY~R~9j2kH$9%FP;2bX=o{JUtdplfQT)(ZU7x7XHuRz()vn}6vMk!}-aBG26Us{Co zm4O_koQHdBhIj8WU$+J>ke6YYHIOV?v=Q&$!~mJ2IsID`u>^G>+z>?LJ(&K@TFLjV zGJTU1b_afj0{IkRBy>4k@+V>g(2f(UnA<)L3sm-#^Hi^hN$?`OmV%5&2yFRxq>)UO ztiaquUU~%Q%LOxHL$Oz_6}>?kp0zgkRb5l#I-G}lx7okocBZ7#skMy_%dAHYDLB>H zWpkt;HVm@c_0;g6z24b+n>&2M{EDha#in$}r9}uNn%(S5f)~ zdHl)o&_kFPR5Owk;2%E+sn$~iZ@3g})F5-YiC4Af{Snx*Ct!ekBRf8uH-T;F77PQx4i4_pETQH zoko&!*|Df8wN2)cpMT8ngFHrlre3G-9U<{-Sgieuh^v+P_+*bz8B&xq79-9n`e{p^d3Yd1H>+S3N z4fasGPLxd#dKG~Qul1Nt>WrnU>EX;YFfsWA4)N`-cIumQD=nv_HBMRm`t^Bo^2({C zYISw>=e|DO^zIg)l`cmYmr35&fBuBr_w_aAJoI~>UB0LG^y$;L586#t4tmDfum#vN|jd{w;z4a1aJ=l-I!Sxq^LTJl(AIO=T`uKq@yKmn)M}2ea zjd1bxeaJ49Sa0v1vEME=@y_gf{ab{M<+YR?8@=DttB!Sjd29O&)jHLmPdH=e!q=1b z^vGnqCp<|l>U?Qvx=ju0ylKXnOM6}?-~Q4kLv3xNJdsz{-?{?-bs`Yd5*GV{Jf!`KhAj|<3(y}=f|hSQpa^*PxuWvxl@-x#!}ts zYCAcQ-T~H>YmKx5SDQL%bHOTJOjj3Q(E78_VyISqf$ncbp~Oeu+{~O^jN!Fq#kMM8 ziV~Q=o=rUZwQijw);Uk_XFU2IbT1G)6QqP@^}{YwZa3)KQP&5L_4WU(j&?SRAS6Tu$tC!I7Jz~XVp$jJ1k zi*fmJr?G?Af*J^~e($YEk>N&wLJQBcvj<+@3v2vP;W_z^`QgKdgrQ-*;?vX9)O2)W z;pZVby1Hsnd+uTpn+ChLaBJ|taC+OaG?Ev7xer8=!7RZ-`@nzvt9-WF0FOk-m-XBZ ztBS68#?iLW;I;mAHA~BeT#9DsdJErG3GllX9ptBpknq zhIXX1Bu3EE(qv++687p<&fr)UQ#l>2zzE0nZ>?dOsF~|Fq>W#bMtP!2SWLg3bH407 zOf~TawRrl7+^oh7M%yCGaH~oxIiAnEP$cdav<5$Dq>RKlgvbLPJQS)NAZ$8QYf!pFzQZ)J!_mzD9$`fXqUSXpG*XBwrWo0>Af3GYD) z3u&+2+}y$rn(2%{!9y?ubumTN)gww34{A&9>Vld1w%}b8ksXnk`{&*LUMYbn6_f*v z6mymAE8In8e1|tJIqztR!AxPz$;s&h>s~wTClv1Pc6<~=GpBkoK=BaD@h1{uZf>Hi zp@DrC=4pDGFqBx&p>JwRBOxIX)_;S2e8M};!nG>Q9nDh}t35a2{j*!}#^m`X18CIW zaTBo;}*T!6-c0v$1Z4mOkUN?=uR#eLUqIe*Er{2AWvF)f-Vcvq*{ zfBUMOKR@U>H4V*h;cZ489i3%5u*0h$P1M%i7KW4@;yrZXhNDJ@4EB|B)nAYIA+XF? z!4&aXR%!a12fn)+7-MA@YzTGxg%1I+xRQU;bIb3Ag(;R>)#U+uFYY?>WI%E@PBWeX zS|S~MG#|hNDhva#ap@DNe*+59hpP;C(Hp$_Tvgx8!fd%*=xdXOtC|P#M>dN zmFdlS4fA&jSk*r3 zN#?59+XEF$F4Vl`^hfiBEHX&pA}`0S;bVrE=y;=}ynSeRI3;r00214zY0b zCg8Lw)7U)qX^GE|Xv8cP)7k1~vFRptqnJ^d!)n2Tl{j^FxBOoYs9@yLjKV}yj2HJ_ zT>J``TME*&PvF_8=;Dm6a7<0{*P^x?$?0@I_Kk7W%4d2)1!=#jji}hcB+D|9YU)-Dq{5(ZI|> z`e!)w{8`X`=+m{BRTwb}hPK=qOsGnf!2O}lp&Omy<9r}VHvorAGjEVGk#3=6z1t$K zZY=0;CtE$`?wO$5z^T{v zv}l_!hX_LGa$V3vHV_4BB!m0In;=}U#oVaB#%QKuO_`B3WtJd^Awttw35}Y;H3%HJ zi@tog6Xzx61|dg~Fsm7S9Xz0mOqE%z8D5TJveiWsRub|uSmXU+3}ihf7v_0O0lWtn z7e~(J^3<8WEM=VVa^eAl7x*^`3=p@=tLJhH-Q`W-w?@Lh_x<}ht<2>*+!_0}tc-*?0qB`#JOV%mF`Xa@a}0;}XyNT1U?OU3#V-u<+xKBLpZ;ZEEES7+ z-2h#AczN>xz;NiMi61usj{fBXKI^UIuK1q5J`O3Vmvb%hzwY~jKW>0OvgQDJxWC^h z{mI)IAiKuK6@J2!l9JE8y}wqNucf*(v1#Md(9qPK)0e${n_F1O>13~u4~z>~hJ437 z|5<+%eDh>eVj*$61j2FHHDykY&UDT+dfH#5;?ClvdfBpJ(C|`?w?MrqaAdsvVLkMX92w0t5pz5#HKD8(Z?V+Xz?lbQ_ z`{aJMP+d$-dHq5L0DO_qll`Gwi=;O*Cj*py|Jo%$V=o4>2ta?CMb)F}8W(W%hX0(8 zmS)`553zMyf7UL8Q2$Bn|2Yyp{kJ}#NZ-@ZoDq}rW1_8s05ug5=iIbHBQ{&nxyD z|MP&n=ni)J|9!&$B~9>4RDfL1EBgHNXaxYmGxh5?*(qoClGyEnf*5iQ2wH8(v-R*F zv9Z1EyOye>lD4YFB%$!6$MNID1T6_397iQ$7=Z(62|glA)xnj`CgbDdo0^(ZE**cA z$8BIrQ)NLyM@MHsz4{^?eo}smlgg$&j5J#>%D=gM;CG_Z`7^J2;#Ql)mqPbclh{p4 zO`qivXc$(uwVRZn|N&CfsWUiko42;RUs0c)7%IzO3gSG|Ih(&w~s z5acJz+!A_9JMVS$LhCm9?os<+=4$@@X%Dx-)IKLr4+=aqssk1NXNC0&4)h?1If;Gg zP#&zPQHH0PWZw0N@ivz7*{aTf-i{&oT-+OSF8CuR`1&d1el-B z6^?EWc}P~(*LR0v35juFVBk8>&lN?}`?I&tLRBj!Z{!TR4=yfnWejkF_l}RJzSkcb z6_=8VQu_OQ@VNc&sggJY>Gs3?;b-IHrc)l01dk#NxN$7g49m@Ye0-o_s#aH>`1$$K zqnqg2Z7>6GMqS^GZdNc1RsnU}piS<1QdcJdmIfFPNpeqLX{J{h8Q`^Q;tU$%3{Tm$ zE$-cm>Rx&HhGO)m2pICsP1h71j*#OWC=e7NZ8bGD5HG!keK!43=9JlPk;1 zuqumNr@gE95p`C=nF9nkFky!HXWc8uJ4Aak$A2Go-Gns)ANbo_@|Rib6^=alh=l_;#oLXXhI5TrjZ^ zNc}8n&R~>VUCd4PM}hKWMWfMR0K2>$ZeGFh@bdb&djA?_G?1XZy*-E`h%(dBS^WX6 zhyv5It&r0dHQ?M4uoxN@)S3Y9M@q-tZ;S&Y6WD44X3kcapnf*qg!gHF{tci89^T## zuCAL^QTq2j+X~zI_)vWR{=IT`TWyw!4ByP${F*l9@~*VeTk4=z7D-9TD+D;`$?sK- zjfBnf367%CV0fvCa6LRdU30!~Y>H$K06oY2`c>^;^^NWEhlqj#jPPI_YO^PFRT2!O;N!1*52v>Mx4osW5ZKz;LCejEhY{33 z27to2ySpQs=kGnpx&U-iK!HDepR8Cq2-327f!z(fXcB-2KiPQAd=vl=Fm?vq`vf-% z7x}Iburb76e{mCS!h0>b2Mbi3EDD~-{qg5f{xAZI#X{EC*MZ7z_&0-zJO1X~yWd@D zRW2VUIknPp)%w}axj81P ze23okJ#YX4fbU$Rw}_lhYr&WPA9Mv@b}TLB(zZX4Wd=ef8pf#R-^{F6MD=sAU8~CC z0*@|0@U2N@OACp1lCY9e;@Md!6Dw=JwP60__uSd-Wne236+%v6iaF%X&CLW)RgYc= z@BR)6{CloI8I8jbk4LS68h7jb^-HwhSqum)z$BmnWt}^a%9@%zt-rGSxT?8VF04V( zsLcH@XJJY>CsI;Ff%~E6NT+hT2Htv zPqyoThLoA{^{$Enn+H0SF;IATEyUB46c{}qVQzJbzcx0nCH1f?h8#l-sVRt_R#sJ^ z^okyPND|jflhjPd8NGc1q!r9odAR_4vNnKrv!r;Q((#zoRGKk2iBBuLxt?b-N=iym zYy=lFzqZB+BoLUTzQDj+GE8Lrf`TA6h6ez0YI^!ZZ!Zy0Fn(HM@EcTP1&vx;U#B3z zdEVoQJvwC#-q?qPwcjgc0u=~%PR}mx0K%{zqyP-Ci79i;BKR+FDv?kiz42}!lexJ$ z5KP)wTp-v0o`9SRUnK!j2_R5y_fDPFQ#Jx%ww{-iSV=|wZ2!vwOuW@~N8zyMwl+;5 z--|!HL1RZY#k2Id_IwnIz6!C+i1e-cet0NJMn-mp=;_t= zc+~m&51_-=f&nhgKs(sAxoKm;D?!gu(;i)&owy;2tYE;w&zHeL08Btu(q6u#h}Wbb z!D}R!R{>%NOyG-~IIH)6fANp%fW~${8XYyx%Fdpj_Ntj?i^+Sh4~FdHrXN7}M|2o@ zLje5M{0`pU-W!1nFM+Rmz*{a;pcuWy0anzjKGv)hH?jM%3yAJp3$E3&y2Z@C0@es47tPfQd{|FirKd zV5VNZe%)2$G6?GN`yi2!#~&~a4DbwF?oQvs2Wn&S_xS2)0UN&Lm?lRD&ISk#^-<_hBS~}0Rd2D4iCtU z8kcTxD+?eWb6!&K>+1o+0BcTQnI^ODP<&5d$Q!k&kJQ)K?{E|)?es<|Lk4q{v?Mbx zD9mDCw|cGt26!vu0E}d_v9fC?O`O?F9j*2E;b9W_C zY5CW$`;HH61z)N)T1S?Y04DG%GZSDqKppTFAm559ZuB#dih=~|*f8A~;4vV|7pt42jDaZ3gXiAa;OByFyX<~KB1B1BQf zGU4}h?mxQD9Ouk&%;!Dt_xtsHKAx{P^BJZo!gAd_Jf5NS8I6C*v0lG=mE~2`)7vY| zP`8p6elsP{bkV^wy#Mf_{?)4`{_dxn18krv&=4Z&U~Y9;*{Mj2)aTEwp_i-M8*FYn z3&ft#-7HIjazBNnAr6N|M=u3wLuDxx)g~hwvJJE!f`kuWmR@@1U%4Qo3<#ki5*^%1 z$Llw5s--vi9yoC3`;5)FuAshLQ_+(*SQH#D00$s|9t~0?GE8OO{2v_$DO({M-KGhYwHFtCw0y->A`!yEr$8h7Jz< z>!zf0HV^U-O7QYuz_p+;p@=d8#^OkIAj6=tO=CLS>6I=NQlYDLnTHaSIILx_ZVO&V2>&IoQ7_B7^h z-j;3D;LPwGD||kjim02ryH!Gg8VBELBlKtQwxS zw#pi;T?^-j9wKuAZ%$2o(DxmuvDJg+V`6**gcX1mn<#jC0$ zz{l0qn}M`gRm6`R&TzJK9)u^$Nju9;@7dnsdDd%^KX_7)>g2dq#W z4=yLqjElt8s1Qk5s4cL0y(Vl=xCPulde9K3@^s)xHfMNgT}YyhAg&Dl2F>FoJ^sF4zq6`yoB8U7 zm^r@pL zB!+3gUK*P+f9zFc(hn4nkdVNxOEsrYdw>4A9AJQa$52<5UlPO@PRXnhW@Dp0kb8Of z@L{||ZK60KYo_{|y(ZSmnoJDl^hX9h*%`ra>#mc4-2mTJh~mCML3UL-8kuiF z%Dyz393}w|I6tB~3KyfKpA9fhQjVS!h?#2g#yj*ix&qMs*7sVG0D?W)^ywM&3nmE$ z0@?8PEd4Y zk@*fL8ln4PcRLO&n%;B@-zk*&9Vi+{KzOpdon6gsIcA&Na-V(3&C}D`P(DH37Pf_A zfGs3I&DiXfUub-^L6EWc7)&4tajkM&Am1-a%w3ipLtDW8GMq)|+G~UmAlYr_fo0q6 zrEY19qmK~}v+_eL30?rRgQcU1Dn#%vb;qC&9XjMgr8*>Ymr6;wZ{B#?hMa&IhOEb4 z`y>ri#a@S*`IdQHu-EK5vZ=VLD!(qIle&9Ie2ZfyXSg0M0aO!|GpR0{cEKahByY(32=-_nx9UzW?#VxUa7dx$-`8 zE`@@RIWHTI=O@(o$WPn5>dBqqiD7%9z<}>AI^%9EnW$|s7JQ}a2+9yf!hB(KW9H^z z8diipgs;i9GGR9?VkZ@Sj+&7X13kIq%f#x6iplPE9dE)?Dr3H0^%u-owI;i^ zJUl#imo>Bxlk8C_he|{E#)~6+UaK&W&>9ohh;~Dqyo~KIO#P z)P^39)_`KSRY}~WIyITZgokf7rYv^9yxn!o^xCf4z3Yxt{fSLQ$YiL`^qkPS6sIEk zjb05kpQjt6E4_6Ej(dvQk$bzU8~SETM7@e4K2Pm0O+03PZ+JPAsdmGm2O*oI^*L~m zRy7ZcBeg#NMruNq66avqRo9hn2I-?+&lkUX^XA$9(pxP9Dl&;GX^mOzL$iHhKRuot z^k>*N-HCctQk-$_tY#zrY@x{O!u(`MMj}NMVwEfFJ3gKn;zRA%pqGjoA`^L)s}JMi z0MIM;&jO6ITLwC=v_x7I>C173X^*^Ko1!6bJu{OVSh&BOgKi<(GYToEX?1ET<$H_o zQltgtJ@UmXrm`S2s!3|8K<9ZmTeO~rT{;5DA9hzB0)9mZVTEnvY3M}SibckJ%uhh zGlQhSnPd(u+fcq1A^Y7BkRG?D+gqGL+mn?W{7-+eRXo2I5%tyn@9%i@YD{mow$V*R zp*)wt4|XhnBeRR@TsFH|rZ;LPs{2;I&!R3r{O5Gs(35+Km9ruO&zuI>AN4&AWR`W- z^}g@*CGdjDl=0Hxh)Ju1W1(+YN;CQIVk8}}$DFV*?LWuWL{B6nS+6N`=J&o+QrydH z&8X|6`44|f8q048r%)bA*~`~|OY6V2?q|`bs_9Gn;#9V*imdr)np&x`p#85#e`%54 zKWHhpICHXW?ZO{q=Z@?=?A0A5c0Zc6?LVgydzNU`jl`r(4%88-2U?!~dVr9UNOD{V^TjOA7npsJd_f^sNv^?W8r! z{o^O<`2VNN^E52!R9kpdk&;Y4evf?IFl@3e^X1!VcN4O->iz#*EB4zu)&@5+t!hRs z^uR8o0I?Fs#FA^C3on$NOEqL|$e2(#bX{9i@JNK5{_|WrBNCZ9t4fM`%uNWehhtju zq(4ic$$(HkI6mzsb!t`x2}~qjfH`gaK_d6gohKENC5ZG6xjmx;reGx)I-E%^`BU*3 z>zMgYEaVhTGuQm__s?%x#-a<;(9=~M76)>x2`~qF8SK+&C4pw;Y1Ow-V~+9kU{iodm3$?rS=C#l|u31Tu$y`@!|Ox|^E9q+Do_34Md ziO)G`o@6qeh^M}9wwnGvOcag#M(P>Jl&9iTjo~xM~)drU(@?{do@0v7;F5#p&!4#gYg&TLg296Vx1-n$|bRP0u^ayiUpc~ zP-GeE0)*MAw=uIL0y0tgXu11Iot!1W^cd=4PqYBg)_E>;=feg`-78XZy^7E=u*@sA zJjzh70hfUmoV3k(p`WFE$~ovkfN~)mt50nFu^25va}x*ooMzEd_A9eY6~}eaIde*w zk~0ft2*$p@bc)i~f!896cd5l#T$ffPlSBwx4X%;-D=TLyrX_mTu0-vU$iv=zXBA!3 ziPqVn2Vcoqcatu&ck|23pAb48Ei8!a#vF|T5$e}S$p;R^MavjR(g@xhphw z{GHpcVH>Ayd)|V&VlkCOURA8=&YH)y!Y-Kl%+nT4tuJZ_6tV&c6I*P>UrZ<8K`-w<~}EuY9@xn&ko3 z6o1o80m>Zx4?hD49^D5G$+Q+%@>GVl5V7N8S)Q_YgsH8`9+F9haMcZIzqo}5tN~*k z4i_aY20TRr;y9x&m z95p*|;Go6vqwq<^OO{Od&tY3JjM8y<|Ln(7Tzo;JXNrz+dMZ(;S`=*ud90u4-Z|8-gAqIc`?R`m>S{)4u(H*vzq?8s1) z_w&&9D^1g}*Ov-8e7FyD|NVAszR`_booPG&+Bnb z+J&~en{PQKr`8s_{oIj3_FuR&S6?wU&8EL0D3@v3P>K7G{unn|r%FCoqL<8_`G)Fe zPvO8joaC1lC4nauzSndA`TN7xv$t~}I^DB%8RB@w#Tv%^d$KUgB~JD+6^G5j)gxcS z7p#&O*HXTQzqhv-!x!)#?9rk3KLfc$_e=f?&Wk892>?1o|Am_swHzH$XG-^|#-{a!Mhf$cko+BD>XDy)52ryCWmqFUg*O$$ z>E_6}+!M6dPWK-ci@+&H#6_`>=*q6o^yakR@gvh6TF9otd`W9F(a8_}Z;aQK$yr*q z{EyyXh5Z`G(@7o^Yj`)36I&c~#yDA#QTD#fHrC@l-__wcpPF8Je{XBkw71GKprKK& zVM$}wwdn6u4m^p}Ee?*1O#dR@(oL@FCb4L}82IP?Y|6K|dvSi&f2Phbw5fA>u~iMx z5}W!{3B`xB>`HQVjz=u8x4;64@rLsjF!mXU8Amj?)ReqG*H96e2TjqU`&;vT2%=o|i5|)1H-{9&V)b zpEHX7v7*!PQ1hq~q)`k}9#`MnoC)VM4b?Bxzi6K#Mbu-NThP@9cZmAP znm-ziJZYVt&P4a^!|bgilz$&XRPSb$4n2KM-mKykKi$Iu=6J`RizxzTVgjbm1zu(9 z>1~*d*_70T|L0n<1?i@4>8Y6t_671D8HJsYg=1K%Lzq~I_htka-9Em z%S4@k;UvAUeB;)?xRU?rhnMURC8M~RUS1g=WVKk1Tz4jZmG~eJ zMdN|C;NEi2d&khnQ61}UOicV~%Pq8VXRdiSTFdeH-&0Ufi1$849Y6BT$GC29wk><0 ztbAVJdjL=z4O0FB?-KVCLFF1O}iTv4>(P}T_ zE-(S2obuS2zs6kp>L)8^XAc>f9(g_-zPx)eV)re9ID;%;Cko6%k0#yUzKjBoZmYH~l|9G}6FC7xT+#uvjq zwN+Q-I9Ga(9Si>Of#!32tur&16wgxsX4Ct5r?F zvrbMw|A%p@)EobNH<^1UMyLMiX#0K`H`1x8Vc@dsIc+~5o%HtYNsOQ2sZfJ7sTK=L zcBfq79fD#~N=o6DlkG7>d>(PYwt^AlwqW9%Q>T7*;KgfJYJDYPrA36X8S#KgSA zZ@J*SNvOWl*|GjyF+hUS@|(AxpFfv9KI{@TTYc`zig5i>jG5RYvImMuCGLuZDxZ@x z?=GBv$j9F6)>u>OO0lf7O4XyDB?mXx`GUTx}p|ER88l zOOaY|u5uv8#KD2bZ!YjArdL}bxzi_Ly6)Stqib($sbpuOGgal4j@1zzpSbDG62`1Q z5Pn>X`{}xu*Zi02+Rx)X4(1GJocDc^d;CYCto`)w5dDneg+zt6W7BUNw`TmpPBjSG z_$RMer{$$S%Eod!E0o@l@IU#-MC}bl!!1)K^#@7o*lfJ*7fyGEg!_(cS{W_hntvCy zaq0J4kr3`zzEz0IBrs)7TFF*zl-c+XBwVPx6+$yK)xe7kuKq=JRIxjIdTArwpwA)S z-=0c?LaW_=q54k!A~!z-!iO(L*LPGBM*ZY4@2lcv@^-%HO}x999aB-Hymvb{OeQSu z*s6PW5?O6yHlvVG?s)suxd3gxKSchHrR%+t6nzGb)|&R=dS4^-@eVydPB^r8ICQ-{ z$|KjV@eJKR7GtI+7g(BjkzIeLdM`WZX-ns;Fxk$Js=KLU6c-qqgws{`3Kd5!KBmtx zGTyf~BWGZk#-*2Ghxrui(-@Z=C{p&;V!Dm(0^%q`3niUv;wG)+_WC#`i@SE7q(%3| zWHWo%RawydQXXZaj1Acm2@`2>Yy^&Nm$TLlsBQ+}y*5$RY zCF;^Pl*})scsKGEr%NV0ptfFaTrho(Wj{sshO=m3?#r^%rAQj+n6>uJYsC?zylee= z=_bA3>oCjt2p4zPa&H|r#w!>MYgPLF0ZQ)4Qv+@_Rt7bfQeK?*EI<3Z*-kF3+?u|( zEa$=MkLddt=?`bN1xUe!&sKH8Y3r@~zX<-`SraiLygorz+f8G9F(p}usEH9Dz>wBD z-F2{!lCq`H&4x-Rs=Ag>jm{JE1~#+}-AvEqQrS1LE8pm=Mij=VlDPG(UyZYV$+|M% zRQsG#sz3{Z8Coc#3;ry9i%hp$>G?vKm~+}zS1f0i8!MAX_=4zCG(Go*s%9Q-99HHJ z)O89OD;OsZPw?F9-MG&oI5aepzbonO()|+6?8nEX6BiSc0mg9-erA#$7~NL* z;Z(+CO2AD@ly3b#u~bYvu(sxDWbIHY$?$4h`gT|XS?4bQ=#j(xW_C=rCt7q5e&shi zM{FoIDNlr*#63m{JGP0>-^@8A@P%{gYfkbX(|QR z>c^D>yR%q@N*U|lXC9izkMFt5(`N@!I)6*6POd4ywsN7|m0G74&UEu;aCgLMV!4w< zL=kqGeJteX&ewA`4eu36QOXD2%owS@o|_f7D9o>x^g)Z7QNNr^B1E0vBhp(n@;#N5 zbX`C@bD5*D((^4swRfCn6xJZz`U9oeb2VRPI@c54y#4@aI_9wt2ZkXb!YvP&H+@dx z%_+AKSMW=B_x|~ky`pT@-p~4IDq-Hzq-y%ZNXA1yI>tM1v^8EGTT;@GNqP6dc4c{s zRl!3dev^)C6nkdZb;>9{$0I8vltz%%VT_w)D3FJ;_ELJEh$v1x(wmx-NKIzqTXn|CBr6ff zP~UFlNh z2G`&NV?TMW&};N`KO%+$S9c`#Rx~3k`9{S^{)ot^uc{FBcX95s;Nn%0P?nsk`K#kCk*44meEzBfc;T>gfPftz0igRxE+4Jr9e zNFghgS8b*EI5ON(;xxhmMD}EY&Yb>(ee@vAMKtIa7ZYQ8sJsPz5`Dvr ze{O)@wEn}SbZYSvkb_ov^U~9mwGHZ*1Z?OiSi|})6yMY@zU4T$RW>#om`LZ?WU!O-bwDcWL@5S+kC)zQo&h}<`YeTV6s&5bhf)? zxJ{XC$pGu8WD0ir@T-Y}anq+v|K0PXl98o$Bx-Kge-8=BBqgTYpf3)%!XbP|>-Qx} zPP09iI_alkf$U_I0t_&{XN61(^_?&^4*;T?$YeJpUqeq#E zbUB*d59jy#`t$@XpFEFd3|%rw%t;AmzLO#rA*yX-QqEMeqVPs_rr~TzaPVoE?x>iK zk9@$ykB5g8ffwN#$*ZUiHUasx8KKL9>(+Bv5+^{99dIKPfhKp z&ts?Xj!R5DOyT{|(){Bp72B28jP8tnm$IvJd!Y}~9$G6mSal!eIpR@NsLC)EWs<|B zX?_3xTT?s1vJdvAUnPjm=#D5x;r4ynkvPNyoO&dg9rd^p1Y{#eGb!BU1Ncf(YC?o!#uZg~Mb|2u!7)H}Hb)KpD z@3*nK|4U08c=+%3-oJR-;Q#xDr>4i8)&?9`aN?u|Q$3N9RO1s9g@uRz-t3uNR;O2! zIH^z~smD^#dFnDjk*b0eRQK$^rU)O;{`b6>8~%lr`&Z&KI~C*Y6a6mnFwxUXT$Az- z?w;{;;FDd77}}QH*w`o?3zX(`-y|4?{pVp%9;D!Nf0f#2ILr@bg@=b5g|+El(6sV; z`}QqXug>2n3~lxO*Au0blVq8;zwqt9>DXfoJK%kvbMGkzpdvz(HxaAH&8Z{6sE1<>|ByvHpjm+E$^vdV32g4RWr3SLp7tg_)*cI z%M67nVZ&|n8|`lFWQ?bFQc_Ywb90wt)s~j*CwBVcmfix>l|T6{`1QrnhK2@(Cr{#8 z%NM>5ud-+q8jUxE^p-j1C@3m+rpVL!QSmA83_2x15s9^(loQ(9Uf!$|*}d}ZR&Y>I z!X=C1JBN;)3T~NfKSt{oYZ&b;xwSeQWE_qktSEch5}j3IJK4aghnGS;-To{5ax%YJ zD63Ywc7@AyR?%SFL{mh8!>szsOt(Bd*G6r&?X`Mf{%kIWxXO*XCmUe|Y z8v15q+q}n`K$M`f0?eX~c5ht@$_Jfx4ax+JdS*gQ>)hzKrdpY9mkK1n@}^o2 zRW3ORo~h%t{{6BxfL3RcQjGk%e8aBq~j|tAz@)DzHF6`)YQ~mW(&GG zjoau}@SQX7R!THkkqt%mHd?r>e}8|yrT_G4Iz*VA%@yC`=%3)6IbXkuk)J=$#LS#A zxZ2U7gl1T}F%i*OWI6PDvY5~&Z9kn9mY$p}8RNNI!foE07^dxld2x(X1vXHN6ZPMR zxLo+XgG#+Ij7?QrJ36s<;px&?Ju<>uU*8s|Ox=r=0uGsl=6%WLeTDVbRGl3iQ!Spm z`Df3b<$PRyz~JfA25Ty6Ar~ch0i16pdgijGhKl4YaGL4>N+;;xdy}q@=E%4$e6B zf>ijpKab7WJ>ZL`{CEZ*Kun~Y-dP*!#&>2YYinnhmkaKUvw60{0-S@}dL24u^85Q6 zaD5G{sQ*Y%T*-GCA3yUxc4Bd&^Ecl&jw`^z1%v(Xyf|uHA4o4tIhvl49cZAoxzXau z8q<=}&~TrGR#>yB-^LecH71CJp`ieuT~ZzA2Llu1#C@1JIPx(wRo`oBru&9=3z7H# zG6*wX82$ogP?3}KZx-2e!?Zm=LPW^W*}1nUo+Av{pk^7*E8=nz|#L4Dp$*fksQuEh~wkyI}3!wJdX<&dWH zc*y23gNSi!ec0rr6jeUBD8xENNl9Q)Q!vvN z3Gvc@^adAK!64WAjtAPvd3g%c)6=k*Wh*7I6$PfmN^ENXI4B~b@4Wr@cYL-J*qQY(9S_){VO^PO2?mX!X<&rX@lXvr*l^s& z>i==(R;zD5ahWxfd+Qo)5~jn2-CeNK|6#t{&qGm7v;TT_au-sGArYyTQX#R6zgl6yV=>CRwMiIODp)=&eknI4E%=7Z&GeTC+xDfqv` zh)Us=yqaL27C_vD&~mpdSS2Gh73WVafD%5Re|x5$e6(O1j50kMAY$=<{*paGtGdLb z`q@95IeVKqMq&RM_KB#>5pKwnrSp|rSo;|jNJmf(xo_{3p|hrF-q;!;Xg*BZ*ALHJ6~Y> zfo{DxS_hyo9=vbHRA(#vEb1U^t<84}t@S75<*^UAuMLFrT0gPc{^mn!3Lzg&#dW?S z#eHklm@w5^I^una)1>1DwXoYGh$`*%K@8&#Wd&{i=C9umX0t@W2F&+jv z@fNeA$>$>#x^v2*DrOV9%D`P?O zCOx^j2zC`1w_g`ps6Ir=Y4m<+dAY!8@d=Sh(@ghkuD=bkH{e*(h#MMEBC zM@cB@;Obz7>kQNgZGdA`A*$XFB>wgQ=A)VYqiBdzR?BJR6(yHRaH+#=IuUEJC_F%7 zBArvFaX94bw*djFnwpxoazD@k99vqlAtxuVzeQ}IuW!^G$@jmd9aK0c&E~51Jjl#># zs1GfZipIuid3kwbD=r04VnDGnUB2Ah4trf+O(p11gcWO;^oye;3IIb8V1NQDGc%L_ zp9Wl=>-T~Z_Il>(@4j_(0xMu;K6}w zU<)9DlGR*|B_t%kLm+!AKYf}E;B9GX$qo=UGc&VvPQ_~Yb=mMlsB;QZpVnCi$He47 z?S>v*Sy>raiua?u067Bf2vZNitamd70@v5q`L!fQh`+tpy$C?@k@&-hAL!D+D=7t? zazoj4SYas=qyq5YNJTpKwp;do9fQwih)eV5zu;zW-;4b0elskZFRKUZI5?_pkN&-HF8$bk;rU{UO=w(AC zh2V2~YoWP2p;ao+T!6O=`I?sdN+-mE_GH<1c)K->wScgoUTF4-wSu5P&%jW$J@N9M ztgJF{D!cQ0yYfJo`H<3f#q4bxM)6vU85kJ2%#}>;mr}D1%mM-$0726>*XC&>1OKay zzK4FC&i!nz0ZH=9^CLDTny6#}19L(wVo}RW#OP^4!2t__u<-cu1|UrYo@P)51Fm6k z(Hj*32~wmha|0R*vvvmXBqZ4kWNFQ?v?%XF{m>1_&<+r#NkcGWU?O@Hm+i$mdqCVw zuuf9`RIOO!c0!Y-hhkb6nfbnjQ}^7 zHr$rrUCexktF$xZ4ZsvDM~jylm{-2Yd$h#|v9+`W@IIB0cm*3J`Q1C>q{Ku{SIx#e zC204quRB5DJd$$V^ew8kR)jfZ6(RR@j)&=F_xEd#kBv>eWzK$}s~cD9I8Sr?4}ikD z09sXmNLHnVg%fLA%4%win3YmTs=9}2YM+4hfWGQO!vWfTFlN#kFVV{Scjl+{v~`N) zXaX49ISpI{mp&!~`jlx8?&CBl9VqBicZ~-khoz;(vi0*d$#<{Uoq=qCl^*&X{uh%$ z0`wLUAJ%uQk(mE^d zP5e+rMdg_C-{~A^K5{$XTh`FJ&%8*Y>_76zDm1NX{XZ7s0RK6!{~S#;_{=`(xxb0- zQv6?C_>@HrY|kMmH4Qa74t_7Ma9v~K;o<2u_`4IE*#R>-%=M>1#aST1BKq@^h=<^R zL&rAVrvG30!vEZ#chcM`e{Kf1HtRm<&wl|%de-wVqc$8_I3jD@`@4Ol9$S+#F3AiL}ThT~>T+&@hv$w^T{aU56OE2fmc^ zJkNBx-|lGKKZ=PDGU6BqAMG=CMwAC5Zqzq6wjwV(Om!xx2XI_ zr+}U4EqAu{JxB`!51Wx6r#<-P#qDel9FC$p%s9QefQRR1c(~#v3$7yONwW%+kwrD0 z+{a$*f^EMuB_(3AxM)$Np_nYwDllK(?yZclV3d4fTIs=@At&rk_vbfV1VfU}wotJb zA0L%S!qr%gtGUMi03;){%g+>5?PNhD4T0RXw;r&E>r~ZY!Jse)c_Z!mBcb56N}Wz|k0A{l^(o$C3lr(SB82BCr(qn@Y#2GDQ{%IN63w%gYN1mi`3 z{DVZ2y1X&qIFtqPL@p3(Jt`@*Luf~J44_B*Q9mAh?IlY@JN1rNqEu(ja{4-F;Zy0$ zGABsQd->gXHN@ZHw$4{(%icVqj0~80E!Wr!m1&5T)b`x5hovFp1zBA`hB8eZP0ZSuUeIEJz85o>(Iz4zsH-G zpTE!TeKL%G!)xBVyR!wb2H_af#osjuncJ-|=mK`;zu437xwnH*5%7pw^Xov{P7S)w zcLIVtx{|#!Tj)?ff2*0HRQ0V0bFL`z+eb%FMM+WKZi_4k3qO{cdKeogH&)q)T*kH ztx6Mue@NeK*ZV8t1W0M~>Qx>UiM?qJzkmM*REU_kmoE=PJwf4pMsV;JF(l8<6V_t( z(`^!Anl^7B;vuFE*jEW4M4(aC@_frlkfx@tPD)T1NNK>`s49khfzZ0p;&(Dcwa^(i zg>yC3*S7-K2c!^}SBFlO}8fJ*=>fEew3YJd1E4OGMcm|)VFbduok z-zg$HX>`+&+PYBX0mPZ6UhTURNAIGH2)4+qqjA0I^v=8wYGWje$e)2*9q7HJXv3wW zr}*R5=)a!!qB{8#;5tOtKnCG&e-2W>o}>Hn#3SdTFfH$k$;HNIj~M z;ONqzl>}5*H*8s|{z2e$srhW~Iy*Z9&4_sTT|knlSS(gNd$e6%r1R@5BKtaOM+71O zDDQ)ah2cAxHUt)Sx8`TS@fGdu3!rR7#;V$xwM$G@k9Sz0-qkWoCpjz1nZlfr2j zo@1+a`H^t|<5=><=`LhMk}GKULC#Lk&hCQRgwwp26KyfD|3eE43#%C5w3?!YG=do9 zyI!6k<9zb{IO1Ku%mRVe1(AmElcU9`zu0;c=<-Z}L&wV0D%XD#A)M$k73V{M8VXgl z-Eb*F+0eow8>-!8RF(qyfiT(gK97|Q9k7u+Y~CE!;^BiNG=h(YHkuuk9z3{=DFyt& z<+^INLr4+nl(?Xk_%K1z7&;hG(Yn5v`Mv)HZ?MTSQZWMRla}{x9=ms#89o%P`@iCz zGPTN7e9yDI6`O8VRa8va-gZOS&7w$PeFOO+Y8ix^W`BU92$0H)D^g%%z^bq_^w^IB zQiS3QD5LxL@0%N5w z8e7hS$$(j=7k}uX>IZ(%2npS=-; zpgcEq+W7wP=|`&9x7SxsF^hG}A!mH{NaAt(DFBOt0PcTqmQ=uJysia>(sbC-WRG|nvD6-jpger;4VH<(ejd;gy^uwKc5A) zP})6R{V%&iNxr$@Y9hC@_MuDf#NJKL%oFc^MIIaRlg&9lbM=)v%crBPf-jH18weZ~ z7#x zM)emBOD9R*5ICk}_+6NaanqZ}O<@4s!~I^~Gu!@8{A}U;<7$fbV}}+NjCq_lYjg*qSKCk4JyKv(8h3Tg71iqPm&cr0rAq@@^ z4c9l4BqIZSpKaKB6-{&42#ytT7Pr5mpn**SLmfLsg=>xy=!-vpd17{;Oce~bk9lL8 zIO*@6@H{=x=Km_xq4=dRucZYJ*T(q0S#remgnjaKrC3VvOlo+GUC!6NKX!KRXcAjk z{@h>CmN?I%-f_O*z-`Oz^+kl*hBMFhZk%m2jlg0hX`*?mt}%s5Y)w)Orkxx7LN47t z4~rhVtb3mm#u%pR3U3bcKTF9gqd~Q`QX9U&IIo^x*jRFTVT;?`dd!u4v-I;mh+^=WpSQ?q1`mtT%-x1j)t~=sCFz3BswK<0 zulOc4hNLvE!U_K7l~*I;hjNTGJ%`uggkHQW+@|n3s@X)5!C{vH)4E*v@2VQc6}sG` zp{c|gOv*?J{s_a%pK!?b=59T`xz+w~(#RM0(w`OXbN2;v?>>q*a`iga(|*2aAbz?1 ze9W#%^T$hr@5()0J1(9e9cr;4$zp5|Up%M-KM|FR|CUVVG+(iXby+bnFf^P&KnA*D z5q6R0ebB)SLv6hz=`bcfzLF?r7+o~;xVzOr__3CenL5rQjrh;aKK|;<*LoG7M>QU7 ze_7B;a3gtB@L*0e#v93}Si~QoN}@ zLFfD1mJNin8@wHKo{VxxN3HZIiK%a+RwFYVoCK?qG}5SVWi}6VOvSPOZ5>1V1xc3F zL>3qc*;HNXZ)7C!fx$XbD)Y;dBE-7_lCVINt*eb{fxZ>x$K0 zQ%ZLI*IhX}Ip4qE1?+q;5CS_FbiG)#%O7c#IY2ij+M;y&I&uSOfRsWb1PfhbKN=x* zQsMPjXja=pkKGhVPs&@5pP@Pe5qhY5HW}pzs1<=iXl`?6G^0)<^m%Z9e&x@Y3)qak zMh#)+>|(JD)f^Qlh!Ok--qiHx$J?9R%Pk0wHAM-iBCHAYoE;38o}2psZe$v?1ucnZ z{;fDl*0=$(RPw=xXNkBLs;i8jFpj-_g~~hJ#_1lcD9|g=X@%w!GB6-S4D?X~>5SJG zMi5(O)~5pWSE=1}JaB<{Ko=zbBa2R)1`X#(DA?}?a$5hsi`u9R^3feWv>rF=tWnvJ zl$?A&5RnMb2II_-14<0IBgvf6OGE44Xed^#QX^>Bp-z3=ZM|9~%qjho*NBKP@E7PL zN+Srh`sdfRu*S|ze&oCEhAz)!ZsCeaEDL9MjBniarS}?6<=D2s(v7`MdWKXM?~j|Q z1GmF)vFjz`Zs*G8h0TBENnkJ-$d@thtDmxA9fySx-vs5x^La%@Ma0kTGZI(ptbt{1 zamez71{@^mFKZMO6i78k2kib0At9lQ7cp(n-A6qrhphehox<_*C^bu)ka5m%{O5w_ zPjpFQMGvr>e;(WBC@sJi_)k5-r>3pIysTC)=NiBA?y@cck{FtzcM+2R;!fi<{LjYD z?y&HiH*bKX^L26qv-evR!T&>_?bqt7n85Jx-p57n>P8XA0d?NYOVpv6a%ys3xJ1dy zY2Zmi*WHa1ntp8&^vLDMUTuQCXBZ{fY^fgo*vaED77J!XEVDB07~ z(cKH&1yT(UR7+Pdqhh$-HW+^;$8$&8b7w|}3lO@gXxCf=7-L0w%vsFqg5 zqa2zus8x;Xjy!V>E-o%g5f8U~{LiMQPAE&`QK<{~5LKZQEiprhddDCzLKuBU!o;*)qLiKQp%Y5gb0b?plCx!|37?KTjN{@Nz#`_tMcA ztM5|of3~qo6}~NM2pI*_6v4yROAl`^*S

    2g9rlxwckKC|$078?!Xo8?Y2E8r#%W@QuF(v~2z7fT z&+uwwqx2=)jjw(RMHn*DKB-kUSIWG9W9&Uce2>x89eWKK>#o-J!~$;pH?OL}=>XUp z?YBTP_DMOE;YEpFvPrVltg17RoT&0&u)2EM1DmXP!|vxjy_a35dx{FQSYF z?IRXZ86wXEgXj4hU(AU{MH%o5U~^X2^I^niJ$Lp+rgzm$cWd0HC>cj$9J#Z!=999% zi;+xiKS>hz^@nQUS@VniabD-)rnA-CFs*Ghf38tqnDr_1vi0uj*1jW`XljmMr*@7x zs6{S&;z0b)viPjKWsZNU_rcy;>}nMo+-r&#NWN24yhv|Th)BLZ5Kh_H+9qfL^nCr$ z%V(TKNR!lzbWbo>5+fyR-GQUL^qGA?A@Nzf&{rSav0p6H-czXs76&Jd?;DX3iHKm? zo`XXDS-vXJoG>QxeDjAyrPZq)%HF}AL%aDq|G0|lDktuU9eTU^=lJo% z2C`|);bMm>YVpLg*~as(-O-fzU9rZ<**$ZBYrGM+_6bMa{kSXQ(%&1tO^3=9b(}Li znQ^rfcZOOjt76dq(ad$iVAQl=R!Q{2&`5PlTE(}Zh084$RoAwSgyycn(oX(sTD$j; zHp1rovOb?7B6aMuC3$~u68~c~oSE~k@qMQ@75f5*(&A*JrgLtxvptA%;wRg0T*ro7 zwdZ~*a!?c(>-sKag6vUNwxWlYhb=%GqL@3#QsC` zjQgEyyN%cBYl4}^Gu2mdo#!@1s|pl%xFnq3cYhdAp3S;e8XTUGe^?7{Hu*nY^4Gf5 zi;soc2>P?s(b$Pne(^dLqoM~lyD3E10BDI4&h*$F1Z)`%&A_Zbf6P#Uj0aGOl}0nR zI^{cIrxQj0;5Dc66V6v%WFDl`m0-r#B!{`9L>(Lofqg)d9*D00ZnM|n_Xc=h-|TuG zknc`Shuq7*I+<*$uPEob%*R;Zi1rnO&rZi_9X(4b+A)H_K($|NYOr(30HJ3$DQ!{$CMjffGTFRo%BYs7jG5@?OTzC3{_BGB!L z0kFAwvG@-ZDOFno^8}F28AFo}8pZK*r8BHhyzn^r1BRML?ODkHnk*=cXMm>Y2G%V? zX$Y8r70bO_1JL%YfSryY{!9wuSccmEYvRTCtq>_*x&p5$4KDPVDLNZ0-X^r4MTRW zl#MS9-aPU;w&LA`!M6{Qt~pnGI-J;+JJSPJzDr8Y&5{dT4{99m%b)aroJI;X$mFPT zMyITzV$zm~Q7?D;jJlUVi3~vbj3kbrDzXPeVKm!YKq=&crEy!h16TBrNS@AJeZJTyW(!slt0e7YvK zIb7`RR7j3os{Z923;X->Dqv$VIXSsonJ4V0a94oBc1KhjWNQ8JWZ|tp99pik1z+5e z=YhED@K8!}GLwji4xFh2t`3^jKw`3_H_kek!cIVf3T^ilWi9I(@_mUT04^zNOfD*p={0Oz%XtdIrM21QxQ&eqxt2uQk+t`T%ysL6?%tOGkuPiL{U!Ya-k<&d-G;$T5@L4IWQ(T-}5cC!lkvI}8P1Qf?b&Tfy&^+l} z(8rId#l^+1>loE?xX5#@Y^YPUa*13B z*zx;va-nnspzGL+sn{Y7Ovqjq*~Jh1+NPtsLw4{6tBA^ps^@fr)Gi(sNtf=5&fg!+ zIV4weF5W4LFMiVbx$3$vzl~HJJ%dQcveW?P%!*R;C^kaqzMq04-&xM9H;2!TJqUh% z?`yz-ndjcr2Ei>k#jp_mNj99=xMxoP>(lh~+;mjdX8FX9hv~@ISAmJp0#|VybWTC& zv0|gia$hck0t&WWF5xSzC9xn!?0`z}s@PBRPZ|l`sX7`G^Z~E%8FSLjXTs-Ko)&h? zce8*sV|6cLE(vb^$>*Q=sE0Lby^3jr<|Uys$3ryYn;z{XV#PhW{`_oN-kfLe5;zJb=vMhr^DF2^n>yjRZ>jRZ+x~*F zjtluDY1D7?`V{^a?9y@}c2^jl@Y!6#*W@F5dU~io%*DZxVCgn`2{l=OgCHN;4fEUx z+x*TT9EX}X92^{!)YP5Q+Dm~yv%Yhi^~9q2#B7f-*f()?8#y?rpkfj}$8~r>p{4{S zWps8ao(aV;O$AJTH1FDmc1O)|=Sc*U^$bNG=WnaAP?c*~_al7^eLu4$O z9B&-{_Nv<@jE$D+=;)}+?>7vb0s?d^?M8K;6>$Th?q za$mi`B;@O@4yc_>F%PF~KvULn^2z{ zw`$&X{xd#mB&l8Zkz3VN_$VVU-2cYegAp|LAROwhFbA2d3#fpyLGE@BJpgOzRQ#zq zIAAa8dC!~A`KGsn&Fxa^m_aFzrSkKCOgsD9M9g<^k>z5cPu1_9y$hp_`Bo>Bf(GI4 z5O`{71>y{azF1sQ$|+4&{rpT_X0;$hs`|-SKHHsDcCp&7F}0`;8Q*(bl`j;?0V3n% zmQR^oXJ9DM{pKyWdgMkqsoU_OfkC+P{)J1-T^`?>rytl`YAl(wU8Kq~jxJRe{xM%& zD(Gz78kGNIn*XW$WjFZm`ZLu?7bD89ET%!F3LEBDAV)-z7ciA?H`pm#KxC%^dqTQq1&zXO1?QK!^sOP;(hmE zsCWwe>b?pwN?-VmMN2xxOFrT+cgKlV=yL)rh_2Hax)VCHyR!!!nrt0M!*7d(4W7^b zrHz}(M@;kE=O>X#h^bt!2=nDu9QP#@3W{*acS>zdL^P`9`ou?{C`_jT3QI1?{sNa`=C-dUtf6942b*EE%J;^K09Go2} z)h?F1=8#*<2mUi<3G0B)clffF-Ux92=OmnC27Cw3`dZSKt+(R1R>zU9tFzJ>fjOok zREj)J$|T=6W-IS}{0vL=>^Ms+%osJf6t~|J5QgHe$BSo@x(^$f%WeORqLFCiq`&QTt zqz?U9(!CC<(_YrL&1ZGUsIkME}rJK_i-N}ZgaM*Yq89qr+vYj0E};}4zax} zs;8cnA13Qm=A6iAS0~~5`NT9~L%?X)ex=Y#yRYf6@r3DV`>o0DQ;&?}Ag19WQV~ro zs&lW|ACr+goroOQ%;`a(0%X{Czff_i_7kXxVE3 zx5E!)!3s$KtNO~?^PnLpgPKHG{ra;}_FZb~#a6l#b#Ur^zY~p0B#vg@1V2|`c5vbP zPVMzIip!cK{=I#a1#j7}$e;O2nQ&vPl}RjR?&5b_t(P%FCDA;;CUV=iFur1N-&)AD z3&Sr+O+Wz-Q9)V$7`MF04tB0`%YsFxQWLm(Bm8F+Rrh|!GoO!Xf;l>_=2ASCqOyJo zlE}9f^I#{@Is6fx*>yYT{4aN^lwIjsjCrE-k59G@rf6%w&R%mV9HqK23xrHk!B2<{ zq6J<=W*$KG%s_8H#$(|Ht&x+{qiff$@k8EQ`9kXP0Q!t!bnd{_;Y4=YMWz8S;FiW4 zSDGCw6_IEXPKji~0gb&@fuRk#*`X>>@8#^J*Z5wT$;@wV6Bt}PMeX|Mv&;I3&q_g# zyKG8~N2wg|$YD%dl;dC;kg+rHY1S!$Keu*fhjz1`K7DEjWey(QrPO`~DUnSEO6@=S zkASFsUpKh(`$82C{gz%jbPCP6nSbUci#qlmq|Po4%T5xW{#e(!5-DiRwOtxqII3m! z%UyCP3bxI9nAN;KjVa~{G z_+W%IYsp>c)kazrj~w-T_s$5SKXj5S&$U=?Y{IF2bb^U?6X!!X=DBce69l~J=m)S| zrJ!6SfN36eYufsuifcO3wz(DhfLwxtnF@^jAqb}ca!G>23rrr(NE)VEwHcC}l0uIG z(ZI84I2JSGtFs*sU0^smBA@XI?=VR%ffX8@kHZOR_VDc2|o^x0f1MAm(XXy7u+ifeXyQo678}T^FRg*hIf5 z*!lE{0-bw7{oBFyS{^*eV2dkZs(5tnXJsj@N)s)m=T5gLQsQ?1{P}JdJWM^1lb!vn z<+sBe(D(2;CA|I^LDACbJV_5uKkuyQ}FBY$q?LMtfBx|RZo za8B`0UG@tIm?6(`dSy|$G4ZpHcQVozS;f@I=pM)>J6#8tY0wF*pmVR}P^Om?*|9^- z5+Ipdkg?tr@%Ag-R1jv@TnVN_0I#>ov&v&{ zYsj#7&^BgEGs>{TUV z&BwMqx<1p=I-7xssRcb+jsr>9FSwA&Jfn%C-bwu>{Ae;_6Q{gb601O}8xnZYge^%K)q`e2RGQG|*ydbZX$ADVO| zw(8b$j6&ddXT46Oi$Qqtge;iaa(BW~T^Izp&l2SdEE@FAe5m>HJAOsW5Nj(e&33Rogx10E6i2qI|-vKRtdQ1*@?g}c6kO~<#DInoV z;WfS^cTQXC+1V*oZI839K=4Eq!6u}Y*a(YKjJ)9DOQf=gYyp2~X&^i*suM}WAS~3~U6`ft10f#>GQh3;N z-f_{+6BO>d%Q4;P`CD6CshZ=_;UkocHV4-#Qy>wkLwat9vkV4EWgkk13i#5kxib6V z>VMF2i0m1BVvt-LoUr`RxD2V1?$fHQbF=#`<(tb|1kRXn+Oe8;$=T1PJCU{pl{4qd z#_1y*uNw@X%d_-B!eS#yVwN7~THX?bDObd0CVINU@ zZZ9Ian;i&&O%Rm?qjmF;jv*g+uhg)4JVY|Sg@s(yKWvv1U|Iew2nQ1QN8fQ^ zp}gN2+S`dip#U$xN06t-><8>`Bs^1r(ySlO9l3jn+YE=KY$);v63{xrg;r9}b#c&O zBZLL#Rg)m}1Wj*T0Fq{JZErUQ=?c+ibeXe_$!KkTs0Anc7M*vOMfPlw>%p<KAz>I!Xh4!O<+f^MDVl=*5&mm- zOAA;P{s2ON5%in**N0!2TEu|U!KyGLS`Chz0QbbT<_w;_&r5>H4?)9Da|G6+-B;BR z&`46SXI+KOD`gntUZ@S(*#wfbdWDO9=l{dlTZTpXeo>K32JaaMCUB>tG0;pzLGR2iE)A$l?0v<(GJGP+5pjTYo<~XSC*Yckfh!>I!M8w= z*1)-J=kG7-)sM!dX%Ny{?`hpX05kn;T+m7mt}7R$ZfM^@z}_+ltl+O>?uFVLuWb)> zOof(o_;*qepTn6rc(DXKiS3;x{)QQv&To#vEXK_348uG+ z*YK@`<_;QkgJ*|iym1>4n49pSHL6A6%>JFS59%@*$WfXCCra!pWEvsM-8Xz?^_S@L z{3FBc13NK>tR^6d-_!YjqrEqtkLgqIUA^ydj`-0EAu$XvKT4VTgy6=r>+CmqK z%jOJ9*f8r%0WE!uaAdA;XN<1e=o6Is8Pyl8f!Ar`{Y#BJbI_B@VmZ-`-+VLVL<81;tz+3`ANsMheXsHVNNJo0-t`Lrw&aMQl5( zF{SD65tB+rl7P*VUepmXT$Ai9p?c)k$^JwH?yKIe3bH%faiabchQC%frAN_ZkhQXm zBnzKX4j<3+I9@aw57;dA0c2Q8^1|^WrS6a?5JxwaaI#ESyle0ET7(;gmp>k9Ik4s5 zHWo=*rrpLc>V&)6|BX8z>v9lz%F|ZPa1cetpaxAwH72av-;#U*= z$7^P8@T?KDRdGwru6Ik!Mu5OvrTL%O&?dK$e@ZhW)Dx7lH^`WYWIm}0NECVh*0s3H zS)(*$H{B}Wd8s9MbGH(3^DbVMsyyi(Eh4n7vCp_AI!XA!?@rUB5<26!6J${zgzw}k z)8uB~JFLl!@?u;|wSV&dzHJ2v^5aX6UEj~yD`0{C_pipvp-4Ma-u9&SmX?{rzJcx1 zS>FxujpiqB2}-fj8k<3lvE#GO2R2ue5UxOP%SgWzPr`n=l(gW*pMLeu-WP^uqUkoz z7%Q648`D%C!MDP~%d|Jv!d>YmHV7Ifhr+#IV;>%gWnsoCz{{Gwj(RdHR+2!V2??aJt{|`fGOR{2{>Z` zJ)7AKMgpc+o^)~wVEu?t^VaPWprGOy7Qip{<@raoV9bOUXmD8tDS8B#>A*>sg~7E& z_JK>9=5QTxxwAGPN#mfwE;x7o01!eq`z=rcwBn2dGJ9dh0hN)NSy1O6c)N~o)FAWy zx(Li*X5g5p$#Gz6e3FZ>Veb?+#kC(}VtXfUQ6l&Ws$2f5H28Jy0`Qce?vxMU+Mk&8 zQ>&R1oFsS*ET=PVP4?*k*csrC&x7WJCg)8cORQ*?^n3qVy6U6J5wiZHCu@UdXiL;< zj3LE^ERyq~~Mc`YqOLT7^K6=QzLX-neNQ!z~;QX!?oIJ%AHZeVTVtMc2!};RYVq z15}3NPB_lL;)f1Mn+1$*4X{Sk?kVU`8&!}z)(pbw`~ZD{)ZWqAS#8}zNf&(h%OAL$ z^W&R$b8+WuHIPu0hH&tg#-&jcr!((W#y4H~?Y+j0^Knf|IPQTvDOM6JBT>POU<+}= zD9Lw->9+~>!=K&EHm-Wq`iWupor(S3IGbegcHl)CP`~BKI{|=wzsNG}1?~ZII`I2G zz_BT68k%9iZ26q#!J8eWYW{~G^z$1104R)@cwulR{~&-khCx$(b@}4-bc2Std+Hx;3}8Z?u*?b>F2I$qPvAD$!>E8q4BZR&f+$W4ccJ!rqZZ)ugCr?1iJ* z7Y(S^H;f`CavvO@dr?oihqU8 z1wg#q=`Bb71ZC1u&}3_X<8$C;1H4gvQC`5&qa`Qd$ZUWrfOJ#4RD-MU0JMoy1aK}H z99YD4jz*a5W*t5QWJ7ej>ya1e9B}wElq>otC+2r}GAEArhMWiEWP;qL>9^Eyhb#S2cv>>a00)J?>8FH0qL7|xREU7 z=GQ2IsAZNxJT(2qdo@giMykxMlfx97HCRj&AgJ}g!wno|;jajjiB-j_aDojmw1G0x zMOlqGo%%0pny*Z>C-8ueHKD^PIB?pA@Yy+lA_&hvTDT(duty+JYsPSRxM@4KYy?DF z03En7|2_wkY}_ykT>SwcXCUVYV;5K@2MhDl;Pj_IZ;Jl@@Ca8m#u0fC=#WC4@F-lO zq*@Tc9as@A$xaZAxN6D@@PiNH3IrRoO=8YY z-k>vCB^>Vf4CJA;=99m}xcvzyOaeupKRC}MpdOjBBqBMBSg=+r2$PqG#4OtwbQZk} zci$vW<+>#|(y|h>k|`FwL99t9Wuv)U4)zWMkwKRAKfr!h06F_~9&)mQT;ni3Qg+5j z0wfCDh0S2OR;XGI!*E?MxL5_-Slt=DHHi+^l|0*u5&&ri7xn6A3+gx%AW-!ro6+>x zL3+@4g6(NJjo9D71wZACSbp zJUjh$XYI2r$sq1fz>R7FZnj~=*=e&1oYV(A1_*w*&LP~^!u4`rWKD26 zx;YoX(#!lui*|iN4t#J)&kKl#9bm=}{donBj$bfGT&n?CIPg)}U-W0@PjGh20Yz>- z?p|hec+5inZiH`hc&&Pq^Rw9deY#IGB>Xc|&GUCHFmeDIGz#CD4lxx5mAb@hH$Bau z&p}l#DJ^YmxAzk?FTdwJeef-q5j5?AE}3lQLQVrVQ(r*TFzbi2z2f>r^imhB!O{aA z5@<=0^NJUpogY6E;L5fJRnWc^3}7Z4_BhNQDg65uu9>bWW^#G&6%L>NXIq3@XZ#RN=lIMz#&KR)3iZo!?L@Lv(kQNbx4K595*Pk3h z?KrnA{pay)0Mm>9ZxaBXjJeZg(4}gXlcQCbGt~9rxiT|Q#0qrS?P_(j?0kjmOE6+n zDmW-mLp(ALc#J*nJzjO|}rs>_qPQNm_FYSB~^7z!#LW*Vdu->|BZ2Ib|Mz6hrVYq{A38Ne$f@jJYI&4v(%SNo8%sxdyy1JJz~DLUNripmM1p(lbzK2d!sAO zd0g}qpbnQ|dWjF~x~Jac&AR@9rbo!vpXs;^B5$pSEiW9T z{3{&;o}ENHCO^+*1}k;*qCC~rX9OWYolxsz3YZu79y{aNA{lk?Yj~3jXO`gIh=bu~ ziTf+t0pPB7uU%NV7T~e+RSR#7`O;-vd@$ACk_xQp`SIirKdk96U%l~mW~q$LTJ|BObAKSv(aVbJMcy+Xn@ zyueX1;CxwZt6yL=LP~}?ComMwysfi~(kWqkor<0EJTbU_Bav>TdWZ#<4mQ;Q$3dQw0rgq=FKv4S=TvX}Y zV@}EWWibI529njKBrZXdm^Lf;U*f5305yZ<&2W)C%|tb_eomEZadmR{Tk&VziScy? zIw1|KJc&$X?$DFFAYAA#m>+}CJ|i{J3>*A8gde58O?3qVSRr1k8N&s)bRME?8EiOq z(^af=XF~->&z&}4mZnTSN!s*nm<@R;H!dI$-No|^2);!WjJfQX94`t}Z`I@=S7|~m z%Q~;iA>J18>}c7>kBjUX@VfV3!INtFe~4F8Kj#yFL%3vE`hiD6nTf_okU;v7kg2@Q z=B81^D2^7Rmm85g27j5CY{U`@jJQJqjKZ^}Vs`}pyz;X@=#4RPh=6PkZ^>&Su!$;F zCn{m8&(_yo!b5FR#tF59z6v#9L501Q;UVsMS{rX4JKhX1cO#9W$6A(ZSbPp1>#I|I zC-?!;5cFUf9J$1d7jf3BQU(b@$Tm<>2DnXlyJymD#OvWJW|u<;g2!gIc108ljEHnR z!6zgCqOd zha8rj3W)>DSQ82YGnZP=VGG^?f>@r0;h}qHWX25Di2-K_S7C5FEoTm8EH468r8RwAROC% zPp?E2mZKb!b;iJgXI-o!*zNeilNZFY1CKt8`?HJD{SCd;Wacg}UJAcE+ zEIOP+-mZt&+8UDY3&ie;Q`Eh|ZAYnt|Ak)PJH|G-Wy&&rCiFYAqIT!4cyBDfhuWSD z{9k>gK|%Mi3Z zeD~JFK7;5cj>~l31b>HjBg(iA&r=1|z~84fK8VnoxvTomUHYtCH-MaPsZ{flnCDZyfj7#HzHfYFm0Kz?|#mt;{N8Rqj%~1N9@X< z0R@!0%o6RKW_Q{dEyer{v&w=?<6K#yl(EeO4-7mXOY9?2x1;^`;gup%Ay-fUG%r`$$<>rzxVrSoVdu6wF&^Kt#mZ~gv zeF2bQ`tX@wjXX8Ee&i&v#ZCV&Gk;w*Wc9(qCSP1wL(hFom8Y#;Z;-fmt->uH;gs44 zOJkC6>#G&(e0%&YqmP|BCy~={WpAK{uC3~*X_T$lJPvFaw#yB(D?k|%ki4ways4}Z zsT_SOwQYpbCZ7%^Y^ZU`yIPW({&Uka)(}}#vp%28YvGJ_58i%8GAznfb^-#zlaLR$ zp9he~)(i&>MBfSo4A%DtyPXIZzn*)(o$)R-UdPMT=IWl_IwQCm{^3Xp{BptN#*_MW z6cGHNT0Vw6Zs$JPh$lzwADzz@V9^LPPfM_3lJ7~u?#F{&F3@eS2Kk}Dr`Z_?_|l7W zvlQBdl3I2!7Wp<9cgyNr>6GMLUW~Ld_t|>2g~ml=m7?rLG8NfdWrR<6HG5UDZA7pLp`#4*0 z6H@7X5pn&;&YP&yLrWp$m~8iMkxy%osqFjSuETvtf(hxt&NNWy^}7!|Ng#0`B=j!M zW4xe#lj8M7d{;eZBXdilYb~qi-m$ma)Xs@mvUn=v%YdwgCw19(cbsN-b7bx9+FL0t z#*{BiekPC;KJ~$K*)TWPNAf#PSMjT(6fzTP%=Jt4v?W+Hf7j{Txo>90-AXsJg}wyR6&8 z8lwiEg>*#`IBma7$hXM%TAFs71L@zh3IAc>Zsj5@z;zEYYxS zBlTbrgd0b;J-O&(u3>U~{z&$ZkrH!x-6X8dKjKXbR}=GtZ{a0b>lN>IZy~iREF-IU zBi-jObxF6tiwvfuKA9X%DzliczXC*x=AyeNmMPvmD_k~caNpPBWF+voAZ~L1CztO!l&gK2kNeuLgunVi0&eK?d zrI?NlgVt_KDNnHk_7993WUD)iDl|Sy4RQIi4-R8Pgy4v+o{&nOOtq%fBt&;IymRhe zmq!!4JJkwbo#WW9Vv<&+A(&)li!Eg(-(!rup}VVh?^mNvMA7`%P6J492&#+cC@4xb zSJRw~h?h^se`621(o;W|t2>#~S3@8pnWk?!aee>^2+-QzM|2);FRIV7xQs*nXz1)5 z{6abxl=uY~FgT+oh z)AdPieRd~RTkSG@gG#leqcnn-t2cx!yT21;EAab2JMl|4zp01{S`XW|hm|TB`0fb- z$Dj}IAxezAyIp70bM*+U(&bUB$>~oaD?}-Y`4L0){>iTn4e$s#um)ZUK|-hE)dbPD z4|J~*#%$e4c|}BR1k|w0FIq|_U*)CgVv3lpZ~M@SK)7ZdSu~PeG)8*H?In92eLyZJ z`x(}o4*rhx2?431)$9T;f#O#0@0KGm4Tg}J(d`)B=Cp!L99lAAZUL3> z@^9A#?zdA*7W9@pO&K^o3#Ewrv`jX}-$T;8l+E5%2@Z_zmvO10)xxi0zb-Imv($Dv=GU8=fPKAXtsEDO{4H5QHt&A^OG`j=K$vhjYj5^bfsc z5*7|p1EQj*Dcj+ciQSb)y-vTecfdz&T(tAN(%Elk8Q@sI&-tq(b?ZReF#70Ers~SV zGJT z=ZsSSh$O7wd5&J9`Y{^9#dAw`Ea-@kd_)IxNOLYdTceT-Yp`FQ^i3mw=LUgsc_!KB z3f}SPulZxXG@7Ht_r)G z(gj^BH_yh#+H0OiUr}$`sG;8Vl2ME8n}BV58&jW4-k+*Xqkbp2^mImx`}0%j7fn+6 zhSHJrI{mrE#+J@8#obvIg;P{aufv~#XCNlTk*QZ#Y`Bjxm7G)A4ZSkn+2i?i5i{Ne zmN$cD;v6HOXB*wIf`7w{9CLPGbu8SlLynfzB$l^FyKy(C+a1N)wItV;aj7s^qIdt0 zqalz0KFNYoxY7d$Hq@8j@B;qEo0+%5bs#{YJ0AXDT+Uc?AKxU4u4+E^uHuQZ=&tm& zeOGMLRMt}M)@Au#N**5Qy4dk6luqY*44LK{*D$qOb>?dV+Z3K-9|K{_n|I93@C6K~ zR~*{)25JNJ;o{2^haij9h>?yZ>}ZXy_SSRF#`{A1YWi-7 zFwM1+io%r+_m`iEt=IQ$>?j0SMhNIoN^9wPY@ct@Ns^c^B}qP#&wMv?w>RF@xXv?xATgGGZVk<>ucO?vzB}M0tHplm`g8iT6Rh$-y6Jxx>SY z=jfF-V0Hl|EboAj*D@Dlb_eCDyaE6dvn6VPP!mNalr7}Xdo-odvXYRk??bgxGY@oa z=WqVW3~egO;d~e-p`s8Dox8sMdzmm0?rQ<;#PHdajP8-#3G4vnH0io>8?8#_l`(y=Kyvk|u8R@B0a}q_e{~(fZm{bKb^* z`p2-dBU=H_#5JD;x&ncz;HL3=08B@mH}2`eK7G|;2mX-zgNlVYU%uSMc?#o|*>B%b zKzaozfN<4toH^DJJ=PX0%ltWuSuhRGY~;uzKWsKCix!=@61qA5PB5(qo)n4bj%FH< zcmUpjGd=7Zd2(U-N5c#r{+F(VFg<$6pt3If%_CG1jiQp~%lQ(v&6)HUit$DNu~cg|z#XR^-oG``dy-Fg zD??!849hp}@O@JfydHv!li~Bo;cyQK7uHXG%4G@Bs-uc8?M$HtUm?D+W46}bMErb3 zEGkx{VWQeY3Rx$t%fEd~joU0Cm;&A%d1O>Kw(IM3l7h_G#S|_XQbABTvdOVi!Zb*@K?KReW*krZlh;o7%lu0(j1y`BX zD(RASO3Rfdb#vd?z@cKLtVi)mLz`NE=?NBkQXME?g#WA@gr5hn0?+mlhYw0jYv^TQ z1frVOGdGlbubo=2^mL11CoLCWQogiO=?1Si1)~!a4H1iIz>8jwQKG)}NgOepxtQa} z(;B@)5&i}r{daAo@!j+rk@47ejp#?qODfDI5tt7@+9EbpOq4@E-*R#+c_+AU=>)48 zwLjFVzRmH$O_G=5d=A^CV?poy)nhZS`&ws~WmH;|yQz|z9x4HzfZ)kbTL@BnrTv|q z<^+oh#cNcsj`98*{tDMCLXMAvajkeN?*u|0eHImBYod!lX3B`rWXpZWu>G+b-gb;n zc_f5FUWE-LhF_xynV0Osco!nv^vG?m$GUdjS)!V{zTZnbI;X2*4%<{pTbQP$%Ma1h zfz2B;9F=|c4A^xs*2MC#?k*&cx$S6_F&kujZ4>dhMbWK!RL$X1^#LNdkAB`{e|IT3 zx5xc2SdklvJFVD*FkDqe#8v7h6v_`uHGlrtsiAvqq5k!!=l3OQZKC?Y*eB;rZVg4; zuytIY&V?agjgM$a-q2`W$Lr>h7rY&%Z+hgDhPI@{YO6(dk1ywN8?$XLENT+*kmV)# z2`(zri0OQMo7$sLBxs{oIuXs)$%JaiI&MY{u>502#V?@t*sGixiE>=guu7UwehQJg z=;(^}cto6|Unrk`7$F6lExf%$ygzuO_gpQaI_oF4&})B_wjU^i_n7{#1~A=19iRwo zY=}f!2nhIYY_BYfLJ`t>Cf}YO z>`rVRMdd``krpXFZ7D12V6oQZ)aYyimU!*6t%8k6s8$!3FjyroLh5R^#&RW?d) zMXT(GKDd0+eZf87?FAJ#YuK{?qPJ!8Z_M(4Hx@rDXptVf)0I`CMT*7=`)q6KpYu}a zm0DGIa%^+byt3y2wkzcSWIntFE*1Ib1{9Hx6ac`3%n`|$YUSE9dl`an=9`_SF%9lJ zU^iFW4H4T_YzXOl_SI*=BfFEuX4z9YgJJj#YL2eF68;_GqtgEd9FhrlE<|9wuw@q~ z^fVFQqaP&qeh+l?A}W}!-5YjRO%g*?Y$j7m37dPhT5M`hVK+8%3#W8>4zN{89G|wj zLn_PP3h=3@kd0!5&^A-WxV6ECw*m_go>XStd~6xiDm5UQl4l|l#>!n<`K9}pf{2`= zZaF`plQ>e4f9vfrM7Z!FjP5tTro?>RAM_l&MyK)9O+p{VU%rd2>thZ&lNoHi>qu{W z6dowsT#BgxfE+9+xI8VRFEg))Vmw9M0hs}J9s0CXFHJ<7`}EeZHVxU7qGrOv%~(NO zkG}y&bxF6mqDN)-YYYVRK7Y-(t%)*)So5unA7;?EjLdkL8Du67yekK{z3}nk=A+>! zTX&8v%(yE}TfEUaE4gNDle)#ZW|_28im`rz-iOf(U3M?+=5K0|3JdT#Xu;IvPiEx= z)GGIqin`yb<*H?OTKSW3$k{EWK%2^fB=wvjv3(3J>bXto2i<53llr5EZgJ%Ibr3-V z4=&{>`f|xdI`mb$>@(m*lO{)wO zum;+|(yX3Xj#6)_n@;|6k{A7W(OeRjTDFJ)OeXR9sK~yPcNaNZ!R*r5KDv?s*HN}r z=JIC0pVw(1r@s*mN$NV* zZBIJnBDvhByCJY+ViUZ%u-DK@7vD~Ykimg7%}YO8hVWDqo;5O>zz1*lC#C?~TVSoDiPcK95{hPNI!%S?+LW)1Dk}J@}o`5z3WU-{HX=5=ofm`y`TP z2r}nM%d9Vdw*!{*Wo}_3!u6gJ$ z6){U&=3z;HyNQ~hrbLDxX&15zXN!mtQM0ylT;T)5ZK!+U}zWf-l{7Ga0LYa`vN7F zuj^sTggaF)cd@`t);fJj=AT0EehriNj21I#=yExqD_!MTDkhz*RlyOla--YPw}jWt zx~@O;wj~oCJ@;w(a?hJsCN^=W8tZ& z=F{%|;i-flJI=*U`F(>*HQIcge0sTRqrpi|0+avs1#?B0scfGMpiKwv^A&W7HgM`Q zldH;=xeS`lGj0N&wQ^Y^!MpL?oh2OWQ%PaK0&slvo1W)I>{`8oF|h(#UMH1S6cGf< zz4H=&K)_xkA!|nbh()%?`dA`Tt-K=5+vBVfMhb!qD(RAzb>B-sFi1>CHBVLE1Jhs# z5h4d}=A_WU%isx5MTC>*Z{ z-UzcPIY>Zn3Y6**nDjb%8@V#4ITOl zob0zowVvbtdL`79W0<7`cmz8_wZLNUT+}!5b}Pi8Qo9j|)%(Nl9FtQ$>5W|V-)iH5 z#QT>H;yPKtgmP<2%J>d#c6rZl{!w$w6LaUEEqk6+s$t)HogX!>2rsR)6PT8l-Kx&hqxxk`e@^IrZqrA z;clANr4lk@PMOxoRl=2*dDu&Q>(TUJQ_$n90g*6P_1ACU_aA4r`)Gym3N4?*@OYG>hn^BWC!I`z_drOXA>XY5TD@F5eY=_=@q zPFkmP3lyFGrTg{gAxza|Nb<>)hxgT%Ku60#!QL}udz#C9cZrx-S0g2CiBLd{FyE#QUzpGoQpg+0jv7%*-|a+ z`9tL<%#wXToOc6VjVA7k*k1+Xum@NoVQr-tVwv#$Lhq{d8QLMIrM!tNuk;V^P>fwC zbc;aj(q_IZ%=p3t0NixrlWJ;afx~~-zcHtT*IMkMFzhtc zGzM+HG&fN)(tB`QY}bx_2toa3l0x0iX>h5^iGf2~p6qWyV}8;B_wbVv%tK(dUZF?e zI;ZbxK<~0Au+6qVOR{9oZRD!n@auK>q*!@7o>e`wUAXHDlUk&*rM6p7i7=vT;!P2I z21p)LH81-67DI{zPkCaWHZutkGk1POTD}L*kJ`5hH~f@H3iqdvIWMd4D(r`eZE!;p>`` zm@({&G%*UNN5$7=G^>?!;T-@`S~-^Lk+`2ujoFwRg+&`1oFGmf)w~d4RH!>u)W4KhrR>? z4h*1Bv1>;VE>!PuVmQ6hRxti+GI~=jJ_;^6d1RGD$I7*Tpj#2`I9(%ScGk-Gl3ntS^ z&~;8Tq!NLSIXEf7n$dJk^|Hh5E zX1p>RVcPD+8&f-G;LLR%r7VDl85;CdLFLRL{%iavA~epAM7}|%V_K>MOFJDllZj2& zy}kCPvL>e_dZ4A0q4$VcNNdW%r2SmL4Q$Bb%FeBLe4{*mdhO+(^^M-vWV|fHH=KdP zz|iJRH00M8_J7%0Ul*kA>2LIQ1e+ArSG4S>JUMuzU1$z;?FkCWO!in|7FrZXt>WMJ zscHhm9^EH;+Q0Z7@OyD3jTf01@)vqQ1m98ylDvV2+)2_G)G-9^lEw?HNnEh-M%$$K zw{Kh`yOa>KEUaL05-h*o>WmQCctkYptK2u8Xr?0RQ-)*rMWOZbF}7NeXI?8;!VEcv z_8%QJK{@=QN1uA&TX@qnaCQ#=)fa3;?%g@@dFUh#5*G5}B6#cYt)X~! znQGr^%)AV86U#eDsCpG?>zpA!RHrP5o2ifwh`!bDI2a@f#Y{)_Vs63H8~(0m0AP18 zAu7^y<89xZ0apG4u<2~KUbxJz#9BAszzEV?a{Kws-^oT$F^=qcr6 zcJ;^ag(GRhUYBJA2IRUkWBrC|?B+USSVI`U^8ID=lzm(>^nEY)>(89~`W*I2g^h(G z>IA6p9E6`xjW@bdTA)ERH@-c>zlG@S$K%dHl}>PJf1-;L(6!>(z&mE7Ieis{RQGbY zPBC+Q(kcekio7rXeOq1j?6ww2Gc>OI-BpNT@0~?kWmrzp3i_`HVsaKy&OULFY%CJ( zrBe0Y->3l^)0a!fB`C&x)G&Zh@)+~+X#oN8^RnQ;^V$B*8>cm-s~QMvmi?EjS*t~Hb@E{Hm*UztcqfZtf&k5DM7OvLhtq@>lGQXa<(<=DFE*#2 z&SuclpCtk--b6h$v2JNr3Sw@B=`wkZm8e@}`w(~U-30=ssgKubNP|Q?f%p2p?Ve2X z(T(dUcAA}2K`~)C0r*~&wmy>l)q6uV7_ObksD-)$pXQB|+ZM5E`H3|aOGVmKd$U%N zuP4El${4;tb2p6gB|pMu&8M#JePdl(tH5OWoln({#*LU2U>9tiPreq{6x#Vg!^ly1 zvh#yZg*#@`+ZAeuv1a-5`m$6WoIubSjq-p;p`LAe;B%tF^PeBY+^FjAxXzkNOd~pD zG2AG*h;8U`1lT2m=HiNYIm!-1BQ6kqRE@2hymDP?0+@rq&=x8Pk?t;C+>+ebJRz&T zqF%LQNgehmGQ~Hf*IPEMuw+EsPgA4n2dsJN?$n6GFWvD8osIebGSzg!HT|!kGju13 zyB&FV&c5FSGcBYfFW$~QGjE#YVAE;Yopnlu{k=gXMBk;E=eU8^YJ%tt_3x1gy2Cji zI@d|#V=qIaZh}=#T@ZZ3ws0$Tbu;&=c}(Fmr6SI)7zz=;Dj9|V$+dScA|K)Ry?+de z)x6Da+w1q>J9~1l0tS>S2BMTN-EW?Hd_>03*J(d0+IZN?Jjk7m?ww=kd=?A->kuY; z9ay*B!7<8-TD|R4EO_gq&Ci^aPOIc9f7O@sOxtv13kgn%uR6}eMtvEoEjvCGPJhWM zS=6qj1-MI~taQL?6AD25ikDH4ji-XYyGum>assOX*TO*6wAETy#-S4kRTld(S0tm^g$Yc)RzYrxtdRfg>9Mn!N=BE=wFR`UghF0^jFDnIDNpQ zsL1BG2cNDn6tiiPMTh3T!VIyXga9p?Gj%gYAYx^$1(WMh^EI0T`roVx0%kj zHI<_0{WVc)8g>i5%nLV5IyYziu+O;o#NTLC!Qz9^CLFl-zByit$p)$ZPi`B%ze z{7(chOL@!zv!AA`rC#85LM=>|k}i*STA1a;DF4!29wSo}539o{Y`MQhhP5iAKAia< zgrYU{MV(sG+T%d%6FW@3Fa1VKRj8l<-+Ste?i;X)ow`b1kC}pQ@Ur|aw*y`sx9hc_ z-d-buKonQmM)FS<6+?cQno>-*o0QqoxT2=*JSxI4do`&3mvP7ElORjkVVwJxu^YwuL~TO)IX8)wS571%|W87l)BJIOlDI=s0OZOEK&-pe+h!y%%ezm7? z4RU3A;FkIdGzwTxs{A(f52 zz1_a4gpu!40T&+i&`c%I`t^BUKh6iNrkE>xpXbAaG!6{OY zgz3K>T|kpd7Y8l1uD+>*i?1uEKR+lunw4X4a?39JSg@F2eDu4fupJC(d#>pPqtj)6 z%W?7)h?QGGy=S7C?8^p8Rb0k#-HFoh$_m5RN*g6FK*YD6URGDx0!ThIx!N>yFN!^~ zda|Eok^h!a3f^1sbiF(F(8en3Kc=o7_}lABuN!ThRW$4dDV(Ptt3~S0lqFJ{M5as| zCM05e4c$#(Yf9VVbuSi$CHx3el{LsjV+S6W1}9FFqmfTf3@L8ph6=h7H4ra<)fasG z7=2%GBOw<=q!cb!y}F{iNj7H3H6mKa&G{;mZGFu4OzvLTN5deyX>HQuSO!MoT=$iq zby~Jz4eHX^Y(47A$CW2npnX!+S!j1 zUpUrsyVLn=)dqPOjnDJWwLDsv)O}n1#GQLUSmtC01D+i(9k0y>J{#XL2<#OelX zeS;r&29$t`>Ryxj-}xNpf*6@}?ly4Qrrv!w7+-kk8gwLG_eMTe*UWnqc9aHeiXxcQ z$yfns@QbDJWVbSw;*SSni*tSnYraN8UpY+8Kim4{u^}orqSnV5InUi>Ms=rNI<55X z2o0|m(?JB~9X1q+5XX>QT>ic+)~iN)kWRgpmnYXO(4anGk2N*qFqbm=W5F(QRoxxC z!cl;@x--r8{Y&>K@Ajh0>3g=%6E&sBb)2X=A(n*%m#&{ZF6tUzZYkTdJO4K8fyv(U zkYv??tnn+nPX-tqMa-DWQ{U`J%9!*QX$(JV+A#*X3Wrk*Bc@TBdhA&Rc0^L=Y%!LXs8t zPrj%kp@ch3iq&QMP4%$0 zGIYh4EVCYu+}5bS^WA!f$HtI{Q6QfVia+2WcTcH>8IRR~7;FZmlK|$O+U?O&v+rp; zmMu_kYrE~bjguWQ;ICZ>YX!Qn8D6!h>FYS_d*mQow!NK7&(hlKuPE?--?D~`Uyrq? zL|0D**DZ=XF=z8LG5Q!|@2EU$nctN>J#rYV#&eR$>f)|_>M|aK)2IxZ|LhZ>+!h?g zn2(P)atDK$M1;zUrhVLXW?iyRt}Bo{u00SGIf!Jhb<}CwNdEn=qZ)echtm)(tH(VG zJzdp>fCs$+%$xB?Ps?Jfnk6tk7YD$2Z>V@<2Utq=|G#4f8k$<99?rP;aN(MYFJ`P+ zSs;VWD+p|RC%wblVPZustod*_D2W64I_w>RjH)fEXtd1QQ)%l5Fuy>ahkkkNR?|fU zbny1r)(HAJ1WMD+5&q+*5R^W?FoEE7B_Nog&V)^%!0Kr%FX|*ogB9pxexBzI!Bp7u zt4aXS1RqMXp^M0OM#R&b4qG0bk9l-Offn#>pZFu!Yb_jC@LB`^zq@jPH~H19mEKDE z=dj?tb4)|P1BJ2mXFu~NJS=53oQsJ+$X;$IGusELc%FPETK)c-&UX0jKG7{@ zTHygTVn>E+#ZHIUh<9IQ)Dk;>VH-l|J_=mRhdmvoU8g#p`9X zNB=6u^Z~JxNeo<1w<3JeLvF-+_?TlXQ?4%jgA-eof9bfi{r#=NDaY(5H4mS=c-WMZ zk1gmz_Xl)~WqVDf22{bE4mfe_x$IGoV))8f7V$v2~~o5`b7fh$4qR>ipn z$|G&ks=&w(`FZ{!&6B5_J~Ki6;n#jV@T+~wV%HL9y&fu1MBYf=!&0n| zt|(j`g+kTpjqY1}1dEnzB4PE;Q~9HNHMghySzbWO1Tl_q&+ZTBX9{W#)scyEel*4W zCrdBy=}8EUK8OrJdO7#-;=OwOAI>Y($Osun$R>|d?h8rx&btrWb1>Fikz2oUt!Iui znLSD!Qfv~bnhF==q>fO#6|;0$tecE6fq(?KULD90Va=DG$92a!oN-n1a4m29 zam|5sa}z&zK|ust$W}wa`TF~pXYmug{eK8uhR*4ljMXulGC&bNW&%wQKP`&Xmwvj^ z*UKaay0wHy5+*J~iqpm+!ch$m<;GLKZa=lyyC+sLzK?GGt9r#73XI zvsRED&K}O@{U%8#w+fy_nimvY^=t7gBkn`NDum3{YCNELb$M)iATOMK?5&+e6?)Wr zuBUQVcg!kQSQBzr{w`$3(ZNH~CUXov<@{&{U07}4F=uly{^Vau6^h z%f3$Auj-Tah&7$pm%h5k;V(yv-Z~9=KMA;I{WbXnS~mK!4%<|0AyoWv>A-%}$XQ?E z`)d*DyLWre58^e?C-2fjE&TW zNCc<@?r(wn;vu~+GHHRY|69rlJioWs$z5@J#{DSxRA0{V+ef{i0?Ye7P3)gPIPt`& zJXEt;RMmIB`pKFzxjVK}jE6mICFP^X?Vde7v0~I_@~%hq8GDxPn>@$!VW*zunXf$? zsww0tw3Z ziRDpklhIxIk)DY}503(7135WJ2Nc?0?Pw5Na_}hqam<_K4-?ZiN9Q^0S!x2Bb+EE- z#s*_Lu94Lb1!wc)V|wG6VgpHPaT7}?}J`KkD4e3EGS5JJ{O|lS)A==Z$sb_QA$iL=c60s!{2+-vJ6M|w2|wRc zKPL}4&JPjYJ!@wJEvGHvlIJ^;^!^|LL(1?4kNi*)XgxF9C#k9Yly)D20#DFlZE7Hu zp+1{tPeS}Vm|calmeo@IiRtT{+DdW1|Faes6q3OoA*W8m1`ZO-c^jkm1;l6^p;cc) zwB(LzB~S8H?6Yh9XKyo>PX1Ri^PrTYSSh5(MOLe{*?}KXL9o)dpJ21idqiY{6&hL-J-4vjtxc^q%DrMV)_jYC3+_@m= z%J!$3rM=}^&uMudWcQJ~qwHDm@DK1+VsUSso)4SwJgq<9e)W{Xy~334XpO1{%xz1t zr^f63PN5j_{6Eco`8$-|AMlNbC$glNq{TN+DO)IOwhEO!4cXTT$u>1v2E(+7P%2qM zq^x7lGImpvvS%C3$QrU|Z%la4ee1oh_fL4wPjk(jIrllAeLJ691vMxYU;V!A_5q)- z18ctrN_FWE6np1`8=FK<4ataQ1UxyZkw9jHxIujS=UuogKRI`!*plDwQ~gk>foczG zuFTghEd86DczX6$uSD~Z{N2m^-=|u0@&N&>lAo=e@s5lmtLv9|-1g>jGrF>wr5Ulb zzkWsoS4Jx}m3$ZEw$HAY?%;L+Y_xukkis+e)r*g$a1!d=k2EE{m>0C&Z#q=7?b&0Z z)T^YMyW!%^(RQ~|W^Oy@O~fcQ_hfKw#F7YEP%KOWXXF{{d-9hq(^9**drd0zbnUgC zc2js(OnbIY`o|ZSz`A++2c}{|hi$InB+OIT#^O6o#M0+*tf()qDX?{SB6XV`- zdcA2SISwifkwjAe8?4vX-uF3~E+H*y)^%vBo?4D?Ud`ytJlw-A9;%oW=OPX=EiQd` z9w_n~V$u6`UaXc&bAisKfbF`OaD@Pd{*V>@>-Ku2Rith9ilv6nbktSXG z8U`Ka+2Ree>c~7;Pw{Ns_idJ9LVZ%HRnhMm3vGF+ben|?`oU54W8XOz93e^>91rY| zLCrjo)*Fw+61)%2zrV7(W0nMDOfR`!O{LTlP?AYqs_`S8vvK=He51b-JjlO)t<9B^ z#pPL`2|d{VSENPS=NfO436_MLC|W_WXTtN+Ux!9kWjV%~P1!>sDm2l2Ks48ewwB_m z`;wN5@dX*F)#=Mj`LIcR@KDAO3$y`4)}cvdw|kbJmva|p@5!b6A z-ajKb>+gAx%5AzauB;u#f7q-h? z)JRjze$?uGK){pr%|B}aV8_jH0tM{YcY=-L6B~_6Z7K-buE6Pe$%UNcTP?6P>ms|i z79O}~sRB`?IRSW-KVJ|$N4DmvtG^c8oNus5I7aY48hRaF!vj&|;R*fSTiWZ=8oIo) zf{aDkGO6m!oQDdyQ8@_mdJjKr?MMDsULJdngnMc>Q!~GPBHyp0l~$WyhvNr0AO|bh zKlaO;L64%ch?O_~Z71ALR`cRr|9Z%a4U&azJfdo>%=J34?PHappj-^9;Dv7*DwBc^ zDdy#*{1?GD@e`WVy<5_J9)dFAyPT9)iC4!BNdH)ASo*WKkNE><%M{L^S75SC+oRG* z$JzBi2v6t<9>82t_clf=hS7oLaRN^69C|S^z=X zHV(9(SN8LIURq)3pITiYAPrstF;9F;>y`g99aF?Xt3t)fd^fUFhj7nQ=q*{xc9OP* z_gC(+I`TlW|609afv|Bkb5ZQ?7WE_3j^xsR;$BxtC@QyE+qt?Fvp^X5lH~BoNQ>?s zSAU9ZSIx=j!?@?_2HFxCll?v15w%~hWm^EqWBR!D0fFe$Omdrx@292Ov$H&~o= zc|z-$!LTfgI~p?8r(Zx~A>R7uJ94O;P^S_My%XXhNyf}G>V$uGxykjM=(L}#ySu17 zo)Bx!EY%WO!2bn`L*@q8wIamiO1&%?SW)ljzaa!Oo~5S%Po zA8hXdbqi9u+UHFn;-9Gq&|b?o%)P2NB(^5s*?UGV~6| zvUN&(=VqK9tBNzO?o}j6iX5JVh$Bc1h>;V2Oiqeht4ec*eTq9LX0Cb(d=%z<113%ePGrxK{zPY^M% zSSSF5>Ku%^STl{2+17^>n<~fAxSQlewafr7qsFl1?fsC$WjNsc+V!3=k^JR;+&Ef$ zlTov6oG;D-Wojdrw`C<5LD}JCv*zq_@EsC>grba&(2~1_rM(SbZYjlEWpZL6V)0IC zM1KtH<20JuwT^hQqCRt=*GhUQ6OVx?pxq6ef$~i+`jOlm=Uydm@g?`p5(*SmU|=^K za!~xV=hOhr#BnIEI#y13Dyrx`<@0T#lNB4s>4#8dQ`j`!lW2rT?%- z2HoGat_WsahPP_2L^Td!8~e(8YQC||DmXTp4s;?JPNNJ@FX@=3@nCt@)pC!0Un4(| z#23vg1GeCXNz>fVJ2HzRODoZv*R?0(Pxb0bsIu$?C$K(K-9uCRhTV>~ISEsIzBA>n zIiG-JkHf;o>x0xkM7kc1V8khPwMc`^l|e3#V1p`-!)rpVS2Q$dUqpP;xc@lK`Z=fD z-)ILG=hm*xj2Uq2FI!W9ys0T7iXVd#Yd%cIHT}MG7-mw0I2;77&ZJaw*Ki0~aW$c_ z-MrX`PoFGPxlF29k1j|8p<8nh#_elQMvv5K)?dDE8g0__2N^R4nyC_e*6rVi1pZu- zr>Z|Ba)B3=!kfK#)P8{NwY^sB9XI>QoTElZs%o6;+W^~V!X@yO-V9>{5o@)Q3JzIs zsz$s0)n1?=Q1BlM3JQ(&*<@wrP&eYsujrsKsSOx}o{Nlcw3a zbZSo1LC7H$ws;eGA}QUYi&e%){2-!NBx05h3zH_pM;qoH0v)PIlXIMq!xMPn0iNB2 zbvMS3TVW~|8VV;MVkI1l!tMuCoKhPDiEdw_=@-Dd1;`B?7jYgXV@?)N zkZV;_rNxxuP|F{NFO^)yiQ|9|kLkgvX_?ErNssjER9yFFdm@ z-<6w^gc&HtRs{{DY&`8?Im5>d4WETK=%Bb{Oh_t$Y`XU}#rwwUZ!*fM_8Nm*An7}g zpy6UpfJS|-<<^w9Baf^S$wqi;^ZafD$iWM?k!8;^vOafk+6QeMOsE#18Hm4VzaLw- z#(ciM3$QgT=^@Gk1M%0N*?#XzI}1_VVE{%M4X*u5#Q&VBNU6VMAYQ`?DI=70(((aY z=0un86P#~8G)UMDwLXJU1NCR8FnP2e04pQQ5)sD`MLAs}Z5sbm9heWANZLzT!k%I- z_ccE#DqEAUcE5LwRh4vVsSn^OL^VT~GD81^PlfG0RK9TxRE-PmT&>1B_b#u=yX5Ho z%y%?gJ!BFjv<*Njv=1pMIaIbGzjDODo^&-aa8)ny{=Tn4=Fiw6tT2qKx30b%+#T-G z=(=|qxrf{)|9VZ)MjHEBpUchdhA0BC;VV@32R${lehOcNabevfR|kz*ExnY(rA7n3 zazz+&;YDMUZxN2GMDVpH#$7HUOo-J6wz6R2@<^_}toBgHIpMx@@NqG27}YAB1DBsV~&cdppmrgQPt91WbtKwB5z1 z%P*h*VH|X9=Ul$+mB9N~FLu5c71e4Or_uXpzdtHrM)04-GeNVisDGe-_-VwlrLW0*D&n*R z|0kg}AKfGjy-tFOjhK7Zl;yUU^JOkS(M)rb+ny7@fINal1kqA=Hw7i*Xt#t7vweaC z^|D2XAR87QtSU+hc`o7)TnJ8+>WR1nXK+{C==Dp#Eh|4gURqSS*Xr#xU!ML55=Rnyz`fHV+*H2r`X<}{S0+&~J zrsNvan1?VUg7fA_Y^bS+`5@>ajP7Btnzcu_Vvoy4;U3bXZL6ePvfRvO#vKhe2og+Q zNEWFpod1y4cxiWxfr$prt(i8rYtkViHpsT)zkE>^$je)91r+X3u5{hIzQq|LRJ~GD zyM`kN45oNF8l1lbvtq?}&-zuucjr@g4?vU`Iq*|Ym03e9%mQ1-XMAMMW3|`3&BmXJ z9E>w=Q;SEBlP7x!o+6R$m32V}Cv9Bgmu{_Bv48tZT*Id_LVGc3kK^2;zFN4RvOOI= z(La8Q$9My)+xw+5S~r-XU$9`6-$G*nyQ0DbGVFEO`f1JT3Fe3ZIpCD9S!D9w&nt(I zB=5~z%dnlhoy**yu?*O_9ASZ4VOtvF6Fnfw`=?le=f0uTxvRMwE zeam_&<0wS&gn>E?X;nB``OPm@x!IjDrfMkXgjy=K^Jqu_F{(iy)zJT z29~_%^fz8?^jNF1Y$~H%R*E+@XivtM{b=;hZ1Dv}V)a{pymO5uZUbWk2~GSv5b#Tx z`?!7b{wwn>lIEX+L~0d7Cc7#XtiXHf2cE#sbl^CZ&swY;GT{Rfv4GB&H zGMESEx6<^+mg3-uBebQ?e!u1=gXGr3)k2T8#kc%pZGg8DO>5Y@(!Cc#2-%iMXTI%N`Y_?uv+=%0cD0^V#L^)_!dGmime(iog zi&JUK!+ot64@3*J`x^i%hJg&a%yQl8GT2joRT*3Oo{})RJ}`q}g=EEG7NZ;-KO>S^ z{!?X~AaXx2VO=gR&Kn)y5nv1lO?1Ahp_u9~qcK}9elPHv#-P0gF8?Ws z5X2u2mWzP{lvrnc;G6N7yDQk}0>R`%XX|#|1Udp~0i%>|D2zG%>HW%_L}~FX)gt3& z;&{v$&_6wHkH8j{t}nhUw$xC_k}I3hXMS|MdSmQ201M(KSG+4tAPEX%{u6lF5hU&i z-1-$*p$v0KWuCr>-<@Bqb_q?v=SDmW+5&=|8*wox*%AiLO?39l;-#mzfen`i{{yP9 zo&bfFvZ#fJNF%w2F%tS4yi!XMuZqKtVumy!XdZc;>#&inYW8KEqiGR9=q(sC@ZdH; z9E@8162~rJQ&MJNDGJ$yz6RSjLKx_!p4O0bVuy7=a*UkjAfxUHUK3|`35aCmwwOzH zfa0&slpoQn7ULaX!oxR~vCP{fs@)|tcPh}ph}#L7$A<~WbLeA8zIf@Ny%PYWNRznM zr*{|D$AqI-%kDiRn?gJ$3UNc^$3dit{t7rEdnYA2MY+OUkImKTRhj{o>^K5tR(~t z#KY@*6>FR`fp}W+L}Vw_(Bg{62Cm=UHt*nX44WAmoW=(R7&0n=QAFv4;enm(dddjo zcdr;f2hlsV*}$`WRnHruMl_@CWA z^yNLSr&vTGr~%3B#&niFZTD;&sSC+38+0ejXcpQog2EoerH0=6&AlE*;mm{vZLDX2 zHsssk6^F}i{F>gk8vkSrPwdUnNt^~rgN=0fZH5)r_{LDjCGxG4LP=I-Ej?@dA>txp zo%%_d=}D!U>JK!hHOE;$aK?WgT?FAT4;X$FTS*bKJ{xO0vl!NQ1uX+_Zt7eC#*D=d z`Bn*Z9ZKB1or}U)y##x>27?pw(z^k4KXZo~%@PG)1Z(Krd>dz9H{(6G++GQ=Cls?I z11a)m9o6T*xW}vdRkvhKya0FGygh-P01@SojbY2ttS@X*9rb8W8~|mgATBb|IeWVnO+35?Q8Q6Ry67mK84|7DvyQUM>f>c(QTCzOZ z+uW;M+S0c**FmIn$A^O0a^V-vb*RkdJdt*`^00J_t_OsTrX+{n7HhNgJerv7#>T!MMt2aAtPHiwVmVB>gdC8QC=xb6_lkoEKR}TP&-$Zb> zGJM5<$!ff%a;e-ZnY40gmpp&rZN&~3I(X?E&@-mWsY)AkEPRx@;i|OKpTE1qb(0rb&7|8-~<@M zMd*@v9cJ`gYADJ%-CSU1 z!1-|bp=pou%dViz5RY&Qd1%NKsRH~4kKqc;%a%dzB*R49 zFhCa=6ueQJJu2)&LJ!*TFO0D-zY`~ZIiu*iFKMfO+vyhyCT3Kfj(?Mr_)VZgyHvvC ztp2V4i>3WvO5(KUIwRhM`%Q%f^&19TNuf++P~WLQLcmWrAK561iqvtnh}o`D?qQWK z)9prX2!ZXKwtcB@E>_ZC`>R~)#Bq&CC;pwLS^$0}f-`x?3rpR|mm~X=9QP#^xg4a) zgH#1Pl#Nr$ejG3u9LPHvaZSH8?;qC_rAT-g{&7;TS3%XWZ7@7hbWqT8cWG5Y5?ad1 zgql<@jgrwCIs(suh+lMj6_Vm^ST?qm(=x;T_>1F5f0!xy*fupZXlZNz0aMcsR;_M@c2jZ@$tVw2l@#nH9p>-u~Ejr;{qNP z%CvR(R1Hjo*o|g*m7}RXJyU@*0{nr05Ad*@)A-#&U{>GdmtkRIQFwp<@UXBj(0?s5 z%-_F%Yjb4eD2k77u}CB28Npr(MUT5N*ZsyqyEYs1j9t1i-ov#%cvD!%FZ(E@iQJv zs2cz;qIPcz_VY*1%Q~aqm2kRW^=Wh3+;k*YiLFU`?ETAXvM&lKVuT@YM^w_93&SI^ zu|Z2J!ql_dLCtuARCb==oC+gkF4EeT_eTHMReM^|^Z-2#imI~BX#kGq$I z!6A_pa3o6qowj1#q4kM=58B%@lII%9YfbXz5?cFXb$Dh_maT2c%<)m@;&#ufd#}#g z+1WXnc;8Q|Et-gZebIl1C%7}d@AaJYw#@EI!QhJ2trSZp91>#KmHBmQtfeCS@!t%? ztL`Pe$$slEKAK^6H^%DqT=@m-ym~*=z6X>YMih!}r-)Tac&zQVrk!!4IU2eql%Q?9 zO@HQDzfmwh%%8MJjL$Q%&sAooQ*88j;_cJ`LggmK1;CTTFN`7-a+&eo|LI>FD-)iKg8 JxZrT_{{Wr%V&VV* literal 0 HcmV?d00001 diff --git a/doc/img/SIM_VIO.png b/doc/img/SIM_VIO.png new file mode 100644 index 0000000000000000000000000000000000000000..5acefe1d2029e36855b330f75363b26c536b527e GIT binary patch literal 143023 zcmY&gbzD?iv>pUOX$0vKkdW>!K|tw{kd}_2yAc7A2I&$}5b16Z2N;kT>FyX{=%I&r zhwFX6ci;H~;lSDZ?6to2tsJ8?)D-csDX~Ey5Z+5Ac`XnKvkwG9-+X`x+{tzzR096N zaDV<%=K*j9Jh1!#0?~tB%FF8bWbe#-dl;SMoE@HVjtbhRzMgYI^B#@i47C$t4ykgz zmrtIQAagIP(lQOBnkq@cQm)t9`{l1>OYH{)BGWSZD$n`znana}f00;-aWxvIj?dPL zpGgHPQI^akB}VVS5Y#k-18ryi!DmB1MKj|&I`TA4^$=)2xr%3t^K=c8yZ-*pp3TyG zyGEXb>G&f&dqS(5w+}K_>6XrXjrE8<@nKl{Vxp*n8Z}Umxb05EK31l?c&xMw^gn zf%>8BX7O`vmV9Xor_V$kH{1A2Iq4CSxbDW@AX$oxN!yaC)i00#->%f6et3PGv@yF2 z-p*(lcA0JMd(FoWev55SwM82LAxiKh=sLY>m83`1I#J{{_sRd~`l=e-(z{6=H%t^T z?7%ZIA!vR2C_5Cfhd(EVc*=ynNg3oRv3JvA@v0}ztdx-iQPNV1+~13T@t-BudPnlu zNcnRtY2v48Vm$G?#IURi?N*wdioi4usk;+kRlZH?gp*VMv(?jt0e5q5ZJs?g*4aR( z`_>HqxguL6J(Ess=6Od2I(ZIS<76DYSq#o7Y0M22H6|{`yx?(_duRq{P_T3hgtsCs zu*EwMI4k)qtpk|v|HMd?$f$Wc!7xi>eNw-WZkGwpPg{PQZq3Yr=>6UtX_XUJJ>>9d z+8?{uPwMOg%ZkMH7;&lT85-xHs)(Je2Rw7Dt!i6xgvu9Z_tFC9e4>2wgfSihU zThN;p-tiUK+kBgxow1;i-trJ5PI$dnx^|`Pg6D@E-}u$9d#pm1p(1 zj$p`XO5KK+uyH->5twZrhDn!ZDgsUsFAT*knNL7I88;Am~vY(kO1~qR0K! zE?QeESegI9*oR&;s}Q?%eJ{hbbQu1j`r;j~+^jpI_Bu_|iNVza3yLg(_+NMNt_+w55 z`_*=C(kSqyHn*-u&*DEn}0y zZ{J8Ut7a>`e94>dLLQ>;z%K5!vjmBsSQe~L$fD}59thLoerpimx1yxRI#fVU4f@QPm*TY?%2%>PKVI%{_1=fn&~?lNNoYkc-lernnmCmWhrwgW4; zX3{ETN}HGaMW7rJ{5CImwY4?&YD+p;)tBLwj%>!?voKD27MFm()RulCVti!_2JhB9 z`OSmNteUH&t4mr@?w4YI(IhEWf2!P;so<0;n9Cns;4>)r74_YQ3ez+_0rtIeP~8NT zZVox}+hs*cxEK>aT=<`4m}h28idCpuH_-ek%PJkcwA^O;%avPwVDRUl%gM(55~#U2 zRpXgy@W4k)Cqs=5Kz4mLhaIb*F{8vU0ImuJA%D%^{daN7ZNkZOUnxSBidt^2`MpC zXsV<1SI$YxA_=Amk#-@=RM3m)BILlx$yel+Pg&XdtBSRqL{dyz-*Cv!;vS^RN^I;{ zgP2G;R{B&ZXn2Q*$TVc9C#?~cOUMFuGVi9MogNlYt&6Q?8Wq{)4Q;dbSQ;1FSsztMmcCRdj4nlx#9;sHI>g+m zS*cTJX>};pQgiw#g4=V_v@o|)-;!oahgA;O52mFl)@K#g@ph))UtHQ4Rpgamd7onc z7OGg{v$mkT`nz%rbx|s!L&52RTrv97aW2z zDSJwJ!p8cK@)J$ER~{2b|QqXqN$9kbRu&qja^{Yx8chku!{OPo%*jcgs$ zA~-odE=4yiF%xI3It2!!M=O%JIjWI@94Iq=E&U%aX7NeY#4jS#O+R&;mJnz7(eO>D zF2BvpnRtTumNl>!WCq<=QQBzoDW9F-EsFWeco+vR##!0fgiBhcv+@G_wnGd6!doeNN)6V9u^i$>;TrPb8U8jPsX z65FVm2RzU!ixud8zLu)8yi;;ZRI%MM*D}b=T?tJY`iEiH9;Cb~?1jM?Q(i4K?}fyj zNTiux_&Q$sF#6<6PLxzsAZpaac6X{4s)p&eCahgXGc33=g~I7RRjioy#CHkd1=TvS z3&W%y3Qsq-R3@)XeUFc9DB?TuB4{srG9YLy0oxhDm}sLYbzq?|DRd|;3oCWk-#F@>P>XDSEj~xmP8$RWqzHUgdTo2_ zB3rNfA&TbOiA99>@Vdiy;bo?}(ma2EWB zRucDcwTek{ZLIh{>zM|E;}r*T1GQ!oBZj5Ey@fk|w~;i9*B141M3m$rz84?8BRBxKesC8|^3=NTj_ngjNx*mm3uRBXznFB95mCc84Vhwp?fa|vsDLdvHZkS#kV?FW_g;p-L}67` z{$&{iya=_Eh3KajhZAD$+G13Bb}k6^$8#bK@fM6Z zH&*#unmJ0|#gq93$uXzdCH|-5`GzbM88W5FxfmL-t^L2mZU^^meBX^l zq23mZucv;ty6YFtviQOL@)487Ph6sh25Tf_k9dDxoLk*od5Gd!6OVE`6ZD<>a)f!P z{zZ@e;j~a)UETZVohtgT4Gm{2EI4uO?Gcq=aip-K^9hK$Xg{IU!qD_&!Tuw^gAIT<9Rn;M(%pqJ_er8RID)pPIhz`s+5qB&#FN8tsLYheHy6UP&iA ztOXAGg=+tcp0=h z$px6TnP>>!$v&4Qo{;QPzg>bO;k2;xs$_~dxzgf~Ct1>#hI8aTQ{Os9|DlVo1gUm! z$t$h;g%n~~r&nt~7{}Fc2stl&G!Fq&WORu7mFVf})Z7T_nds2QLL?0*R?N`(-@}p=Q$ecQC@z<~oXfJ#ce(Z!Ud0K{YB+T;gm7J>8XOFjuKTm{Ow(OdQTQ9EKpv2wx1}?Aa@NYV| zV}0J&w_lsCUlGhbEsy*n&yOOX3Z)kfZU5*s+W|c^!(t@CIP*~ZOEN-*=7jiI)9r!c zRr=ZQ-dznGN7DFez~SQFx|)WD>P(M*3B=F_yYIyN<+~&-PCyEo0)%FsC!BsRWh}6- zAcL-iMi8nCMMlZLYnyNoFGsHKX>{WWPYAYI4Y8q+K0nOI?G6ZSc7Jh)}Tdg)alqt|knB3InBCfvVs0)w7X& zUY%=fX&n6Dbj5O$R|P$9F|s0l7kw}kzuPZx{Y@K<13~Tgf57wam)`vE9T{XE+e`@R zcPF|s%KtCd?#(Z4;3#pw85c!IxT{t#V1NIYj{n^U|22AF^(AhfABiUWUo-o6RqEf( zRtEmqgO~F!H~eUw#M<`59{o4l6qVoMWkO_^2j1Z5Rk9K`VD~Ob#2x`nJ*j!S~?=(?rdDv9;`)<-G`J z8E8j}zGCw1D?68GQgXNA#EGHooSYDznTP7& zu8MNgb|nHgcIH`bbbSFSgz@4hKCxK-6@ESA{9*@>);_38QK_D}DmP@=A}Ls){qz=t zePzF@yZD}2a!qmzRVp!WST=EnYG8AQf7VTpt_>NP%^=Mu2N%gS0 zlr74M!ul1TEwo5W2W`V*4|@?dk&I9pHU_zAvk1kA<&y_c3E1Z^U$U#KN5V)oQc_ZA zAFUDs!b{A5DVy@)gVHVTD@3>8)2CsY3YQkcU&18cG0x<8FHBcl1H!VjTO|&3%G;zG z99Uv{7m){66I8EFb$@+&0cuUrSFVzbQ4hD_?-afViWHd5HqN`chtI3YKd{nkM<_bQ z2<-8;5>jw<^if5mr+Sr*?s~ROZXK^JY0ZA*edCtLQT?4cBK=Ymc!^R90zxnV5qpo&Q>&;3^o>h*2k z1h&w(XLc@G23a!-Gs-nQZrI3Q{C$Eo2M0dVO;M3qrfc(Sn7As|_gQL0+@4tkw#c2# z+TZ?+EFR3J&K}ZpmzrOv_7;@r8NSgBNSIT3ab;XRz!S|_#3vo_2sEjCO*WftPYpA- zx&o`u;4&O9uosjzb#wrh!r67hk=26Ni-mb@I+ zMu=WBxqG4OwQ<-phQDHxRMr0IT?Ac-b{MpJzIa0zFJ8lPeR#7ToMna*$n zn}gW7{;8C5_#_?y8YY=_&JbX7xsGLK)wirpy)ExQ!4J|l$j;r7NTYO5%+;B&YN{iy z<%@}NovuZMYaFNAW2)@k?8ljX@19+UZrIqlu3niez%HE&+HK*x5gNT( z{gAml;Na=RShuC{u~ec5rQlNQOoE9y?j+Y?ulo&g&eN2^UJYZmk9bHf<&^1y$0GU^S6?-$11`oBDT%*BU(z_NF%o+u#x>5<5&Z(D)&yJI`>C7WK%7m z$gW;;zlbI)nEJhcbeWL*UzRdnHPg^=ciC$HTa!EX z0Du6{BWde9s{tLD728MJ|%wG6Lc%i78NZ-MMb`LD)SObTbO()j&p{=H=H((`>l7xwf1((c0tt363>2 z$q^p>;ksPB+?}IkC9Ku6&69Dbv6cX{{a)SYV-X0eg&(=?7;lfL4&bX$oDXh8hHnxj zW{w_}IlcS54tFlAIFxlG9=%@mtv|uT-ZhFljAfpU;bG(n^-iMGPTpIrO+k$&QjdK~ zy{moZ7ZwKpt(l;!%Jw8G?$-dGv=0rZ&*WwaT>+n}XKc8Dz)y)(o%!M>@1`r__pA1L zGc=0`0_pFoiJgG(CJ(NVFl4cM;4|VRPSf`6yqn`9BfqV097c@^uS;|fPbz|Q=xz=o zRq~|T`VW=UxYj#vQ5{X2U!v1R-8ZBnEjzy7^0U8n{pYo|XH&jj5q!+qEx0z>6L8ca-&7r{+D7t_M)fy@bT^DS3 zIhK1Gl-aMaBe62`*2{a=eSB~m+?oU&Xh+doLctqK8sxmZ+m_jyYB(DuN-Duw`NgaFro7)?mL zmf?BeYVumf@PJeh1S-8@(wpW^nsk&saA|Yx`PPiV=Dixd<@v)5w09BG#HSaySxx!G zqKqCAgHE{UVI2HpPjNBM8_e}i3~o2BVBWs8f{-?~CJact~f%S|?R_HJYhV>6Y`KeXysw4^R?X-ip~;HW2u zErAFrte14M3J7JOsapS?wv8_%5_k4k81%0A1np5TSLT>lEs_Bb96JJF?1 ztaqCKO%Qx8r(15+my%OBG}q+L0L;k9M6!Cvce@Rd+v`wn_FfmRe{^CTIY!o_HdZ z#PIhWXS(8=#hwQRciiI(nU%WrZTFcl;AlS4)xBP00cCg=)7}huH=_1~;fJqFrgXI- zIg`fF@9*vb?f?{}^KrE&)}n8#i2ujukl)Q>POT^>+T!m^%}5xQnW8a`Uarf%V87-2 z3)8I`%4(7+f>gps+lqAN8O$C2mv-BkS-z+Bv!L@;ci3SVY9GGXad5vdmV#g38A{ZR zlxV+N=XRe3H)!hUj9D3)n9u@wvphp6+&2UE5)9@vtat3A4nCXr*4EPcm0^?HXL@s# zCQFe9)05L24s)FM1E)>8yPGnzJK&|JY##YBXv$lyTY)g{rL3(>sxuwYmQ&@I?+IjP z#xdsL*9gDRrH!suTVDnuK-c*;rZ$qAciN3?`)<_(e?rQi5KavpEC+x4VgIDh@=2|? z`Qzz}uaac9X!Z)6?CjxIP;IHp26U;3{ff6!l^vshc%tzLb$_QBKuXd?hwq8a@mChU^L+GEI|L}DOdT; zfdMI69>FNjgUf4-Yan@%HTemL2&vXjjJY7Y$@rT;gGPDy9KOeLb8XBKt6O@=q5;r* z(vc^sU8u1*l2j~heePmSFDa- zJNSje4V1e`HwH2wjjpShV55r*c2Fuhhl`5F(5`uQ|7KQYpu|4eRGZb*gWd)nYvu;5;;BIBmyntU zdQbx>P1-a-B-|F?>JXrD zoi|>hr>&<44LqBNW(qp+;D+H*2_5vC-nixUkVLgYKM*OS<`zcy5_@_w8l4Cs2j7b` zV3p>-rFtTqB&Q&R ziIAU(Bnh6jhKeqN)S;7HKvWI#TcCCtR3DjGmX^f7^|AaGAKhXG;r7S{d7HIXf zNHyn`s|hVZN*cd+4{i^xn^GzSM9 zQ3Bf6Q8X3)2&-=XifJ$6w%{Lr!f(6il$c)i{`O0=^}qvY>-FpC?-hCIA$H7c99KAy z$lJ%GDhaRFYXVV^$0qYKivg?QzPNxb`ASWcwZvMwc|!}W>NNDv9{@MaW>tN1UnuvJ zc?;L|APD~S?i~y7APJT5!j#qT zuDQ9iLsSW~l_zlKU_uuiF~khwdIN17BXi?k&jep6AEL zQ2PomA1M0dz7)$*1@C6;PD)l5bH0%G)7I6+rfv=48XaW63mhp>l=OJVjf_uiHR)Lx z7_de^hg(Vqo|}`VrSRrArmwV0d_*4k9IU4mgY9P!RjGDvM_*sIHhXaYTozt^!Bcb6clSEhkg-rmSJ%7Z0xW zu7$U$a=&H0V-qb5AvyNy+Yx`fTz;&MUT|8OVZ~EgIy{-c>tc+sSqi~zVW#94Q(laq zl$5k%f86DRnbR#w*xUY8hrYqUj9TU2pCh^X+ZdYw9m0FB_jHJ9odQ^rRZ zAw50yJbdg3$$)lyN-Fi8NkPCPH2BE{KW3kJHT!Ucz2PlUq1-(^Y zEbB5MBGFb)3>_NT>Ci%#yT%`WYA3cTN&8)~bOHCba8o(loE$USsqOJ74{Kk)1;7s4 z3h^6}c_^a}dk)cSk2`94)BNev>Yq#{9*Z4)C;irRJBuDOa?A?@gP2|z98f<9h;!sL zO=t^;Z}GFJ_L`$3*`H0BXhV*JuN2!om%{_h7bHL%fpGEG7GM5ik4!6ey`w*a!u;3Y z3;5=p^|F1LrF}P_+$=8ML|_3++UUs2cF0vf?Cv%SJe|I>o#wMP3YP3{YMM&zh7U<3 zKYaT1x*cg1!q(srN(CW;Gk&~-udIV-9%u(`0CnrT9!f2YDEe;3!%sVb< zMGno2s5zldT^*<0I2jc<2H#ue+ARA9&Dh}V_CN%Z0elv2Ej0&iBh-f+!A`la03U5> z)uw2%`cPk&efdC)nq}r&mV^4p76@28L9OAwGbiWhbR9wh8;8znw6H?ks5OQ_`s!hn zyesM?&J4Lx!EZfK@x3HVPHfkq1CuV0vt!d&XmAiZG9&hcf6vUtp=ei10@j5r<;n@B zIs3^ol5WjjKQI3*MVZe)Ms={=lm6oe4{sjyyTX2A{`2L@n|zetruG9420jtYr%e2K zVN|5t8xh^nc2Ur2O+7_(HMPQ3>`g(A7W2cEfz{88FhO`W6uq0wX=rxnh0-x9$);AbY4~dPHJrL%_P0 z+&-AW9|{>e2yTp%6cnKD_wxk~!MWmbKu=_Pv$EVW#BpuD7cI zSctK~UGNg9K(c^P?gs?sSH~Mmh_s7$H4RQc_{m>9#vlP( zZ10E$3lm1i4yqVGNKhd)C+`c&YbZmq%^`%KeVqb^JcIH@E<=$0#TR@AQwUy32l?st zYoz1ijW0(@l!h&TcsPN!&M}z~_>$#w89O`4j64u`PIFi~he?7dgSNewS zl1e_xe zSpQS7#{!gI#;A31-~oFB`~;_j^36)j$O9B2BzGPZv214GY9#ytUgt^UoBI-gjEfIV z{vYPIRjwh*YC|R0doD9nlXxS4T(Aoi=KE4PCzpLOrA!$a6&FVL)#_SX(`Jg)vX#VW zzBTz$CiX^R+-oU%7Sr96_-Z{l?Tn#VhYK*+#8)TI_FAA(j}P)vU(5GAK7(Vc-@SuQ z*Y7@)fECuC;wr@G|4!vJWz2~)%XC$UZH}Iq89jRxaFVxbx!N4`Yq^fRC*WS_v!f#u z`jp=g*Xll4aOmZwR#G3sqo_v`Fh$)7O2-x}jiJR1IK{4U6#9c+ThyGV2fx>QtAB*S z;I=7}9aaFjn86pCS0_sBbkzsyzmXq#ErMi&Zm=C&67?Mg#JvJSfBe8{-m%E6Iu)#O z6cft_{rDlJ>UxN-l70|qBphPZ?UHR&@7(cLqi3TzsNV5{63AQLS;V)+Sh|S>1wS4i z$C+wEei;a2RJh80_paz6h7iBiZ@uXzWX;Z$>;0uVXVX{o8d0m37PEu9^HzFZ?awo_ zijtC%*r|`nUC1)bMdS+{(s@^3jcjoMkfIUiDylkU0@XWRV=2U5;*Ay>tFqQsNj?w@ z1B#87Vru|#zCAx!2R!|QNNLN-^6;d*b06qxkB60N(UN zZ)f43LiYRbfv7#K%KTak=1QIIky*R?&&a{YPpeB`wRT}NLg0mgU*S0ZB>L?E7qaB_ zy`7_z!B|jFL&p7NzCn!o`45Q8mqj%P5)S)Vc<0n?jxDJ=_CAGK;3X)4s35>MSi}IZ z`}pxDP5v#Q3L^zLkBf6pEQ$yZuL$U@M}UPBRlJOYOT)~+vT{nMeEgUK3=eJpEM(YW zfhaYo@7gA*MK*&yt4ehpTOLCDcCA`^Lq~bP6&6lVH;Z*d%H^Znx5tXH{2$!ehP)>} z;nKkaqEkT<(QL>k02iklO6^`miE^F&?0PH6>8bkIUF32NI6#W79&9l!RBu%WMtx=3 z=HwwH`d)l^xD@un$bWZ&tD@t|jmu%eGEvC`@6*SRkBqzwtTvhunBR-pHk#l^eS@AN z%kLHLdZa>9li??b8sE#U!+^u+*@xknCbOP_ZRHl$nY=2aPbiIJ%^L*-2hHfw46vZQ zKn!QzdcJ~D-uM>%6B6B(a|4k{&G-OwK~!o?o@V%oEkl>I!p!So($7 zb>GA@5(*Bvr$&kGDXFPwv^`-^O{q(>c!j&V)oBAnR7Nzr0+?gNC&+Ztw3IfeV#tf6 zeYQiCRA!L;f_{nDPKy|b7B;mt6Z=y+J81=Jg9Aher1ZPyn(9`N>(g(H6T0AynBFDGs|Lhm1 z;q!oF&2(Oil{{7^gqrqDU;dB3O`7|ba{AUZoqx+SSpFjaSZsAX3E{^NxOhMd@-*yh zA-d9I>w{E-diK<>fs9y;Fs|A9`#vjC%SN8#^;{?q4Bnz_E%l(ArTY>zDx<4i#8gel zp)<@jFV(>Sd;5*xFO=e59B4~x$q3PlwaZTOiO<{V_^OzBh1ge?Bnfzd;Jo1bcf-_f zKH_utFjUJLZntO&;w0x4=PigtAF(kJQ&=|4@r5288MPnA#$N5%D4t9O^*t4Th-rLv zQ(ykwe~+TC39ifUW+_plZeYNccfF%V%5g5FXY46lV=Z`!x^ix(SRYozX}Y-_T!R;Z zZ0)OkfcR1BMx@Jg65PYHl-5BFVXs)z&`)2pkw#T2<4uMa<#8<~Dq-Sc7@U?9?m#SQ+w)U&pH{-e!H3Xj<@{vURTH&|L_-1lTU7^FZ{K8=lzz0 z3!|XpfT*>s=eUvID(t-&F&!`;IZ={liH?A9zmb0IE_L+eO~e)B|JZGWd>RabII+ttF4x zC;^uF^q-!4($f^s*x31L^ZxIYCY7uS6@g}dvF`Db8iTrRg`ks?Gtt8?g}s&vOBpzw zltiB^R1lDqZ+38yV7Wu3uX_UUx<$Ef(xzecl2Vk45?*L@ ztq^2P6i8;S(=y5JH*|hM!OPHz+PC5L_X=cAm`QFHqpROd%**>F;EkoT3T@DOy$*Ga z32dIYx*|yhe5M&Oeo>TsHrKM5Kqj-abT^{H=B#C-3Myni+X79`LTH#ScHEZb_*&D% zS-73eGhTEO^zb|Ce>A9}6urGN1~_u$7AINuwWenI($a&fy<+i)PkH_ET8 zhw2;LrOd{YcdrSDQ^+&e0eS@>uk*VL?tt@P)ipVlGu7dex<+9FS} zMs9W}1#k&cY19p-x34dofbpeXm9p79B(6vBUE(EYV45HEj%u1JkPE1qYaB(%RpW3q zn&ri}ZDcy=H@Ymd(7fwSSQEiKY<$79>Gd$TCpMbb$%q3Pusc()R$Z)(TAcrsoD6&b zg!JaL!TdacOOfWW&04QdM_e68yr}!Oetqc&?qFXkUthKr*W_=?iaZXwjLQcLEyFY<%e95f(?3o+D0qG)D;XZRr;GF zamcmg`+)tC3qBhvso1FY^CTr^uD!!GQ!=J@kq~igVFs`ar{TR;q?*T{A!(gYX?h+H z`{hrI>eZgbfBblKt<~Y!U-#3#71rL}e$s|NAOqnFxA=z`t68u!U&!N^%5E|F@1`1_ zZZ(Q~?~uogMpL^59Y*s4jH_-@FlZy~Pi=bs3!kg;^N)V1s`MzUy0WZsL*cPhPT5p0 zn$F)Tz90#tij?>KiBrdrGdbWm%vQQ|O?;oGWjW1ES>%cDiF}0T!3vsZVC!jg{cx#< zoclOG(9TEF>Rs=k3k}Xz@v4^tm<$jh;9Z`58NLa(#KRL(PK#U1^;bxGMG-?o1+VUZ zM#0alCI+qqe9X-`l<4XL_Tv3>E`XaeU^=dsTPGQm(ieT2rA8Tws!Z8N!pTn!6rc7_!r-2sP`n3BSr$a8>_S$`Vo3`}+R=iE+`!nNpCo@!M;!*gu#zQvz^(s$coxNh98RHv+hnVz@1H#YI zuQXUtSEX-SU#YQJQtX5GD(#RPCN1q;fMZf8Ndjh6@Ui;SxZ#bfapF@Da*sF*4MPMY zH>^)3ddk#$Uhw0nT1mlICV-0C)M7WA38M{|l9@$CiwDM%!ZN*&8km%_0HxLC@z(q2`C*dTCXy#(+9V_-JQh8;S3$R(v~j(%{BPx3 z7ZGXyPRda~BO%3YzjjqeQ5~>8n7Q?ce__c=rS)X`$LkVSHa7E>uBb>yC0!Gfp5lV>v~4+v%wiFQQ)CNvLhUp;H^1xyOsu1ODur7L3JT8oA<9bM)M58m zA6x_sWC_Pt1YaZM3x)@RfQ}*^O!ADHlarG}zcS>ha%w_aS|r@J)Tk*5nEOlv%C4Y} zMOYI&xBqFH(XZY_#-{ytl&ziJa&)&ezZ|dN1B&|tQg`KC;J(FVx$zntj;yN)jP*rs5Iw-KwYOhs zNA0avL1_!}^U-GOMNg+JE=JPYyAGjr9gBNq05+(D#JtIVjQ%rY7sqss=R<JK%<-Hh~ z<{_raL%s&gn09&^E5wjjO&&f43O>Ng(gt6-9wCuvB0$mXe4?Sfn;Rfn6{XV*SU?2u zxvyk1p5FHli5oAsOMF+NSklG4xqvcVJhZr^1o)51kQi#2AXrIN74J@Hz^4o2 z9<&#~2~RnLOI@rbZ*Ois;N}OK58u9h3lAO|8q#%luX*$44GAu0N=^=E(I~}Dz|K_F z5$f9B$qBISTqCYDd}+i|cvXFM6;Ni{VUpyrGsR0I;iCZ<@8^4=A;8=R+e=ERfW}f?1O=iH zcz^a`;I?D^kg~3oRx)vB*CP5p2baYe;o)sEQ=anl^jNhvZ1RB`|)RGZ|YtR4i1WWY$oIeo*ICsDrFZh zCmJrtOhI3uh?8C(jvqgcx|`WRDjdgi-0@KM=wcvGgE^68W9{z97{P|>#{kC>UAJpq2( zyX9dI2+*x%o)1^<xK^T} zp#h$Vjg9qNOH}lL;0eD^D=9CZ=u2jK`Vu(KOr?1kS4S(7TiPV(!m91ChsqudeyyMo z!PR!G1q{Q#W@9T9BazX1c;AvV`bj*L3b6s=;e}N8B2EYs&_E!j&-!}%U6-iDIZVGB zPvZvP(-I6n&`N~ev%YtopE*dQQ#lO_KYb!uhr{pA8y+71rp?b&ein%5@~?tAe*gZx zc7__Cm?&IXd0VDm_58()7uEV4z-=vA*-)T6#`yBtvuA+r;#j}FQdJ$lK3lA)uI3xe z7S#p}8i3R2mlx5sj?>i#Zjl6Z697Aw0(cxBAGbSP>CTk&uLq>VBzd`6;J4p)_9-Rh z+s1~qm9_P@vgxIkv>zS_g!}EsGrHGB0Mf$V+fbn8h}@!?ZR#&b9_uj@K4ASboF6A6 z6DlJU)M0ufBZJm)n<9}YcF_`7ugGtJv|5=#M=d-D)iHY9is*s_fp(lXM^^J{Z zl9Fw(Sv-t;_V)Hkqgy&}-ehu+Dt95IfawRDR-2k>9UYyo4i#-eS0?`cEmG%8=&|Iy zU!Yrb*FhbWl$4*cve;YZgL>e*ySw(bwh54B4Qp#_A3vq8qB6q1pKw<5u4>4S(C?|!F-KI@u3>xO=(nm(t7 ze&Bn1;Kw?zAktWF_KK3|9_wEbcvOWCiJ6c61G5H6hmWHqDTJMj;%EB@2X{|%A!_jA3yr!A zvnTD{{z?LWgrKWZ=piKGTciL>Qpb9w_rwY>kRzBuN?Iz5cmKZyea4AUFYW#lj7Q20 z+3``81Rx%bfkP}1?*v2Nze1gv09Go?7$&iyl`#NK_GduClnyus@z;j-Ph}k z=`xO-Gh|X&zEZiOx!OL>8d*&4b$|ta=8h1Xi|#oiQet?N%>p9Kd(a0md*Itfn=6T_ zeRT0dg#x$xIV;l+<*STtjfQCVdmvEyOVj5Me(do~Jz8$190**Z#31Cpd+NjC4sZHn z*3j>EJfk#5l*wwvs|TANSsKh(VkIF|q4H-42uHp$*DB?^^fQ^=@{WK~9y zBq1x2l`>M1l2m48M^^SIGD=252uWp!Y?9}7_WRxQxu5$#p5yr+$KUZiI(+MLInU4e z8L#zzU+HWU+})FSJ|Rhc=|(JjuMCg*8nm}5EQ=~%{7j-tMy&`f+m7Ldl1qJ;Q?Qiw zwQMCx#Z1lmsvSGSmLB=Sl#g!h}qR(#7;ep={I7e2<3UE~@ z*Bh23O^b>}**GarsaAIUoy46KQg^bpm|J9@t-rc^FuCvyvymaG@q)mD1~G1nXInZ7 zC!C!&kVqWz8#ac9Thoz314r1_sYm@Cqll-18Ka}iu_P;Fiq$6pEvwSUj$mR&>}cdT z@L(5t*CB<*o60xzc=nM3LnG)^Kf1?vpC7K+tYsX#<=`<|5sIJgB$AbA%w?;R^IGju zF+DdItCv3Rn`QU+WHk}&YKm2eii^wIZkSyE-Q`V*oKkm%Pw8jJLWzpS({enwP4^8w zwm*M$4pIAX(h{AW(B)6`F+Uo%_)GrH6`1JgPTTP%2U;* z?I1-)zd3y^W1rd@vGOR}^mX^z)t;jlaV>b`(CF3JC~pq1g<} zRk4ouRiwo$Mv9LpwOryqQ&HFBXQia3rHdTr=W%Q=TBS#1CMNDb-E1t!HAhB92EGFg!l#somA!btb*QNw=<^<+MYUAE_kyF*v16&p$p;yN)qvkn z^AWb!Yu3)l*m$%ibaTn~`zMf&+ls=}bEswVntsFH{_*2eg~_tK&h1osvGUK(#$7(h zz0dI@&NUpZDFkpU0ZyxaS2oviqPytgliU0%S&tv{^aAxlSuwJ=PY1R+W@eU# zaOKGNwrwB)NeH}~Bk3NN8qeoFzH19B>u|W=?+DB9JS+KnL!7J)I`er6FxqmBnN8H@%VKOy7HPym7nR$)H~koFzzF#>q4dfbmaWzdnG2LRaR| zkqZ|tc>P%#Dm`+d$aP4UKs@0}^AC>Wq{4}q{`9FjU$`ckbhO}{miGH|Md|lcwf(ts zt;=&`Mi?B-8&M9r(W!xI0{6^M_DfdwXFq(%1!VN@yUQF`L_uNU7}!i39>o*O-(T5r za({?l`+e4DF2geF6h{f98?w9d*!ed%wgB(l@AF&p@%b)pd8cjUqmhaEvl};Pc$K`4 zjdeV4d#Zhxm3qT$_xbGY!otE|eY-3DD*JpE%y*i;Q0-r=-8VaCxpuq~AyRjMMx96i zpt+x=lcUj99x4N=$exkboSO;2q6!~0xy3z4`yE|+ry1Js>HLB){z}x&{=TsC-B}j6Bz>kyLGr6F z@dk_2gYHY;qt7o+4Lnr5oJ)XYzct^2{Cqo*+2#4d%ICmVT@ErwVs>j_PDaQ1E{{yf zILJKWVbBbJWtDpC$dMxhGEH$xCy*n)OFj~>Y!2K+#lWL4#c>Q|0&s2b=^AQt7#hrz zRHSR3<#AKAA(|H1L-AWG9#>;fefKu|?){DPSBo+^9j$}J4b9AAY~Me8cKbHNkvK&& zV$--#*t<2OT}=C-ynFhG46^YS#+thTwZG_HG8EMR=Ro}h)_MQK| zIPFq=Qr`KCe{OEBw97XwBNLN%6CRqZk-RFtcs_?fAqN&RjWce9g}D#6B<5x9yZBZ8 zLU+D)WWL+TQKgmfyyJPcw?@ath#iT5o~YMA3y#ggqbb-?KyZTnJY;z=(g1r$)zkuU zRo^^HtK)knJj|V6ZA^du{FdDcgr!bHJ*8)Bi{Wefcv0;w?v#wI5*^fEucZ^yq4B}4 zk}p?jXaB5Bj!pWlmEtfslh@^jt?ts8H))tQE+^P?2uP?bvP{$1!+51Ore#iZFAs?{ zEPkM1@lDR2cvIfZO&duKZ;wUU;FgY8`j%tF=T`dHEEYbyhFe^j)>uW=1id80iYaHS z4(!awi&%CtQD5tK`kz@6P9{tMyna<16oO01%Po82T~kv>9lu}Z-EDe7{d?%t+}+)W z=(;d4QFreOYrk!5{0ISP7OWdO)JU+(??mO_Q)(bef=SAe@)=dw4m$?V#>B*6gBj_l z#WUqq@W?z-bVCA>ShYKM?tooAnH%d2?(v)*Hc$d1 zUxu{9-zsC_H6l`uQ%oK!7c+PkRYf}NmREA&W~-3JG&+fitRQG_jS_z^d`bT;jwtv(kSx6pc&>I&u;qf>iZo*L%0HS62FLVH#NC zhB`VoFgob^kU^Xu7Ul9u7f`UIk41du%o&3CpFeMS@nVi~rfFhQl91UBHvDy3LV_wv zE$)z!ByJ#9)luwqqnN}d#L{hgoObo z9kV{PwXKx(stP0|CvTOD)x}LUoX$}%`>DpLLB{Nb%U+IOG4d@)lzPw zAGhz7kr7i-sjQQk|A7fdFiLRJg9i^5%IF+Da^w~U)adBZq-Tes=hNahzsGRybszm` zx{o3xRR6oSU&^6zE(xYwK|W9>&Vxgfs$p-m(q}xOmE<^Luhu^Eg7PD0D%ELW<4(R# zMSq*A<)6K|Jr{Dj9CEuRa(f(bsl@l)4!LH}W8*aj-@P3hP0EQud#Ipuudi)dwdl9a z(~$N#t%p6ab8sGgB1+4LoMoGqcy^ceW?j8{HP82_vn+P*`jDP4Zt^Rv9LIOC$;CG1 z`D&7n8X9_kt|K57rZH-a(y^fv>DiC#IQ;`u^u`^U_pkpNaLUvsNB_tslIm_ND>*Ng za>>m;YdBeE(FaNNL%*;tN1!em>gwJm09u$tiD<`>^-O9M^czbk=~NY= z^ECXc+C#F6aHCgbG4NC4xtj2kWmQp|P3^LUYp?o`S?ky3RI1W3KVob``1kc+$#bk& z`hh`Jy_%Z-%fKhFXrJjiGdnTO^|Dxr3C=dd+iG+&o69S%sB}`2u3U`(-67M3*FBPI z-bhQRFZ=Z=N&Zi7#>6XLO}K1wsImLi7nhU(<0B$oD!&?KYmN>-9=Nj3zmGX`-KMMd z6eN9F0q$YfUyWD2NRi(aCyRA-7?RW_J~)@0U6#x&=&E$r)>=db!AM5bU-wUd%H zNZ&?MkM111BRw@#_l6dXY5SjeS9Y2e^6T9su;#$mXES8D8+}6Sd=H!snJZ>r{`1OH z#$q>>TSM8TYOVm@Mm>p+h9X2_@=jFbyvQ;4_Tp=QtON|yy~=Q8>4eRT{GQ%OA{UzK z=7j9oWvb{le13N0(7P`}(iAL=f}9bgRH3ljHq=ZJR|vFa5`XNjNZ`}5+w3BGOz4Pd zb&&49^^1$Q*HwKXe$|G+B#O;m$=s)`f9ZU47BpC(jXltQ6&S*cet3GAtvicFD(hwHGI-PmGKwwCcL|Uy@9ja>aBSmV=jGIt>FLolG4hFIN zVC~NtNv+M?S#)U~iAiaLa!%bYRmCrg8YYP|0j}#pRIb^OB6Ws~52rASE?n}L%U7y? z!IWFGEABg(WyIrDN>YRt_0OQ%5ubOHECLnuvg8vltoB!SmIG?-b?Pe%kXfh7D&nHg z^w4-$cR)z9$s1{(P5y&a_~Fk70^?RW#}Cg3jF^tQ<}S#AL*Gt47FoVjMX`E3yDUqB z%aTz*=fEq2B+4`9DMmMw?VK2~ldFz171c1jV*k2nNc4a#yZ>UXTbSzl(1S%$!vT8v z)s^aWn?)K1r;qaDm-t_+t4c0rez?wO^ZT)y%+7dlO95YE+6ZwOSt(ma;bFbqH$N>} z$S_T2jX3w0c2K{?Z}GQ~(pQ)rb|sYy>QgX<7SS|#{QR6YJL^UuLWyYcj`t(2$RdCD zD0K&Hc{ku(lgSJ5jEa%(<2%X9%+jAFhp;(?nVn#=3=$HU@hltgGcj7CTwRF_tsA^` zJU%EnMcwUMy7VSqNIXp2_b^N`*gk5^4aZZx{NM0gsbqA#2sX^kks<+} zm+zYv>5RlT_Vsyw;C$^iKcTw3mo@iI^%ASo*YENhaXY%5dwICWCxTz^K9KkARIRFP zm%9>!t-Ny1A74`FwyXoY)tej(GxGBZMLfrmCP-hAt}J*xNA(Lg+ILL6iA-C$diKx0 z8IAEfmgAnpk2j3G8$-Fcj*d6$66ubVkyb}bO9JSweRG^r?(ydX35enTH1P8B@+^M) zRtH?=&^F!2EvQv2uxVg9bN1{zDY}Wi@)I~m)6>%KKw$${Adbgdd`idBHbeg6*K3Z& z-`NOY3Q~8x;z}_A>EMivG$~BpdvjXuEcgEjCOlRUPCVs_p2G8UqwP3BqsYWjx{MO$ z=aBJ7;Qicy&Ra3}+-ans)1nPExY>35lgd68QXC&8{gw`a*b@Z%sFzns#ng34JDiO; z5q#uqR4dJPP*SuTus!#uYrVMqF*--Szf?I}Dkfe|w#7GLJrg7awrs&rvmW~n4|?^o zIAIR1$NYiWl0G~mxlmz&ncaC-NONXwcrJ12ISXsu04uy4OTV~^t>@>?&$0*Xfc(n3fv#A7J(Z0KNI}`OV2FwuWu(}TjLwjp$qIs#uNG-S1JuKk@jfuPVsCKE$LOF_yWY4i$j4LIkuRvSv1F0QG*y#twSAlWImiW+tbP6k z)dS8dT}K{2*TF?~##g*n%G+}sRZW6Ur2??f)6++iqu)I{;Z$yvmX_q=>=Jpf4m5`1?D>x?^i)smlt|o?ko%6 zrWbe2+WHCX10IH8cpmO}9vUAt2kXK+;Wf|stu6TBceOwYn(M6mV+5C@UUiZ zFZrq^s-VFA(mk=8ex5`#svZ9LOQ%qKDD5jmla5H6zItc z>89(9Mn=lX%7N$H>FXL@Za;j+J1r)CWYB6>*vKBn3jJ&5*&tUNXR=QF;naz1Jb@{a zLz++D)y~LKSq(o(kKCc6Vma2CZG!pWi|0Rv&9OC1vLcmel`wDyk`5n3V+o!vtx3|x z^#M~Wu&`XfvWrhbB*C9pW>Gy8gb#_=tE538`43KBsnH1#vXYV#*B}SNE^BDG^O4hq z@bI$Be%-jD9PhhW%|BYrsPYl4RA^KAhOwoMal zO>x_IPhB}WFa<48P59u=VYbKXY&X;JA2`JctvJo}svP}~>BIBqq;PJLYO>YSWO?m3 zc=}()ZDy90oyP~gL6US*5yoP@RPLhO-_T><*FA(jiKr^8d-|e3?IdS3<6q$n4Z)gZ=c{&GWbBAF15&IoE zEj3lku}~q2CjH~bW4+iN@iT4c4Pm6OpHNaFzw>y$76>h^R>id?=?a2d5PcP-LQYD=~9#F4`R1K zT}}T89^=D3XKz<5zL6ZAiC-%tpTm_e!_7~{c_J<;sW(}1(?c<-%_Rl9j~$ON^`S)Em~*xVfbY zGwBO3Mf6Wbt1#(TO|A_!uWRR1&P0wRHYZ>sE!*&WD!$>)=;+S&xuW+F6d1}$V( zIy>eD%mpb9f)tj|-8U>t`3{UIyXKsPc88%Hfy7E**$L_h`&^Zn%@>z7A?sqlhI9GW zu`qu6GE7N`kl&nT@5RJye>8EoEH_1lj$7t1#9~4m_q6mHTv&1cy?7D6?xhvq+1`KU zjMl0LqUaiqwMN`rp>xv^;iReQ4Q|Sn-`@s))ze#TaLII9#~5`Tf}bf=rpgLe>XTs7Cuk6RUsI#b0YOs4SPa6dJ0m80mD{5DE)e{Orl zN?L$PHPsD|%`?SM`Q+|Z9Ttj6Qe)r>Gl?AcKM^e332Mr~WmMiL5x&zhj_OR5`sGQi)NIyE&C1dx&Q5o9 zAEG-&nB=(V;+hrzONs?5aoscm7cWY#cP_bSx-UTzJyD(nQZc5Nmn$VtNd1k6{93wF z{_+fx1@;aOz-V(!1q@oc7THkeHTlB#!4M|iPhG%z<@*3T>46alGo~n5l2}9IYx{yx zfYW@WH!bH%#%D*`jEsy#s-=Pw&ZxS~ET!AzaO|cF`#Y@|g8U&ce7roa#FxE;P5Ad7 zyy@4?foNW_XOQ!Z>giqonKgkaz^-doTKN2Ac6N5k1w^R3;C!_1W7))F*CBhze}v+H zile*SyAXZ|VVeY3C*th0oBsL+s&zgN2KTQun|jgYfH2g$ySwwREV+~~ehtGJ`~e}b z?O|^|oL6}F_AMb?+kH$mAbdSUFEB0In|a)E6)GVSC+uZ)=EyF3#`IWthNIy9oetlXK53@_K1N--HORqoea}+LM6S7rJsa z(7~Y-uqE^UeKsNrh4DC^YZD4Y&A_jmsTRy|Ztc%1&QMTD10SFAlM*KC>te`0t7Dd( zNXob&Qxrelh0U5U_a?6lDPYV#v_8?CLq_okj*Uo!Y7+sZ2tM^t`dlPLP7Cjey-=&w zQ#J>XHNLmBAPHof+O43(BrH%}eC?_c?&$%=7LHX-5n9qu3RSlUVq{nY1Zc9eBUH<8 zF2!zR&kH?HY=zGTYu5lE)5XO_+Gp8~h;X%~=ym?X|4RDsfzXb{@G_j;ZJYHJ6X7%# z_c|gT^k4CZEf*Co$UGthz~AGL>)JrNV0?=LRN;okFd^MMOEjQ={`#g3{qybQ0%7!l z%CAmJle9?YDMxM|>pYW@eq}e^p~e2HkrHD*mV19^`Er;ljno% zL%TO1d_;M9`Pc6bBOG-OG12(Eyu9|$pNR*uF>pV@<44?rRQTa+fS^2l^a!rQHt;9d zcm#kUm<(K*Ez}#9StDcLp}R)*#lc!cauybsK0G_L7q-=Nv%G`R7G7yt#Xq=wfH~Ux z5ob@mqC%p3*^<})ba=zjftJ&Q`Rk0X8W}B7*E{PTp8kt9?sTN` zJw_sCzP=S8x02fO9^(%{(^9GUuju13i<@NKBh&LMpES;xyXoEr7cI&Te=T!jD2o`X z0cS)MAm+p3O+#o4hdvenVQAYnK1jsiYM$W-#{)o+_Wix+%w6(N=O-U2IT&t4+|O&i z>udqq|ND%c=)a-EO|p8SQOZ&`IIW|Z95rF@3kwP{PJv?w@{qPQ;y>ay?)LynRV0k#{|tTUoJ+2ujkW)b>bim;3McQ6a5iiV1~=F)t)y)mIkb-&7~H{lA3Z7*fBDym{^k3qMCuKGOFWA^*J~;M z-$koPBFr!Pl8Lk&T$=c4-}C1)u;i0Je?IvvC1v5ok7Be5f{xWN;)Xjq!WJg-)t%pK zIB`#3UY7&0K|v+yNs-~fM(kKvS~qkT5+C7$fSbY@Qqp}NvY6vOW{k9Ae&FI^?jUt$ zFWrw_=`{}=nWeI!0@RgkBKgaDWa;F#kkU9QkGyXQ(oz>Ek9A(E)8?NuBCkZHt~gT8 zUN{~0?UL#adRyk($_b(>K%IBav!kTe&uEEt8o0XD0`$+7MmFAbESs)H#xKNlSndcZG7MPCofq0KBc-r^Xst((5C_-jXpU)UO2p1P z7kQX2Jk}(gzApF2UzRnU?^FbjmTsawK&-!dUBdRp+pca?vjtA?IX=ha9I?H7b2Sop z{Q;*SCsPV_o&UF*0w5F?W{RMOKx=w`*sXg6$xu7+l`PegPMgP2_OQTwI;29H>NW)n zbCjQ|3tR*#QAIu{&*NHE4hPz{9E~C*R#NDzn~6c3JsU{FxBo__D4BxD2dE!}0|gMK z49B%%yl7Xg<%G59#R_DI+Mq*ouqs;`6&&SAGe!`$by$pShS`(HHb5zsN}wi9-&&FN?;{d(taNdQB+ll1aS>!G;p=As{K_+0{2V)@I@|~Z;ARaSUN5g!i>aI~#I7*8N^f|>X~RTpJbn&tnx zu2Yez@~arRr`RZ&`~^W|{8Wmh3y97e7LntLRTjM2KrjuJznHN*LC zxf}XlgU5d+ha)moM(r!L(Oqm-f`5QZ^?A>{1!x8R4 zbd`__Q3@ieq@+}K5)jT~qWc-5Kz3-|L|~}gygZy09+Q2~p#u`i<$$vtDk_ebdFJ3# zQ=UU0CUR?qpIyRaE_6S|hK#cMDu2JL zw3{7nJ)U#=I(Y;FDsiY1$U5vz5}_s&DHJp|+^40)n6NEz=-l84^2>TGpkd+af=&!UyJOFo`o}C^2?z{Y1bfOPBRgXj1HGbtW zp>#uF<&||-%`krc0mTz;ts3m-(3HmON6gt-OQ^155)vH{=Tp$AV8k$f`5w7pXeJHm zg3q-`Q#>~>HHMNA`4ssN*a&uTi-{->P}Lk5&v05w+y|uNo*_O%*SC(;(p!7ZhoSy} zk^D90;n0P8ouyi3zA;-2hd{$FY8rL^PNQF1*YwlQmo^)R(vxWouiN~q#?7_s^tFFv zwK^Q%Jxxxw$CJmCA;2mc=VXB_5qSZ^I{+LfVpGta09Nh0a?g077UUmst>+N4h(7hPFi9%QLpC)8T$(a+sQVij1&qs3c;-hkRshLFT$;kKljajml7FAb0jYMQqzOi*W+FNh6@|~%IGktu{-~yA@K(LJOt7!f zmpzVm+wG&sM4bQuh261){yQkV*Y~$)@kt3{h>-Y!Lh}?*7!XaEhA0*wlxJeWF8B2R zA+Q0^G?5L2tRGG0m2*)iQYO8QjM^h*iN;Bu2hJ{QLw5dR_vpDm%zYviEk*8em~sEUlvR> z^(B;NFhD`AW_vH>a6C@gls>~Vh!G(rIB~q#D8NO zJ%@=PAK#U!{Qxr0PZl4Il>SccaUufon@Qo)LubMRb8+4JKw*&%`e8I)I0?NsQl26YVacQH7M`aTFPjgY zE;vr)MF`gbb!cGU_D)Wn2pkK*=R(unw_pxZbcl!&dMJ{vSiy*80=jihLTkVZAaZVG zZ4i#^%0DH(;HJUROR&+hQ{udI2>le3ft-fDCcAw8A$jD6cvcH~B~!tH)FUYBEarzX zD$<=qv1M zpe>{Rz$9moi2b^lQ>Kf;q|KwpbF@@34lGA%8)v6zRe#yVt=ca}Q8$*T{Edt48lL(bc84({;Di#Pz2FJGuFXo3Phlt!ks;5X=lG>& z(HA%!HMg}ToFpk5D4W}p!_^&-BbDnofu!*ZBO<+1ABe2=MCGdk|ovZ^NOsTwd|sHq36h zCT@0?M+z7J`Sa(gX11_rCyY$=fIU!Tc(J1yjcrRV%(x+IhiA>4&q4A}-1o6fb3KH~ zSN=OGH^1T_(JA}-3C93D{uLI*8ybgU2H*S(fpNiy2OJW&Z87(kW3nYxRXsqi2tWE` z&Wk*~gN%PBk-S`9s)o^=e6VhaFLDbsMXRbZi*PJ~r@p#IqGaj68r&{Nl$lh03Hf$e zgf16~YyfAq_MVrUwA=`lb=@AiupMk_LCj8NI9)d*R_!>GP=6q5`G}=u|)toqvsC}DK~0ql7I(l zXGjJHM&A#ORtXs_^xibOn)v1CtRFPvS9PiqB>kMbqK%&8ji0s(w1NPT{PT8OMAy-*V-4XK77|kGm5vxJgIkKaElM)EHXnRfq{QmwAkTH_lZcvC0x~X0Ne5yxn{_Ng_ITNTEC5!~fGP7;s-?}Z+8A~pTpKO}bkNTL>J`g%Zr&3+CFQbX8^G7B+1 z61cK3l+qpLVu`*7He-!GRReQd49r@+|q(^tW zUl(EX`c##QxY+>}?jVs<2c9+g>?RxJ1lBvp5i>GJV+uRS+8dzIe=AZUsN&Ny3%x?; z9kWjH**a`tcl7t~?;I5%euA1)pTl)6UqXdxloaw@J++bB-h3rfe3@}t0*M?_NR(sS zTlY;hEV~Yma;<+DfXDOZgIRC#t=Ki|_aA*#ZAvUuY)i7%A@Pg$?WdBgo!M>Omx~*U zX-I+9II@wv##x%789AbM{u2*0M+c>_}}V8uu*v?ra2Wy3PBU{ zFHKsQyEKR_H|Y5aA6?mmth3G|vGifq}@5hr0@#otxI$6t<_>hb#` zy+j=)7&kk+w`u=!e0)%!Qazz(j)J7BqOsgL|Jz6z8^~LN=I{AmC2Rf<(S{qc0-(zo z(CU#Sf1mAJmWm-UjL?z2>lP*TqIEmM3fu@V=w!yO|Jdr6Ho-d%`6cD z_ZZF)0;N7}+Ab0gUH$Js5!DOx^Bzhl5GP7r|E%_}nFDQemEm@Mq>eS)D3sp_f90Ft zR0O_&tu1c76zxw=GX_L^gR{uU8h4v=&oPIDz)V@VT{xIJ;V4_EC5tf)J zAq+$<^Zy6r0EC$cYR9_Apn%TqbJ0bjOaP)Tk^2UjAx4h~soX7t#(=->oKVsx%Cd-x z4?yuLZv+RB9w7*o_oOik9xBk4#9VnEPVh2_HXGsNl}fXbgxdzJ+dDr%RIQ!jIO{+`I=!7)-0;EupPS87ijYC&plS6==4?KQSZ(KC zXz#FO0L43z*dQ1fEPFymmn@%+gmU3!jyELgz`PfJ5?EHEbezDiV-}&mQM4$F zA&@V6{#y%lpqcyW)t{Ft+lb05g0g`Nc%c?!7I~7#dmd0w9_noIf8|2n-889(;vi=~ zx7B?(n5~B87kS@Zc%ZEpP}P-uO1jkZ!an~RjbWMu@&BZ+|L>JAT#uLR;0Ag_Lgd}) z96MNGL`?+>;Xmw2Zvp;uEE=FBs_KYpv=SqK!lxma8xZE~@0sQ?wA^hW5`e+gg4z$| zT$72){f~xvBg7}WKv;sB?}jR@)Td9$AAW8~dJWNX_aC{9yjx^Ayb@=c{t+lI+S~AC zY_A@1vbS8Kt6I+?`cs%BC4G2vdiS?2R4kO|%?I{6b`B{o$e|CdCd#mg z0{;5?;g^h6`e}co@@jv^wI1d+=Jc$A?ry@+bFH=YXTg_ANC;naX@0Ywx4ecFQ{n}j)tRvsqcSLp5V0dd2>byLW#Ws*l=kD}*;J`_F_z&$}j0N;XY z`+|9I^Ms55<3RL%qu$1}W%W7DlN-C_t|hzwUK{WAb~8NdEBSk}qoe)hHObs!j=>Fz zpO`2qnoPfb4H9HmC<}59A{Q9OM>>yt4$Iw5*1lU|v(wm>#=I;hA~Nyp-i@}NE0JHS z9*~b5rXdHay=58?a1p;5yFoOFsaC2&peOQqkMEik%P;en?p=`;@dc*uBImz%v1>QX zv`=2%u>Z6^Ixmv`@`pzP?Tr3+_c6O?yow+Z(=0;Ch zN=i!BWto>^N1)7q`BG@#K6cb{@^Lm-I8VU6+yPZ8Hyx;uFG5j{La$hLM zA?U5D_rqy4*@3B?kS8(0S%NzBX!va<{tIz+!C_14-K#~7=R`t&ER^Jby|Xp=?{7V9Zmx8AYuB+;t;y z%Nrr%hs^Zh{Z#6#n>Zrzma4l1XdinA7)?>^4%atXA0$R16Ay8TM!lYEIHAKOpW?V0 zL&?rtgMDnw2Km+kI(HmC3w8xiP}P?GgrhfwT=LDrO?Y<$@p}UXvSRC$*2SdUxP@D- z=O4fM#A?{j()|Qi;@)qbYg>hcl7=@&=wNbx-SxZ>X+za<3|ft$fspq4jKGl7>au-f zTkmrEv;JCT!KHnX%D=(KBcCU!CtI7ooA}|H0k%*(Q_K<`np>hI#l$`RhkULN?y0?` zrES58t4^Att)B|n&oFChgppy5{X0h*PDuUOw)@c$!T5y`(Z`Lpo5|Xw^r7iKes$Ta zVnNopbamBJw%h`JqWZzSGtnr2ny#`w!NK`)&+U*9Ar1BGHs30V z4=B?Yi~3aPWLfm+z(-BS786|U95tk$W zNq#=7wzhTzc@sp=Iy4Yy`Sgjp;P@>lL5irI*V5C|G&0(PNU#3UqgPSxU2U6p3UV>J zn})ac_1#9Yg72yTUC+Vb>HrMKsfC}t!y_a6y}aai@7^5|A0Lj|XdDJ~2(&xP@+{)S z7Q7(@pTz+0cJ10V=H^$}Qmyj3riRcvtIxW^V}eV0d06;qN(vFTuYsnjZ)9{GK(Bhl zjo5P0?rA@+N{XQCFR zC(cX1&OBD}<6{V>035Y*bPUo>nNbi>aQ=dhhv^ZIAK!!m%OzR)dpCYJX*TF2Kp?t@ zni!a&N~}gbB#HXjhe|`Gb05gRL7?8?P=ro%;W?{l<5eG7UEFhI*+ zMKZT-g!=W0xx zltVPKAJbeiv%{>F_P#C3oBW`ovh zL=!dOa#@#e)F@UaKF`2TnhXCSuS1C>mAbXH@Xdq5K)KG-Up3H`%C6w}$s*@tb7Qq9tv5$`AYqa!S9&L% z=f}-<9M7jVH#aZxoEF-8_<=vH3RLP)qS+f7^Oju&z9Urun%_Vm=n5P=x`vS7HM(mp z8QIxm&xJ}Yx)f#wZs~~r(8UrF65)f+@_ZMebs~ppan3zqmy1`-Wl0v(7F%w$~;JTGG*D6iJXUBbx zePy8|Z7EcLzDy$f#e%x~>&OIO0j0LPa6v;)kFn8qkDEL%R^Sx!(3EGJ9#3ZpYqJ~^ z+roGG+nt1hunZ3rkr*O!nfUr<2ITwvkx| zr%xRnlm*A>V|A&Xv{K_vkmq@Dcq{z6uP{wb%RG0%xYl%tKbm%}!R9r9xxT)X)UySw zBj@6ieRUW&c8QZy-c2u%s2D)pO4juU-3~Tdb%Pq%W+ak)ECYC=C!_=^=d__VAits$semfpK}0H=y+fqm4a;+Q>WPop;&vD{cTZ@vfz7E`ZwGGZJ)z&b?X zE`FIC z(6E*4TH4FBVI3+E0uCgq9zV{7l@<{dbsbJzd-esQA0sv%^as3JJ>dV|wi>GvW=H_; ziTbKPwwJ>Xr8gO-=x!vTg9Db|fkgeAMLy4thNAc!FM$301zkuUsQCTy7t6;YQ$!mt zxMjgQ&#u0*sv66#{JBu9FUpD+D8uf-D1Lt~MBxuN6g>~W@~=(v=U_j0`s~?$R*g)H zaxR!CecxpqKKb|m{;{vfXGI1($qUC`dBy3P&Ax>JfUQlkD){ip*5MaVqDAu$a(V4K z`ud;{jiT?i%?)AB-+zf9pY(df<<)om>GpcSxoQC4IDhsTS8ppgFDfCy_X0qOfo{1> z1^wtkkrTA3nlaAULdkD`pR-L*Pcvr5K0rAIQ_Z=ha~0RcqQoYNZda}F}xC>^wt;wTe5iN=8vAaGXvUgdnqE&CQ4 zMv`%4m_9cqZ`-!A<(I(}kF0amq|ScqFDgJFO-|b=uwgJ<+6*A3_hcl(ddS=%v}0^% z^dOg>2IuwolRt%TNK`CDN%ni+T;OY6^l|?!drVB^o{q>pu`S1RM6ks1z4|j29fNV7 zolFWRie1hK$P5y#FJM(VHI9i#=~M>k@ianrqU^Q6?T&jWplUD_K|_4@_j)WWh*reM zyxrenw%bYx>o-=nb4U)0xU^TGA`tzS#8t{vY;&&O$o~qkwu$Y!%7`R&{#%ZHj;YQLB+f&i+lb1Lvhk(v;!CD>=*;cNd zA@*){_3?3X_0jT$NoS*%8xO24HLMR%+re_@;X8beFR8IHCj(;0Xtv?;j6inv485*wc zgXvpmjPKC@;u3EVVh_AlUp4lPzu(pR%gIo(+Q0jWj-&z#FU4vJ7e0bDOmkn-dg=20 z?XK(L1jk-KvTIvkhNL#EiKu9Cbw|Jyx*GO#W%Y9W$<78ubz9#G=1UE1-WkK z&pvNF_ttt|%}s2I?uZCX5)^B+`~A&1o?)&cbZ)_r%rRb4^S0nd)Zo*47LXf5zm-Dk z<4$$&9|e3;!ecPSbHRs@sxgt9p0Ot?3Z@8Xk+KDe5h3YqTj{!(*%KC$TQ2 z?X6HvpQm*vd@>gIChhS%OF(YGnc!}NR=Z=?5o3QVFomYYW_O-Y1TouQA2g4JiNG0b z_SCK_!p2!qQa!PbV6k?Y=|ed;cDzO(js=E7YAFE%di*Nz<@0ZG`!L_HDH`l`?`|ty zDaZKO>)T#S+@mE^UIqfwdH$#Og9t#`YZ;qET$aI2-n{71o~MXxKPf2K0u*uIT_N=K z`?g*0{R4!IKo1yN**7k764U2nr>FdZu2A{1J59}682kqsLN_RhI|xmU7>AMl0Ckq= z4zhi03X=6YlWYqOD5IG@+GMJ@V*gLt`0NSLF0S83vId@u6$>wx#v_begy~D`7j|k; z^wk9pUKXS&520xY5%u!?agk+1(|6(r)LChKz$`G$2~tL4+F8R_ZHXu{&=?tTjG z#(<|a(4L8`{TdEL4ty+W85sb>C#k8_$Z|;oau|RaWMxU*yLZnD@%tBD4yL6ZJC*+| zTIUxQ4x%7BSb)0vW$S>m6CiAP)R5fgK<%*8s04922_}5#f)sHPgJbV^W4`;|U)hUb6PopCjr|taryO^`Y5v zQYzC=)u7ka&PAk8U@Nj6fjNIb_ZLUsQ{@at8TJj??;~3oaP+9F|EiljmehLJNDEnl zY(a5xT6}(M0ALr6d1TB<1;;1MlV84M!yKta#DD^)8Cup5kVq=#Fag(*XLy0iKBBMi z@bGXI5Fo*>aM!r%lcgT?(UO+6sHhuomIVt8K^L82H~C76TpX|o>FG2L4GoLSW7*S4 zYYXFdlU|^y+<0#(J28*WoDl&u!b82Mv!*wPo^1F;kfUX|Oyc)|;!Pm}kyKX30|f7h z=Fo{p)27f+86bfG>x&?NXMsJxqJd2vN}jI+cMz;9Ni+#F9s$G&SH941{=C0gceL^e z%ry;d+aI~1i$CS;&sSP@;#lB2PStU0?5Y0Xt&)G=aIs^^$3)hp^u~|TvT6x?dO6c? zXSZ+;?Zoo?6)*Ieeo91}CDT|O9QiNy#97~BC*Ak&SPl@ZkctXFC@Wa8=53z+_}E-b zRLWZiDF6-;21&p)2D6jmx5R#J;?D@xcN}Mbr753bMRdVx_a%t~vbVugrmT~ZJ zwL@3uDir9T7j$|5bZWajD4qdpqH#uItKGpZ5$mcTG2D6di1xX07y@oPEGu|`M^kiT zU;C|g`VFA+W-+XCk#=~_3n%pee74tU;iqqCNI?R=9v&S%aN-2_hW)BI{}G9KkFDqQ z)h>st0$P`XXKyP1RlyRnvMlDSqYfTD0o^0%`hau5f~6nijy}KYotodgv-KBEX~Gjd z)Yj7l(;nR0D8#I>%~xjg#^6k`27>(@c_cG{qWz$E-(SPc$U!BKBHD9-s*xfdJqiO+ zn3MK8FvKoSBjy*NvUm!d;y~K5r037+H*MNP?0+ZjQHF}7bCevkP# zaeX@3eTi%o<|AihPm(e#SE|m+)@d0@n^3J77Ph|6l@j_zQE3=@P|sM<4DcGOgpyR` zKE{U9i>ZziPOpF_b8}fp5fKqmb}gIv`6r*NyUNG*jXp;@6%Q9{2DgSku@Ahm*)6zt z?-umpsKL$OiHlP{y#h>kcwfv!j2MNfg3`;Q-Sf)q^PlnN z+K-e%Nm@+eiHFI&C&&c^!4UlDB>frP=B5nK)InV6?^CgNuX`uhG&O}gWK<=p)~3%nqa_qH1n`p9QE z6E92`^Mr+N_!1(vEpa#>tP*@An%U7@x)6RaAA4yFm&pZf3?w zB!@ve;6fxpTGM&P5*ivxOajnpsB~X1aTB*rdqgT`;LnuJ;ExRWCV23t^|psu=4ux&PW#iN zbw5kWpLwUc{2AVTP7EakS3=TEP();-SGjM*-rylOc_@Mmn6TIpsIPumD8WDTPCdpo zdw9qY*Ni&~NgD1=ZnuAf)Lbw!dzq#=NzGm|kLZyOm*Sx7V?wPEWweAj*9%6dzQ2CC zkgACDppMU*4)HDUPV5O3w_iW`cYb}(@7{CHA9vgs;|Ak>e0c))-s`*8TyxG(Ohw36D0nVJ zWfA*m?m?s3W`O_gk?cK5GokszL3(!+E$X`|uEBT)B}{@8YKdiuEKv4F!2N3QI_zp; z1eCz=eSx7eZ)`&uj?Fz8=V{{hyYE?d=&$ORLcoV81fR+3nBXb zU+5*pL+osw!bVCq_S70HFS7@5fr@F8-{qB!8YdyM(Qn>Ea=!POX#xgF&+m2>DWFtD zWlnV!<_PXsqT-3)_jO9xzfJeZK>ySOeK@B8{jp?9*viD+qCccbnzhV>igVD;(| z3^%C28z1;uH8gH4<};|Ktr4i1r1HkY`|!^8En4yYGpUy$g8fTlK8+P~@9tE+cI&U{ zQ7=;F$g>#uo2jcB+L9d4(^{S;BYtS)kMsA)|I;F!1pw3#;`a#vKyUkCviOkfna-~m z`lkaD#0ihZkx>K`9kEJS@4nu{Kt+9>EBsExRhnBx|808dM}=`WiNpyf;Eh4tC9v+j(eQ;@(eS0$ab&|!V(PxVjc>Jq2WKLAuMmbLBX zF*y#A%9Bv`tyARjKF~rok$zXX;l}B0=ecx+sOK7vuNErM%;9scEe(qH3XjPNdh!?y3WivcE>YFjT~^yIaBeaD>81XQ3*boSqv<`{94cH^ z2mMSqJKPISm=KNsJp4r&|C;TF?N$clYV2wsJ$*H5?aw=!mNH~-nz~bd+q+L9RURSy zg3eREqAqXCg7IqA>l7tA3jKH@&5O4nRA+pjsIb*w_0|P&`vIhXa2X0&mPPys5a&|n z_*Za4ZluE{`tP74NMl|Mbx-KHZpP_W=knKkaBQYxXaeJ(` zpZuVEtp7OX;|3nP)a<{4SjouPIJl~4MSxQ)CbLIwP=b7$ zcy773?9@@7D96V_ymuhcTBa6jir{j(gUGDKoh-RY5(4%pT2EZNHQ(mT6ubo{noCr|I*E)4~QNt)sno5U8x0Poa6EV^em91Gi4`pui|jeN$Brr$=-gJ|@*(-~FQ=+L+UBnMSP5M zerPDfky8-$L7e zFR0?o!ycM={%xXApnJD(51;R{75A$9UNTknxI(AU#yd=FWAG~Z|LbMB7mV~__MOFW zoUEpBb8|ZwDGQ36s`JUu%WIv8f&>adN&tCAK-vnhVf&J;5bVee3=WFE>h4lh|lH^&zSwhKFri=mnU&U4$GReB-qMF=%4jEZX2 z7Hq(ViW8M_<%8&)q$iydlD%g zdK-KVs2_7J`uA%z-?bCHp7!`=&Ch|+v>n4k4yOtn1PK6@X$77Xae8kg(A{jI%jFC0 z59pepSOMDxaAMjE_(T91_74nTKxGW5CX`zntFWH|J%<9j`^y)AW!r$Rn39nZ18uYg zXtF~o78Gd*$RmvSXooffR`6z;9HHXDScGEYts$SaNTw^`W!6h)2LA(K2;k~^!MEt>4x7-4wWt;=MR#`* za7_zyX*|SLIGH2s`UsH4zc0%_Vy|6eBaize&{#*fwxRePM+^cP9E7hGo67QcKd{la zx89RflYpHFmivm<)@0xS8vt0pO1oz4wh3T3aA84{4ig zhL#^blrvx#!J?i|0p)2;4IO*}y+T9ynP^U}={d^ieCT8W7s3{bRCo?h6{_F3K?z1F zp&+e%n2r>@FvTDa3SL&IWTQ!$S^-QvA?^9EnisTv%7F0#jVB7qe58?xbUj4w5W-Ip zg|~zt?-7)DNRuhr3@+nyC@cJDi_6Tbn6|*=VpwSVcvL%94}dvzmRmn z&8$28DGlw-Sy%W*a$Vj#@Avo>VEK`afzlTbH*lH-u(NjV>;RG3hyRb%w;Q$)3xGrd zcNg^cHqM}j0#8RdcT?U698~H7=Yu|Y2ORQKc_YFX(1?wHD0vOKSi_W&iEm*x3zP+3 zbQ5i(w1gRm#abN!Fsbm3QhQvG&A`{Q%v*9)2 zQUxRE2>67*Uw)nr|A9F(&lRSMM8L*P})L^G8|#5 zfL##Q_o3gO{l7f}Uy9Nv0F4>zX+m7w>b4154R#c%$vX5nk^3LIIlwUuh4l#78PI^% z7Nc`Yw=VF}!dRi>iyzjW6VHPU$s5EB4Akzfm$fqq#AVO8_8Lpr{&VDoN>&0mwhImF z9HpXWuWx0GLvzn+`-gs&wPa({7@A6S0R>z?oEB8bEZ*jHYG-fs|ChAtp2 znl3{xU@xHgh`S&S&SQ}IYcK12e&F&dm-<+cVMVBiG7-nN>7~DlxjD+8e4p~s0duTu z{aw|+tp5}ESzgHo>;_;bnU3x0qJKlCZlb2Hs{b{hAyvf`66BQhIadrBtG0I6>Kxt3 z?>SH0pZB$vKg<|av8xVbAZ}3j^2sF1f-7UrBzRhClrSmsB0eW@_n?A}u`vJu0!xHF z_G-g+Q&uG1>=Gj^A@K(^^XiS)vt&kBBAzZW`eVL#{bVhxOqY20cXEMRng z({J3yRC~81ot(E@9m7tbg8T^iCN_1+pIklQLDY{TWkXh3(8`UGibF@mXxWcwW-P+! znQ8mIw^x3mMhX|4zE>l4j|%g4=)*7(fBd~WCPjFzJ_lcRx0TDg`soCcVq+yCmf3NIHrJ?OERh!Q;hPF8zp@Fh!*L^F}Y>)Y9E)cLCoVq^EP6a?XP{v)TB|Ham* zAZJxO-a_6|g~}Dbt?{TN?w!AS#&27vH)_tx@c#P2I`On7gg6PBC`(CX`eZZOq^O4~ zn6RcIq~QPd#nwq`@V5)0faTTYrgICx<5#J=v+Nc1@V?HmrQLmOVvI?9?BA9to%>G9 z3F0R6SJ?9gY&3z@e8GF+&L=Z7k0Zo^RcIf zyG7gmYs1yTt=o)*)M+kq3jGLMMe0)^$?m&YxFEMT;bZ%CJF?yW(8e(7GUJfLX)MLr zUl(OOr*YAV4=7awv5!Rgo++HiDD$#DvFqsQKyckerhm9Dg&InCgcVr{@J2vroEj5m z`aqS{%c6fDsHUvwz2TRQgCN&q4|@O%!j$&Bm_X9T!cHhoS_Q+r^M4UYn^36cLoi|c z)2C*xUVU5n-|~bL+}nNjf|it~8N#IXQc(UD(LEIP{hKB!-!1-I!LQyS8k}+Hckvas zR66Zpmq+$LbT`)QPY#FF-v%0z=WS!jK}W)uwZh@9zA4TZ|>mXp(^9X~lpHLp$rxb00b{PfkWb+DCt|_+P0Ss?2A`V$pVX3ov9*E_qa5^qW{m-K zshn((`T!F(vd4~o^pN}CGs#=-AXU!m&VP5E#LsGBU)HWk3N!qSVnan+!|t_a)N4PK zPx0~hJ_hd}n)KeOF)^JQMr=P|7GV@*UIS;IXw@Cr3 zL@dXDE-pf=aSjY&3JMEbKzXtW`onyn9D*7~1t_{uiO+f0xvh;~LEht1Uv@O02|&dJ zx?Aqh?-SB)(7uJhf&*D;0cc#E;0+%SuZ=>`*?*s`!H)`ZdFVbz@Wkrzohpog5XBd? zkO-3)0UnK;j;N3V9g;x=;v&Wc#MTCMBg^aSod^TZ609ULfWZjab(i~Tq zIF|zcD#{8lNfQwN`OpFPQ6CLe+OWeFG5W6seQjVLzl9|I;BANs0TT5B@E|3C!;7|8D6VmC)RirB66@pKdY2}HLq(PHJL7V!dCkr~R(AT>66N=ha#@2RtS{8- z038bX?>Qovai9FLfT}(=3Yz=uP>9uC2N)J;mVl+fM?{)5rADiPa?n=+c!xR;2bg(~ zkRgQy0QWG*(hlM1!kU&Pe_8Wh0OfOre4yVfSr9ERFE3Qjuo-{|eE`^h1*|1NPs(MZ zpzndw&U(6jPP+pk)WbdNT@jwl^Vjzm$9C2H1F;k4yKeYxk>>8i{U-!4L|%cR?Jj%X zZ0b$Tr%-=^Ee{3?s9p%)6&V-@r9eSR2{ww8lhYSV)DkI&uZjUm!ZckDfH0KrKxl)4 z1O5b=6)+kAdF*Hj$3uA9&@oCHlYebM0OV*OH|FN#SamPL;{tP;{R)7s;W-0TEmO2T zXI)_e%V8}<>$*NEg=Cq&AcZS;ol{0B0u=*z?BNi<2GUTH+B9P`!JX3u>xl_qHUW+njUt>Pqv5Ur>^VTzZaid%mIsjp$7}J))wJk6&>l zzIg^?;k_^^$f8VkN{qa=(sKB+_h9-^LmEsLcko8_$+lnGgm zeov;HC9sv6;c(~Z@gU0$tYlc;xe;T_-3JU{d<6X0X7CP0IM^S4Ak<>O;EY!6;aDq|DA-n{=8898?0UrS1tpFKx z6Id|EftSJ6bTiKK1QTG+$f4iu;3b0)ZQ;x-mW|rNb&k+xq5EQ5+6e?rh)f&%d%R+e zD}AceMVhl&hnA|ujoHU$`J_FKUIEbx zlD9W=#PLEOkv)pRM|~OPXOnwKib9xnzrG_O`S5@t!3iJl+%6UvE(=e zAy)8WaQN*%7THX;KFOGFgI4G43SaQ~>3jphTZ2(<~b zAP9kI4${{DfW*_b2r(RSl9fF_*#=&UVnBebr}Py0y(g`U`+LO)G`&h2wrM?oPW`*? zm9@OeO2}?kh~U&ulD#HwYR*(`e=e9&Nj6)sMm*Tgc~aAezhB6Og(@*1`?hP=>N#Tf zvp`fONVX-XIJZ=l! zx*wt9p4SpYwa@>ynP<=9ymmdV`cHMJ%b!te_iuaroDbY?ZEB6WxV0a#B(qw-7r~+X zEOw$PLlpPXqx{X`hFjMZK|1GL#+ra(7~$(94L#Z=OSO5n2XfCCgPWOrxEsADL$uv< zC4(rQb}X{#r=SQf(Equ1F#655+P(=BgYZQ2c{ulcx^K7w>freM)WNtL2~nj-xpQlg z{PDqJ7QJ2J+q{7wlHDnql$@A0$}R0pO|y;iyeC!D?IcSqbB|w0PM>D$DK@V}yf&d| zqUBS1L|R34ER!^^J#ouqYD$lg{a3+8*Nvk)2cZr{mR(w^=;Daen&g*aDk2rBknwhp zTCv%1MhkIT!t(-XV3R4swI2A5DjVbxdzo0rucOA-O@492iM=czan0CRQk;88EcenQ zuL2maMrLO5Kn_s+s7C#N1cbL{eWoSyH2-B(_Qf-7%p=md--TSa>6&QI-=3BLi4EUsvo_j zXIb85%!Xw$--Z?C1C6N53r|6xI&R_MuD23FC>;(~K4F za}zff#mX$wf^Egce?yP4iI%$-EaksV2)5uj;voqq?boMRG?x}Ma6e+UMtRSpd^O5h2J?Id6z!LJyx!fb~7?ad9Fp`EcTe-@v z>&HtM>nF9=-@k=w$uLM{1*=9+te6K$diR80?upW}afb+=)bknb^7^^Cdvi{V$_w3* zr}{b(SIOb*{~p~N4!htnJk*dxMV>=5-@m@Mq3}5S`hjrJ)FIBv{cWmfEu8Dxq4vby;WWYcBSjan#46JiqgwOa7<{?TLl|uaxbq4 zbSbZ4k>@u1e4EhJTTXr@6kko&z)ni{`BC-H>d+tZBeti!Y&7Z~SaxR~?&_bG>@m<+aIMyGU$SrCf%){QLOiJDA%@xnTax+ zL_cZbSl`DCvHH$DQ5{o}TwN^XP21W5{f8INetTmm{udYE-n?$7XS^72HG7V$nsURr zUn%a&q9($JMe-W`qPw0PO@4UU)W($2gUCnGa$}*I;d2eFE(=-DOU^&#^_YB%gLdGb ze~3;pJyqm7PH<@9(Sncu&g^c!<}2EV6zqg(3c@dXuNSJO&VQE{xU00@`<|9jpc96| zI2^x~k$bgChBFT{ooQyl%2Opi) zv*!r_u zE2tcX{q|?8@uxU@4=>i+SDYT-bF#m+;`w5=2D`Wp?*eClvs@&{_j43#*i?5R?3B=t z6AxDJL{Ah;YUTd4VuEsSK*NRRG3h-}dg`aQgv3YP6MudbVY^~+*Invq#?a}=i&{MGFR>cZ5GktAr(XVXG$RnQ@B0xzuD?Rgr(p zd=t~4y%GMzPE~0$X^mx;XyQHu3E#iJa8GJ-$@v%3Q7Arc*-)SL6aKTM(o#)B&e^1O znT$6tVwy5G!F-i#&2j7%^GWRo>WPg2;^N`($Z0 z((P2s2HQ zgWp<{yol<%W&*t}T$IyI?F<#zu7!;jmbv({W8km1?6~@lIwtk(HZ>J!m976St zS&+y_)4f=D6xQZpnW^&&17p+#VVy0XGHw}(9?7%3@jtMr>-34YEnGo(BkT|9w6A2= zN>c$#0k7ibUoo?hw70Q3r-ecNqgZT=+r{|0Yto0P>ccxJRO5%=mB1!H^n zU^K9Qt4o6DTQ1;?@h26_Y5lrAHq}n7WQ;%#2}6x{=X0IA!=s~-b#!8+p@d1YvP#cg zmcKIy;M_g7y$LCH`RQ>~Fr3thvCuK&5+5FoVns3%8l8Ww$(7Ofl?)fkyZhGYNogjt zdcQR3T^jtw!9cbf#xUos+)l7_tVx<(b#lTTYYtqkR#k5MoEr{N0p=k>E35! z@NnTYkSuiMaLLND#c&eHo>K@U&rt~ZE_010`v}N(bsZyS4Xs}%D9mZ=XFmg%%Y@9z zV`B#sdRMpb?!cQqS#AHg%$8Ohlh-C8?F02BWkLrp&8ID7j8Z{Z6GM zv;00*QZ+kd5mfpAjD7#e=7JHYKueSNnao-CCpic;NLpFODHo0%>1^1QGZ2t8JRICs zdb^{1VrVwA(=|_o?s5-_7j{5I!AMnd>R*P*nr)6TM^RR-Gvm}k!_t_zW9sYo*lTOw zhksX3>mjxdzWj=t?s4R^w^w<{Rd)1u@I9BgBwj8oERg`F6!X!tQNz^#k#ed1JJS5p zDf+eYxQe^gu5Ts=@rgRAr*|?{fLU`Z=uJ-r(9qmD&Y7L_@SnUm0YFuro;|G>ON*fd6<9%|B&M`pbLXOQnI28Qo>C>+M@uQd- zrCW;;-0EiEM2ElYWwqpuJ&HKbZtzcXdEa>4b$-=-aajB}FG)XEmogE%p%kaVDyo6k z2E&E%MA1!>Y_@^dvTr}ZISu1_))A%Kx1RNfpJEEq!tM97;(OXX%iYM;y;!M#4%oDa`}g7dqt;gtWZAFMjg6CZO2 zTZ0%I9IS%r1-E?7mFvYFsB@|3EPuCEoaE@@oT%F#COJ|j@3!m}o^OeA#9G3JKT@=r zZ%WQQ^ove<{U#_e3YW5|=vT|y^~kT{7+3EwU7#dubGX8B$%)(SG6zgvp2LCLzBsc0a!u1#+jREJmAGRdznDWVUfW@6?~CI!S-UGv z+^~tjqENP3rxo;Lp?9UetD)WHs_*o9c|f(n;Rdc*mSLJXzQ^AFt=me0xAey*Rw|`P ztq=a3bj_X68l&4CpI_z0-@m5;vMWEPROn`vc9oeo1^ z{ZT4WvNP*$WfB;CBU0UVFO8@KxD1V^v1%q0U_D(Wqgoch3EjXzKvPpPDk8$Azu$_G zm$Uav0Oh4i;mMCZX{D!>s?F35Z+?v$F~vtE_nHgQD_~m@CbC^zbSXD2BXzdz&+$oq zx<{v~|0rK08$S^bg^s;ToA5jZ{uy>IMP7lT$F}_onSB+pD+w*lq0d>3+K4f-xx4>l$H$9cRaG_C6Tbt{8RxQc3Yqos~ZPD@ZN!DV{ zQLJLE3tH_zKAf|xth~XSFuH5!7}~PQ`_o;b@pwH~e8h^Ew=UP~NmTVo%Z!t1 zYYUfVe3nZuVXd8E2ERS)_(u!QyS3WWExy{UX;`mw^+R5SUu)AFqkYTKTUTzaI=s~_ z&9=V#xpIveP`Nz6_sl=u;xQ?@;ZKm}{{42oZO%3o{?LWBaJEL%Q^|y{2YjXdc51;l zA=-9dHFa?EMN%5~MkLQ?>45rLKT>!1pl}KfBMhF<5eJYHORcQFRU)TH9rO>1pe$T2 zz=vbMc!vfSja|;1pk|U{koLlbGm_Fz7b+`9=YRIx(bW1ulE1|POCH|$wk1c&g+qAj z!JnzyxJepG@RU=sPWkLaavG;u9%sqbkylopht}6e!$OQZ&e)&e^WD6X$P$e9J{Ia; zv{>HtpWEWZK$*QGhHq0cOfa51VWL=he_QJDJ+S%^xi@m9@<<>+9-}MioGd_|#IrV# zR(j{WtHM?xx=olE3$HQy=TA9FKTj%CQ(Waz`8Wy==4c(<;qOP`@1H$mu&SiCIoRYL zXOfA`qv+|OmdpxwJKAw_ts8=~h-+YQ#!TFEcDlh0TTJT3H=W@Tb38>{eM1!L@n?Es z`WX|1o^lxSeg_achIy+)#4zk2|li_t3jAiz|Tv8Ls-NM;F+`odjC zg)@BFmuM7N(Y3k${V77scyQg7D6b%drzmVSx$>g&WgjJS$K+nQ&BMoVmcoXlXi@#c zVz~0z7qqm_F=xY-2f(T%f792Kt!!;^w@Ba861z--Ade@f=Al4Qaar_0HBLxOD3$~` z2Kd8U*gQG@3TR!gwO9~#P5tW;f4#g9x3hQ%?H%ax>H@JR*9~Dq+^2l=C=c9OqIvjc zw+m;t56_t-aYZs|+-sP^`tcP>(|be4$5&^!c~$(9hK+J|x%I{7q_mN?v|O$re^^k_ zo!jB_B%_=hEBBtSELF9yh8 z+b1!#J`$61z zyFVXc;ga~_i*pT3E|z&1MlO*T{BZaOjnK^_2~N?+8C%ne1}z>b%V7mDaQV*|2KZh; zBVDHji7fiTppz%M1WfY3wm4NT zyF{5y5Au0ZLL6;dBwP#F@%5ApJTiJAAIJ~S!oHH*N-QV>14~}@&f+=7Y#G;(1AhwK z6k+|IjSdeSX>PB-I3F8nT@!C!(27!?i!fWqPR4GY88>(>jaN0%f4{gl?l1t9h$|QR zlChGj2*0WFJlWObc{b}ws_wDP1FW;5ba zSZUdNNS(#QX!u;DKYX!!JX7jA!{l|=*@1K_jP17aE&OG^SA*$PUi>?lyX)z69Xo*oS*$K<{A}kD}mEpMBqZxeb}MTcGfA zKow0@KB2)1x1Amz!?*L{=$##fmPLA$VpLRA5BwWN^au*w?~ueMcS;E>KIcljx=RbY zlAitztBn8Y;ig7}!F?5@?+*$JGwBA!4Q`y{LdNjZ9k1Sk>DjZ(DjwU*;&YE7P&)h2 z8{F_w%9kRIwzcnOV?lK8q<3WHWj!Nn)liA~HL zLPFoqpY`!4C)sd$hZ@|%dg~!{{pAS(DhEz@WNRn}*0hSnbU1kjucXgas!b<3bz+smlp83=g`AI;b zs8REWU6#?Nfz-@N%*c+cb<`@B>luKk+S6kRo+CbWu{vDaif?6NdIc>pA(|4ZaeRAG zLnl6=ifYbL+Q7}8=og~k8@V++s@qoMK@>*iuD-yMl2QS}&>42Nxd(>E>9fZh>5;Oy zRWej0B$O$chooS^Yve2IH|CfI(s0b0Nunn!0)My9$yD_T;1$C3qB}dolH1flAP8F+ z%K|B3SDrxNBs{kJsGiMIk};?|(&BX%Y+K>L`}nia#5eWjUUo}hUa1ap6egE|vKpuq zov>>GaROzxFo^UJ;8i;7@X@&E`&Y-|B3QGjB{IewSe!l& z;~|`d0y-o6x0^##cfX7myl|u8KhFoYJiHYJ;C&)GF_?l!1|Nr3#122`Z(4Rvd3pH~ z3#nJ{Bg%d72KJW;__8Jr=yot^%_PR__ZZB&7wV_6&3OJi&VA=hubyzk^2(`^Q6y90 z@ya(pi6>9UJ|6mLYg5C9D>Jgylv2Qzz|JLg_Q6%HaI*gWdr12-VFRXJL0J?1?yhlm zaG;#3K2DMbp1$G7hi|&l2;Yk0UAiRYDv28{8-&{QyHZg6oUC|+Sjj%3*US1;7|J51j(5r)`dhvL4&J?5i zEE8ws$y-$Wbv^2Xdh_k#+}ii6`>zD~rJKBO1;?)sj$`L_44w;wt=3?`p+%YX#m3mg zy;6R!!4imu@e%(h-}sn_>%hS*R)Han>D#rj3M?2#>*wYC>yJIs?Rg08Ufo zFl7souOQZEz~_MJF43^r5IZdSY%&;T-wfB1D^S>B7XZRJ3)}=yrL*DKfi3P>tr!1v z!1gr|wIa@J2(o73JBI^u6bghb0Kk6*kUIc8&j&?2Ogtfbceo2~p2P?^3Vc|^@(mnl zft$*Mj@4e5X|@t-Ufs1pNS?pBf=BuQiAH8KV~tw)UjlV7Fi^I@c3}a`P?dqKjX2T3 zECoie-zI)nJs-;)Bt2|iS$Vbo{0t>L_QrHpSU6r<|KQ-BD2q@I4iU{u9MlWB z)v}0ZI}=T;ZWdJXC;j+!=ApnYAM0G&#(=^1TW=Lex}2)AqKqa^osI)Ola30f^)f;7 zhU6<;+qo56?%3Z+R!NgI5;-&m;dJ0ny7$uASDsb2VBTa1?Xd|i{=Clzj#&Axb#)<8p5- zCr!@%ox=>eH@n@KJ2$+V5B0vB2YncqWB%-)R9X4KMD2T1-kJ{~MTekPsTNl(JFE@( z$zhTmWT1-2W|NawZ>a|Y~%T&C--M$%dF!A6QO5)&u~K&}X5^`z^^A*K_-hLJBV z;Oj?PHcIq%2&&1X*1I3(5UVSo5^ZgDu`E<{F^7YxfoZ8akm(WqJ-o8#K1Z&_L9gZD zW|zVzvSdXuV4NB>P=9nem=9h!^#p86|P-N_wr}Bz9dv_RtPqc^TlPJ zu5}aB?*yLyoz4FCLbed7Akt#uS67ZvkRnrqss6hKz(iEh{OlC09}7ui4bJ%9-!PX? zT73_|!fQ>3U%p?TT|r3j?|^3O+h76kJua~ETb-(=s7pT5D+I}2pcFLp1V;k+__-Ao z6mZ&r{0~o{rOU(J9U+kbt-!9E926Ri@&O11 z1`BDrBCf}4XXoWIu8K*aSht02)k(lIP7(#|2I3deuYY^`%dw@$RsX%p@V)HZ*rbXG z1!ZgQr@dMWr-d(>YN(Lnckkzmic98b!FN>0>bV+Fe#J|;a?Z$|F8$$=l`e9wtG3x3 zVqjD}rlR3dbxIQ6m{Udjb5f**zjvQS`N($*n4Z~wTAnj97cr~>^ zMExRMeW7i*FfB~M|5v6<@{>huRKbXaB%`}z7R|TqPIU}6Y6hDbd8SW}!t>Mqx~!MJ z2A=H_2An;lPh=ULf2#nlti%UjU2qqA1=Fm>YBx`|EvtS+_2HfT*2Q(4c2qUb0v*4_ zm*+mDqZYRr93PH7nK`}8;9ZB=mBihA_eM^6f9#JB#lrS_M5+{$fu;#b@*?xSf;VQj zdxYHWM1S=uKz;H&YywPh@b}h7Y`e+1U;56^IDI-_DZWK3+?q(q{Sl;HXsD(~EiJ>P zJc@D+kAOEp0%Jx+Oik^OvzucWn<3vo?XhIkV&w{E&a-{N*W32ipi5AcqZdOfKN$)? zW+ieZ!n^!ptE0G=|Ddeiqt+g8xG3|+hKBTFF{nGFZ*N`J!m+0hlsB|?t{kJA_}1w? zr=MQ-D00?K4dV@Zqv7X`%Z>Lwy?YIu{^nwSzGl;^l1S)^CMTv1*tf$d&@IG~5j0RR&K=+A{Y6gBS@7lQ z0RKGUfCE>=Ndm$Kj8wRc=$3jfuLe!Xth_uqxjX59EoXX!@mA%(xDNMWEecVaYIgzNA+aQg*QX=Ej>!lytH+? z!7oFHq@^5Y6sKieDW)e=n3R8Ux}1+uZj!pS+14fOSwMO7CLg%%2^|D92cKxzEB)w6 zGtJO3I@x*4Juq3)?7uf~a^Xm9vF*B#@mhe)4#-GFv4l0>^TqeHU zG|BS#^d~p>)Qt;)912G71W~ zweVAjl?5nl5Vr~x!XSl`%KhPJ?}tJ|zDXE@fN<}?X+9jri^A+}8{mG@ir&@Pl#@M} z4Ts+aPPttm!AZ%=N&pEHZk4F}PfeZY;w0esf8nLy3h(mnk=1K69y<}bC{m`_7cUqQ z>m;D55z4&%s7362VWfoIdj0nG z$)Mvkwxm$$D*F_LFGZy{y$>fNiMlXQji=sNkkX(+j{Gjdv_o2<=E%7=CVK~i*|7@j z;o$=1@nH2RqJ=Jrd6!`A4ibss=B2c`b^;Oy2gB;4m802hY^8{+Bl6vpYP0!C@dw%G zhtw+3(r``CN|xim;J}%MC&usHMsAYyJD8g%+Kvg~sV6x{nXZMKuC;x(FXT&GY?A`xUU3Sdn(Z7EZ={7V$qa_GWwOTT@yU=fU?`UEX+@(C_C@$y~!&a%|}51vBv7oY>SxW29?GL2$iviO{~%0*zK(3U=M|G|yAKLf0W5 zl{=6$k`0&qSIHKQ6mK`2Cx)$2nF}8SP1SytF>jxn=l3OL>S|cCv0|f)piI2fRv}J>`4<87^Fkun+*j-FPBmcz(0L5e_(HzikqhY2P7^XmW!SjR$ z^GRYS{4NyGTVWI-su==TISkU=!@F?iHI7t!h(iik#(_JT{b=4_@Q5O;aZfmk>M%$g zDUP=NjOHI+A;S3f>#Mrm9Vy`lMkG6a!LHuRdKb=4mOQ__xHYusO-b3%-TR@ny2T#tmsS>xstLT25VKo-H&r@x|<+46Fg z6qUnh9z9}S_Ix?JAe}{X|GqPbqK=ZQq@2w-u;*H7Zy3myn@&uBpZ4XTym)bB%|gb@ zK~9!g$|CRzQLzz;hF>j18rKh)k}}fW=d#`+6CbZgmC5tDmg?y(0BJJ6$dQim`0czI zPkzNl?*8m6mqisk_EeLXX7il%YITZM`@cyZHg{R>-@0R*6Z_>#6MYfCZp&`pyL7ro z#xyh9rqO~^1b0joX!r?zlOT_|U`@~i`8Q?aS8NE|R?GdlazPEO_-vKBf4YIpEi-8W zZgF+lB=lkhLu>YxPVw>LH_7{v1j6;);!?kgiFdeRywLT^SdB*0gln# zK5sn!+5maTWU+~vRul~eBT@I8Q8Z@n`rCN(2O@g~UD}tj--6whG?ZnS%zgzTuSU7J z{rd;!Eh(>|DIEJuZsY^fFfm&q^XwU#T#fDmWrJREVEF`-t`J{GdL*NpNkt|z{j>ha|q!UJ(N9>qdF&QyQAaT?Dp z!gUp{b-^b1xx}(D;2$6H*PRIRXXb0qJo4m%Ha{c=m7E~J{z@Yem0fOG+lb|xGH1+p zf1W$xwLJ@#BeN1l9fXSn8htTL!$>DBx5mnIcR?_!HWP`b8^X@|7N?*8%XiCdEbW=4RlG#1u%p8hrV6w@;uz{0>StDtN-FC{tYb!FC3MAnH$h z3->$ddo31f%Xb;o7f(I2z%Y;^v(XC1(LVWOLldqP%h~hsHfQWb!A42i;6rVC7?S|% z<^$5~1=sFey@S!O4(23Y3kf%UHyT1sYTU7h9iWuMfe>H4_;iSE!;%XtzLPqh{!UlA z<(t{L=%xqzFDf5I&jPHc2KTeXj4Wv!O?GF=tuyaLg|jW*`XdMG^%`#Qu*HLUxoB!r zVHXQ3&)R2pupAZECT~2Ps*(5<=p0}f zJ#cUw88e^$XTnxPEvXADX_Tl8{_Mg6ldmfHW+L!xhS~6?B*hIXTh+ObAZU+gnQ^0~ z?$@vD(7t~^rR^?dj=>?ky+~y?+$yXcUGjykZjjfhIuvn_Q41TwSeYL@d_`S3N|%y* z+DUJ790i25<%aZL)Np^#Kyzt|MjW=?rAzMimDA!6GBCgn&&7>54FlHu>YcuEE$|1L z9k(hOCs26TrpkE@O6^BG*Cg}~-okl&6(fvQQI9VdjSbdg_+h9>_&c7HBsISr z)h&?sJu+QWQI9Gfa`KY!TqRH4GQt49A;5Phln=@FVdtW`7+woS z`BLzA`E>QAjlWCt3i^5}$LERU8s>ZQD!PObJ7|8){Trt;K1;7PJcEg$Z<*y1y4GvQ z-gggH(<0`V9?y6u|HXlm8ttz;BiCHz88ZWYsP7hw-)Zj1DVfNtX|Sq(x8TYW?uy$r zHGa=3xW0*^;}Rkw9VQ*s%scx&I!Dzej3nr>ug>0$IWP$wgom6mDU|urgq)nw8Is|A zXIL%B%2Ust`Ca>9_?%YEE3qp|vlcO7(q{-23Vpz-hWDuxZk$*$x%>CWEZK#bd3D6E zS`(ui96Rd9OKL`LWL28}A$?nldGtQ7K<4cazEmFRa+{=A??%~vfCszZ$vAY%!SUr) zl?p3+o_uqN&JpGs!PmQ#D%ap`5v~;X@LYH7;0{`EfDP+of&-~3@jGMm0ZU!`67NVq zFSP0${=lQCW|!n5Y;wivnwq{xCVapa%Vb^1IdOcjAm=xABzmv4!XH+wnyP@)RuQ&} zszDopY97(i3Vr#Sh;VSqbeKAG==-~&$?!=3`A$sX^~7^ z0y?W2FI>*Q(t53W9$p+&VIv^Gev6uLy+F}%p|H|~lMs)$ih?A)v4DMO`Sd|dq4=HI zp>WbM?{yOG2{ovxdyLWo{rWM`fB+4Cm-cN=qxqf_H}XLHD(2c%x--xCuCP~$|J2WD zc#ox-I(Jd*unRME?snU;hl55*vb~2V^}RUd;n>XY?V|_8r)~{9-YlVd#G81wV~^de z>z2avU2)iouF<(_@$h(jEsGj53jKW)Ajy)rW1rWYmQwR3PffDyG)_gBJ=Q`W#>_(# z1$t62Lk2uX5_VkuO2Bjct!{QFjB0~KmqU&b*%=gzi`39^5Xp@BcgoPb#H%sNL(iDOsA4sE;C0!V_!DjZ9MW7`t4kp|d{1(6%_v(c z-YqY*=xH9z;Bj6--U1j7h2xU6!nE%^Y0m$Jw>N?6v2EXle-%9vJP(>hQidiK4QQZAh|*m9xIFKFuf5l|zHhJfec#^Cde{5% zybbs7zOVbb&ht2q^EfiIvYsRUJt`rg@vkXYT}EYZohwBAyqB{djp$idtv`M$d!1}1 zy^~0E*DDaff66ATEiHcQTk~=`wQoD8df?N=PIKq|y;R1Z&qb6jEY|cfK9YI-Yau`GIGB0PANca|Q<6hDCzU=IdkA4d-aIUn4 zb-`Vq?@#}ZJ;5U%ghD-rKY?U&uc0Oo1rjm0V;l-)#!ixi0Pq)a07?&9tzKMXMY&-X znUuudcGer7DHuC+MHm`!%|Uhp;7HlXxISAV(lY9g>0jeMP`n3k;eRoN{n4kAv zobRf6@x8C&uSf7s!~pz6#%55Q3vOoLJMX^Tg&*MV0JYdngJVvNs+W~^-o(D)$DS|n zne)`bzQ`qYa@>U6;3|Lbx$n>THq%R=Xj=0`xA>nTXs!^i4@UXmp&NcG*_S1dtG3_u zGct<Q8`%NNga^EXbh;Yyh7mYCNOMMw#mcxrE`$0U&o0MzlO4BI_&8|9C-0a^aF?1#*l~ zJj9>}@ijd1^6W@wdtdGAlP5n!29ihs0|w)j)Ya+G-V-WON8q4>7I8C0WbvhV3vW6= z&6tfM^xh=yBoD>{$GdVHKmvvnQjV0?FwwzG3C2>1ixCN4!F(VFfiG)4T1V^I+FJ)j zn}8m9|KFs2{sfXfRcI5panUMj72gBshMk*2y2rWlHkh36W(yv#8haJ?);N0FO?DIg zOwWxSmBYc=UdBD1H@L6gpIM;iH`>am>mOsF_TQNdajRMi`ce!im%TZMDN9(2hr+0a zuuQ*(8i~;~AvC}+(c?xF<6~lVY?PS~m)6DQnVQ2G9|LBG+|jeMKTiO9hmRz@U?$8gX;-zg)ahCIz2s2d}lG-TY2GkU=Mfewl4o_GwBZ2rICad&6anQ6Pj=Ql;N}suk;3b*Yokhqi0)3m zUr|gkZ7-U6y;o&4SoiO_4gEt@Nw{fhL}9*WBOF;6F=KX>sPKH0+KUf|V(eh$^}LCKxZ) z?8Ry;vCWY&F{G5mzk<8+|3E#6TdyM2Lqr49|3p2IiBym@n1c)^eoe?Jq6CmZP>L&D zg=~O>!x(iR884TVlnfddD}K;EN@gj~4Zpn)(g}A0q|?)exFb6c-CzqvP%mXUOdhz! z_A`}?@#dbarz|L>>*{*S&2 zoQO3E(|vHrW91$dCX#{r9Ym%}bWBVug0UX8v(h7vY&UY80z1xtq42_HI62j>{Q%Cc zpy)_Y6q&+DGT7#_K2dL~-`V+rWXoW{n^xj~HIz zd*1r&0}M@J^De$(zNU=FPjs^=FO4usDbf(H4PQ+??hgQ!bumxItsGoyFNrz!fx!sH z;10)$U&UbX$ZJ;ZyFlEy5r(u0R$!cdv)rHvkv>a{`=rZ!7SqnSNlNJkz%CCm*YArn zPSQ;`xFvgD)WUmoCuYXMy%1k>gdPj6UAIpBbgz{2`#dV7)US3scMi_gH!^d|*ZN~V z8um$nJ*;wGVkD@GWH3EAbUm=%`f0qSUnuPL1X2gz!E^#|)>G$w&ju$ygS)E3#gUvS zSRCPD5o(A*VU`Qf+uOVH;l#{~TnFVdLJn);<}3#A9H9Pj-|3Fo-^nZ2($dl*VS}@q zr%xf$cdGt} z@bU)U^cW4o$8p6p5~t{wU)*5O4fg^PCjKVIM`QCDyFc3BO*i~>4%YoE(D9GFZO z8OVnO?~15`vk0()_QK{%Q{2;uYi!b+u-QC=(Ol4@yWVTPs}xKGw}ioNpO6~lxaV3! zjT9zw$F6ZIa-;|hKvnxJ*MG@LBUynRs}8|I&tUe9Iw9rrR{!~S2zn+#&VRl^c;9p#J=iza@%A~g>%tDiIZ+7_bTF*r} zI(?3h+ec4Kg(~eebWw+fB&f(18m$ z@tY_Eb}NRZij*;&KE*x}u!qDV#_%%=0(K6^sWAwqPwc0MhAbpQnz9vFVMPk@`7O8M%BiOKQR2iBzfS|6rm;OOoDgB#bg zG*_|)~Fc30Sv%$IKLaqGdxL+ehmoMhPgI0Ix7uXVxyIoUZmcDt% zm_n!dLjR&f!fVQNHHIAn)SEpDW*VM3f83o;YO9b`!EQcXX{uh?$&Haz%QGM1J8bD+ zhNN)%C+ifAdZ?Ayy}IdoOS^i`n;tZzm zV`AvC*wsI$skb9xZ=--aP9&$)t4b;--j$ng>*CmveqwguRDNu7ZpP)I99=)MbD9qZ z9iMvgGhw1;==bB5x!n7Ud1q!0X4dDOk;zz1eNQb|5x-68Y|sqn3B9c}jMMAUp1$KZ z`LMD4bE0f@!4w$Cp} z$nVlDnL z;%e*_AKwCP2AO~XG5TG>VvF27V?Mvs7y?49ThgdY%womTb23$!b6@kvPcJCgNie=Q zpy?b=r*xZrX!yvFQF76Gkow4uf66PsD1RA$YRzh7mo za`Nx)>kM5k-Z-P&`HCcaGERqXUQIDkWf7TAnc&ft$~zJta*+6g32caqHW} zZF)D@wO}bsTiTICz9&l3_1B+3FGZGY{^`k~<;V7=TW*wu=gf7`e?Ya#gSK9`hE9We zrt7)$xcVtATBaxi7;%N9WEqR-_-rr2p1s&#Ivy%;XK^NKQH|m9d}wvn8n1$m?o0A( z&Q0rkRC)VKshyx#VZHzqW> z)IH_h?Wv0c)tK{o=m3+yu}8LMhmhADfofngDSk{QK96ds3u?>FFdKUcrx4RDXBLLa z&6s~sZ@z;ysj_9zc3YIY>hI_0xdaM52KOG1*fsw??EJLM^YzAMo69V`-LloBt-`-9 zP;`svj_x!?!5(2z>bErSim=rb6@OY=l}XXOw{aSL5`^JQ$?I2P*Ij}5P~DrSW(OAZ z`=!?^8W+6Iq+UIEHbb^1bD&u0dQEevs8xk(%GP#o^KDw!nCkh7=g;NZn;_R$Y3$!YB6K#vUrIuEl(n zx=a2qHi0JU_${lCoULbd%y0oNfv@bJPd7eRoI0$=oURi?wN-Z|G~=(w2~1;%LZ#@K zOX}5j8`L}yB}=}z!M^T6>-&kW__#Q3P^Z|`)~|dPn0FBh`0#B-Q3|`vz?Ns?4r_|4 zhJXW-<+_7KXnrwfaW4MihOQkC)WWYgT@Uf*&p22h@AJnBd*4>bTMVw+5>+sKgJCM< z!yIk8iv=Y_uaPS-;I>bbF8{bswmn5goE!cuP6>upHTxYqRhRu?j%qNaihr;SrD zi--A|7n>WnGzExI52pMK?a92_h+$umVzk zRPpnA%Krv6XpFhrH57IvJ_(jWqya#8-HRUSuNf!&GOQ8HN<98?M8g*ab(AZ-kr4;F zomg5zPz2{o!Xo1oetk=vrnJ{>T|r@?vW%98hlkhFbQdxx7OC+Ii1v^DeD9^ji~e*K z2rxhiNgSY177_EBmyz6Jx8IO7g=Pgdo|H9fvT_eIXWJHxFx>KD#~z_;`8m~LaU^RZ zr8;ZmVnzKjC)4zXTuYv?ozZI>Iee#dQE3i*IF)>bYYj2ML6Z(uY+&;TWRRfhB+)|8 zPL~dnawmw635)b6zV-xcLP?uKjHA&9k@6ARMp!d3Lf1yDR#9vAgR}#u{}{S_61&vl zsJ!+i^oaS;PFBu+y-jpfz#j5R_z{})TT*9v?)v^QMLA*(r)v^&3!gGz9vsdLbN_b& z$jFEo)HNteh=2>Zfh3`bKq%<@Aw0PREzuVLg`Q6&=?LCP#1e`CDJUSl|2*9YuR8v( zf{6)e$EDfcP?=gKy?X4&fPL)DyiZ$E#R4+%it?AtoB?F#EhL2A`t|dpX!5Jh+x;D1 z{fya`2U!;@je>mJksW+ck2^sijBwS^JOxnE;Ioo2h=2wOVpm~?3_lv=PyAf?w8HVPs1O>7=l##F_D_4mHNh3>ma`WXfE9U4S3@mB zngAj!cNGyY{BR8%I5ZR=Yax?@ln~ZBaFoFqrU6-0xA*TZLyihc9=s4JSl&5$lt$=7 zOhJ6N5jadk0qCP+W)`lvG^$Mse%$XHNK@hhenNtT*2RP}y-{KIl@ix(-L>)8q2GxX z$A^JqsCjSwsaupNt<{q=!P6xa&R)4+_mtP^$am^Oyk^kv!R6>OjMP{xa<>rWBES&W z9+%S9!r3n(I3u1vfBxACRUou_B-l8)c?*3SHKcg|JLG%)QW_KJSc!}TS;|+t##K>) z2Gg^)@hBAN-uy!+f3n|y zX#sk?eUOC;@bI<0q;+4p2Zi{zu}QnF!UJJLF-}6MYB|?^TNL2Qm{$;i$yPLxCUiZPt`0E)l> zMX`ma41NJn>X~GBidtss2#B4iTSaDWfTjfqguyQMuc;RFtHKG(aS|aY zX@zGe2WQE9_v=skc@4gEuGX;vcc=Gpty{GYv_Rcn-V{H({MbDR3QT$YaJTT<<@+PG z&DT<{;2@Kn7Y&pMWb7pxIVwH(rcKiiJ(?oWSoH_#%N!Kmp<3e2*Jogo3A zF`WR1Z~{xOUcG##`?&woG^%5-vGhkI+4;EN+!yZRnAD$ZiaOA`IOnUL%`6?RB8Bu^ zri+MlZjggM@vr_M44o_w1`Nh;#J)&=OzfYYFBOS-GQxp{|qk6#qiub() zgLTjCU@gtADl*gqzL3efSMWawf4h0y;H&u;>*V>IM-WW?$#r%{D&h5DGX>RCQT%X-uFwMN@RKp)$laYe`O zGrYOU{)-fL)R6DVAtBzwdfco%8mgRrC-1MWk<)71ILo#;9&M=NCCN<3e#JI__R9K? z=R$b?7v1PSgna#f=|(@E2zZaYKmwwYxG*TFX_2P|F2car_M?T2n`T>N?kvKRDpNYLB&ez`Fz83WZ zu@DD07<4w4StM1*K}m&K_xDVL#`fO-BArpMoN<*9FE2Lr`PR6!D5v~9)XZUxK_uz% z+lC7hcWD(r;RwILup{MV ze_S2*Jzy8tJJ($|g+@r3d$6F+GH%liu4|hamv)pXuwIr}OCxAes>k{dqsPB=-JP{T zBl)5_zMId-84nAO4D|2e!|^bn;_i+~^ni)QPcHQpd4t1D;yY7zq}X?qhZ$M2JiWB> z$1~<)bX@gfMp3BUpX+;VI#2cC!sHYyY+yf)k8Pj#U0UxaXtYK}?@V{>+4Y=ZlKvI- z>sIbcYrS$T(3)zPZdwp#tlxunS^Nf-X>+~4tjw6nXSR^~W<{1yOvRf`u8LUD90UgR zM2F9orujteCUa4ZpdS$1v9HP#BkjWLM>_hCxgAfw#`Ae#Z{sn2mnN$o$kxa9JHzppTl}`Bc#oS{i;*@T z)3aY3W~HOy9X2exL6iJ@xy&(BcBsg%TlHGjd40xpru#}#jo~A_XuImq&{I( zM$HKH=){K&qzTvcN7J@?MaLa@NB!$zmWjbfEkT_JU*fr?s*t$NJ_|xAx%4|W;u|wGP+k<`%GJ&h|jumDKd21O$vTM&a zJ@d)`Pr0kcfWT+#jnHdsHMTe%8rEouF)X%6A1XOR0>uwsR;qaO%k60Hvo?F__!P}l zYKdUw;fSYc)FFy;8~0lBArouNY0>C{+2rE&g&ZN?koor4XOES=_l!bZl#;>U=!XC# zXMmfA>*fymI~BwyG96k)EukB$o>FYhCAU7vZnDW*@Sm?gew+><{9b-Pfefs}s|GRk6OOAu^l7tee zo*xqiQwiRHR55!_z8;x8rOa!W%^$1Dcdl1^K4xmwTlE~D&1SQv=z>+XX#&4 z=jPnc(f%8WJqCr1 z&X-8FAEPs3-Zk=-YnZYjGRQW1dRaU{otlcT@pV@5NngdTxXi}aw%MoHPv$izefq&F zZXM(|_sX(qd^#g1M+;+m*U%UZZh}#5!!K9!K-SgOo!bh07O+9d#)&U#~xi$k+)AV*NS*0V~efVCR?W=F-wZKQrkiMGN`@7}@HF~u6~%J&`;CQ zJ$*W7{?A0_cus{DenNNNiOb}#s5UVbV}U_2SkJcm{HS{L_3Kx!GIt4bV=zoL^#dAp zAwj{YuJO1NTg$&DI!(RY5up|hVF*TgA7Pf^@slT}*whjge9Pfxy+i$%cNPBA^!BZh zmevjMdS9l!wOLz=_u98`y}2c>j9EV;UEL@oZb`z~pz2qXFh-|@L_|7(Ch@8xNvqT0 zQBs-`*S#@EmLAoUVcAdWgCtsf^F5kOm|n@;*NJT2L!m@6=kLuZmwo!FB>KUFVQWjJ z@}O6lvBSd*PqUxU!Qj)Tc{B)J|;d{?2-M0Sn4)VE$$!e;zzfCnmtt6=Ga?y z7AxWK;(71sv4^fwSpXE%@mZ?8r}Yrfu{eirEHgh}x8KzS|Bs=cUv+1$W$wU$HHd#5 zkgs=f`)=!~b@ujVL4)Cl8K4P{{hIm^a@^$Y!|22@_kf-hmQa@})@z0Mt{&tgEbyTC3y)!ypQ zmE9K);Js|a)774zG(>2y+OK;7dRh(hSUJ279}4WqTgDR= zg7@MAQTaG{viqwFhSk z#Ujs%W4@TvjAzbv4mZ3`E)dD@??A#w|NL{wW;HeY)w%?M5|+pYn-|X{YF+FtvAIN= zmiN3EPjx{uXG~ig`W}xni;pA@0sNL-&1=v$TpPGY= z#%rmkt{w_|sT9~_jO0{&KVrY#*y6%N2$zZxJ->I~KC+SHCGNyUWMNLJX>js!S(yn9 zEjRw>5Me;Dfgm<^l?S?hLJ>cEvbZ3Bng<8aY(H6lyqd$ z?(Xx<1B5PTpSjgF-T}b0XSF7NhtJG+L$EeiCpcj?S%ln&>2DwOG2z1=?21@;Bvu;Z zb-bwXNxcC~^gV2dZEg0J<9Jl;xCi)(vA&9#vkmXDTO=lK+sw@TI4@7EfADY@LX`CY zI2U?vrBG5ku;*oQz{IJ3O{2uK#+(P6yJmw#*b&=AU$U6l^iIra_kn~rMVVYS*$Nbg zlCN*}fBAg@JNB39xuM_QUw+RGO?$^pOgG(5V)qqgl|>HIF^PRl#<-w8Z>1i*s`)YP z&E%N;J_-b}ds&r&?>yTKiMi4)OIlo9#6Zj6Gr-Ml(>7&nsTH+i!ouUJRMt3Fu|sK< z`{O}SD7`OTxYx(Dy&Vkpkz^f@u2=ansoTfN94+Me!?Ua^HKro^u)E&7yZ$RYMAB0}+Xpl1h;5B-u+dxJu9@G&^Y($y^IT~vR!S{Z z^j`I`uu$dOMvfoOYIqJk|2<@B$S2~QZKW|Ke~k0vy-HqVzlYYh(+4aKzrGy5&UDWD zUW5Fa(jB}s6e$ZXD>aF1j^GFNbuVmc4u2ikMnj3baBE~0g)+i+P=XThKv(sq+@*l1 z=yM5zn;nC$0`^U-5XoLs7(H$~+#YJkembVG(z30KF_Ym;OQNO5yHwdvTHX6%b}r7} z_e|!N+WWC0RQ*qlNYR-fvyJ3#M0`$J(A&K4l863Qp z8Q(+S%b!Z*!0Q?NZ3nykI1akcY}p46Ppe!0<5MoB)@L#1jYR1R;q-w!_oG-Aw~8+5z^9J53>0w6#HiSsabtNw-}|cGlIsE#u5+!Y87aqknb*D$ZoG56gN7_j zer5Y%x%3RaqaB|8Y@;TpHUyl*QVMvr@dg$CUo~1`zS{|(-#X(faN8sO4NV_?=RCHH zIzX1(V)D;>l^&Ke8f`mtmksUO>N<=2?|A=6Ef~u@(P`0fRlmT2_dvPA0)B37{+dRL zt>m*cYStp$HSn7I?p86eAtyy~n zSA!$NTzO}LCh{W8fgW^?K1$AkIY^o<=b5VMn>foP?V6ae8>QNE2J}4_Zlv9v@5P(2 zd!yLU1vF5K2fs1ViO}9j%Nb_v5% z-v^m|X{9C$snqxm7Oa9qY%Fk{XiK@r_!OAd#_{Q~wA-iKK!9!afAhOpF_+X6oW4_0 z-haNO<1oCPD19z%(XZxv^}=a+#16yWZ*peL*yQ_UG{C-~M6xd2HBr9u%DBSXaFyX1bAAZJu zHI}5IAgOeu-ng>GLI-;`G&_8K7@rgp3R|Z61x2aDx50u(`G{jhy@^uihkM^lf^4Ls zOg6K2q+t!aZeJPVX$V?_J;Th&Ph1!OD=XN8H^tsz@K)>_Zq@Sbog0Iw)tI?Wslo5% zkUNB&5(5F|Ht+~!{gK`gJxgoy%HpXdNJrbDzs<(Yw1gdG! z>+x24c%=U-=gqEhLn*e-!e)g`3|yU+mB*pI&aLauBYh@#&~e#Mb6Rq0G@mU-H*BNd z!6mZWu1eZ{9gYo3Ujr|1fWd9|;hwCWH@P1lqqf?grGE1sX$!%8pp0uXJ(ct@UH{P- z?)^<(`T3Ct1j?55TlD%eH1xQr$N=noxW$Dpo7MGBoVZ^-oqYyt&yhS(5cSg!cl)ZN zi#~C20d7L1qno>k{!kws9cZ!|Ie0e7xDAEibsw7adRKT#`|mG(^(y?#r{Uj%SWNgX ze7)0_I_%L0x0t&}rD-K);Nq@t+k0exuj}P~&h|?Y5ukkRA!ToBZZ=+7UfPRrPF$Nk zM(6uvN-3^c@5@i}XYhn8DrCy^DU&^EK&vQc{dm#S8>n5|>c&RmX*#a%w|}#nkI&`0 z#K+_W{>6Fj^a9EGD}#4NKJDtXzucpXdjguebm2*AstPL1uu_@IiISeFsvo|)moJ_> zSBTzk^U9OFJRLCC#&&iOMJsq!++r+E_FoUEArveTfCt`XLZq7jmUktfN(4ORLOIYwKcpS>V|km70<_h28?V0jwge`@)KH zsP#xyH2;(K%iQ6e*-Jc;>Go9gci7@=)m;fRfX<3+p<&_S9`G!@&Z%gDl;9TRFHJw= zT-G5782z&rWTY8Re5$b|f93G`CXNB6!_n^D4v+p`J~EkdA=ojl@|o!bVd@UCc(U8d zzrYbF=qHsHx#R(2=!Wb8>sZw8(#`#s7GPIM&1t-j8IK>g7+3$=O!f(McCc%!;dOu& z1^CEz`I+7aoXbD2I-Wk=iB8540}m@p=s#fFq1Xz!Fl5>HAZ#DS#&zQ@ntk46UH1>a z^e)Jy6;&D(-KXj0-YCYKFgYf}h^7QveJJk5oUv+VleHp0PqX3?;245;GA>AaUhcV*)>6`nB3z3GCRba^-F+SokUwu4c1+jcX*8}_d{vvJ*0 zr)i)>dIx_pk*(!Rh`VxvB^lX+fkO>uGs`|ePmRY%z^Moh`GE*zFRhey&0kbV^8NE6 zai2?Ks=bLPZvDi^Dl_E2qmh*Pex5fSNCo7+I3W~Hn-`%21JEI$sAwqa#ORX4mgrp+Wg;gSKO*E~as8aTRj{{ConhqnI4^n@LI8SX;^N3wbO|Ljemvs{ya5G4O4nS_mt#a;95#jJoj7 zm!*NHrWIYDHX?h_xP)?Z#485UMYi-cBF zD0!TGMJF~tTCFT4u5cJtbWCidGuC6{d-?$S;mKQVzw}rS?LDx{xn7JKZ<)lk0Bowv zY?aT)xc}~|Us9Y{4b9}~jeq6}#jupzb*eLUI=f6YGvcWR#PL2lNZV_x1J>O_A!jqq z6|e!->6(`(+M9{*JgfJ(m4FWfBz+e z`+YnVis+WiJLqhc8roP!iqlziFMOpHUKOO|7G$aT?)z^#O3MY@wHEb!u}c}-ZP!xc zass9tw{I%`5?m`FbKlapsq5j%8r}4q+BNaUjWuF>d-$x}lU*-#s4Jfn3ZvZfIld)& zqW6hDaf%`5g@e{j%Pr>bA> zzK)LGa843BHcKV5O94-PFBOH+E>S4=3jYFoya(*k4NQ+j;(qNKEY|dnakC8*HSe zSUqXd>!Lkv#D4z8ogYnY`xI?oic=-UzWtL|H0+Q4aIzZe= zF_L@ni!k~J^$|95&=Pgkl>c(`3OR95Bgyr74PKx869qWC9VoJ0VjAhY>go>m!O$3o zP$aKB^fue}I>y3jH4EUWD#~Tjwh{X3&Ye4_kIUCeTi*|G@E+(mk^UEHIC*4-ikFAw z#cJw96#-hWj@rFFzNJc=PFrHzC3y;^(^_H+r98(&vwF%1z412qrxNZ5v_PiI5BqFojO&zy@7CBRTyPD zR()~qtW9r;%WW9B-a}w3sq`^Y*-~0PEkc&SSo@<0Oug=?`Gi&Qb@m5TblPdGNnE)Z z8EqIW%K>;g3TomVWW&X-C*1dTUHJWVr~6&FSazVHAe0}*uG_HJOxMyd5DE`0Oh>!6 zVm1svj{`p?K72dXEzXQT{8;Q1|M9{wySZEAPH)t>#Xd8q37B0D8SdaPUHak83Dbd3 zb>sxp9_k3Z^f+|2ZArRi+xwD_Gx-g2V}2e{`7U=Qh0CjHXDa0otxD46>>cY7KQ8CU@_n@zgdn3|%_h1pGgR&@y&*c7(YLVcg-~VQ7q- zs!5mph;Wp6*|*7i7vb0g#*ju{oj7BQP)?hFInB7+w=;Wtdj|t+!2p_H_!38c2;x2W zqW`VJcr{%FRpV2YhsC#c1+%CA=Age4D50rc;rrrXZ|XH0qrE=_w;%2HparfB6nVhX zzJ5+k^!uLL57>Jqs1Hy^gv<=1eeu#0zNcH>6Ytp3Xl#!N)qMz%xF|DB20c?TKyOlK z>q(lR^tW7`OG)8DHOuc{^BUC*^uL3OK5`sbz``7D9z&R31xJPMpu6x?1Q{n4v8a?< zu5?I5dGqbpEl9f!j~~y9P+XSk|0InjsC)G#QUn7JsgR?sb+{!EZ1%9cN+5d?hg2l} zXx6}QZBacGGbNd9t6D62nxt?_r5Ajeuc<6o8xXXHmzbaK|?c>Y`mrwO1ldA#f9WSUx>sd(bc#McTsOC>KK_ z#7{m8UcXJ+Eme*qg3v-(^bXjE@Uk=u&cugch#ji`4Df)H;wVc&lQmfCgJ%W9_@c|= z_rlUIFFExOiWJJGe$b$5)h6~Q46RO7+)K4v&(U*zU4RGyU)=)lelJkAI(=1~a{5H3 zXE@n$LD6}DQJl3odUIDR>2WSpS!mvs``h?HMj_ZPiBzFnI9+6*Er3TN-Nb``sV_`< z-bX{YjQw{E9-Hmx9%9_+!3|=VE+acTj<;&6?Px}NdT6e?5!M+wE1~byRaU-?t`e=& zW3+7il@SQ4H2`OS(;*R*$~)KuG2k#W0zfmoQ?*CrF3!=lR}RW}Pd&!_KaB{_k>W0k zqfO$ZNuWdu_5Tt&thpvF)5Y>zrPOHed(%q8?GxQCs>_Y403-v>eaMLZ7QFp*3nb=y zJ;n^yv&$HOvg^bW@_4p>zgjf$rIyDTP`*4rZfIii80T(!R+a{uEsr`wQ@qT^rltuf zN;1F~so>KSvev+;bDpyh+ekc_3ul*cSA%tHn@DMI3Q!fkq9yVw!mV!Qq4c@0;9hhv zAlm{#AmBEB^}pYb`w19Kn?O3a6>t^x7|$-{yLcB9$SI`V^@n>Is1^dA0e*gw`5e*+ z+pWRGOj$EQLX|9D2>ii~E(Xnz0+&LuigORT)KFryBVg5?%QM0Owv!i&F2t~gsxUh^ z>gj`~;!S}bVlUjsCHIvqvbEmKHZ#=KJ=;qQ)ciyLU?|2$6LD6Z?HvT)kE1hwe&)xg z(@Xic@Qs8-+OkEMpa0QO7n&VWA@InLMS~C+7$|yu#TE?SE_4-jlcX6ZY%#!~0|yRN zbS;h<*T{UIMr#4>#w1r32=v1@*vR9D8lkUWL8ILO`VK50;Fk%{A3V#)rKF!7d|@h2 zU+ZZ-uHPEW@KOVZOuqLT3dQ8cO_KoG;%qJ(k<8Z()3kR^y}5m+Y4|sG$ENY$jlWUVbQm$v z?5hu|Sel%pr6iCNp5mU!PNS6hf_dH7Z(dsX9Kt<88$`ypemE&dp_mPPqT`ZBvqH&X z`rCaOmtInFD{|p?+)5RQikXe;Lx+sP3gypppLPz3Cj+7#Gn;3`A~{Gu(iNI*THkFr zlJnk|H?(ClC4ePCj=S4j!)?G;Vq*E_%g!K?xO=(@9#xdT?GPpBdADIgebddW`M#us zp>Uah<5032oA*gzvE^I0S(|d_8sWxdo?5BBD7mn9gN609PUNcmeOLcBGaHT2^u!$b zvr3eyPKq&*#;N}86Mwg;#dT&Jg(vQXygl2#Ak-egkQaXXsx6v+jTcgs!zShK=~&<= zro||{R8*#8Cb}J}c3c$7_o1{#J+2qxhR5O_w$+VDEyaYd0rFoG`+uc=0Sn0$!zU)n)Drawq3!j*{O``Ie?B@W^fE%Ic(SucL-`0tYltO8@yd;w*4@ zwM2jo;Tg3;J?^%!jye}&CG=jW(|X^Se_tn~j`eWg%)VSNn&|5rH@I?u(i;gb8Rr6> zjZ(2Pj88u>a76rMr#RUkT;p9Y7%X7A_1KlBobQj{jciVI{ghJ$=Q@s@YOpDt>`91wYG?c>scE68u%X$P_Ol6T zsx*Tc?Tt^^HHf9l4p0HmQU7B)lkRe5JJXWV0R4`Q{>{$=eeq-5Ib(jfCfWuW8_^bf z(uY3#V)$!!kvB6%=5k~f4O~j2F-WtcU6O2sj-P8UHB_DK$}#s|o*UkK^7U5MVD9AR z_>xINYY_AvlMJX*dLFtgLW7ixh=Rvx70{IFHpthU`J_P34^*`8Ud{C(pW zjU?wA9Pz%?1pxjC;`H?CANCzqTb^18d}O&9z)Fd1?AE$_=XUJ^c;+)(=Gqu68*!mlM9%r z>%Kb6^GEE~3|bm`wk>1`FPyHZiY*G`9inMjA7smp(ZpB+)TxHEB>mirnxP$tWsl^I zwUj&Dop;4M4wyPG1T(IGsi&*jS>kar&4`X1m5nVqZf8#HW$IuJ;u1YqpW|}Ao95UB ze_oqK%IES(XZ)D?`rUr_bp%pzPLO7d9B;5B&Il?c4in>GAxOdG0S(3oMlD=s7NL|R zRe>X_Flfy>P$7E2cxD_!bjDm8ThMA{65Q*)j@p^(xis4K+frfMp$nk#LY>VT+RNTU zQHP6AjZaVX7?WQ`aB0EayS2&D2M{gw*DtsATg8;3r(kMh4-cKh{b%m-jwU+gwBjV6 zhR}>0tjP<#!&7h0`02y8BZqeskuB}m>xEEaCbaM=PS`r-&jc zx(JJl2pKJx#*B&3hE!F@u$%E|CZ<|cdGC}ACfI&ypXY7SifU{ou3td_K`HX=ufgN~3a(DYp!p5X2x~s=qb`hmqC&ml@_Ub_5 zP*P3~KkLu?UbEuo3*?>j&R`hHP)#57kU+c%7l=R)vTlTP$_^4Pi~JRT=JCtvd+~nX z?!nF@)&*?rbilt?UAyMke@KbN?k_9P5s?s;?0}`o-{v`R>+^agzLAl0BIe0wlIZSl za(SbcxB8xJK^BKnIcbOp2ZQzm<6XIEkqC=74|m|?pi(#BMNWB!s_$Ie{s?LCg77*F)emoI|*_wVm5XqdQf;1>WZrG}Rkow$KhTOU zu8STXJsZt??yF4rVZ694(toM-)I(*J8Pl%<>6})EQf9YMP7M@p3)p?%rO8*~ zw5Q}vjDgFv*yn?-Gtq*fM_#yx`Q1?c^gF>o5NB275%ctez^j3{F8gQOuGTU#dj8P+ zQ|rX<741toA*)}duPJ59UUk&o%wU>YjS;U8DWlOMq=PY*S$+?=AUoB?AJ|OylXH&< zVggO(`PprFy-~TPPUuIIr3Ss-k?6H+*B0S(dQPzHcj-+!DB zlju#i$$C034&&h~6SI`)k|od}px{Qd{pVu{OO2fg2p%>IafgM-6c=`gzIfF!5cpRu zshK2W7;SLuScbO3oQmxE@39Vv^RFzIQ#5bytEUlHC!8PjZN=ERz;-!eOp~y7kfZJv z+~zvBYKxF_5@C^qm~QZ zT~pZlETZ34oIgW4EHX+h3BZu354Rk5y+qUinP9vW=UXG(A!~4gcNLn68oUdS&RiVa zP6+g9?>lM=5e>07q`5wcW3e$(7AisbRwp-rRnTCQMB~CXt5` z+F7Er6yKzqnxFq=IHbh6F9R^n;J!TEGU#Nx0`H%1ew!pqI!6e6`8+Ccmf;D5eVR0a z|MF51MD8^sq#?%ksP*Lf-0xw|nOhBmtwgN@9R~NZ2^zFN-}^FQ7$L~dKV0@HowV{~ z;}gytOnHjx05Al)t@L~MK9>#OPD~u=5fpN?40K6M!$LIF*MEQ)2da^U*oLp}O#E8! zzy#dzxd>h4w*9B?tllxUtvmjyXxSF3Q``5Pyw;(Nn?aF@eLbDmBAvxaTf3pNaxU$n zLN16~e-E-0&5GGNHAM7DS zm!33vtl0D@nFo1=tSC~ZLJGUlhz=EQQj*vh{je4_>);8f`dF!{lsO{QJ+|YEcWqw( zHA8!@Joejdx>H4Y3ssRXXTM3ErUWeU?&Q5Kb=F#99}VTD&ZPjHulCboT8~|npo

    andIc0^v^Wbzi8hRuH;s28 zm^YsSu@&=n;pk`o(JgXO@uJ#fd&M^*d^EdHk@8;SaNH$>b<}FKU?VAdqDJ@aPCd1H zDL%nsGc3WP@WJ$3B~BzRaidi>lTArS0;P-cd~|vwss(P}VC2tU>+W5Duf2ic-e!dH zay`7WF|uBYhpT6wwq9{jrKHP!i=OeWxFz%_J*B;?ph8^xNb{PEOQn|G)#=LeJ+zrW zVpRT|ncjLrdzCSzJdhAhZdz-S*-jaGcdiM!;?}obmhL4AFMaXRF$>Q%6|QdSWrsY= zzF+(fr6p0vedc=l^r-Ew-G;6|qo*dckBoa;UkYG6)2dcWRL|ZTb*FCH*GAt}%qRqX zEPC?bd**c$cecK}`|XbGq_=I|(yGs1q?MJ@D5ox%U2bDDsP9&jd8i4!ppvoJhr}n& zj3?jwYUVRLE_@8ED4X>Ar^OdvFY~a%iHWK<{Z<;kh5Ajc{O0`%J@^i@(L3%tr3x7c zawst`-&JS+ZKKfzSqOPi*+j(CH4u9o4eE z>iW2%+i*f^_E?#DkI=4_x|wRv;`o;*ce<$%F4VY%oU zzD-UWpNd+~oRF#8^yuSnH0fubJ0q(rDpjWa&KP8c6jZ_O)z7S%<7gGS)WdQV>Qy^aY9^}Od3&H6rR zWNB;eK4+$jG=G0u$wp}M3d*LBaald@$^MYN{&-rU{z6p=m1%}D)1#{rxOB&bu9DC- zw91n=v$YiAe-L2n=DqXqp&(_Ej-9M$cZs^Ctc9xXQ5i$;^>K!>f3UpSc9eWiWT)P~ zU(NW7(J86^?uLWrnJ>0golH7Yx^c9FMU21&(y?L4cT`O2O1LHp%7 zTTqPk&Hs(7?~ZF~dEQQ_Mw&+HMUVhW2c=g*Afba43H?%}6G3_lil|5pMUW;M!O(jz zQSJo+0YPb@MG=sW^v-+Y{d)EH?#F+Kd(NJ1GtbUEJJZCzD)Dp5&`cGDOk|Z?Rku{< zC;-dOqUy6hz^_abtep}n}JtZ)xFPY@~1*y&(ZUZ0;q_A!v8WREj&h<{&og-wbfgXKm2w0oY zw=}}rP$c_(~ zQNZE_SaP@$SWmft5097hlq86JvCg-yb9lYAhb%mMOf%`*1_EV0B-yAODc(r{-?Q|P zWUmg1;)#+(A7>S3zXZsz%~EdsRD+=9C!~6$qG}A(`ey60eFY`R`OqlCMhOD)B-uE6bw#pzkqY|43%0Xf$))8n zweg^35-x9jO{72JsijU&E9SB=f#9 z7#Lf@pTmVHA}Jz}YWG81m5ZnML-t5b$sdMfPnl<)E!ItX(n*2md;=pVo}mB)7hnV~ z(Jd3K@C{LssoazTmYJVC2Tfb}m699A@_n}T%`qri^vtip0hMR#GB~fq`_kj-e)S$y zkGw;kchh!S`FoYOpOyJo!&e3nl*C|Fg#tWaL{%Z*0RQJMz^ZfX9E7|7;Mr{j;3ffx z9p$EBa0husa*P3lJ|v0aMBS=FMqvM|Gs(u2h{NgjCOT2sKvgtf*2VYv>H#CY?sf4< zC)c`KN>Bz#)}vv(+`hFg?=3{sO~?Ug`C()d5dad<`bZ7hAq}fPEieA>>l{J=$$nHi zfhml>^UgV7WI}MyzZ(R>>&hFq4}IPNa{eP1ur@89P&!gLp(M#jv;#cXo3CB83sx7z z7~ifusT~`eSzHYythFC>57f@{MaP(d7JvqTiohy0)`jz07@IP(OnPl!wSAU#TyHM_ z01hg@0IcC!HAZ071BR@)3nR=+eX`ks&A`iTfUz5;2eW<*ibV4ybl&^>uv4526Ie!C zE)QeQ%j!Gfuv-uFx~BRebt67jMyoWzkUH=vn4}_SoPw`7cw`E&=JN_lkb~7R*E)b6 zfbKoCRDW+m$yKp(Ai&(!Rz6#CF>3^{-!;n*0F2=Zu)evF@Z`NRGF3}p8KGnUrMPn? zTy+>%q@)(B2!>z1K=UGto5_l#tAn!Sanq(=3O3kh5k5wP_j&863P41PpHI#Q1!oPZ z!*L|*aoRKamy>^8xmbP70&E^h&g88Hb=mvL749E4!ra{F0{O#@uB20 z4M5U8uME_Dk(nhc=T*mDxWYn+r<+WUcV`zZ^Er~zF%QuOy}$Ug9j#d?&@EK+D#c$5 zXFe@6g}+w2)Boy%`iEphr_}1QvT@~9#;vvKheMNR3G$7$lk2TiL}B2`pGEa7R+0js z?esi;A)Il>4#UgkB9dZa!FC*OdN{A2?%>v_}{9K#p?*!+c25pdI?5ghb0*7}kuhx6|Qq`;>cjZI40Lx^C z>FZC%uP>&)3=!l!d~Z1Lq9k)%c8;rV{E!Jm+AAxDQbQG^K|iHT(M|PtZU_-@bewv- zW7iwQkCBbg$G2*z@CcwL{w;~zi2!g3rqTM-*83R=NH-EN|5B1gtNpw+Lh9m(yy@Pc zkzqP6Qtxu=(~RI{VEX{QCmQ}#s^4wTv1#kinvp|m_tGMIygt9)xNM&6vi z+m{u&O$0egs!4K_14EF%U=N-4bT-u*>2kY}=4XE8Vyt-*0s|aM#0wK>y3h2-&;Ko* z>S+m=cbx!Uqxw>^h0~s&>r;h1d-u8T02JpXk^jHv+`j$gNBWQ95Y!_;n$gKQb6)z( zPYZaNciAiH_==EtsYc{KeNSA2IRb3XbdtK^{!=>H8Thwq{v^zUUMvBkNm8{~!=`fN z_5I`5l0@z^I#%x6*_*?6XMo!%AW+|z=H{A0Q4Rrvw=%pq!~F<1R0 zNLF2I*Hrl2*Bp07_gf3qX$4m5z+%{bOBb ztI;H>jjlPfzMSAr0m?}Dr7YrS(_*q55q=h(3jQK~>_740>qywO51BmEB+9bE% zc%r^hd7U8#KFcoqCh`N=48GgqI&{32YxP;4N{|4O1(EbM)0v0&F%!2moCAQINC1-o zDEJl9YA!!xAKOx2Qpf=Of<89lgn)1wB!T!M&8>3wHRiS$9Z=H?N_Q5+dHI|nx5b3d z>Bqm$qd)x|w-NV}MP8E88Yn0llB)k%%Jc4-y#O?0&FZrlagZoUh5Rg*RfVS6Ln0e4 zyWg#>6hNqG;Ubcc;eQ3oP8!OeMH0$r{p8g@mq9X@N$NUHA{Gt1%0g?QND?J44gqQb z_TkWv+$MJUbBkG46#B(5&B=Ei$E~?I? zOGq~ak?8ARTY%T0bsgplt8_1jmSH07dl+bnlKoe4edM5BZs2n@1QwOJZehOK|5Oe5brVXlkyY3ffA7b zUSjA31c)#fFasbv?|-)yca;$dzG(o*Na)a0I0Ilz#E?|+&ylHT%)0DiyliJLTLHMT+|RRqHH z#@$E(6vxrw`qCp|4hRUp`tOqYLQ?!dvE%%2&Ryrzx}|~JI{zUI>EzWk;QurJ7M|(mxFmvE?G>OsJ z4*0EUdZub25I4C9;5}H@dJF)T#$qmd$qx}NM?Pw0uQ30^pg@;O)qgE;;Exf~{k8uU z^wKZs0{npYBaPj^1?}XORt+CC&ECs4!n6u5WTnJjS(HTBKKr&rY+%K-!fFjr}E%Ci_S^6@Xh1_%Lu*j25;$NES5wg?Bvtygh!`|4F$BY?F3RRXRi-81tn zIktTmC?wgHZjI!a@=+Z5fZ`D7y z_0NX6)wfKm>AuJ!_AzdJjEI9K>>(duR?c%dw~_av`?1L*l6L=o)x=HL?M#I|QC zu znu`_Gcu-#<(kb_5_ICW0;P@Q#>ld@IF6@85O#1ZVyKwgjNQ-pw;{(Dj%@~F zUKBBw{C&_CLq%UvQ%Dw5TC+Wkv2h6sZG5@pJ0!?P+%me3e)zc3u1eCcl{SO)l7^&9rj`q_C0oGP2JE;jJC4Hy~JDYihj7NY~g0 z#4>&P*63E|%(4*fMekCTW&9Vrp8iw8h4C0Flie$9&QhFJ3BHU&ME#c|NP6xz8=w<&E|f76G9P-I;~o6j|PzeA!>v-`H4M z)ReGvzmZ9}xb*Sa+aMz>e62vF%w8W_at-rL_J6|ROv zN*~Ze=HmI^j>dV&CnPo;f--9zC!R*#+fDjdaX~g;am1*!fgPgVra47(_-rZ1xu=Yw}T>%wy|W{-2Hsu zIo$074LKm!Qgbkd!sQtEQGvL~lL~JW8A09@Y>XEjHz4aPHVF*q7)Pm6a5U_&ujlJZmaa;qNs{YpPruinAvziTTt=J$nF#m z&(ajWuImt+Z6bUUZz5#eR}i2gb0q}z6ngE z%p@JT(B{AV3hVQxY!-XWbsWoXj2NnS9u^!lt8A<3V=L-@VS^ZcqrJ9XriNrM6;YYi zTa)@Yyz3kP>Kc3tx+tVA!^C=}?AoA9A|>2)u}!8Xw%e&y(@1 zdk!69kpW5DjjO!i{ zv=JVpfC6VsllLgAOct{)cwP=_%Q0JB>BPH7j*us_WcYRcIk{d`eK4M}yV!RH*}sUjTdMGitbs}eB6}Xe4L9ue4{nZyGq}>+{-oa0 z!V6Q)Fv6jZx>GqOhdW?Ip6A}@&$x>0u~)W^Q6o%0Y0!;NtCBTmBg!|Vg3Y$Q>{{>Cl4G{oK6(U3Q7V%%#Fso~-ZDXz1@)QR}Y?5I?QMD)kRUpp9f zJWvX2-luZK$o%)cK>k$|M&)}I z<@8U-OM25WBbTmjMj8OIpIim2&jm7;&vSS7lj)O9!I?za)ql4z_`QKCorXg$ z)?o(}Pqjl3YYEDu$JJZBRaO_Q-iJQIJ@!tZ$R(#vWKZ4f`NfPae^29c@ z7%1Yb6&0|xskrDS$g*fn;153^M$VwQh{i;A{L1W61kDjweg2W+r9e)U7z(@|5y_5l z8ZAO^<7FbN7S)S$tY&i(CfhqWrQf~6QyCi#$1;#dAdsA`RavJD_yv54Q|>rg!%5M% zJFA-P4rrQM*>sMGsXWysT007>fJ^yJ-7a)1nM9saw36SGj-BPi_jLc5C!fBYXMF91 zHJyy(%(CX(J}oh)GVBiVI`O96Wz?nhOLPuXtb67g@_yu;_%d`qxqG+rCGeC<$EiLs zQh6jo2p4^L&5n27owyXXb9lZSv?sbgq`WJh&}<$r@Z=LG-W)B|y%RxJN*&L=a$P2I z_Z>rY4p%CprCAu z<}-V25DqsH%3Sq#DGFUk`wQJW45^zFnq=7>HTC>tO&C>rJ6ob1(F2O%xbf~4P2?;- z^F^>*YRid}SWf*iB+bBvemeiOHu_lZL6n3T&zDg?*oP&z(RmU4RT#c8ks{KXZe%pO znx~l6b~Uf&=;$)>0gU2+_M=U_cXLM%oMmg(=ST+5{n-OvdkG?@0@3B?ne2R@<(DXq z5+MHLWF-bGbALUtX&%{x-o+5T*dQ$g_R_oZkmEk*PuqVh>)r2qg}?{!LdF{pmIK(< z!FJD-`}+lauUEvD06EszWt?K4CD+W*i#o_gQ&>$4e3{+gnJY-8Xzs*}9IkF06(Q`T zKmX7}>HXeTF##Cjl0Vd6QLV6b_}NM}3_S*srLM1BHm5Pm(II<$4KdX3MvOqLZ({6Y z9i(tu3$Pn~Qh1%7+T9zoPZ{~ea>g#I`}q-~13Fn{D&q+ZS?A`f(qywo;C?DO2~62*~#X?^LI0Ql?4FZerMOD##wBYk}K*1bq$ zjZuyJrA6IJ(lg9J>R{E?08xmKH@|Pq!{57?O=yQ(gj^wdbWPt5((-^0e%NLT8+~J; zc|WUR%bTO6C`BH=ck2^*G4~1>Jf}Vzc{a6F`*i-0%2i}^_s8Ll)dCfR#GR+T#eQZy zyUH9gM&9mcGU`~{6}4WaI!*=fiCi8TXhIe;2A&(uq_DVj^>7MVdK_XLHteA>mG<1U zqv_?B2ET8|b>{mG$-zq+qgyTFDIq;G=X}bQT|9T_`QkJ& zFS*({>*M+aJvQ4;Y5U8n=z$~?Vi>B4> zs@B6Ot*|wxc94S$pXqI>WVj_>lXJ_a+Kt1N^>$UxiBPfh$h}3LSvF|Bp4X^yk_l*- zfD{E!ndMl*hcAa*TW4;scb3U$A}H2^sILbtH%fMNpzldqrWkx4}>E*1AXP zK&QIH{O$rkvNc<(shfgnQ{W?|^$Uyce%5ManGBfi@>*n=OJ~CaJxN;U}_=rMDZW~ z&@C$ltEqW5bMSmpqO)F5vp0(aM|V8T?to@-^Jonl_Lt87$tA?>XKm=Yu&2dqLuzwN zp@Z*GS0Nu(DU`=hKzPD0gORZM12&v&Q3G>5Xirtni*emHtRsjC(vR$xY9+JML)ztl zkI2`#B->`tr~GTUq(SSBldI5k@rI17f6So233{50Sw?YJY0=&C*e{3{`+!2d4d!`K z2=5kLX6?_3V|q?jZNxxy(_h)#q#}BU*uI**B_gco&BIWq^r5@S%quwF`G~5%I`$R$ z=xDj;8c%!}i)<2wt0!%9>(CvvSekn=%$^B<=WuLyi@#&ydpI;|^2WQ@9RN1*tD91L zSHX!$9Nm)-ZBWclaw``Yt$tTn+i%y$U$%cy^3h6IZLT=}?xdr2ZE_Dw{xgZ|@jp_O zJ3T0rmH!SrsA363Q`97Qcl;p#KRSULcd!qJ+_%w2o)7m+pI_iN)c_!uyRm1acEH0l zK9Nl3#G!lQD7;h(*K_yr5hRzTIs=4<+L(`LM%BH@sCKgL;f%|jPpD!G(@N#>0}&4O z2eV0^kNAi^P4&OlbiE5dY28R+6@ z;0@;|0RsOf!MR^t0N~HT+eVbFmR!MZhjT6rL|3BkY(?ttiNPA(lN5g>jPmnK?p&r? zh6sbXCbeheQ-rJi=oVDQzFT1XXTr8@XjgD9%tQn9G+1Y$#bq?q&fK_g8vt|tpm-R~ z=i^9`rG)*@gOUXD#9wQDyowHQgdb>^b>>=Ev|B5Yc=6Q&|1|RMv4=uhY!Jb$`2?Op z-h6g6gTgv)htft>tus=WhiA+PA5|iOH*(>>8y|b|V(3TR`=_+^l=W3d%`_+u*N{LF)LE3+ zdaO@L99}H)>8b2Hw`~n!n9V5 zRHRu<3vu+V`2S{cR^#A&1YHA@R|+wWHU&TjGut{`^FjVNrKO}$QKOlQt_V~h~J z)W#g>(9qV7p2gOD+y5qo+gFerVaB{D8L%P-LVapM49P)_B_1l2^^cmF!|4?h!fb-l78pNAQaugfHA)MYyO|Uke+kW)*>;N*}7Jfff zpQr%Slw}HJUnhsAaNZcMEqsW)1~)X}$@^S^HT^;dD<&}S2@&P(=+^%#90~w}#n9cm zH=!RA!nnuMtHm^uY`9_p``(xn6=`sN*%!PHg%T%BItCDA>hL8z<7e^$#4Hz==;jY4 zXyJ<0TwXH8%{cdDPRfZJWSI!ZsY{oa{H130VY){U$XGmhiY_#c!p5759+qcLU9Pfz z14^8v4Ndtlw%~M%fQ=RbCoXwtY*=(NGh2Jv^s{+-Dp3LZVIO0;;qPQbJ*T!@DaAIO zpl~tbp%X225^VUU8r4Ch`$|AGexkxc|2}S03r47Ob6(bbo=;zgU!&k`1M-`A!%?U* z?gR2>VOx$)VZDByaYG90wN;1S=L(U2_#VW$q1b=0J|5=K&(<3E^Ey!9&4>?YTO+6x z&1y$heFx9&qC8o>WpJf#Yx8WMdTPoSg_t^@VaQ6e>kxDa?^O+RSFBX9S)nKg_XXX@|C{iUmQcAoc* z$w}(n8UANWwW$)r_nQ+iZZ)lGz+pn^Jx=MMv`Qn$O9XP8%d@_%6>O;Ykm62Ur%X;; zoBM=189shv^A$b|+&7&oEjdyX6rN6zNdx~bm1NR5L{LyR3P1TISz3l!tXWG9;{u8D zGCq)s+x%?4GDX$Y+2Ok-_2|R6C!K>8*@Ol`*f^&xJIVt%68uFKF1GC_3NZ+vn$jYB zn|rJ5%!FjL18EQ7VN^YV^Dt__he`A~xW~^=y-UE8FnZ z`~b@~H@STOoH&!BpRYIiA^5z^<;GjQ>+4wvKM2Y_L`F4&$dGAi; z`Gvpim~WM|Catb6%+4#p_paL~IvgPNS6#Uv&N(*-7o-aZL+C0r1CpiwLB4166uaz6 z%|59$cUOCV-wE%|UK?-?<%GQEOxBbfl%r}>u#ZK0P~vn$99SJ_8b-{M{ALC5OK?8I zCHT@iU$}TZipAl!woSWrw-i04&8Ke_1}S%2OYLJ1F`%WGN&}IL<5mjbOZ<7`2Jn!s z2FI{!kvqRtheO9d*v5GZqKWbO>oxX=kI>2RJrr!+iD`zu?trcX-@MQ)%1yv_&x6wnt)6KU?ivMBUh#kUbQWmV(dE7Muo z?uxK%<=7wUNOc@A8+MYXctB7k8`f~-5=fCy)(oSoymi1)b$)M;duCyYdbYyvH*mS` z+fDgfI zJS+Q1L`Zukl>+?LR|(^|8a{V_SDink1hDYnvg)pZ~@q zgna!sW^(&o0vTo{^!5G9_%@Ij1%K@N_8pKn^^}C#e2CQgC46qe$9>Jg6Fe)P2Vbu| z4k$Wm4%zoVd;$1!36$><2adlyE~5Rv2C$xPckD*u32n_nQEa)-^P z2$Q`&L@MZYzqBxVp#%sF%esJ?Gahi~(UgBZSnEcO^(OZ~>>O(kD@l2~{3_iFu|!U;cYXHGm@#$>Ei zb9Rp&cM>dwI=6o2qsINmg6n#AbR z*%JJ*^!YtlIWHuXp7+ZL#h@fAh;^ng+TE;sH>?vSyDmzUfYSDo`GZ?&C$z{aWs*L+ zhGjh4ce1SN1Lc6YE`!H~0jpTSY`6`XVq0w9qw2>V;Bdp85CPOpxz?v2mK=#ijyYEk z`$1D@0FGF8wC4<4Yy6#0{;?^(%9qmVtVY(4bfMKs0K6)6Tpf?Rgc&(4!Y9M-EeX%3 zGaNBOR-!lLH^LV|Cv<`2D946p{W5ot41eoR<6AovHef4;qx2}5e)1`@<}>x6Ksnd` zT~Fw9Jup4@7YKeg(lzz$%B=z)GjnDJuTfQomZB^#p0@zp*c)Rw}00;a+-`ee+!gU|omX`9(Bz zcsW`17A6KAT!pyXXwR+l5RIVkvZ=Fl$nuX7sDR6mB^&F~V@~6@(qP$?14VU$sWM!x zvNiIfcaIXst9FNHEIAjxT8NI5^FE4%MtxIPWIO- zr)$(dFw8c4!i1HgqLP@&RNTLg{$cUO<}Xul=oD7!i}d%x7;kDNsm?-;pKMDQ&u+`2 zsJGLeSkE51y;fsBrq)pcEXypN+R&FJJVQnaTXO#Lt_8BMvhHv}Zu`5k00*tYgQgQ9 z__fY%ka_d5TZH^ z)`YGOIby*%TWS(Cq-*mzJh6>@NJPzh*in|FqwZ9})346o*U74$s-btX_~p+Jz6S`j$ja!e0P7`3Ps4lgjR{j4Aj_38rLsX_Im0v z%BsOX;>*C?qG$q==H~Yns@n`1(-7F!fdu5tF0Vb27CIG2ee&^}l>6rJp8N;?vT4JP z)Vuej6-RD$D7Jo?4`Hu0?_%@)^qj+Xg`>v*xhWNc!K0r4z%5M5i4sNby1AY`t`URFSCBpq{HwoaW0aQ+=5TkT$^?F*ZG#3xg`x3hG1n#`gWR+Z|sTAJ5xAl<> ztuZF$dN3ZFSJFi1O8U`9h{P&tl*ZVJAMqm58=l#IbvC@sqV_bU*kET>lDa8XVtVQu z3wRC`p@zH>&kG)c5*sCRHs7~g(w(cQ6&+20zwpy#J=KoCKQ zpUHScpg#=hbOn1VB!LPCp1{(d>ms>q)CruTmzSQmL{^U!*F4TrEu5(Re4Uu;$XUxc z+t@@dkj%Zarb%S`t-^3uiz25J6BksWj>SB0Klng*tkesO`BSwh_b6N1Gdj_m{)8vi zTwy6!@!5Edu+kw-q)hF0&&(B3!>PK0gV)5L0RExl$=w89rj+ z$XU*0oabjT7A^%bjOTIB@FO=jDuXp;MBR9VA-a)6YPdLDz8+LWewfGl9FKQPr6tKJ zFx=Krt6qRLH=<2kO?z6kFy~PI`@!Muil04TO9h_a@6ZaNeF3>a9%Nm*SY;r9yI8ap z6t2NK;|8^f<2Ch@F=U|W=PT2iX$V&zM!63UIj+>rI(e*&di{rMCBNIo25m;R`^Mx4pt_};%pwReKq@Z*FumBPR#)GZ^u zg=1%qo}0X>`KS=PbalQyt2)-oV9hLM64u<1R;}m3`*s{v40}tAn>}F1_1{R1QkzfY zzT?BHKEq*c%5?!p?H6XrKD@*FAsessZF^aGclf&&ImZaOqW=94gb;i6T#20V`E*ez zM#_Oavo_31vv5Q+=C=lBtJObX$aRzduEMbt5+BDa{c@_2MZUgJa*w45``n#d3D!*D z5bA2#ElF7lId+~4nstuP%g@wnuW%lkL%kU}z`b#*rsn?TAF6I?NH1P_J@AKFWl-9G z25@MZ{pW1MdKMj23JRUx;~Tm<6d6FE*@K~Id2KhY(aGj1YQD=vi-Fg;@;2kJlz3(| zdF0)&T262?>u5mY%sdITAeglNk7KL0M$BWvn^%{`F;_6N&2ZR|A4HusuIg*t~VA5D3j1d!JHKl4$ayM*0=)*Mm^v-Nn4oQoILI zjTrvIJ*pE06HlPf>KC1lxESceGM`SqOs@-;kM!HRbTckL2p^9h!>e!6bM8{^2<)QH zT`fX_g(;<_m+OR3%t2uU5(44-1A$~A@Ne-?U}#o`Vz4M>IQSkQ6GV>klMM4|>Z$j{ z?34fm!QwKBOU@jYin@16c@I2VruZ(mKdrLkmd@vA_Uh!4z%mq9>eiLmD zx`x=R;;N^R&81LX;{h8{rrXr!TCb8rXdNW`t>a z()<+%ByH$}DBoL=BZ(hZ`Xp=HU^grtQpjyJoLt3n&IrI+0=QA~koSGCFN3~-E&0os zE-{zIhHuP+s7(yP9?v|11%_ZK)C$rL_rx`P^lRiHntjSuO)H$Xpev^U_y<>4vQhQGW26QQ6wC_g z+@bV(JtbLjZQ49o&_rGcVsb!rZPKZ25j1mKTQJrP#PF%5_69d|e9~0w>_JeDRA4KY z&OxE2yuNpZAT4eVfr%!)EwLtjobdal9cN44&Q%n76s>$R%2{giW6U83ncrPe6Rgb1Tq=*O zzL<4m%>=8xX8iIlcF{u#vae5OqpNh?EpI9sr8THuUg74hQs25FW2JufZ{g|ICqLM_)`aEziy7kLOkTvkb4Ug;^uN4he@q9_YBjDc zi(KVw#KntU?G?ovIf@j0c~j{+`{@RD`)eEd2q;b-z!O4q!&huk+2FKS{wyrqR!OS!Ab#rqsvBgQ)p-&>g>7^ldca#^u23y1Sj zXI)(zl0KYx!|XlxwJ@i{=sTm>~JMp;RD;;lbhs*!PM3D$sGDYL9r z=Xn<0?Xz`|$JqwMe_860y$phV3whHep+@%io#dblRpdE+m?!5*@{2|5S!6a$JcJ&y zCg>E(fLW}iUrhCi8@dyM3Cg19K=zHZh!4$ez4wVHhZl8rBzoA(^~@RrF5_a@&{6p>p|y&y!lE_%#u*Eb+8v1s`p>Z zq#Ro!{06LH6SxL;XKUG~e4S#5*8^^Y`4w|#h(oXs!S?$|ntNRNt^I`ct1AUbx@wY4j2W^nPvP$TmkM)A(1P(z;ZM+T`wcwxBk#&Z%3gMfnA>cjbDQ zs6;81DUZ_UED_RwBGUrxcS&N2=UmT1%!0djyr5Y}24m96QCi0)Cm&i-((e6MI)?{4 zCbHYtJ&yc>w&pF#Lr+&W{N!Ad_u63Z-GmZahcR}mZHU0n^|fXJa-9~AbmghD4bMfP zF2}_aGr`eq%3}^#?d3F|wIpS+5UF!uJ4Kg8U7h~1iV|dz;@3P{~NlyS~lgpC6|3o`EBz}U5}MyWr56p91R3v zI9!fE9>^y9bjtlrTzOhafZH$pgVi%F>MVEerFml}z)(5D1t<+Ii47^0Tj*zLop4#o zz02zz=jEs2&ly6=MicZL@*d)g&`Q*D;Y=uKLmk4>0sZPXkp|}J@Ce8q`vw2^jhzgA zvdT%8eOU+Sx-fB!_g?EbeBFPP1aDSA9ONIIKLt&&%QB4yCC&&W{qvUIu2|{{hh+fo zukY%39D)vr-Qj+Ij}tQCoUo&MaF>1kxrpq^U7|1V^|S(}-w@?GZ4>z#cuH09trywJ zB@`Xb1VCtah;phjAOaW0R%34Jy8}>+kD(>x@%;K8PCQ)}Rx44K8~Iw<-_lwGW$N_z2Lm>mH}( zL|I9IBlib4XO5VSCl4z5Fn)hGRL#bA8lC=Tu8vJysgsmD`QB$|9LZmBf%gwvKV*zh~t~z8L zFX%Y}#77%@*V5R~owiSC22c}lyiq23u3E~ib{W5g83J~?9iFm&19(qoJ9>?rIgxnx ziZ6N%%uHScX9*Sz(yPsK{|(*wdj;}3nGx?RVob!Wbp&&`2iosJQ6>nxZR^D^dI}#A zuLsp%57JjxxQgE@id|&2<6t0{0U40(l9|hRSn3I8l=9c8T|hVWNYL~s*SPzqu8sFd zxhvBiiL4v4whv)rmRg(+yI_HhrLmh5(6c36cFo5@k10G#9OJ_gY8}s#RTnkz0`EEM zk{9dN$O=+se#*(C=17xoHBwfuiek$M{o4vXwLjTBR?}e$V_VyiCbV4ip=lGln#5gv z1FX2nLPxD%bVJ_CbhU!D1b^VOdM9}izn1jEr^f>E)3Hr5bw0nIYC^*~wQlv0f}1%> zb>;##b$SJcYIs7SJ)IwLu7*#($HAe&*_@Rc_9BE4$C0UyWY8C|?={WLa=pc94Bl1> zespgJeuWx`wbX7=`Ubyk(NQnNx+@=SZdrplTiDXo93ExTGl}f*r$N!^#xS|FsQQpg5@^f55lNvJ$qAg@L4^2Wx*`K?l~!W#1| z!urH@V^@DANbpHcb?CAf3Q4~V&@gMatHOMB1>93gF29|k9gMEyk(P0FH>F{0H=vZX2%1(FXu`aPJ zQmJQ85UJ;~uxaw=g zpa|1=>cFfhcmSyCkwo;Pt^=>lu4YcH;dJ*7W8(QrXA2#<6K-N4aRlJz*zJInsjbM5 z9#cH7>JF^S`UBY_o&v`TQ)FH8$6~hh`0@4UX2O)6#O9fKSWyTWb+kZF#yU5ZS$ZdS*fs zDWNYiqEO^fmN@)C3095-O(13z=fkJyIpFt;%D}naqv0gtWu(u9AhGQrc2gLdQ z#KHms!P*)Ywa*N|TCcHIujFehjY|Qp?uVC!%sjZkw`LA(r$rM^j&h^dRL1%@6TrEY zCvhf^OA1bF+RYNtZfs9<%w#;41n2h@U0EBd70o{()QV5BT#0l6*~N!Fa;w~52DKMU zctg-l=(eSDm=9Xve`TY%1Z3*4EafAq_MAVY<@J=mQ|} z#UmiAN3v;=nFJ6EiC$^T5Qw1p7RckNxbfigCw(0q8X&pSgyW>VD;5aBBl-b|I8^;8 zPa^;IYf3Z_SjdvILP zlarIJZP&lLooY1}6g>@?1@#H_C8aJY70 zZ`yWnn7Ah9Nf&qOxpt`Y>K{_8!0p4e@&s2`SJHQ{uCA(_P_GnQRLKIt^<ab*0|v|%`AOXl5aI6~kg4^^`$tJ}O-*WA8WWH(DrtbL zTbdLZFkd(0=a9X7NVBlIx^w)x1T+8VHpahDKcaNUumgVcBX+TRe48cLm`<(6wVG!tHD~LPF`wuZh3%$W;rkGvIHl z3h5sCp&GECvk|JZuid_zy7Aqs-b-r?ps23F+CG^lM_gheUqZ(TnXQl3-{qhbCQnNQ zXz<5kh(Y4NvdHz!wJz$sPJr#XiMEc+e*fsz3?fkqx2%#A`o<#fgy-tkN#ea1YwnkF zq&LHAj;t2u54HCjcET988SKa3QIyTk90kaJ+x29C)CQwVD@&dpt*%^di*RpCc5f>X`Zk>)y7A~-jS9xawO&&suqdTs zAVAnav7)P9zI(I@&4@<=p3Y)x?UTf>Qyc36tuWURr=K(7+H~&>q?Ml9A9g8bm45k# z@{26B6NXzW?HvT$JsB#)xFL}Bth>TKcjeh)o=cBQxi6{ifD$kaSKL!=Ii038u-(OH z6#-fg;DVh74z=bz5*H#{;7&+^{loyR4f`bz;}!9SW%I+20or2)#yb)A4Fv@1;vpX~ z&e`CnXiEgzp9^P_h%HDCLnou3CA*bdzh8TY95P>FIN#W{)ZmCD=WV)EYH5&emhKc#X_1gzSUMLFM0%H$ zmXZcR0i~sT$)!W2YmpM^Zg|({`+LvXb9VpQ`~JktTr+dcOgxY13)%9p7kFn3Pl87= zic?655L35RXSZcP7fhI3plO@8e4(-fQH8Ujz7HqCoJSZS4+v!RO=4IyHDaybmr!D|`BMXJ;4hg}fvMz95S^Kc* z?yrLDePa_*IX}pDE=t*$!_9H! zlpdnjqiidw<2STX3wZgz1;|(IP0#eB%ggh#7=j2(A0zHkf9R&&ZOWaIz?~~fB$AM2 z4ZgEae%eE%uXnFYPNIs;dYoS|;vA(ZU&xYN86W|FPZhAG>f~0Gw_37aPcEw|Kpr@+ z(M*#YA~WG;(5dILOPRmSCRBnitJpiE1TljN@BHZ#J?o}n^c{sHe*yzys(z6JgK zJFR6>8+km`5U_ zkcTfeR|rm6&y7P*kHcQS$adg#qPcQE@#ts&>t@qBz^t@Hkb`*#2$>ag5yvMBSsZW3 z+#qGo!*7eeyOsMC?tm)AT2(iFFdA@yupL<--(Ar?PtI%k-;TO@$1BgBzR2#(9cX#8 zK44Wc%alaA?3`w;8^=6ec;N1Su(QU5a`y$9MB-h367|Wat@S~x2jgMy z{mrI6+x;qfsO(^r(`4xzM!V?|8ggBU4^<`O zhU0O|?R0x&kIWzFWL|$EJfrpyUm9W47(atN)2RPj+kfQBdE|`L{-U^WdIbG3 z?)9_y_z`2)wXEx9@~^1>RQ4AEUp%MIw_@KY7qBy4-akU>l32=(fzA$uYx=<^or zSoGhM9k=ij%@$YO-~sf(c`p`#9V8jLGZMEUn>7q5(l`Kri9J3jA43QGg5}ZoEQ$Ba zVyMt7D@A=>w=!t$P*HJB%N6Yx*d5guj0)coZ4}>Se$n*{%4+;Cr2EDCJrhLaO}4Gj z6ECqy>!gclMtB%IUTf0p$mLpXjqfF4)9}@F+%KD3nWzwx@sIw|MO1~-s9h&t<25&j zn|6p!_sR0`xP>io&v57^h;OE*u=DS4*g|umG@mpiuiHc9kEDN8qA15^VgFk; z`o6A0TOhtunp6aqb^RmT>uhU%}wwFRG_1}OjUb{QAN z%$W$Hx?Vld*+}Fk>i?C`H%MpiJrI?_j8@6BdWd_+b$*d!)wBAT{AEq_KiJ*C#>~zv zRl&u~9Yi1n$k0(Jki(Tq#N1Wu`5kqaq*?yAn{*wd1r)51+KXA98}fgBorm`mN|bEZWN-nLX)#nJh;6 zpOSJS3ZRCNA7Nc99Vopo%1aG=G7;p~H9kqJ3t5vI;!pa!J!>33+yG_G4z*4c@BZ z5RKA`=>L0Q+_e-$$mx@xz>&z$;y<29EfDK9-$T%IyLtH{k(W-pS8~GnfsQw#1!3h* zMyFYmfYdrhsk}OawwTu+D%e7zfgi9O6601T>T<7es)gQ<%O{pw&+G7Rb-s8oK~*{w zzes-lKfo1_p3h1+{|@sJLoO^(_zV~M?Bvtk>44Sws=SP9YQwkbjdsPb@~GFRGCv>o zKQ;Nri#=I+_JFr;4ib7bcpCik;UKI?O3-cf0j({%E+r4+E(fcTFm!6L#g7!7neprK zi{!ljIb~l;z9nLkCV}>tU!0G4oqYOLd-b@N`z|BLZaV7FZLrwm`Ev|>cGP9Z|B$Mu zLX-65WfE_x7_m0lGd+KOePy+nP&{rmJ@TaQb-H-ZJ(ORCiea#_vu1b9-`sn4uDh}X z4a?RB9PIj6yg#jJuD+HcALmom;+|xdSb#@@Mhv_ zj~H%57tVu2B+%Z?VqhzIfW(X@v6PSO+))JZ)jpOTd+x$fEFF^{?0p}xm4hMZ)p%D_ zM$R3P?E;e6dAgqF%GENjLFZs0P!RHXqlP%N6%urgV;YWw`g6Ci-*veEdkh&?*ANfp zL(H_`S0zSaQa>Uoi9SzkWd(0duf3RdX9$)vNRI3;1g?<8y880krn0z(t^o&5-jS@^Oa zNQq(f8%juB+rApfP*tdt6A3R~Rz?lneQ@6cZ5#acxKW=a4`!Hp`Bk`q1@%Jj@jvq8 z!BD?g@Vw$2LK%T=sA@e}SC;G)!)vlSx{K~CC}U_Pd`n3{^xJw=JqM+pChJ7nwJTi1 zRYm-?)Sf!G`bjxKDf$*BA;iogQ_d)U+HQLAbZ7#v9>6!g0FIb{Qoxq=i}(doS)VAA zSnVy5AIe6`c-rK@ ztD&tOZTo*WBni_sc7BjPnYdXIgCTjV0LD^9OR|^fFdK@K$PBf4O&s~~si4$QTYvJ^ zLZcP@cOON@@a41(ZAklVvrks?RTFBx{R!vNxOKaA%urW}Lmk}nVoLfKQT)6-8VM`Ak?rg($iMc!DHAYy!85HXu`;H0Rl`JJi+R zVEa$P>YRpZrbhc6iR)PHMc(1e^z9$-Z79GsGMw(EaZ=OKmJy#sNTzeg{t_^TKGy~q4<5FP@ZO4-gKzO#-GUgQ}(c9GM) z>=gt*VyIW{=U2bt)jRXwB1|OhzxjDzQ~6nRMr<#va9#uM=13sX@kX7xPNx##T;n?@ za42%uhKmyN;4B7ADE$#{o$NtUNl`R4^*rj(uT}p$`-;3*L^-Yrw1Z}aQbyVh*MY?~ zf$})1e^W5)F25n*n#w08TfW5enuAa4aI)gjv*rOOC_5E5zwl44SfprfW7F1%WSM%F zKRT0P@f8tCkx4y?D6BLwG>qEKz#g3CaU{9qUU*_8=6Am%mVU^E5P}+{kQ)}7`05pf z-24@mkgj}w@CkhtE1?Ine*@ASI^eS`OX ze(y8Fn!j)W-kQb)iF~jATOM$7uQTZV65_IqEszic8J^I4Zk8dpO@YKl`XGadmR?J& z1)%gvQh+(y9h&L_n#bplrdT>KkQx!@7+M2@J)fiLqO`|nP>V=E0sBEq(^pGIQd&?+ z+Syj55Ldt7MVfaaM;tuS!a9Q%L^bQC!J&Z-k%Wj7d{8zkQG8iS&vBWL>#OY{rJQtm zCnK$njBDe_TF*mki#Hq)Dv@YGEeB*5{+t^12A8RycgDFvihIWT@dkm!F{Yx>Z*X(U zFPvzHAiZxqw9zy1W;P0ci<{05FyB5?t}qkn7tnu>8PS~JxPCM*iS2JP9Wc_GL3GlqGC9@4$r9q-u5h%&ifbpMmC z_kG-NWtj7ps=6$6i!pXRGFo%WUL(g`i6F}~9g<}9;~u!Kp@xnY)kCg9M52eEpAQn zm?Gz=X{}u)jy#a|ray2sPCtHAxqZqO8YCP&#oYJf;)=-?g9y#H$HEfba^V463xlcq zd+i-THMVk6ryTV2BL)Zu!hPh7IvY->Irg5GQ5`gzqZ>9EfS-lp8F7^evK+Uo`cU78&397u5_^VyV@>1Dc;>SkKN;b7Qs?eRc3C z*Wp`iE8zL5n58scli!7%Zw6%I->uq;|2o)(= zd$&U(-~h;GAjWhF69zOA&&SjX{tcKvqAHH?Bt}k{g`4N~qoVxbdL}BXX z+s81XJ^8&%RGn1@c~VT*qXN=va1`(`{*2a2R)jG%nf_P&ZmHLyxT2QoNLQ=dlHiW~ z$~Oy>0QL)zAQ7_&qVlsi@e_ZE5EUL;@c-Ut^yxUG(vxn+bwA?#NYdI|MzU0i7Mo$3 zbmHNLy!_&p1Y#wlN;ng3{U>J@m#^Qwe+8^8`jehf>k`|)usRipc1`ri`U!LDCmoVE zqyH0EQCJOzJGTyKwO2isuo`e~W3&`0W5TBMGGX{w1_&riJMt#y)F4siO z`t(Rnb6aXB=nW^khN?)=m^xDJ9pew2`(5jW4Lr&*8TP98gxGa7!qGI+fup+iP%$*d zo2btN^Q4bLnFQhfXJ5a094(ldbK7OP$H{BY=>rOz5$PE{X>Vf2`hHFxPI(#HjCQFGeq6KRCt`|jCQDp9xv^O4R+#>Y z=^A97!{AVGysspesEC%Jw)PKccg_)klSsQ%1a`pv}QjGv9l+YA@90(i!EX z*)S*M>c{Ow@Z{G6{;psEV9?G8zvDdEVlr0^Y@e|(yC+MSTUrJ*o|2nFId8$WuD77-ePBjUQloS4%aC4b*?9z~KsK$_oN(EAvSAbs*B+Wk0~v#G z0;{a!xKi{Q(NeOugV#)68tq|R()lzE@t_Z-9Hy-We{u0@Wq;qsSosDQtaA5P z{F>-LH7M>6MhjxMG0^H)S&*qYKER`S(1&OAo;$`YdzwMwROgkK^Y?XG|X zRtCaSjXC|3RtaJMp9`@54M-7Wm%c3^N+v}qg;vJnzrMZWk2D=|r;8QG3UP(j;EeY9 zr9N}1sX(mlkZ|E;WqOH`Ez|5%Zm-t^r}%s%#%3SkNq2K%IGK%cy=8w)Koo(Jj~|Sa zmu#M@cMn%9&R>|Qc%u{8>%U2-UMyl*rWqfQoum?SRPpWGT(oams_3hL16~Uo30=&z z_z}-3Hn$7t;I?uk3Um$b`M-V)tKX{JkiuA&lk5}g8Z1?dBt~JSomVjwkCP^?E4i*G z-U4sN*X9920W^M8SEQpfqI^A4BNrKfRhN1z+JA`3?Grix!36#Ip|UihT+`RmBhmAC zr_@Xv*HX7*>?`@{jkIH-UgXm*!a*>(`O8G$pyw0~(<;RrrXqV7kfN9{SjivVieu4N z+F;8fiV#W*ms%3&2xTrNt)}Chji`&eN~@7uV$#jZb2MzWJZa+{`2}_T7AP>!TdhSs zQNFReo8f-TDVXeaA7o;|X=8LhPA?|`xMB)czX8R=-QbLKq=)v%#=5-A0v~T$-#x>+$U0Pn3u|To)8uSwI2d1Z6mM?uBRVM$N)TMpRAZW6#_I zTixBz7nrN-q46NNY*tD1pHpEfWS21lL2DSAL*w&Yv}V;TrqZ_vTdXIxw2C@@IKgQY z9d~jJGW#$K^K8m&iA^)d9hzJU;vunv@}t`Ab~l$*Vi$D2thW2N?}jtT2&P*wbGQgWjSu+1`Vu-u4RcOrp%lLPM%~ z(qP=Zt_F9n5Ccvfe$ZgD&fulY$NfG-Eu+1mz&TNH)r*I`mvZRo1y|xUW%&Jtv;*NA z9*)CnSv8KmpR9%UlxjtJ&pv_h-r~eK7*92pG1PB23d2SM3Cb?Dn;b!r>Mwx|;Lu_ts6l|&& z?!=`NaD!vg><+Bb!+9(Wfk-$D1i8(WEykcL{%%IcF`-t}@l;LbEBFgKp7 z&-QL9LA9qj5l`7c`@M`b9R8aMHIC|0k=dV-nPLuy zxa%gM#w&U8<+vf%rsa82dfid(9$E#?DRelQdqq^N5JgK~!8fn?@6MkjihwAK=Sf(z z2a-M<&w@OM{o)SgA_$M`Q4ST%tWhj6pqYx`2qjX+K_bM@6fkjV6{g zteDN<;dP8)dw_NQ3d(uCI6sR_KeX-r;ekF2YUySdt6Pm|O2$>LmWV@TdX-TST`N5p z2TXl!A3&>uX9N@S|3NQVK~t1v zZV?pY6lc<;>}LK-Z1911ug*}u=FOjJ7y9qti$y(FMqUSpBw2Iv?iCC@nC0xLTZ3*@ zwfcgjAS1 zxx#fElYe4hS&1$9($k!8i|4K_2(yCf0zST2e`Sn?>NQu&_qO|2N&eaetBIx{wmLY$ z6rI!Pfj%4Es93UGLYbpu98J=Ot-lAN`^ejDDws`k2b9)9NI=Z2O*caH_)%dy6X{Jj zsptJngzJ-K7x0zTEp*~^ePd1wQkiAd(MUBU@Fl^e;e~_6|Zu# ztrviIiu`{F?x@`57sU4N7H2gvi>Y` z2Iq>)9bLv6MV%wB!asplSr>gO@tizUFgj&`84hN?tf8rK_|-7DE?ac=1mjJmx418H zJAEuruy+%3U`c+UPCvd2obV!%U|$d)RoFCn1Ly0IJ}M}=x%`{ zO1aK{>wwfWI2-gTLJ%KzAKkcZkcVMDW0( zw@8i>S%}d;&`1Tu8)iA^>i>Q|_w~;cN|tnxqwA9k!YdA=;>xJ&jcp1}x9ed~09ugz z^^MdKlMG^$)1kobY}ZfzR+0|7c@XUlT|6RUiZLBy3U}Hx^~6q}YKvO=8avrlgnNN# zVQv46jZd@o7D6pdXvWi)NZ_eO;W8>T+4e|d5)_CwbGDNHFMK?}ItG7R7GfRhg`VYq z81Gc5sO@I!^yD9G*#Tmi9R?-tjX=-uY(r`ny-Cx@wiQ&jlUc1HVwjlKj=ntU=Ds~P^XovK2glz}^J8sa7O128 zLvz~;wQEJ&#Uth9un!P&8|%lvn%GB`Q4xzLU*UFAgm=_@4-TKLx+3Awx^pUxen`w%w3R^xRy`_9-B9GB60qz1t+(PT=BiN zo;guQWi`0C5jG_yH3K_t1wu#bVz_A@=Aj1bwjf+No&%-r($T@5AUpa^`#9X3_?pEy z;`I>Jl(GkJ_L(zFWBTOX*@u7DONmHRbd9OK*aA2nghq@iPk6Z|24yk9|7Q6kd60BS zle@R}{vX;CZMxO`4leuED;#VNO9})|z4?=x8P7w#C#?@M#Bl3h397MGYyCjnn+X1t zXl7!Z6-|S-g2}Zl-9MOStu?*-uBMU9^hc#tF}OED*TYen?ONO@J&0K-LKgXWorl_^ zM~0Z%gWL?-G|*Ue?A%055D zl2}_nurCP9DR&d_$D8+wYw4D7iyg53>s58L{h=k2eWi(6Us=hV`7ml`=T6wCdjR6r@H{Ti4uE><|k$+EgO27wwvu73kDz`A{jXhgwYPz4pZG zVUNjl11eZSy?$f`?G{D}=={M9-gxx%y_LV}uxHE^lM)%$dmUO%5$4z%J^X_+f*Q5{ zMF6HhcLllxjU8Z*E{^X!780;X)VcFlWGfe_OaIYZpTDe&d*EU8gfEO`fUkJ1R~Un) zHyh-4_6jLwvzWc9y+p^)o@i=;^Zpqv!R#WE%Z-r#8!mR}(-Ge{F;q6Edi{RHG%v^N zj{L%A27)tM&LxaSJF=FTvbGA024vwl866M;cRC&P3v1fN31vTj9~J#C^wh6?5iy@F znkw0Aq8;SST#7}Qd0w$8+ri-+<^|xM)>3OpZ~R&H>FK4LNsTk@gHF7?rMAu= zJ`iF-r^}P67-W^wyi{b_9MfJ>uM=goh&J4m?~#3so?u-_8IJEJd(xu4|f{% zKqyNtm8AVu(Nu%DGeKfX86$iw{3Nzu z+v4c&a}Yt!TdKP)4Fd3~@Cv5$$bQPAcoQkQZllbv!hnJ>Cv+K;z>gSOfB3X44f5OE z$sanfP3olSb*D)uvoA;c@6*Q7TeY%r;JANq0HR$lrARO3b~!EyLv=&xL-UKpOIZv% z@&bcMrZ-ouwfsEfG{VHUEVK-z=v%4w!^+ZIt5u}&V1Y=29HL!MswOTx zkwR$WPppqv1T57EJG~*_6rP9|x4w|Rl4h7A76nA6*b0tB4TXiik~&eiLf{{58Lwqc zS^pV65dC|!%OJN;{W+VA+fm?!`#2Z<&Yy^ox8l{ToTfB|5oR=U@v@-JH_9iX3!i_O zL~~G0|4B!0Q5}Pa-h~{US*l?#oSPiI#(PakK(cKOwC>ypCXe~@ z$dZf^#@}kAFvMq4Cr<+I4wzK8d7?dDmAuYtF3C*FKy-(;KZp_^wT`H+E*}W`DS2L> z=S(H>KZTU^l}L(K`vmv5J+PLw96`MGjKA;(C{RiKb(|Rf%|zsq<}5?&V{OX1^+=v9 zjd3m4??+V1U1H2|@R&^fy0RPp_j9^jl6{YU{eDtVmnM&%x=VA7CW zqgCGj=gu6&ul|RL1FMFGrkPXPy{GNF$8WDkreADXX%Byt{E1r7J>mmm-q;E}`NW=R zh@NlM{f;!UMhH$X+kGIUe4A~(^Jk0cTfk>G;0p*@HITq%mur=3|2)cfap(^}t zQx|T0lzb;CCmB}%G{xo;uXuhrG9udw(H4$M+(YH{XU6=nNBVy*45O6X%0H4poneCt z)DGnJ7D3B8rCUx%QE1gO(oX-A*8bo~suE6v)H(R^Hfk#AV-qw4@K}`yI{mQxL3@*c z8#|%7P78g`_ z)l1k2z7$X1DH+-cj;=dDA?GX{ho8#f8I9$^1>wfWf#16MRJ6VLdrSA9p)!}sDrAHw z@f6AH%uRs|@e9*waG~rI8pcq3b3}p4>zERK`QZyJ)TGoohsje^8;jjBlMo+betG=( zrGz(V67hF?FV=+clu~wDMF1WflsYLL-*Y6sB;b%4B+5? zYj*}3$RiQY7%-1on^YUz$N1qU6a(xxh^k4}GK;+!TwgvCTO?C!@*nvr_}qQgrqqY} zNTeU55TM`~++V;D$ZIN?&>dIHc4RQ;FNN1cGk&fiOvZp^wZ#(W<$=4GDwn>)W|YaW zp1l5oGM&wtzK%pBXz(E-Yg}le=Jxx>1)V_x`E=Oi0e@}v&>X{9@89ns>pNmNwEzN7 z;#L)Rodn|}bH>Ek>QtC=T888&T2obta1S>eng<&Di>Q(g0#XKyLs#_kuxj=qI?hj8 z#RV-&8Z#w>&Ic9m{pU%p6gZD6VqhS_Z6MEZ@ewu=z&rQX{2x4M0d2j$yiOo0DCD zy>yszJgPiZ>EcxXSjpn!u9dJ2Wdy2Rid3s+g*l5<;_9e=Tj!b!mBX|3pp1C;bT=2L zSc$(|2Ki`%e?Mi*wx&GcKaV>ejtk_vE-?x8WIoC@Z1)57JCpQcn=lHtq$5#-L@4_X zdN4-RYl1`yU4*Uo$+Xml;7@N#?$71fw&ZaqH(v1RXDI&=*p*8hm+C65e z;IjxcsW{UkPd)_!a(Zq^KaSp9Bo_^WUMnFLMIKJz-x zxlY|G;Y?^)b)v3#$9r5=|?jhHE=V%&UtA{c99LJW7>563$BWEQHe@5-x{F!D|R zLqt-o@SE#kWQ7<`cHDaUh6&T{?|vJHIMy@l8P&-uChT_7$%sD$HdZuZ9IZ&$txT#X zU$y3_A`09W`O&P$Qvp6@XQB+_FCK*JN3HMOHsxGnXA~&X5owVFsSO@C-U1Vq3DO|a zIMkxLbX!VJG@%4aDNZCxPSRJN?=P22jgg{%=GZW`L%oMDhvPy|jp6XIIDetf1Zo^( zR{aTL(HO@m6=|3AW>`|NB&h15t#LA7>w6rW$=Kc!+@eV1Zt@`wXJaeJ zrD&pqgrb;V8(CkSf83cd_$?96~hOdHgwX-ydMXe@pNPjE`thMLCAo;B9I+|xJB z9(5!WODFgxH#G779dU?@~QYB;X~MO#Ik_&P{jo0i560ldz;wf z8)`xwsbJaS+TtMVm!t?l}fcSh4{vl-Ov0EWO#4{-3=T3eYg&jSmeEM+I?^i`_^Z<+*{`xR(L)z_VMsf zHAS8HkRISxAq(B^iZ%lvFD7%eR) z#JX>{vX}EaIYac+_-RImFu5OktY#RC34H=iu=b4Uu^N8}inHNUP4^#1=txngw+`{O zl)b)CEB*rjQxUg`(#?xkSWT*L%Q(Q=?*X(&mclbIvWHmhxp01jhtD-U$8Jb(6>hdl zaAWZ8y4>sC$cXSEFChlcGfQoe!UeMsbf0;@~#ka(QY00pQ~Q@NAmmy7_%lJE+?x$2zalP-PT1?ZKxJ-=34#1 zZZmhD zMN{%DHs4navrfjieX4gohV!{~-yL6)iHUAz{Av`)Q_e>oToj`;pT_6sREbc^12zz6i#*r%KxHM*5bWBfOE7T|zC7R>tf!^O#?8pB8#x0|? z7T4%JB+|Zp$FQFHL!?y*x(>!gaZP_~_L}KiKJ$E|BBL|WI;vr5ktyV}x2eQ1P@nBm zzlX|hA0gzgR3ya49gCC$VVKeD%TT<0A4+w(jf$aZA(|;^K>6Uo-4{+IrK7K!{+9eB zZ1`S0%TMAJt8w{?@h0*c;I@N+ZG`6Y^0POmcP;C{B?Zjd1fjmWj5w(aDY{l4jiPeq zCm8d8UqKnAXL@Xr!_^#WLdeCYkt~?Ht#b8E8|IlBW)F#9x3<9ew)sj||nk`5rI$+5yef%xwp@@<^d*=V7HLn+lER|00^e{zOYcc6r4Q6y_S3<5Z&vH*j}y&+QAN_b80NJHi7r!@)l3!i zGAzAx;&`S!R84jAv=rEpMZ@!dQ1L2iyDNK!DCOH*s4=j|SMZ3|qw`(_RY}?Vrk22A zjKKV}F5*}Hb|}4cxaOZh?uQYG%q!FkDaCLcTC6Qe*}w))*AKsNA=qJSBe0YZ@!tMK=yNNUDDU0|_Uc>eYu&j~sn#LqN? znp<5Uj#csJ{ed)Fm1%5javOZu^lvHDG@p(pZoXdI&0|3RwcC1#8b{HWQ@j7q1rVek zN9c`XJ7Tu8HsmYHydOgVShN`!vOngdNrGBtR!n+?0i__UG2vEg9~0nA=}bXvmv*>- z30d6>cg=(VecDGxLD`GqG}D|^%*A!0b~Ud~rgqD}^m0`a*QU5i%ILplXTe;@EgQ{@ z0}@hu@ibW$p{BgtzX1i|5wE8*M*-sWU7LTGkm}?q5LocO^u)Ia{~X;491w1%jbbQg zN&y0}IMpnpGgpk!(>&VyL^(JDb4}8*%YJj$wFF?a{vO3?DB>79>BNjGH1`5*En!!D z08dEy-fjeo+w&{NLl3ryOK_FT)?K(07-I-)<5qIs6o`X&I|$6x^I~E1+~#&3k%kW0 z?5btz_%57A?TRtpw{@I!2oUew2Oq$=McW|s*D-mcmt54TBmuCl6)oOeNIj*W1rH-Z z#Vl138Gg=;e6d8oE#Bj)u7DMP)5@MWyDr#4Cqz{1X&;Pvh1UMuvXAgNhias2|5CGe zri{;Dn&4pCVy3fh=Qp9r0a^v_KW+^lDK9X`E1!z_BOxXpd28osW(;it>0~ zFt4|RbF^i`itzh!Fe-d~h4EjE6=$Bgaedn4@ohj$&mh%9xcoT6T4jFw&&L$oaYm9r z!rKo%h`Sm(b5jSAutUdra$J`I?Li>gWw7k*thbUK2cfXiTgr<-QrPAxfzg#*?9W|x z^SzMT`QUXaqRQX|qe9lL25KC%?KQ)%@|G{C*B$=iA{(BY!P5 zh(jP4TE$|P^O5#~lk299NtNB&dpap*Yc+n@j#rsoGQetY*#?9HZr8Jsyv zhp{JGyFq*Ln@tB(r}x*Q zgRqe|y|pjOa}|6hs|GQ?rJ1SoaGntP4^z;Cjm_T*^exSh4Wxg5GW+Y&X0V?gGEf1T z9Yl2cAi2Zwldh=2aT%rjrPxR-5eG&jZilPI0%BmjwsBvVKdv0XavVtGdRG#} z(XG_%+IJ*=*uihP2kqY87KlThLNMmZuAjvHeq_Gr%t)Gn!&n{%q*8-1hwEbWEKEa7 zepL;AQyCeY%@NRKFwtSs&1 z%rFd^!lr;f+p&!_Q5LN{)J3=qHSvjSiMcbuIYh@a3q%iK^y#HNwe{NRJ|d{*IF+K%xYf`pfcacWIQ-TD z0mrsFU*;XlL2ONXh+*Oz@BDN~`u^4o>!G2n`KSLn*MMd#!Mw8QfKOdQEnUVa4-ZF2xS>!HfFc%`sENmEQRUvMDD1lW2(;#G0J1iI?J|6hm1U!n*rFit~hj8>Cy$SPi|=5}Uu5APA=b8nC0nrK@Y# zjpQ+NtLP+8%T-RJ{=A^Za!VD_igb>;-HnH|&f$7@$RbaQNK{R~nmGL;IrXEqA-F=DCDC%`H^m&SZjWod53Oy3VzFb`MDKbToK$!th_8Pa#-hpL?iPZX^U`p-zU^|wFDACps=`WGS$mHF*#{S-pzPKWZWcmix>GlPJtUrFe@#t?lM;6E}{HR+s% z%=W>I(Z=~!=!#lC&rr#G^eN$@BMlV8Mu$xUToah$Eq2h|0AId;HIj!Swzf$JTRUs@ zcAog{J#UbGsP6>v(|D?!l=ncVLfwEd=bCT%nn>Di85P8=+-m4rlmzHDaO;w;MkzQFqYvr@UN7VZ5no)#lL1l zBIU^rOb==s`?Csl=CVOi>2&rJ;c?wr8_IrtRv358Vq!JO$ob#oF8h5MQ;1IbS9{XvkLj6M8Z@^%sYQt_rQ-_>iJfd};tg@Iy( zwZ6QQFd+kA1B-MzC+-|&tCd$s&qj?laJ__{&ix$crCz~K#$7qn;OQr>k!enFg--uD zD_y>pYHQ<%L6eg5$yRX;&D>pKns4V8r8u8i{DrIWV+#AOm}c1W2ov7P zfP2o@FWh_Lw!!qbVPWPaFjt~ORw6zNyc}qAfN`-{B@4~B0@Wz(KND+ATO+g|$X5;v zdb2j=kOXbicjOL#S@Nam18&O0jE~*}SX(fvmXyf?KYVP0EHawC4vlT-8$8DND;}Z^ zhPb8SdP<(-F9-!k%2w!cqOLS{8o*Zy>k_eOliU+gx>`=PZT-Pi(%dQtHfX;s?p1w_ zc#)BFO~8q%i}4WlZKC6PRWo6-DFuMF2c!9aJY98E6K>Q7Mo25t9ivOSK}2CA6{S-d zAl)S$f`Gu-5JXC4fJhGs$srP>1?d{yFuLKJzwdnC{@QlV&i3Bj``&n;_jxAeyy7kb zqCRghz13%G_QVh1xT=_v=r;KWX=2T%@L`N22*#vMlRPPcEh}Uul)b-em}F$mf#>nE z;Hl4US(of$4Gv%S+9+8EMROHAZjgKVgsbe%;Rpl9(2I;rEd|?AJ01LzvGopv zPH%;6H$%hNs04vL!SpEA!|C6Bgtmz5u+u^xpiL1Hu4nq{I z*&(4c{Y2%ci!VBrZ?*5@Q80QEefW@3_4`jpM11!V(Hv%;7u|4Qhp_P;u{_z(4?Dl>~-9vR=AZD7i)vN#8QH3 zTkcL%y=G;@PXXjw%yJy?xXPPF{Yeo-Q#TYlb$xQg9U@i6cUm!0o5ipbPu_IM@pj$$ z(Lc*}EwroEy4Z_8{rD6roVH;8l2G%NO&16xvS<$YSDt{ z0`UUrt!iqCZxZdFgumX1By>uxdKp4MPEpbE8|{HNhy#^y1_+2;;cZ#olChG_^oFsb zx!%8$HRfJBm|=wov{wg98(Y43nRF^D04GsL;bDY7uJ}K=_$>Z}C3b50#P`Ru5Jq^i z9YLRj=BwFX;t%9iXrjyh*|H5RA38(rn(Ri#j`|9x^X4-1Dy0b|Seh_<%MT-O>h|2MxekEp;W z`C@e35a=b&6-+S3+r>?xpoh}A3@n{;PV7(+=j%!kXxIMHJQU?kj`5LQdBC2}au^f? zm`oo3)lBw*3ker@18(ey<~P*O zG77aUz@K$rAwGOv9UN>#-%CE)G%u$*6K)THCU~GLfD~ zeMnPKYX_3G%=k{?ez(}R@IJQ!eKj~2;pI=EPVS{5_L|?86eGf2z;h>R)PdXKGB>t& zMneM6OVI|zr-B>&HT!)Z0%1kWgIlXQ56YGU*$xe@e>0+UdzD?d(~mxU6*w_El5e3D z?ib^9WsDvzVtul;^I&O%2}AqKy5;y^9+KuNdTBJF|1h8l$bc+mGzN{a@3To0g}`bB zV`O5y&O-$DK?^#zT3CrGdEvnc?4`n`D|Fo zJf1*^%71;h>T4jLui&5N*p(9b{f46&!3RvCW|NHh>9Z#3xA|8lG|@bLB(kgWc<6zp z_TP22idn~t3}(ZdrQ?K->3>-iEAZE_94{!gmq zc4u(tFpB@2lM=lzFC<_0RqW)0&X)t__ZBbi`MbGv$ub56-#Pu1_{`g~md=uQ_tC@C z===vID`6r#s+257gl!4(BxS2g_&$GdBCapAXr(#+Mfd$@8pcnHb#}#x9Plb$+INr( zgc0iX-^K7ARiEQ~ve7YiTI4*n7EH(rm7tg83~J&Zy2szcO*=OA<*xDjS0+XW&E~py zEk4fJ#L!8TW2GM8t5L(BsyTmPR6*eoWr_aZ%xP)%EnCXXhNp^TzZQCA1fRdB8YM*-Ggn z;|WNILZO=__9bCHbwZf|2F?1z;a@u8Thz0hySiUA__<&`C7rP2Bk7OTBsbw_zX{Kt z!;?yq3?pZK!wEvDOVIvp=~U0eCJO_p+%&@@7LHRH-CMbWL|(HrReN#)9;7#kQtrq( zzN(HLd9ZeOZ<~@seuez_qb1`q8Kt^6@x#;?nloPw`uyZF0=O<&5=Z$+G1?N+C>ceIIqJgQWYB@1P$4qoD* znThhx*^zkXM^$)BT$Y2I6ybp5?xHs1s-fR1Djac7`##Ae;u-@!Hk&Pk z+9%ptk^y@+LgeSndOSEXES_?S4_~eGsQj~@m!J0)e#R%qFKu%xC=Wwclc6S8E0eAf zj}~y;#hbadgkLN0{jcY8Lfg~}%U*ZBl-3dEd;QvtTai3`inyW@!rk&Mq_B#+`26lK zd2?~1MDG{=Axa{IByBD|e@b+`1k)E+u7p>%nvdg_{dqgTet(AOsn?i(anRz=ju7&z31#nvrDIbSO9JHh%&UT66)%rJd{BPn*2#H0Mh` zV>abDUM`&oyLX>)6J6m|PK=`N!|(Wos9)6!Q6xvCtWmSv)}6$I>iLuG@~n-kyGc^V zdkrV>}@&@X?mL3UM2u451ucrNwQG)B>h1go;Z6BCY}FYZk=SZ6C2s3X7|^Y#@&$G zr6sb~Nvy4NW#_5rN79+3OqhDfX9|OYFvjV5Vz{y5XS^|E~L!e`R5HP|d(UDEd3l*g?qb zVXd>P!-3Blyyo$ha*%%G@|N$>bs0%H$T~o*Q!GOxZjNnztis|Bq|JMR?moF#o6FxE z#@CcM@a}^<^-S+WDM$f%oee4kK+&_XcHrR#DFJkk2WT#HLYigxn2r(34HFuaj-e z5AMiwocVjVk^$uEY~3880g#K=JH)P0MlZ9VH7b4YtUm|7FsMa3KRYm$F?+V*)8sDR zvH5+HvHnv2oGJ0??+d~+k)To)?7hjJ3TezDhe8kZQ( zJ5#dusIre3qZEcwHRLZsgoG(Nl;^uV1D+!u$)YAM($zr8TF(wH$Tgv{VyBb$vA41W zJ6&;$w>!SZpN#JRASnO!*UHnzmuZZH*e&(nNSK$5oZQT#`B*?i1hV^N z?3&NI%n@A~f%MCa4(pc(52H$KrxKy16+Gs z%AfAG*O|&YYXOBP(!LWH_Ncl0WTj`~&e)d+#<;sqMiX~Eg--r{N@rb)Jau{_A#Bo7 z#rfLXnrN&Ix^?#oy9YW#l1A0`*nh0INI7f+ynfKi%+UE9zQp@?Ca&+08)UTW5ey*rm-8KZZ z+P8}0;xC1@=~JJWot>S(m6sPb6vlqq+*}T$d|ssYk5^JRxJexfS3cMUleNZK(#|%&ZeEvtD^0?k0ZdOO?b1u~$xU1uy(d zA>cLMziEG;nwo&DUe4a;nwUDamqlF=BseDsn3+Gi>^b>iF`NwhPNOKc4pO&LHxJhw zFnsaicje1=ypNLhWYvy?)(busOKZa8-P-{N*P*!*c6f(tr-Yjuf0mxVIk^ff81xVg z4}fOC>#>@gw<p{uoOdxUCLY+xJVizv)sln<`|9Npt`4Q0Gg5E4@1Y6I#L! zBEP3Ij-7AwF5l-5)Qd~)wqxE;e_ImRWm)g5Uwj`WP#-DKGli@v7%C*!YjD^=pI`5X zQjty!i=yGnA#)YuhdpRC*gJ1oWH8j`)X$2oTJd$>xPHOUM|L(madRO8a3%f>mC^>O zVRjp>`CxI90Dpp^>6tz^pVc9S$*vAi?ecD8CNfkhG%0CDHCT3wN*Nnjfx~G!PS*nJ z_gdZ_ozy-p`xQevohjvrOJx?sD{CoqDk`Eg;kTB%t>N@|Nl8Y`%tE@kGw8m|fTUtl z%xjx(`0Gv^FAsn8yDGdUpM^IR%NiF;J4U|%P+mut3rU|!OSQNt->=g}*!z$_S1e?_ zGp(bir3n(mg(@5ItIwf~crSjlW;_ zApC~1v8gOYoRXKrraj-#>D5Zl(qv0085Dzl&lKQ;!f%`lsgjdrZHV;q8UHi>S4*QN zGTNBqcWI*oWzXOohuzA)-`~(viE19FH!4e=UcECvT{GpqGV10l7oN(x$}dOSPA;Q! z`f@`rRY^2zd^AGc!}ppK*SE8&9{TuDOF5K&uJPOUXky6rTg?on1y;{|l?I75tbc88 z2*ptc7v=af-{;f)TwM)sX;F1=J~kHmK$a3bvoz7*Cv0NlCb9XN*J_*}9wvmdqi5_N z7_SbFGL=WzxKtomAlicqYj23ZU5xNvRZCa+eBm<;=C5)d6`GpX8bdF5fMu#wF?<*T z*DR&s>_S2H>AW8#S6m$+==4jvcJug0Z7mW|zAn`nP}S!W9+ZKX(S*|1tUU>1TKA$<0bPwLiBq#S!g((0*&*tL($B z=)nyii(kIlv|&Wj-_5{ZOTEcEh2v<%SU%a*@OMs4Jub7|t&U^?*`>sthDq*y1UXxT z(*@FvWzB`-JV?Y08AB&*tn6BN+Y+RZsa6XePRM|U`Fv+^%n4d$pDp)#*Tv<;fFtQ$ z-`&NL5i8({ST&^SWyyM>@JWUyCc4u_cau|$k&4nxf#S!soGgdwsmC*k-HVuDkf{G? z^K;P7Sul=cJw=#B%4xt3fJ`YwLkz*V41^`+bSzmS{h3^C^-7OS8!SRaNSS~ zanDu|+z?1KDIY|ZS%2jbZ}&Z*Y}x5T5m|dH4I4K~?v2OjV+RMaN_7`W`95W z$#^nirI5rnR4%RmhXn``#=iY$pG6v5#rOhuKrW$cTTgcTPBlu?Rt)Q6=&;{ako;}c z0+_L*3sWC`^m-{MRo;`?jZH+ltU< z_+R!=j?8E|=-aY+00+hWDhXbNKkr_VSYDJMTQ?f7V zz0Axb^Pp?n`QV3#bf{O_K?BZzC2+?1*4UV(v|ArNf3+$%C-P$YFZV= zrsSWd(nM1O>x&RXbe^*GuqDS1njK{vhmi&`f`9?54{4NgKnL1N60N@9YGB{RZc_*a zZAg?0`|x*$Wq{Gn#NZJ#gW)$VfEQq&q711w#`jiJwXQk3$rs`xM8e2q>Zf} z6*9*GYCrU}3EGa72YR{g=7NUr#K+wCBO7lEf`~{0c5{L)dQxloIIA zdW!dasEr6NfY>|#Kxi%i2Zdq63a4-MGoz<|rli)-K3NV~-azP$jrX$tov3=}YG9$0 zka-Hr{9SIPp_tYDE}NAd^yWo*XXfTpC;XO2s{w0pScVPPj`^JRV!gCE6A&&P^#f*= zejjbP-Pp^P+~Y@v)uaJlk|32@3;y17B2>s~GQ5fex`g1HYS7%P3D@U(a*Y$roe}5x z^6Af-;qdR5lIXXWl;C59G@NiSi7TI(!yb=%^+LC_i)h$*R<}RKU-IXrG?rr6rc9gO zp@mWzPS|N3QSc}h9WrdV&UbMuvzGevR1;Ztb`3d(s80I3#@m7$kJK>&wkp$gc>}`* zYP{m?FwNvss859!OavJKM;7y3&1~%;aFT`HP3J_2pJUWaDnzuJ-)vxr=2Mv3jt<%h zGq188V5Mn2Z=)-jQ1oYB?mS6DZlYmW`_0n;SgQ|1rc_PpE$oNKr(X65V8_ByQBiA_ zi0Sv;(6910gsd6^qOID-J4UAspqw*$!{pn?$n@(ljE5J`O3Rsyr_hG~@$}-s1eOR# zcgp}}%i)Kj|B^z~5gD|mle%xnuRal0y7OE^WMNOY+hv?QxH`;|Irm&hpr2>HE`Btc zad+OY${_q*OW&0TA{%xD8E41##{)_C6%fvj9A=QIN5e)QKv8Uq@faR&lDlxE*^eKV z1}5V?=uT9IouELm>mcAJ8gkafaTVjsXZA@1qq+!0Pce~V=KR}qV_A~>5Zt+XZdSZM} zNDX-Dj`BK9$)GBK?U&ivwYhmbfNl+Yy!c2`VBW4CBDOyqzm=cz+b+L)nfn1l2~5k@ z#489OxE4r6IvMukOu>LJw6ilc>PrqJU_%Bn70N6q7eck6w))t^G~0lNtS&Wtzoh#r zSgKg!!fQCjLlt}=^^ng=tv~b7ve4kx;Gktc2*b~t0{U)p2p&Xvz`g?lpyqV>4<5=6 z^@5uAsv-G<8<6TjKS*o($>az+X;mj6nDc|fUDhXD>3*;6YJk!Go2GVVS zD&rq-)}_uSLZ1wf4QWWWeTO`GrLkYL0-W-uG%E|_C+(|&wJ6Ws7_)=Se)sLFMbP!C%&EmL*<;2Hx(&{|b>_vB60@;%>C_tryZq{3C8VYinO zRs?2rrKM?Hv7EZd1S$7dQiz||{qCmA7p@d-$84Eyk@n*28Z_#)9&mo?Id0?3Z(l;k zUuQ%}p<}v+MG?;M4_Ng)-M`mk@3-uZeCx^_6hw-2z%Nek+crhAP?=<#M;fG-F&q zk8d1-qf2#&Pq8YQ1z&vV(U@$lDB4!eCx@Nbpy|uRC0<0&JQpJLIX~6_;s5z$O1xY6 zYzrjO(FK3rI|v9rtepQz5y+|lz7{E#^` z;mb01l_=f*n>&46U`e>d!`iimZX2v3#v9okWWT@fZTP4vm%oMw$J?B9PHf0^n2(YI zvyCO8jyuK;cwHdjZ}BC;yo&b&g@eL_7)aB>%$8-qJNw~~uD)3aL;uge{Xx?VX!LC+ zLK8!4=n<+!`pGFT1orpK8Cj-FOLDe*i%;GBB))QnYf~_};HB!lK&8r0M}p;f<^rRe zH0h$3(p%#de7sxKe1jtl1S1j;3m0smx`w2xdbLu=P{QM0Tq@A4I0V_c5}9o`C6wAs zSLjmjKbG|R`F>kViF!hP^__u;mu35kh~e2Dv7xR5UHmH0 zq8B7*K@0e@IVp|h4M+O3H0h|2m}Ra~PAg+MID;(sa&Ki>#nb6||B9x59WxbFI_|%32KPhBT|CKo-I;>KYkv40ty{ZR0naMzdQLm6EI7K=^RF5QyjCXUS?t69}XJiUaEXq1|_gDR* zwK-MxwwZ5b}MNsjQ(3;zmsKF7-y>K ze^LWIKCVG*p09yMQ&}R(wOMB8f}{lVO}X|XNg-sTkEf)WSVzA3sAA_KY?#w!byW`L zTDb@A?ed?*T(lb?EP~WWVl&}9P84UXo)l)fmLO+zuFd8<#GeHZ^rNdp(D%O?-C{k1 z9~8d*Su%knochnd_!Cr>#BZDMQSJqvz^!K{)Dmg_V(Bh zPof}311Y0NAyEM;=xJzd8$)+zNdTO4@_zTvr4NiEBl^uBUbtjYT}41%iSiju3qklX zMNDQDul9hAbOBJ#c`k_J0Tq(;Xl7WGZ>PW*;{;jS4uzZ^1b~Wvdo3SdI%7f~tZWOi z-X1ME-E29WnVSL95np~pi4=#iFdA6jZ8gEIK6OhOR&@9bsj}@b9CKuEPvz_ztR$!< zk(6e={dR}Eu6n_ag=WN5Q}U|Dq9#hNf;%{nLxW84Cb_vE-$IjlON`r|(dPNpk=}CX z;xklm_W)98Qo$d9^}`$^-Y?kpLoB-a&N6URWKVb-6RRxAl=HSHtP21Ih+5*+KIT&g$?p3m8+~|^Am!&emlG0KD zQ=c$KA6`XC;kzpm-gw-*!pfiREOkE$BQIu`_;MD)omnkStLFJ?ze;-*ONodxbekSd z#<$rMrbYo|# zJQ3b_>&2dFC(bz-M@+-H#g(#P18w*MurA3m&+-liGarg^`h2T^GxQlPmoD#0lJF+o zEkl%G54+Lr%oq+&l77xjyc;2g6t(NX-H_fKS0y`(S7#plNx5>ccY`_+C*H9N%vV}o zmN+!xa&Q@MQN!R%n_rqWd3S=ulv9p`l`_-DGC@d~0bZ^SU!IZV0;?9^yXKCre#qDQ zFJ~GfBY66MbJ0r1QCJ`Yon_&-{U zJeMGGBczI2WqZ&kVj#0y*ja$SX+c8vlnI!bWQ7jhgR|m4ocy zg&xP1mzU8pl@7+`9@}qQygE*)DC&>@aKw}ha|D+3C;3Cqhps#JS~Gz+b9%Bu<)W(E z(F?RR6v52#s)I$h`%^mX(QFVvdjRN|5ln;Sv85NB^AizlKXZpY;~Xs+hxbWwV z)=LR@_Vw2FRcpGk!Og>jt;_5`8aYp3Yy$)XpVb5`xl*d!mL>e|gB5SdRFi>D84cZ8 zmyPJ*&0ui)B-7bq@r5@%nq4U&`}3T(?3%U3>gUaotpvb<_YtvSNf=dTuu5X~VHq#o zX&BX&l5wp-NTs|OAJ=>l>~YgA;0D$fXm8V59-v$cYq6E;1|ED~ydXyAS2vzD<@{CO z171snw*Hy0$0Y?$XI_i9RD4RTWp5Gpw&xR;LcEcxiP;ma39eBWirD>O&7xTasz7DI zydXw}Ru7)Fqy8h3HcT6SW$vOkwZiX9N&F^IqgO>ooR2f+E>oFAavg}18E zr+co6siTXOnrSK!$xxBn#}mK%lbwZdF@ZmgSw-0~`Mf$i z%QSk)PJt8|7Uz0)BEba?-e^W;fFjG6(CD76eT0#njd0MmT6DHb9b7pZmx2UFEsa@a z#Ch$RQ+N*(4ilER5B9czqgP=MPfTxP8Ypu|$>y$vvF4Z`V=-ajfp?o6l#h;R<+7iJ zu$pGZKe zIcY?}Kx_&Eal(r-(P6exapuh`FyOh3<4MRbkaupYh%=5}7fq%F;`#G?%8C5<5ZG>% z4C9H(!WGd0S*?8bH8Y`~tJYV5F`jq|sZA7tX2m?i?jeyRbyD(~k0bPX%^XPRyQ(_I zU9y<#pp@?eQrV(~!7{B$km^y;ur^Jlvk^Hpug_OOTzT&9`+$^2ALvtvUJgqZPBynK zA@gvJl_PjA*R~4qK0flRbbsTO70IF&;1^`OaUFTMJmu!h!XgYbb7iS4KC6GbebbbB z)$GC%YVj=RpJne_YMLkQa*{6X2?WRwx152!e!!6T!Zq|EgTTytdEEHbdjuSUPVeo| zA(&@C`5>BWL6e%dCvmwmdz?xOve5fyN+8msc|dFD&9O#V?WAYW{(1P$qJN_I`#iZ^ z!8P44KHmHv+J!Pj27tHo0MN;Ne)lcI1;9xO6j2a;By)DZIJY_tF|Gh+Q58jaA9z7# zj~Nftvdu$6ZC#?Q53()Et~|UZ2K8aFIK`;Qa&hP^IZI?Kk?OP6&j@v2F*I$KhQ4f= z9{cHTDYIXg7P6OEks=U(!z@_j8o!VSB-777!f{l5Y*K!VoYh{9si7zi1`Rn1XG*zp z`E(^O2ER$D&_f6;sLP(R=?}PdrN&K0b}*W+tF7f2&a|Wu)^yU@O_&+1PtDZGb}ohHtaWeKC01IG+7+ZGrMW#z7I{SD}B@9mITW2pGGN|}otqt>dqUdLJz z5IX*l8?WYa%5a>D|N(TFy>{HZL*ToHX2bGtz3uLMz63!iFRCfaP7-rwljA} zIX?Ruly6FcMg*xTfI~=0mv#BC{n*JvA|S0-;)3_Qf|vko3+A9s^z-id9RZ|E<=dNw z6DZOrZ*SuJ6c2{IDFu6WdwbTaq_qwa4y(7`s=eu=b~w#K>X!ZmgiV_-Of*nL@KpW- zVR2C^O$x3-;lwR!m*+laXSvFoT2SynN7Aej!0#OF!fy6nKJLY?BEd(!8wO}=FwZso z^fJ*-FevPX;?h^g&?)S(ae6CQC@6%r9{Lw?LisFzbOGUX!~~f`;&o;RPVn^HLJ2U@s@+rVy%Xw&zb27@176w->=b1eLOHV|3g-;F~t>jN#;qu@tZq|8&}2dA(Kc?D)!& zgk$=^lt1VWFV4x(1}H>ZU6y;CpuTxo!m<}KV`&+{zY#YC=IfGU7#GcNinkK}spbZG z^oG_9FYs@~76X)X0skn&7f1CMDF1-RLu=nlg_OCRQ%N=4z`8D^MSED_uxznDyGbG} ziI7FVi@`4`M4V6+tpBPO-uY{=y{p{6II&^swV6eNJoy>7S=8AbEc=1;?WZs7D3tBg zfC%9LPZsMMLl-{K^yj-HM6`0V33RjA1`+-o`9cy`eVzRJiIVGfo>8QsdyN~@8#=X^ zutGbwvpW6v1Yi4|$#(Cjf5iCsyt8Ay+} z@Qzjau#K1XaDb|F9|NPSu{C|0JyAPiW4OS4P*I67R;v%}rJ@tyRLYBpi5 zBkbbx`Nkgj=~l)Vh`_xDvp4XD>#vwb?sQE`&9r+_>#aKVHLs;Ce9eSsGRJ&+(tL~Q zffH&l$8x5&v7U0f;a0t@$fE4AuE~CIBj~e-6fW*_kKR~lBHJwkU|dYm23&aChG10pN7?|xc;^7; zw&lr=6#)A2F5W?i3-4fs=0TH-P_o0p)hF|i(qq|(8;tpU#1_XC5B^2(ld&kvP$1O0 zpw(kumS)>rXH0cZw52wi@E1iG*f8hv-X!IL8)jpZHU5@N_mWPBypKsPW4VxZs~R%pa@e-8#qhA@_nH=(wYVP*Qxk#-i^hA#&=mSY0-Nt4e)YWYd zNJlyUw5OZBQycSj5f2Cbl;0%Ms#?sZa}7T_fn>9(!?bO5Wbc&|-GGMITI#AfgmyS^ zQR2TKg2{rcw2+?}U_KNigP89-Pl`~FyEuIwTU?4<776%#-AC`FRGj2iQoA!xoeBgG z-|=_y3W@P83lc{Q1*?X)Wa%(#=kfKPK|?acQ@Ooh#O;m=cB&gsgJ`e;zyV)!>?=)o zuaD?DeTRb-{_4={6U#pYO?ZJsXjvDY9nk?UmUoR{#o3IA-bz^PiN(^c2Y2z!4EW$n z5nvoHA_;&P3OZAIn^4qSD*cnzRXN}rW?XeJti^a^ZrA5ic_}}%a;=Dp0o$sCK~^pR z$newptRo>8+%1+D&f$bue&l=X#z8D@01G-E9f^nrH^#4}Moe6HtflZiYfD;AzGe;7 zWQra&#SK7*@osfCYuMD8v$CnOEmtG{lMRl3#pKC~t9l=|DIj7;v$R>^o#iH}Z}vF& zdsD&*2Y5F)$7<4J+e^BQ-!Z_W8sUjsZ$R8*-^}+L-~Ua|22Z_EPNqdQWNhz*vpW4Y zCK>~%p+0Axe8inb?$!{ra-R1Xa0lzo>C^lOH(RX#-*4OlK-kaRhA}6vkaV|KxWS#o zQV8yRvO+SK_RXa*k~Lf}ehIcYJ|4jXCKzJ?yRYq|{2;x*O>|f$!|I6x?>)#M>>uFj zpO`{h%#47BO0%{}&bd6T1$jmVYz-uf-E+u85~MweCkSx8fk8piKPg6-w51s5sD>E+ zYO3gYU8){jO~AvHxxo6-o4I}=)mD~3wV)6%v!Jy(D?c>dx(i<%xL-Jm=vh$0&DX-} zzsfu3k~byKv_(f05g73K3G4w{3^t$bI<*Gwd@w$6%v1k#?h06is@?JpJD1;ICn_A` z=yl~XvpP*BXwE?~$F?lJQpZb5o%(1gF zs7J#bo9(D7h<>mPmKx>J%koJR_kSM8WJ0W#*)iOj;5D9N_iIx5s`@K`3?1rA$4VWn zcKwzr1d;ZKGD;^AKob-s8uU}~(_=R=U~iq$TUbEC|6u_@GK+&y;~bs1P(=PC@(nk+ zB6%uecJNJFbp#kV{_^#`K45r-t?&iG&DCBx+`M1%3^4O7cgiR@geFI#Fla5eaLz~(>_1#09%Z04E z+i+P05;TkXC{5q=MINsOUpbyo+Zn%_4iPumsKYeNX{NpVa7SPHE$-7maFrvT0iG(k zE2qNUdAt_6z9m+IGT_uk8rg@;020`ipOBTv-$9&pHLnf2q+@!@?_~f7ho9^D;YZN80WQ!kI z;zAiexHk}wsF=t{r^lJ0AT$9Lu#6wpu!R#QiueCHseeT@gfvHgwKjz}GL->3WyJA2 z0eHNggi?bQ{8hzRV>C>SpD{ODKMirkZvoZn_W|afT%?x)!azbyyJ+pzcYZ-$e=YHv z5=7Q&Q(qL2cN=cGp#l=@Vos%$Qk&o$B-y%>9i1b2ZAQH}n>3n3Oh2=9z-9w1 zalx3zKk5ljY^t-SDRuA8uth_Lq0DDO(`3qt+rO03e{VQKACAMjNgZqI-O3J}Mcr*m z`lcRQ_c&+1tl2CJ?bvAmKi%eE7A*=cGeq0F*ukogV<4)5zfkc_!|xRMl1;U=mo`-kJs78kgD8m%+I5rMmwYnQe+ z`JY;Q639k4*#uC*B^)Czlw1LItzNOG)Yn*ijL8Gffj+z_KEID4P{A|~hY zD}cOA95$>BaP}9iB&r<(6^4O!ULo~oSH1@%@+|W2XZ8(7@*1(>%T(cBuVbb1(&&|w zuF6t4RT?;jyJ$6vp|%r3!!M6a-uIPOrvBp0e9M!Is_A%Q4Se+ zHteesRNv#q&V%m-30pooV7nm*gqURkVA*;Fqe?^F|3lEIwYR3e+;j6XKQIwFRQ2YMSZw4dJHPC zAlyB@@W?Rb-~*zS3Dpn8zZAmM{d87ElPQtP+oS5#C4YU|@IY2mt^*5b!U2}lS9mrB zB+tM(G|GE_BM@*uv$uNks&CS+*%r&I#WGa`vmQTo~Pp$VR? zO?D-Q=a7mw76~*R)xOA+Nktje)Q7MO+E2W=Dz&oO%~!KEZnP8?8&`cqV9N%Sud9-G zCp1pAe%T7dZ-_I}`5pThV@;l|$DF1oxVyg5F)l~fiZR6CNI?8g+iT?h-y!aV)XV3B zqU=(*g~JC421s_fN`Sv@i#(bGn$-Q_H$&kwY<(8@jVc3L0<(4#MO5!~XqZ_M{jFwitovzUIYB zV^UH0ka;v3BCgHgsf6YAE(%xbTVh-J|FwT?Dv_rr5a+?KZja17BIz508MWjAZ1{q& zJ{S!C~jgZ!43x~JP-VHOv+ zlt98mC6OKgHTHqFWL4Z~=)aJY?n_V2wf7)OCc%~Sc^cjH=Z;X=`&-Z^=$h(`3)@W7 zX;siy#m9RlSuo5q!%!0T}9AWEDEx)M!*2gb%?{$ zf?f-V^Y)MK673SI5?#dtJ<0!nH#D5R)6`OL+513=Tt4mSfl~6{j5qflFrCq1bucVI zkhJlS;XK}xK;*AU^7q23Cj=!C9MGFr0P=WI_OVoLnC3^F#QarX8fm4(8$P${NU82= zFu+qdNatM8bH$U&AA*Bn{CreA(@ZM`j_*9&5dRaX>vitd z;bshICBBLKK~e_qY5spBJ_@ao$1{(}fF4AXgH(!1JG$Dtd*&??w|03-Lgk>_CFXbC zc-reW$F-wgl7pdpzLgxR7arT#yHi5kuh=~}9B;2-}pJ20x0;iIPUr9P|Yw5F{v z=~Fl2G1~EY3(M9Igk!Swbyj-XY~`Zva;cEOV`zgB3H|t>psHHa*<^KMg&#bE4S3g> zw!7$BtR5wj^X2RGEln=OMhzY20!H9XgTvqw$ zJK&c6Ol-JqD^>i!!X zFyx*8v?pcA;QxJ%Va__9n0WAA7%<724HZtSrAJ;I7D9z3G>kvvL{hJK4zHD_-1Kz0 zL=>PZz=PEVX~wmGIR7i@{Zkx!BD6Gc_c5w(ynZ9G7^{?jE`0h7QY@%4uIlK z2^kijX%8#<-idzwf1ZU~pme=69aKED`?w4>5-}2~1t4J<*W;XYjKfbMvhIzZ{-5@) z!Yj(H>r(?1jdTtONDL_;DTpxAB{>YKQc}|W zZM^S&ukSzbt#7UGebz7wo%5X7XYb$dcMh}9h4zm*L&3jFOO zKw6B5^9@5mGsrL^C7dvPB?59*(QbD9=pYO;0rS0=tJeA~C?a}_1J`ap!-)HT@f^H= zt0@t3&N?TABXlla9?x=JezM?Pyrhq@`{&=rBwG)Ez^Y2Zh`tjah%Aqp_K2X zL@e`D=U;5}-cPx`DKTV&t&WM|d{S!C9vdZl`In=C`kgZc{XX@*GYP%5gc*SpTKu8S zjg5yWwR_Ale@{_n5-k5|)XPlCIG+@HOs+!$j+?vtJ!aT%`fGN66?m1emM?JgrsK|( zKflAYG<Ey%ksAA=HU6| zM`g9k(53T5zRYY>VOrZ5TsCL+_`GRQ*7b=AWi!hrE=znR`+h zSy|t_Z{S-LR|z7KeLX!mUk|JyP4jZN>}DHFg1}ur%d@Lt!prH8a*Lm@o8}E%B|86% zvdpy8uqA|n;%ejDl6*~6_2&ZC{-L4SnR~v4wC~@lTotPqn6spw2mA0ZmZJ&9)DX*c zMYOLr%dN~eH#Y~q-Lfs$M78gurg&Em?lF?ods=Xiid1f|WtD;h6Sl(CZ0)(zUe~Sd z*U`mdu?MUE;sle0HOp>27kj`ILR-T|CkO9|9V&%#-;3o!LNXM5S^l*sO{m0`lxI|n zgQ(29y1E}o^N<7q3#wqc>!y%_VLe`3^<&CB#KOkLq|xWp*o$rKGZ&XQQRYx86beP5 zZEI&Y@$LBrMgk3 zaiS2qT3SqJ=(yh?k=}lOgxQKoU|9b5+vD!-h{S*URcwNBAF<19ip$duUNoerc{u+V zmU#S_8vIb8S?6C~_2v+E2N|bguj?tv$q`XsQ97y922)XD(a-K~|7-sYDtvbV5aW`z zi_6WWr6m&zslRXLZBG3!#{3sG|3b3=sQ5pEo!qM{}ga+xPN zY8oYmr*I&%a`;=7JA7(mW0Q)ZC}H3??dj=xxW(g#g|I|ytzB6PpYP8B(4AXYxa!Wq z=&PO7^U%W5G6Py2AJ=79OjOyjSIL1G^M#Dkq93g0qzj9S?voLOTIHIXYgw$lzkpH- zFa*dY_XI27p&^A6(hTn$?@x4*dK~uk09j-rk;vtvu2hT_$L?Mh^6O%pU)1c@)e{Da zD9|j=JE{2g&ZI9;RVE~>2A(j(__&h0yZeY#FFn6S9~)%c-cc*k?F3E(Txy92-e7-_ z+5xa9=i=fr($ve*3(Nv%nBvaO&yReoQnjZJlrew&%AB&;9uJ$;6VR--t&vxL(e%vO8e%*z{cig3~+#9 zxa+4&@w`TaT9vjY=&gATIBTfArHz0=G?Crx!C|mizdy31reAc5sb`j=mR<^d^Vry3FlOWunzd{RdGu7XjpT$(#f!Zr5vPQ{C0;+?+I; zRL_HKC5y@oyB&nms_g6SRo;3i5TuxLI|iZ)5+@NAHkg*3wVC-JKa89F$V?~{Gryc< zn9je67Wx_?Wo~Zn+Vj-}eDfq_8DsY$1*9GyP`8rsk^qe2{qFaq3j$TKh&HjxX5$Vam~U~DRTvDnVq=j%d{%&Jl6 zc4NRY1`^64oY9bSEbZ#-2_Y8cZ+U|tcpU4@)D*p?uKzF6+q5OiECOF_WMhf`1T)9U$LJ<`ad1gap5&- zqcQD>U%S&|xWBc;?DR#MOZ$BUWEhv2b|yxxc*~ZK5=Nbf+Na+XT0)u7f8->8H1I#) z0>U$a#{iFvjI2PnE^&Y5!?E|u;_@=L!+L(t3->=30(;Bi| zSgW#bu48<|@_6!)+PS)HsRElz%{0?O=*Tzhb!#Mlc|buG zC|z7pK^WJ5N>vrLN$!u2Qah8YLV~p&(u606-rJ}z!CveYrV4JRBqcNxCEX*4Z+wNG z@y6Q9<@6hRQ&Ls+%c7I+TO?7W2?L1DJ7Q^aRob%f{$T<= zHpWaN(>OhSQMcCByQxVEN^b1Gp!f4mNlDS5NI~E>@z~qjdl{AltgkyJr=-A%T<@{A zR_;0d-WeS6NlCsOLFNLC1&`ji=jH`L5w>Xg*9w;x4RnpSc0KHcm;r3WBb0J_Ez5fr zHz(J3SHHGKGlZv#IfEe*?h_X2)=5@rw~UN1bai(dlwrq@$5*zI7L3VCSG2k5-0Be5 z`TBiFmYffk>|ROOic)1G zuQE6yOc*#hIp4p3U+igAu1Q8jL`2#)SKjuG54u%YR5Z1|OG!*Hx#@-~qy*#o8BG5C zNu`uS4fnu2yj9Cz-9O|JKuedmcs;b=RPj?Xn*Y)d}Bi0{H z%cfeRuY5Mg4U|WpP~{nPPwOhY#Vf4h!6tzIgUojSjff;+TV-ot_+x-d$qc}>_*rZ z%koI!_W|R6&*dC*RV1&*NM=3q?w?O4779RIjJ!LUljbQ|u9-5Nop*Kbu-@scnU&QU zn01(wx$XV2wB9=1dXGRo&)sibyU#&da9_W!%tgDlFu?is=`HC@<$|K3my?lwMz1?f zQ7?MI#nsf*3ThJ1$$+=WM*t{JZ8@t*}r`O^7b)%%Fx>~YM*FW2Wn9$et=-`$lGD2168ZqAO6mmBC zk3WC%9e9d|g@-G1(6F@gZR>4lhRWhYzpD!`Q3dKlH0u@(<WpLxqme23uKcV9tFEU9AuD$=vSDE0T=)5T-QeJ0 zbse4NZt-K0KBZn2l$yiy=YfxMUqwe#8<%P99C{X@P@VekHf~MphRmIhG)Zu|)~^?< zl;hy$7NlE5q%)+<9oK6uc$VDXOjN+_RY#42iAL(MsoJ)y2!a3)S6ff-Qsmt`G%^7h zpAQ+Z`42g2x0DJ13NkY)4k?2Nl7O|8=jZ| z6ZJTq_hHdDFu?6j6PH6iY?zv2rKP1UkpCLEe5su;HZHEDwA81ptSoYu+Odk+^KkP? zzGXqL`5o2DBSjPr4q2kSw1kRkL1E$a&W>wrQ?}ek9#WNj)mpbrl3w#Kc~tzQ_@!J% z78a))^(g^WvmTvZb4}jocH;rua&YkW{1EOc5@s(HqRs8Ei858KvrHt^w||VIb+%v1 zV;k#Ij9CH@EBnqCESqUwi4hVPC&GEJ&24RM-M~Z2eEvLgXi*}HZTZ8T?g<1x(?K5` zh~RnSjM?6tUK83o6e}GmIJca%PLYH%c5!xIoj5*n8Enew_Hs(pc((|r*h+P0u0jC1|d3ZGjf{a3fk}^>GVg5ity6+q}oN|w= z0f2Zl#;5(84|)a{hXBtz($P?{-~Ppm&Ow=mAob$*sfI)?US{%3 z(XA}et?G_)3FjoGT>_g8)wQ)>akUEx3rm5wfp-Gqc{L`xeE015GXJcgA!N=8oE=bP z(z)gYLS&RDpH}hQyy*|10Nl~s3@&rxCEB{WA6K@ehMaWIWV)AQY-mVM0cJGKt~Z*N zH7+@8?H4@cAdpd(6*H;`z3djZ+}7}^W_%-JQ~Fsx*7kvoh3p19EgfA+eZ6hU-QbLX zha9hDGkIqs;rW?Bd}{fPGixj{3dj*_O&2m+l2fU3J$kgn1i-eYDZ_W8UgbPUyO`G9 z?P|P1ACIe%+1oHajsX0I8o}dxZ7Y@Y2Y_=+z=};g0G%)&KE`~v7Lomz(m6;V0)b~E z?y|un6AVk@RhP<&i@mb4E?X_*RboQ*c>)Yegk~c9(Orw1hK`QZ;Px3Dl9U8*^DK29 zTL>o2ZMyN0;sfG?hn*NRFOP$UeRXX^m&LUx3r^% zHs)9X(dd3GElsViQUV=px}E=15_kR?W1TJq{2r8%u5xt>pq)GJOn!d;``X&CnQt{&hYAr3To$pC@;A|zewWRVSe@k5RLv#zr&Y}0 z+4aXq?(a0OL4bjVIM`b(;z!&PB@`AGR@c;&rbun%cYJ$dp3f)_UAPSE)K>}>DK_SBkd zx&@;y=vSCexk8nztjy#_pp%dfKU-ciIkKs(t(6u_^KY7J0Gas1Ss3nu=`Ii)k#=eQ z_LSJaX?SErqFnP&7Gh!oJdkxbgzJrYc|l7{HbB$?8N@|HR))T#NX>rh~O`6ys`RIC{A zSHgYMmP?uF0?g7hfX}vc(T-bP7$EcKQc@Y^9&>>c5hRIhsNmXQ@iR#8HJ^lLl7^iD z8YPi9&=%+#3&x|J845MS9$yI0FP1l~l-?@k_7X_@97z) za`n&l_I8HwWP~r2lD-HKOQGN6vok%77o%{hlxybTfEnBr5l-a8lCGA|8rQzIEwjys zX%c(>lK^yy4+~3Lw-)**OsJWe893^yTV0O;8DKXA3;gp}jDQKZwzfbkQo}fOh8&(g z_37__jN_}&3^)!A$|&p86PAu};j6oG21?^4W^2s;2@DG_9Dqr{$Owh3i1u&8d1>PT z2K2)iOj%fymqdWGrzd$0mRv?TeepIqIXRRt6?(MyrIvdokugfcVpOrM#gH#!zhuE@ z{8ZVd0(-PKS33kUM_fCp{yggZg$pw~J3C!VKr+pSXG^&I5B}L`TWNJzAAraku$%&AlURL?nLM+9eiF``ieNh( z#Rg`wd!x;rsm(1FYeMgbtJp7lbOe~m%*=czijCNZ=V@fboES6=&6je86VNwI4#O7w z)Z82~NJ>A0Rk$CRbL=^@8cHovDF@~YhB>SJ=B8Tyz-rp@fthg%o4ndvyYb>rj&g2K z2&UKpfT*O9R z`nPL?x90jRpI&eir|ve(#ow;IVNro~suhxk4$n~1)_~uxxe|J^=4H=t*L_o*84E`G zsI$Lay)(SmW~m4V4Adg&dDP?u%fE)OGW_=WSy8H{-9a4`?I{VbP7gkj=Oe39G&1xV zLWf$vH4zXXb`h|fra2dPWYux4a4X34jBJG#+i(5LKpSdy-MB_n7FxesanNypL>lYW zrNEbw5XE*HAQqe*jYeO>5J-4+&o+Sogtd!87FFN8!0nW-5ZQbGm_R_-2U_|R8C1Hq z72NPC*|-?56q9aU%$6|%4^A5%8~X&Cc%R*1nHMO%8vgPCKk_aCL=!AV#E*6^(a0q9 zng{;VbyG8;3C6BEKc*`rK0JfA4sX9$vvE*^jXHy{w&=b-s``VU_k@_kB5i^)^xfT= zc0CY)^!!n+Y*c{+z(a#WLuLYo|BN$Zgg5`QEM95gA80>GzWllj4$`(BSwwPlh`E~Q z!J3@4tt}Ah18YYiX4k!qKcF61eZcaBjmo>zv}tf~kn}&ss%3gEVE}qn`lBMxx-Hpw zX296b0DKvzLHu~PJK-oNK+F`h;>x#)a?BD)FaP#$l05XxyQ#p1GRnZnC$C@Y;>cFx z;<7Sd6zUqi-Q_VfpH)0jg%Mnq0BJAS-*Z=Z4Md znA=>>Mx$esN7^RC`D)%B7t$s#18y_|hduV6`Ina7*e$`!M}GTcWF5pK&q$yj#RdYC z_`9RB4;!{Hj_q^?n?&^pH~BRgH8SM4w-%#{rA?|THTg^j^ ze&!&+*7T4^@MwjX>(W1ScyZ4o9yz>fWrcm+vEaPGV<7N@uc-*>W&NfzgGGsAoWMYU zjUU5FuK9J2hx9CE4w1T=MdG=L1Xbhd&PR->i%rIt69WGuih5^_H1C>nU%_1ZXqh4; zG8E4tPkE{=&sw28-kvEhA+3&|jekO)@zs;QFSrZUIEpp9$%PbGyEc%{!7de=%tw{K zd2GO(qjQotwmxIn^V-<++SxhLeiv}`@d-^VXH<pR189Rvx;g!dlnKJ0+aWyaZ_yaq+A(IPMI| zJ+87aNMNC-e1^NHo|Q17>+r5K!?i5=kp!Wi@$bD!E6ZhN$X1O~q_q$2<`qOlD3bNa z=6xoNF~7M)OQc8EKvM7LTPmR?bI8tt|BSS4G$d(T(a$(j6-GSl%F^N$@=r(y%&qey zUXy*G%~pvH^*2^yk|n;hbPmng$u8!&enW8m4C##XXvtc72Tuqx{k|8=7=fV=F_vEB z=82guGQCv#kB(KYd0BhhdURT_&*v<4346sIGOsqmFJdRf)_@icx}?URMYxr`G{$+$KgxYK8IWyoUtMt Oxa4J&qzfhWef|d`@T_$J literal 0 HcmV?d00001 diff --git a/doc/img/euroc_cam_calib.png b/doc/img/euroc_cam_calib.png new file mode 100644 index 0000000000000000000000000000000000000000..a22ad58080a42b088a7dfbf3320a6aeee1c224b9 GIT binary patch literal 423200 zcmZU)1z3}R+ddA0AgzGXAkrZqAmHdu=^EV~0@92YL`rF-yB&>mGXW`SMu)_hiM6S|NG5BWHn^F{sQ3#qplRekHA~xQRd#dyCd5cKrXZm@sl!!+2ccLohyIQYNk?>&0oJ}uba|$|dfYAJ(3xZAJ**2vd5WdN1 zGI6Db!5LkWUVPe+xJ&S8*n|>ywhXwgse~W=x#v5@hAg^W)2*$!ihNXU{cvOz5NJ63 z{{+MT9QTfp{*whiCExd}1>5y$XyD7CBHm!_xP!+(efwPBTUfstHf&7|N*rW-+%e2C ze1W{b${;5Mv62!qD!QZ7&i~i(vO9k8K7Y$X9?w#$o#BIkFUN&p6TXORstZYE!~u7= z%((ubGy$88rfp@MH@&@bvAww4zDI1oqV@j5h%->2_~WtH|BXLFSYr62j|Jq4=EBiU z`laipZP%uGM(hl61;&NYJM<^GU4P!r?o)Qyr>vieU-A3h3Viy2d3$##CEob|2LHc4 zuZZXubT(#kHD=alcsnTJi$u694B^uLRKZea;#8Ap2r2i)X)~qM7cQ`tp~~#D8UoGz z+(%9TAu#=~4fSE?p^VdDWxmMhyu>v*S(tr*^SJ0qFsTM9{o5uSvxH7Gb+l^v;sfAF zS8PUHSj7Gt$V-sooAE=&HuJ<1{*$;4;ix_ z;Ko@E9XVbSJ36f;G-qgfFWf7rJm%x^-=C|TC%bTNZcZwb)D8K1b~QhmFyEj89nEiv zD~?V)uJiIr@UycgkKn9KLLXUSn_t2zoskDlw*Na?p1AfBoR&jZ<6Fx z^j-VV)IRR~M;es$pS(_5FAJfZh+M>tO-Fs$zjtS2H}ritiX_ACEp8fIJTl!wdFG!q zHZsGPXQ+fW9saak4yJPXP77{K?7~Gu`4P;T_!E5VyaNSnK|3R$qKB_Je~#tqbBcV} za$duRcH)csEHSa#T3RK(;`xJyMyP8cf@pnqgfY7hi=-3!6fbrt^z66oIVU%Fg<$N9 zKJa^+U#X6ld&Mroo#>;Npnq2}F4AA4%yE?jpJio#(xkyE6YA$5Avh3ol<58GzDE3p zGVhCfYM%%Q5UrvPuDyMbHw71mL07K>0>@=0qy8N+aR-kI?LVO!o^@>hKIrZzGYxlX zYPIcgAeH@o*5WvB$N%nJ)Z5a{+(l0g>C5KoiFeSvtJHRCMgsPKnkYKNA@gL}Yx)6K z)zic1^FWg5=#yrOPB2!XeFUo##x7OA+r``2vyr7AFB4G^(aG6=2bWvk7capYw+-Q= zmAgw1b#n30mD^eIXyHf?c%Q34&(+?8ev#)97x!2m_CJ|c_8GKzl6ZDSVmnEA?Xzp~G~T2+JYKx9rb0x557MN#B^1}> zyU3co?uEX|c@Vs-vclPW=1!z~^`8xRJYZ>NZcpomDbvq!cqO>}@&3q^ZosM|yb>;Z z|9VJQHZKjG4rjh>>cJ`K>~LvY_BI4EnHgW%jh`r)ZpT zXPSBO8%alJysS0MjY-!QSw-{)Ihs1ugG|DI*PV;AE<1iXQrP#sa*lBXYV>Q}K8pGK z-d@Gw4?(*AcS5+steeT_;&-r|teQ%_w)HJrPAF~BMPwvpTK#C~AyWjT?Xs5nkB^gc zxk%{n@c@|mJ6tFZBga4DHRMTcKuK!AyI=p=rZpZ~jBB!ORTAiv-!6d!9p^+r=s~YP z@$6FfAx!Q$r}B}O{g=K!3rXHLVSV5CJQ(mdb!R&p(ftx*AasZFKRjBw75al1AU}up z5VdW2UMvqOTAc?yp%bnBc+ifNKl*e4`q-b2wYPPD=*U$Dp+|*~Z(D#y9zZU)nDr}=u{HhP0pJxvyrE+}9zuk!ky))&4<=ib7D7XZW znE0~Fxk50G7O6jtfcd|ezos!WGVHT3|5!CGHspaPbegHRo)rzb+4L8WV))IKcqH=8 zcNz7)7B{BF&<<6e*1F@@wuii@swKH+2|Tw$KiT5@M!Ns+3gd$d6!Ge6p7;s7#{yts zLo4v7{tvz)S0nNvm3{-q0s=GVoVL6aIW=vzf*fh@;SwO6*|yyX#L;9TZA2!+^rxs;p2LgGej54;B|IgB1KsjcIqmYH3%+)QY}BPtX(2 z90Xzc2O_{eNPKeBg*ov_g_EwdZN!HNc2KO`Cg`m;(_KUOO*}|`|9Tp5rDfWGvV4q7 zZ6`4CQ`3om&u72$*74>r64&l0zeW~>_HMrOT2kbCwc)$V9}=Oqyz?Jk$5ge67aKYL z++wGPA||&%H~ww60}n;+i#ZPAM0DMSrT;50%j(LKAy`6K5|7kbei5O74S5cy{{nrB>$4K=(tRy<0=D{isKwp#P%sXz5P6#w zT0kDHA)sSYdOfv=KPloux@~o}P(-y)`52DhRPw)xjj35!YFSK+KK~e5kkfA~cJB~y zuACD++io3mMPMC6+d|T`Vmg4jCzmLS^AnK_;^_8ty;?as(=&~SY}rLtW+iE`iB5=G zYAa{>>`*x>xVAkSX=ct}CHW_;xHw2I!VwN4p;ncZ_95X3x(x~Y2MWHX z2!f+J`I)1{m6Hdg8;`_Knp+P^$i_D2JqHy&@?}!06b~_^?M6?wRc*QBB<@B_9PSxB zRv|f)`3K{`9!jRr%RY^z40ih1{apHH&UEz*+a$JWMPJJ6*yCb@`|L3pHn|nrI{V%< zW*zo<0WJE5>z&%o8chz&X0a#M_08L>z+q3{gzUk8_oJhi1^TRJ&dvnW4osh+j*gDD zp3Vtq6^;m2QrzyQVGbg+fsJ-W)4#jH-E{TcjUJ=0O|A0$aCuvtXx3W|9UO5kcJF&J zhhf@V$6jl0NV?Xc`$;MCM2u{^xoLY1N{Ek<^KvWaDQ___K#pw5QJ5Vv* z|LuB7C64E3z8vQ|^h|j7AGqf;^uNy>27oMTK+*3LD}S9gW%byAHCH#+5(WDfptlso+1HBwm>ir1KR5AVHdnrV6uV z49pV9!x$Jz%m71-JOl9j=4R|3yU#5^mtf}~oF`JI5IJW=XBLi$YNjk#9DOrSUWKB? z0*4Q&V8mKPxCI5P2E`mPN@G3$WXbrqWm6P=+=i8o&SOh`Yw$UF40|;rDByN8_i769y6>po)>~`{(b(z(3n1by zLp?ZZ^$x-Lv#)!UK{dU2+&HXqlzrYt)^G9TgT<46sV5(#YHx$`f*IMKD_W4^J_IkL zzfq~-?d$m8aFe2EH}{f!wlRWI#4hX(n^vU~@JXG#<0F3EWTD!iW*EnL6 zFV_zA{CsrF;`^;KZj7@SzXz#zn-Y}o3@}Y0iuh7ev(0HtqXD8WVHVL4TxU%B-^_4S z@C91363#B8Y}4d`t|K1U55y-Jr~c70Nm;gU@T|5$tkvm0 zUTLPR?^)WG>(f?+l_hY;WYGVi!;!s5$Z*y;bU1(Y7%!(Js6L@DpeEuVV`5W~j zF2slH$4Fpqc7i5jS9@P&+KRQ=%|&R{rWFxgcb2z4L9|WxCvQ-`4M7`1gq?LAZDV%) zxV2kCf{UKB#zOB_(YRXoYfpX!dQ}4Xk2c8*H0hE7OzWg=55)@px4mhK378v4LW{N{ zwA+8uDuRILF(FcUkH1Y^?Uc|&f>S;mBzez7t=?0s=^pINZPpz5#Gp`~)Z&5EVckGb zJyc9s{nL6dP!KOhxo60gs==PD&iPCOcv7a_a}V-DQ`r@z*`5;YU3&~Hmz&!Y1OlON zYAT;%-TI!t(^1?Zy_|(PQE@zPzjeYcyxS}oxaWTh9HqLxK0FMYC}Nw96gQ7^IraPj z@GsIoU{=ze%cLwIW~Q+;NX;P-8u>VC$&$%#Su*4B4<8-^WPbg}7Y40bSm2gxktR-q z0YP+hG+HnTi)!xVu32Cp?TC$sk}6vTyL6IlHf$s5VX~x{YqJqyqnfp}bI4i9SxMsu z2=nb*=gI}1b~)$Zp@atI09B;_%gO9v|I(3P?(csdH?_U8gU4?ejE&UdANb9-qM;oG z-Ct_}LBObZp^|_JoY#%Iz=$idMw9bd*ghHV!z865w$>ssJg9jNDemN2hDix1`B<1T zR?7cK%$K*!S*6tpK6mx7k=r+DIyvceBSp370COTv%aRLu>H-~mZ>22|S=KTd;lT0( zyK@!2dh6@jn6cD3F!W`*NZ0GMseLmMwFWsgqERcDVBLArSVTK})N|t0KIK|uH0Snv zZeVYZJ&soNldbsmyqe#968Zw;9>GGV2u+WN57LY$t=7NZSws(76yPSpBNnwG6yt5; z2q6rli-$=T^PA*WmK&q1lSl0PtT{ff#UUia1;2aRdTSte%I?+qcFs`R>JG^ z1NkCNNov^6`Ss3w5bLw(xh7XS%Gd!eV`bs8z-M_^vbUf(XGd?R%%T<<=PxMX0#;n- zDFmvzw)Srkryu4u@?P>x%gKR7k+AfL@;_@l&J}Y>vF=v0tSqX{yNeJLhx~5i_08Ox zMtDv+ye7r{z!szi;R$R4{ag@QkaiXpwQ+7WsQ{&KAA(|0Rrp8Q`+8TXMipm&stv^V zsk`x-K{pjc3+tD|yo+9N=hi@Bl2OpVSbs-iZd|qJ9u9#+^6KP4I3*DpJ?lD(-$W$! zTpQMVSEgZ`epPl}qZ)=aEbzF|vmTj0CKV}%LClmiRqdE@*j$-66I`jz`uy$W*FO~21_>O$%m}k-!0)KlPy=iconMfc_Nvf8tCl-kFfB{tk{q8b&h~P7KQwsGj z9CFV+pSU5m9LX%DI~$lwwlqL4!U`(R>o$|)gkL6ZNJg<$5OL!4z4~0tW>EDkpS9=i z_S&ugsUCozEQF}nyRqqHYV`Yl{`{FFt(@>#hJKJeL7m#L-@;7~B402uB|{n3;NA@M z@@6)gd`1rQC~E}c_M0BYv<4`J5qq;$mR}(6+*F{Yc)T1#Jsio_UQ%dWq}lBwGO)Nv z9nniqNGBF!0*!QU7J2%v=AI)N_xJX;1}kZGb8}Q|Y%C9bcZbh)^ob%slW^}1aMP)16@$Xdj+JS^^cIup$NFvD(V1~=FOM|$kY-^B?kOv%i z4s|*vLJ^<(*Qdf0XVSNMORdd@y?zNa9G4+;tc4TzmA<11C#th6vvZUSD^gd`TKMmH zfO{marN(Nk8jy}NVOEJVuhf3)Kr5hw+uG@449e8PLZ;3I9Zc5-TO@OTID~QJOMe~) z#Mw`y%4fCpcE2~Y=vw#2(fF@0D)z`UUs3E`&oyqQ0qxS~<_LDwg+T;BL0Y^HT9_|T zy3Tk%HAXot2seOdezUz%;H_D5DOhsBuKg9Kru=x%%C};=N3Zirr}Epk^#w<0|FoWI ztW8~%Ma@UevhcNcAAv%Rj}Gi@apu4;~>L)AE=UksE(-Lx9mpSZIs3wb+1#*U;k^q2|z!8maE4}6i zd>CDvjqFkMh*HpZZFc(MMi!d+6?VMFmsQ+(0>Q|%Z4N|X)>(*ZxjiwUkjLW=H4 zuOlJ(&gRIEab#2^9x;Y+bQKt^GWyD38J`VKG zq{;r2JC(oy5_nlAm#%)yG+b+3cfQBUKG?@;MsW51=dP<8HMVh~HM+25&Io|Ie7Lhp z*Xr26l+N;)mFrfN>Q=C(4%1JD5;}ISz-laE;|>k#T&dC$T{XtQLznb%>U;-dP%@{| zB)`?X=DB-jEkOdKWV;EGr9PkIG>)D{)L7Mg<;Ee~PLE^#H&2>RlbyLf!by0MqK`L?=TJa;TD zRaD+smp!@oqqT|jZC+nf*5~2jpPCTY6`OU>uMm3{5`K*N1X9Kxq#?UN0T@*frzbBa zgzhbt>&H3Fn>1{F>envuhbXf5xfbJCDPrmm+ogQgD*)ZZfjjlBKW@a;7Wm1rfb`W+ za3uL}S4Ni*nsoyhC33y}d^vh7@T^YX*tj34P#utKU;+QGBsHP5QO|a5ON8fSj0uF{ z)u$KlK{P;aQU{wA~uEav;s#2cE-Cj zQDuW~=^En8JKr=rCTbo3@Na&yr!)!CXz0Yyh;}jz(Ro9FVSuy z-vsXmU|ZlL#0ml>)jB#hRxr7nyK-=#G*eSpfKqmLYSddC-Vk8c?o>s7T6lhzyljf- zZ`8;t&si7UuOQD zFsdo*he0C-DXBq|_@$oD;;Q)?9CoVsiqIcaTkcGofgdE#a(uDp)8kj4bevY-qA>A1 zoRZw+>=cWnw1W^rn6%-c=d;_I>oFlvEPepiZMpk?vfA)w!aF6I^KI9#6>aF8-eop7 zyZ(YKRt-mLd4`_j<|iq5Wl~L*iLZ>;sJ)qdH5Awges%?_ANf%unVjMr=I&{h9HSXZ zAAggViEzwQ$}U@U7az4>UKw0TST>CYI(;3+sVLrel*e zqd%Vz^rcZ)vecA@rK2>ebiKcm?{z0j*EAlpIBQ(yx5j!eD#9eo6(7$1Y7=OY0D&veUs7{&7O{F&L^jxHQ z)fachR1q_dV~-^nGBYxhVQrt)zgn~~eo%}$_{R%yfnSc{>{N`> zhNlXGZR+eUD;LJj;?<1@{Y$A!@j1+^JhkU*t1&?cYv-0Y;i|~1!T_!_K}5Gty5$V< z+@7G8*mS&Jj$V%Zb1xrOc923i3jOs@wV86g!BCP8(ZDWFup91++I zr5~+Uj|2e=4Krj!7eiFo(b2kJEb@c#_OP2*b@!i3EbC#LK7=hbOv_Q$F}P~mK3GPkaH9-q^@a>b)F}P}KzjHoW7&H88qvc(R#jC!UY&Aicr2k) zFia)TRrmbYrHiH6LkKOV^ak$A zw`MDvu6ACxVDXf?ifXI~nY*~4XePxsGFPl5vH7rWM!-S1qHUqE{@iA%DqyoAdB)Va zlR(N@)HiDZToqQ;l<-_>+~FM+?3G_TEhtM>Ke|<$eJwwlOR7jSJ;9vgAc=tLX8Q}< z)s3&%2V&_h_cxW!W#`()ecS5BHp7kQ)BF5P0aXXm34?JDlNplb;jp*>d@KxL?N0oN z8r*)e>g3B?%Q_b{$cvalOs13fwtvq*x*IskJlB;lak6A7^!>TVGUNcA?M>~xvHnZ8 z^$iWBp|g15dskO~%SdSaFFSsz%KjJx|Jw|29;25IeUTGpx(q;U7H7vAPIShdGmd^fV+Bsh_(SjWsJ^^6@ z^h|1DFMLBoLwb8j%UPkgzZ|`PL`+CJX zL!>dU>p$ebYe=g!im<9XYmLK*)oI{z2%2J<-2OG_M%BAl=SV|wkR3H8Mshc!fnX88 z9PD&{0?0*2FD;=2%+qritzi_(_4`GAo@csQ0aRuuiE>|quCD0gk96cl*eCEMtKvU^ ztiQVDhX@WgVU|(qK&(G`{$OZv%5cC!kD^rGv~PXl+g)mtS*BH{T1&8rjBz5B)k3M; z>Vz>bM?!>w%8vh?=}-L#wHnv=FY?(=IclsE1@{=j%BeCMq_wvd)9hGb-K6H`d~TfP zrJML$X&e2ZXv!||1ASPOXW_J)l`cKP5P(qv_qF3k^Da#jKy7PlqkhmZKM&^57?Ch? z^CkC`@!XGW%|x(AS;G>re5e!8&f7yJ8XD?@&cIW5 zJ87fCwe^x6XGCKS)(dB~XHy-&pc|RnaKVScyRZ8iZeK@#+;)6i>7{lpd97qE&tf_k z1k&jDvVNA+*vS=%vCrvWAoif{!buz`wgGE+rjKMCt8}FSY|>z`v?W{`-+#4}K{nG= zm+r71|9oGqBFM>r0OBZRE$+$-UohGuy<6UWf4IdRM3Hm7xLquu ztp)k%4(M*k6_=(Gi$^ncvxtYsO-5Xn{FLS%9(<4M(0T@38RJk@kEbo`rGI|6rgF>I zt%CshHL&ptltoDEvx*LM4kOQLo#sM82*XIsR=eVrdo8)dxN?=QqeDD~Nw1)Lef)d( zkIHWX?oM)Gzkf47d-e=yQ(I ztw8MSM3AUrLaw(CmNRc0Du_+3QhdvFMYYz;5T0UfuTq>CF*90zkh`J0p?YUCsNbHt zpf=sjnK+#OPR0Hnd_NpVV)#u}wH%OYO79JCU2cm#`V$k%Pc6xePpwEdF1-4wmfz($ zuD;t`7Yy7GJQFEaP0G@!$AV!^IqW1$G*CU&nBc(4kjDf^hR<=lQ^idywiz@^`Eu^} z1nQA#I_?X~p=t(~dX%JV&%7z*WCuIiPEEUMr_VUORDN!kYeO?4vON~3b30{Lsm-1@ z?_?1eD8{+*P5=|F&Jf@w?8&&#$jC}E_02$dA!FTM6!EaR#YLHtNt~dc;~ULD8MeZO zzs5tRHOUmj`NQL>w<*!|Ek19(BG=B(KA(DxLy_iaTK4DHwF+}$8R}^>vwP zX%WhX+7&wcE1h(1)EfXd)dC9ya5X+j-Ac>KB0!*35He{88PKE((wkeS&2GP}`aJth zptLqTXJlRD`pay#fL8Km7{Mc*vs17$PkBrB?eKWM?Ee)Du=_4zLZI0DH)z+83zdG=X2aS{l<*z472FNr$D8> z@DDmT_#lXrz}Wrsr;5*vh^UnDa3yG_pLl3tj53#Ft!LJ4TCZLV|5_3ig;Lhn`*xi* zd!G_e4Ji{VPeAT%=&#SYd5v3RjFQ#ou;Br+i$j5e@I=+35;vP z2ZObq`C8XDJmld`WoeT5W_w7r_BfPXgMm=M1&?aB2*nKTACw0eBh%9<0I*iQKVXvHVzlgNZcaa|>JVUqtRIS4z@KjI`a_^_;`G#dcF(1KM%BI6 z$-fGMbvJN7CeyQUvadh!Dnl^c0@kQXXlJ;?Xq9bT11Vn|XzpP!0@_JE=F=hw&8K^g zS3gds6*ZZh6ls-tAGD_OuZjlKyy&Myf8EG0;zyUQj4eC6YV8XehITW=#$erQkiM<5 zFW$sEsH$rQ^$xnfu45i!({?w`iA0WEpHO4X2;?dzFj^TqFmuCGP?Kk48O}DwC<;y- zCk#W_W!SgKEA4I@g3nf3wF((pMe|O=Toa#5WpN_V)uP@L&FC^psB2?GIw;u zYd7H*!Kjk~(r0MvSbL^$51rt}T*S=L^iKgK_DJZK@7JQ9E+x}~&5}K7u~aNo{5JkB zMv8%L+eXl}x}aWkKJu+@X%iu>$Va(?CjwrRTimQ#^$+pQ&JR}N4XOlC<*Z{`VC&oY z4oa0TBC98RGLdIclajMANdJMzH}oW?KPL~!lnd?A3K_F)s_l%YmiK&}#38zlRBTjd zm)b<7ncJfBCK>auvgLEjiMkM+M))d`vbKs97#$b8TM(LWos`7{4+ej(0P@KV9Zklmbpm7hf?Ai2 z#L3HtRM%GXXBj$3FJaDDS<~>Xaa*AJWcfLo1JX7yTi@|&EuD5qQ(>krXqk74n2Yb@ z7yQAMtOUGBwqT+QX!X@CEubQJWm}RG6X(m9=J$8EKu-NdZ|mz8pUIrXE408VD2i#d zJfi&bQ7Z0z`LnvaZ&xPp6wBvhSVsoJPZG#jwlCS*1{O$ArmRhrLA3!WJQOXctRTE8 zPM&sl`^R-4*S~B|A}{kC_t1ss^FRz`aj}$Go}0(k*X(GpZ7}RDUj()5$gJMd( z1TCd~2gvE2(v86jy)69Knw6=bPfGanuiyE`jcBflR%+#XHjIsVc&5xYR$=|zBR6iL{D8HvO`=q}=c82{QVSx-_j+5(GtT}jn!YZPS1Pnm73)j* zAcHJ_hBS+g!tcxV2=Gv<4go-K%~EMM^VZUPpBMT>m8zo7-7aR)P{&B6 z)>5~h-HLs6`K{fU?Mxm)sAu}4hHFYY$E-&*j_hFzD=8|Co+USY7^8a@NDdR&E2vmT za;L}xDTKM8#45o@2J&t%D&Y@2M{*S9v&XRh{il-ht9KtiJ|J7reWzu zwQj}RSX(sn-H$-&2LMwU0maMt0en+uwJfU~l}16oBD(Ik$OJ3@^k|{D-fUoknhQ+% zPQDvq33h&)MF8G6V1r>3fbR`pQ*?DJ|hXd%a+o1{QRl)uCZh$j(^4mS15lX$*;`913h`|5kjI((Z>1(CE3&+Ds*n3^d zxm$-E_CIa8u!Q=Xw=~pM8N|(gMmW5biUcow)Y_p~&Xj1!f&>ymb(Im>)sn1PuPK=u z>ppQmAWwv!Cc+SiUI;*F8yTUHfX<#K5Yy==P0R|QE z5c`BjbM(_b*{TMI0iZ1Q3W3r(O9Ko^8~4)vt!c^li7%NM8F+Ex!{xy6H;i)V)ohB6 zXuc=o_dKfWViRbAIx8^T#MJcg^n88e?Bt~Kq{FSPuJ~QSgamM-hOIrdold4Ct;zQK z1#@|4p-4&~@?!w5Iu2L-Ex`s+Zp9Z5z z`F}~X6;1lVL5i!duP;%h+dD8Ir{DW7Fffqa%*?RVSc77Edn%Vx4SMWn!{p!(j}mTp z&2DPYxIitc21`ly%xLbl)yOCwQv}!X=DFuvz6}~*0sSb8k_*;tYlM^*$D>3E*_YABC^!EDK736P@>*6{ALozo2nWk?FCjnb)X)xF+`F{avxJRJ8)J!+mVGy0c|Io60s&W z)I`X^u}$)oF^{CYi~p75tu>R?X>ny^Bdj-ef(Fiu#S=;b9@q zJaF*p8@7$DZ7&s1OS1tWIt=}I3t)(%ax&rFJ5~sNN>(2>jIW_ShpqO=GUeE$STMego(sex*YrIUDkYn&eGHK0GN@_F}ecn;%_Tyg3IQqcL5p#_z+CMWz*B(q0#Z7X3ABguv!ko1I9?Z{(etwCO-R%&DW|Evb-X1sfeI+yx;H!p z6+2OsW1MEEu+I3%!YHg&4$1->8#a8;v=Ki+Wn$xA<7&q1TSjYzfVs!VAe8V~Y!-3R z`_XAhY_HDRp_QrUU`ZWKO(s zD^JX5D%wA9pKjg;b#xVBj&9%X#8hZusX(2v&GgV*StQ8&STD;-uu}Gaar&k}TY|S8 zo)^1UQh0L8<4~ai^I-WhZCu1y8K)lmQ$RU3(Xi6xW)bE5PWw`EjCEnuZ?G0Q`{Z)r z_re0DuC6Z7ohfIInbr(hN!2T+0f%_cLQk@i^{2;J#Zl4(qsIzF1aTDF_Qi$7HUVCZ zsWx98%*kd}t9os_U==1|H{!qnmiobVJ%JGLO{mx;i{`_T`GAnWf@2SUtOx#^l{$IYRT12 z^IX)}enzmQgoGrDsvH|kw!ysaqC4o=4^P9F^A#J>$b=^CP-BGdmcrQdEZ?;Es)xff z4#fvEvMg9mpY3zTu4vnuRDaasJD-R^N+kvPLXdqmXIV_aY~BvhP8rAE9dFEU(Kw=& zq~LBvTV-wR<|Ak7ITEN!XCjlajwTt*1IMjUWh@v#bg#2+W$)DoH`{9)p@(<1Kv zqEr*g%~n9)>bU;XYsD*BF!9KW8HqkPpjk%BTvT>K9`}|K0vY@YIVeb|ln4z?`;yb=d%(Y8^GohxXlxB^mh&@3+y`&y-|oM?!oA&Qxk)4 zS;3tzHXA)$n}OKqG^H!wbP(v%keW|J)yt8!tBQC?s&?F1O`d(9u^NO z5P+tR#?2&RBe6)jPOro$>kZ{iXMKK|J&%9ah?>%aP5aaYh<;NxvXl6RWlT^^ps&Dr zl(rndJx`F7B+-cY0NyBd9_5{;(6W^zsBL_TC_mSMjSu~3;`o<$gv+npKGt8Gh*zt5 zufX2pZy0t+On4K}7y)+?I0Yb69Ms$Gz$_GyMdz~ot*x2%O|lu`(ALCoOGCSiQjR^SdIeEr~D259dk0Q zx8_-y3SKKrzH&)@VdlS+@Uo2#74=78%<-TXTlR-FVj@% zA-ww6kGEYxm-!%57~TEsNTmWh*m%hHr@xmn=FVm|q(~nwpXxKu@wh3ZJy}D!w$6x& zRzVy5D-)uu|0}~<<9^3?ujELO1=9I?6Sa1U24tN*4jT<$3+5+P^|_{~ea413SF>}* zk9!@g3+X=>9OLo1IzKZi&IKoJ=DG|GMXdvqeL$}S$Od5T03_w`WA+@_aaw_{! z2;$K}01R0HeH0MN0Gn5@CLtdmA3ZH~tQ_Fm0i>QjK=cN-^_>vD>wCazvkz|~0^E*5 zey6O!HUqXfU_9MpsK~ga(>XReYT@ES2;@GCYG&8Kz(A5}qn9%B+ZFLbM9QO*C2g9b zL~|t*gZly1XYSNTCcYHAzKR-@sScgnyWV(1$qPX=kq+CZ--qZ9oMA-+vr0cExn~-4 zZz|$)MQa$3=2zJmAmWgN_OzZ98h5j?it}^!~Nj+2xpJ$3)lI-64_b z4*MHwH7Y>byZLi)$0c@>KDN3Z%{>r*I~TtOs3JJ9cw3zA;6A{xq4-oEw%lFpt$GP(9hDMBp}h zh75X$+>rb~oTIP40}Q00p+Vxp#mNcimDoM0x5m)fn(FG{OW+$gBO`eRRS{>?MNcYS zCP8kTb)BryzR>F5U;0zfCb!iiGn|zYGCVD@STQtBdb=7|4zORetsF#dam~$Aca{%V zzMXjf7as#krHu_1ARTTFCWffkuDsI(jJSMOXFQH@Vo!Fsk}CMJkg!_dRs79llu|Ne zgjp*;Wy`*+qB|Cgy}Z-6U3I~}tL%LGdZ!NFr436n$?*P0z>J!lQ5+<9oOBKzSlP9l zd!Fc73ram6JgPXKb(1nK@Y05TN>BlOpZH>Xfm!1gG}Edc`(Vfq#LJp;f#BK-_r6+B z555#<2q-I4?{ZUg3Ol!bxUP92a9%7E+0?PLqR@6;mv6*i(9s3KH4SiUlaOFK5Uj zTBNpO8xMi`7_O@v>lfIS&AgWvS89rZfdQ`TE#QVTtNYY%abYDY6b1129;|n#_d6WF zewAPO6mt#y#ZL0WV&h>}3L?E50GOT!u*HHzJ9ak_xVshnKv z>5+uS?|wCjQ?IWCUiA7{`BEGNEFs>_cRRpx&~dtkA5)3uaX5FksZa~O^ElLLsrhSJVi^L>{Z^kGbw|9Q{YiqEudaZle4Xr z^7SZf@;t7C&f6W9cYhe&o0l*kh!7*;X`jcj_1o<$?bgAtB*>vO230y?yoBA2URStH zo#|*Q$JdB@-b$K4p*>7Xt2m#jCJsc+k3^Y;bko1_lic0(P_RS4(}Dm%xtUW&oK{b^AhRcLmQQsYW~8qbx6)(~ zLqoWK?Snvps7|NCiF9caPF5@>WEq}`dK73o-~&t+p!hD%&OqOHl|dQ);|0K5auJMq z7^g*i2E-ds!RYlTXCLUqgO7DQzfD{3QCEajgp}_YIddfJEX+DdFD1oM{P-Y6?bYKYRp z@;$KdGca8%Y50QX9k@s8z_RWqXPL__Dbkk4^ekP+m2G0!udXvWx3F#Jz=@^Z#Jb0% zB#~ACBdxY{Bjdc<6^-pxv3oH@fvUneTmH8JB=>w3GOwolM+bY}vB9K;^E1j+p`}iR zsn93xD$`dislSQ%@ZK2vwz}lgX+z&jMX9?nwFM?A7+XA|k7r90)RoO`BOe1<%gT{&g;GZCL|8^1p3v%x8cv6j}~$1eNiV<4eu3^98)t z2!H5ixb~~Os28yMV;D;)7$p$cMIdMyswHMu{7+a?vmTkG{2!rRaIZl zf$^&r5gD_Rh6Yi|!qbP4UQ__%1~k;P^mH7|qnn$6!)w({p^!utwS0Zf{CTGrfKgT& zXba|m6$Gf~eNiNU1sONIYPvsVwXkhG(n@4Focb(rfzcV>HkUkpHyvn6!+Jd2eC@JkM-FP`BZ;7u67SX%OGFmq0 zPhXAiIDB|>9(3ZGdFUyWZ56O1P1o~O&nU$7s>l?#vwiEOE6z#~N-yYX)3P5&;Hi8N zf2H-s-&`-CyJh9-ym1fMWT5NDGrf@dYaIrn$mb~9GzRc!MglgO%sok42G;_CTdld3 zvT^5uLeN7c3wE~(tZo}0yG!461;1EI>er+WoWV<2Saaa9w74V}=G=(kgkMUJ%H6h3 z?6KlOI0m%A5?19T-L>iFUC%wC9di|~q;1@Ta-R7tiO3}<|90A$nHedn!yp%3S!`9? zAI-&V@KBj*uKqkioSb-13uFGzstK4tssN^b04@OEKzQ68*8QA%8;ksFdbzVKw&^|p zBQzdaqhA^pXI$5ds%CR4lC+ax8xzZek%J_)WH%Z$_6!lzEFaJ}rA&9u68lfUtW*R6 z9_sim(Ik25;Tm6yA_I? z0BASJ37-}aHvpI8-`oc{nI#~70L-Gf`?Jl47br_&2k^82WBAXIq1X0rj?kaC)xHrI zr>hO1ik16u%#dCl*KC7u6yE)=hb zGuj`BHNGBhETn=KjcTM@`x{bO929lu?%^au2&PWKm-ZNn4YOB^U8e&5l zXvNuD*4l{TzPht0u8`gnCuYiFO{x+SS_4-kHP$(&AS4_<%VZL4uyo$@+U9-d zGq^5cH1RI69f{DIXLGIFFCVi6AODI)WyhT1273K1i|FKc!_dF*{OiLOU6=Bpr4i{)!o(%!Hg93*e zM+mLFlpCreD}(rp42+NFe9aMGy?i+zA@nCcAm2_{)lFy;+XOBQ(7rRMemM_=m9FfW ztK)K~hi-3_?OnHlje#*)LBQ=d4j&(%)btRT2p5!`fj0xC7O0I1<>G$HDwy z4y!=&2k6AdCuJ(y>A;tu^qYGm18|f>NgQ(7HtQS&_&hl!i zgLl4bGEoB^|D9Khb>~3+()}{(>KEfhkfQ_Rou${M%!${Xb{$o5vpze9M@3)0F#r-Z zhbZWAZr~~^u;-cOhrmP+e0>fwk+FK|yw^Px-mB*~f2BKMeHYz_5k5DS#u5E9!b%VD zyNh-HgI4t5yRAY-;+RWpeq?O$^=F;c`oNpRP~pE4m9Rd9$r*FN*0}H#1^(fB%gX2Y z+YJ-5>g9nB+MS)9ZzOJLkP!CAy~u`hWKJtpXQv6p$L>_m7m@)Fc|i+bAWq z%51X8J`;dQTagWwhz!b70EzhLK^~1qY4lzv&)Zi_2x71*Gwuopk}g(x1LzW|eZQyM z(uEFhxV?QZl8PGdS(emEchyP!{?=}w2J3?F?fSz%U50)4*N_Y)dO)lJnBbp7WnlqF zWg2)UERuP@(|Wb3=z#@wJzku05y+oax@3*2wZq+q^)7p=4wpa89qQWVDMK<)IqnvVN@67L` zl8X{kdIcP1RKoPeb}}F8$>dw*2D}bZd9reTTodHUd@1*stQJXd;l<2rZ z)k&7~T7#){wGNLHk^L_u+m~QzE}q z&`B~W3P>R5hAbVV?^#@n(}jfYc@c)(&5d!5IoC>jkDJ<;umWd^g=*MBD>huXISHhA z)imG8hU<%_4wgIP7#SpZPReWUXgkVDF|5v}oV4+z{dT@K@@%rgI_7tDZ`!^sVqK`K z07{Lf2exR_XqGNnPjr(uD}x>GN{4d8a>CMyVlJy_((@QP>wVgg;TWJxe_hHoqT0nj zF%@mF3)^n9i)mUC(d}9l5C%o2H0iW>?}O9(w5i;wBPCJuRJD9nb9qCG-CGN7!M9z{ zFmNi{r+9*a%{K*@|u19pBNU5M`veetHcdKV3M?WrNPml%+vhg zuJT*Ba+xXFwoFW1Zq@Rr!LPvq!A{7C+y|;U@wxc5ADp>V5vy+Ni zG_%L%P0@b%DpuCTF|k=Xu)LTPfR&v#)!cj^*EHA(ZPII`v%{XiR3+WMsWEx*H1yss zz8s@^aDASLvD}ODaFFd?z-rM$6}a}u2i}kq5#PB9L=iWaYbN)WOK$s3mpA-NA*##% z96=8ax&4_Yw`RAn;3JOOx!tw9?hF6RfAw`A>h}T!Avo7mtvW*}`-#6D5#SG+2W%XE zBnRy8*{MCZb@)a1S@mTp)CY6rkXt<5Kj?@Ubq{BDFzA@!$RPN-^l}!I(XAckpmn2z z@5PFWTe;d&;ZryhZNKnt*Hb$&QrX!)`UX;n9~pE<#3Mb4SI(|s=qL~# z=-k3Hs?SvtM1Vmkgd=k=qjP&=j8ETmu2UTJ{4?it-fnOV%86fp0DOPGA^SRzbV>m% zn(DTfYE|{&RQ1SR{KDO5*8oZSoZC87kPmcB2)Ur!xaS9S=Wg^4bV^S~oBtdS^DLi< z=vW`lO{stXIj+4(Ej99ov%>?`9rwy zf2+sM2uBA;M@(xcu5?pC5WZ4aE{nCm8L{%B;1{N5vXY+x=c&K{9RLXd>K)~&Fz1`2 zL=O-jz%=y(=IQ(ZNo5@ROZK@dd6YxAN@=(pRUl77gkh!wkgX&u&~>J0SI(8-yud10 z`Y-wdstptjjUHJZ%2M<1xP=>4c^?;5eKjpS`QiRbb279jy!v7WMG_agnkZYuv(uv_ z(~WZQNV6GjV#5OMKu%73#FS$8gZTjC2-|bK(6XU=*3RL9Aey5Qdk>K^8tb9Q!uB=k zwJDvo77#3K5fc;c8NMbznFfqcB68~TGFasD^<6{6gJ=kdCjvl`;Y4Deq@xHUy4y1|9ohjPyJ2m(N2?hePI+3@orlWg63+QMrxucevzSpoF4Aa2RK7GOJ*Eer*a9hfDJ&NR8; zJG>}hhy%YL4GFNqUE=72U9KVl{13?cr==>{-+?1lzgqiHN1lr>QyG*qAQ55`9=onr zqQlxZ(5`CuR$X?TVu?26&oxQ3x}e=r@uT)>a@HjsQ`zndReE7XOIKj4vBP}G&g|jx znrfbDD$(LU(gXbwc({QS4{&VgzAJW3-`#mL$KHMn7~_TI0bulev!pvfEN~2TxonSPJt8JQ%(cL4(#F$Zg&Hv2jS z)OT!FFxl+M!!BEksjU^3A~*N{*2NpDz~>x6f4Gmf{SW%bV8$^pu>;?-Bn9y6v$<;= zWpe+6;Sd%@wBEBsPN`=+kV@%`u|9+`r;d9edW-`~rgUk8!vt18tz?_74EejVEU(LG zx4KVKO_j#SQ?i zf0N(+-u=yo_fMAsK+PUr>k|MHwW!q8qo2oILD#vr&scND%{tFYGXH(7+}0Z>VA(?+ zf$iYmxL0X%XZNq>p`a|ejj%0r2aB(qU4b ztBq7_bhjC0{Xhbu6v_2k|T<*outsz_=3ZEY*2QN*n&YGiTd_>gA#N|b(b?ANsfGsRs140jiEO>vg7ME>duQh3*pX+i zl{NnPBe$js!P~^mgnW6w1Uy$jO9XF2`A)B~RGu=B@cU_;Be*+v{gvs3cWo-Z{Mp@e zhyq+BSAe|C)IviXkmWhGZM+P)@D9G1Jx1l*vN8$YRy6ruDt>2+AJtd;hk@clib=U9 z8j1XO-J37tY!ot2r2?>o9)Q%vkiBrqhWfLYm-?U9+HrJCMQ)5)!F=@U-FM|#$NF@G zyewfVU&rvQ5Igq9JFPozuSf;BC0>&_WpjD9^PGe_I`U7LmGE0;|0igvLBSx@xtOD1 zYExTiE`^InkaL-RElpwC99?r`AN`*0S(SU0BFPqa?VZ54G{NsEMQV)yoteoMJ^@x4 zX}$x1y@MHHK_;G-d}71?Q&z~D-{>BL)g?O+q5-y)Rs8#=sma!23v;+ah)wNad+lAw zcHAUmhnKQ+bJUK$FlWhe|GERe%CFiz&<2d5#ET&$*Q7Z0_j?RqyD>&AknU2S{rYx1 zA+BNv0Jcf{@7FPrVa&wSAo7?-bmj@>sFXu3y|G79tgbbZ9KkwL>bdghKN;#7Qnp(5 zzaNOCcB=x-FO0W|+>}4ve&3BU-x1es&Nhiik)C=@H)IYsg2(U{M{< z#;>0pu(3*0Xs1V+C^)obJ=}B=IvWtjvUc_TO1cQ%ju>;fU8QchXtL%nWAoaAL-r?~ zVme(Cx_740ADdD;vCoJQ@|K!|QGqifPcgDu#h%su5ePO7>(PM!NunG3UhJTz5^4({ zVnJU>alCd-au-gi7Sn!HtzQ0b>hfn_Pmp8XoD27hzt)1?Md? zTJzdAYc&g~HM)#*?TF^YD}=X*xK#2U>>TT|X=mjPR>IA{2uUFzmWO^uHKEUXPh&I( zXH+eh`YckwA~G*eZ##OeA6PB)b@%A__J7USf{u_unm^>o9N}Ux*=38|^q5;K$^+cVs#a3Ev zeW{TChNR=yMaHHh?Ssk(3&(7g#!31ku?!w*y}D?ss!E70S+Jd9!P!s@g$KETaH3pE zE?W-I^o7pK5#j9!SeYm8kEjM|m5=sDI0iF~FQqzn&!BQ{?FAFv*LFNA-3r(!kK(ZS zgeV-mI?{@mUS=w5MttfDcnAXNf(~9nt;eg9v%{7F+nLB8QVr3H#Kf*hnt0QPJyt@| zq21#ZP>5`_D?5@_j?O%9H&p}Bf^Yjd-ay_Y#k^w$bK8pvUloDUG+M@&c>gM9iUQ*& zmnMJFfE|#DcmeCC90#OCzZ7cAipNaiH9p~B1WMfWh{^qNInv~6Smzg;v+pCI2LyzJ z{8G@({$)(}<)hnK)w}04UFZ4%8!RTk!7kfnJV(ieM3!yE%z_&-C z8bsJn+l45YS2To-TFn%5RlWW_%9BlMwU;g6iUwX9h=lp}ff@xMBi~u?7Z(?2?Uyn$ zGf_hRPg{40M?6GBr)=8^7sLO(Eddx-pei|R7YM0srb84@*4MV^_}R zbj-m(a|^oQ<3Yr(t$wXC0A((jxIG%b(&9o;HzX06ve{T!@JUq+;v2jabIIs&^)9KBj&f`8mN3XqW zw*pKqj77c}lHXh`^eM$g?U+B_=R>Im#RtSVd11gy1b-4b!ONsu(~`WWFYyIVn*?ew zMM>kr`iQ6#eu0npu`L3e;QCU%1K>2{I^K`81nPmfQ?S~CRKs{U9DZ1WGH3@1_eizN zI+tfaQ(QX5Lw#x&KJWuxEPGRdNTnkq#XpQB-+L4r*h99*Q0G8=!Ou;tr%aIbw}h`o zkK!Hpiv9@lda(&*O=qQ zy31)?iYk7i*6_uLD$u-l`1N2`viwa()j36QVE~I{jYact*D&5-^|h_naWqEaaOOF0 zZ8cKiX&*CF@A*gnU>4Mlb?2x~`HT~S;q=AVXH#YI$&a<&MxW~KaR1(Z+vF*91yG3Z z2+4|dj{+uVhu@;{Prn7sIP#E26i=jK)C1rRhy_4+Ljt};u9?^QgZ05!;qR((?xW4h zrpgNNqr+BRJZFb1pMvpz?-lxhsd;$k$I*~pSBK92^taCj>#{AlROr_Q*MCq_{qe@B z%U&RdhCErP3unVH`_fNO8%jF~DRMf~pPOrfA`jwgHqSLu>&?lz_7-`z^-fnt-dxr9uAOatyij5Sn7c+t7 z<%jCIRr|L;H0i_hknt{WKYfD`{ueGuPC?O62CL~0lR+ceTZ~|thXyYbnaA)Gp4B2! zDSc3;)NsVFXT*8o{odlIk0VPW*)bWxs9^3zXuXl1X0d-33ye@w2 z9O29lS3xv8_JIHq6Akg_rv(i^tXQa-@q$WVYTIQ6)2v)8g|bh(TXt_y-Boa3Fo)1H z$QO>={g~99ImQZrG869e)AXanu3`4b6#AyU+TDDKhgmdZTR5qApx(f{jWLs!|3upI zozM;{CWfO;!1I`Q(o|ycJ)eY}Jszi@4ZBWBSY@-w<_YTT{P@r|y|s}BiUqjyUH6vS zo^58i6V?FMRp)5(_iu|tbY;>L2694vK^Kr51jJ`>hnJxeC~bx{xMg#TlUY=xznjC~ z>$6ag)@{AiAJbKjlJrdvun7M$+?|EJVb1$~u5MDAX+eBtWb=@6+`U}Wjw&>Aj z!X0h)zOQxRhw8|$PIB6tU2|!k`{j~9_nstUW_+AATCWb4lP-E12_qiPbgeaoK?=88VS85>#gWgF#f2MLNsV5L`{d{g&++%> zuxu6tx2UM&WhQT^Jh1_x`@YSgbf|rCo9N&oHfFZ~6{}otJt0N_)5N9HbarRi?q_?o zhOc@=>5ac`ZMSIJr2Lw$Z+O7Yw}n(t6vZ#!5mzSU{S|~JH&Gz zhj;lVRY=`)^aVW@yS3q2i~Py<=YAhTq;JfjocoCcR%IHccQa?z^^%@VW0jq%y*P-g z^|RrQYxb@|uQ$HkDer1SNzt-*1Qw4Kkmak5(~*90?IxigF>5>s_q`WSKYFzvv*ngv zFq#}ucuB0}@GqjApZoZ$?6+;Sdg5cmCczrDzt!+3FE4RHPl|gNtJgG#Q4 zN+N2Ek`?VX;j2Z!y#DR!;JyIi_qDg**J|qwD(5Qda^2dND#HdbLeh<@Hknb}=~%W( zcS7ripKhT@A+^$M4ro zs;7GTkw2TC=x;mS{_opC%iakX(=DG}9x-rZfR%b8tLrB=Yrl-v_MEY3!oCw{_0t7rm=N@kL8 zP`f9hEa=f;o>Q=?BR_(5oo0om&;8lipLj7g?h_g6JYnpt4p|wOs!f(%UAiltO^lCm!$cD$GT`5C&ce@KNsq}A#>OT;cgNA@1RMyHsb%a z0CYa@LRBSnh;XSTMz$PnlooJ$yBV&k&|rL@a5IR?ixp7gg*^ zUb9Pz5(y%-U`Jbp@xR7}4=_-wjJw+Dh?IHJ{3;sta>A&|L-z~|M^zc0bA@Pgr8^9( zRl#;kH2(|4W4HZ%!~+{BZYcj?%A0mcawSW^PRTex9WF$opCfVebJK=i=;{+Zet1S- zPI)BxP-q!4#`{xj(I8KrSV(NqV_yJbzEgapR{fsVY~X!RBLzzh@BSkgJ96+-x78*H zKGR+SwZugrc6?mL!_zart81CuqfC;jM%7c>aZ=V2th-V|*#pm1MLzDJahscL7m`pW z6}O+uKl8+Q98_swazHn1(XB6v`0J&{ARk=mr1n^8B%xLW!vhE zbz=4@)n4xOdkQAZKMqk(Bxd-Oll68c>&lnvP&>3G1g@lEeB$fKYcZqB+ZC+e$@6%c z%<;Q^YHcMDCNj@bs|mz8(apP+l657qUuOX+K{fSX182VCQchGV+HLDL5fyQ7P}}Bv z(CYS{Rk~|b&czyQ3+DCG7Zdm@Z|5K92I^!mQrZ1UIqnh1v>Iy(hW`<8kH&xaIyS%F zDD04@XjxD1uplXWEV{w#opl8FT9vUBvV`OWgB%Q{x9ZQ>l2ocmC6&e&IG*FBWn@Tk zrT_T-o0guQK0%>4ma-_zQoi)>UnlpTw24h_I`}JrdCx-l1WLy5_F>U36-!*0@J8k^ z)3lZ&msqBouD9gZKO#_R^hwq=iG)l^4@it~mX(#2Qgn-Ud)D11w~e?>Ubi88rbQy= zqn7{yTRYvJd0(u4cyqV4v%_`&eDhQ1PYQWpW5bE+0}CZ*Q;Mz5G}bT4#?IVprNp;9 zYNh92#^jnsOU*&hLu*BG zlHkH2&P9f^M0sJOT)guNAdYH=VV+j=F>tzS%5j~s zOwCuXT#LV7qf#r^{=$)58+7HiRA>2Up3Mkv&~*~N0(qC6tvio+greKx!F2r;*C!}C z#BT2I)**dJ z<=fTq$PtW4Bn0|!yXk_;y0a$}?0o?xxF%%R4M7Hu7#!+=l%TWR>*p^$JbE_Iex-o* zcJ+Hi_xYm z%fn-bHykJFc&int7BI5;>Wa?z+v0;i-lR6vx{B8SofJ*1>iUR7H+&ole`2|N1iCtI zUxK77a3z5Z1R!xcXYFw2_X(MS+H$!fABBw+tYMy+gyGY%PmdeXaIzkq$6U--@FKSZD!GdSMv={lP?a>}L1Yre&TmFF zqESoVoxo~|M{`U&Kbe+KyYR5=u`QZWzz~*)mncN zYve^;4bis^b(k;qj@(5V522F8#nsbaA1X&%ENgeD$qZNhYRNX9ZR(B)9d&5${zCd| zTuszf{?!hws4q^A!{Z9Ek<6aEUk0+Q?&|zjyPR@y z-Gw!OiBG_@!#(@ZjP73{rwJ<){g^7RPEmZZ>+Q9^U{I}krt|!hwu!E1)S`8JP}0Hk z+4<3+GynZO85YDU%n|x%YuA2zS7p5~>5;^75^&0rMi7>eT5 z{f9JQtD-Vt)anTy#^j2C)|dT05a35-64-S0z+7JZ2*u=b<-+)k5R7G>imAV@PbRQY z0ycn>Oh@eaOUnAfJ@Os_CEvuX)Lz5Ry~0~OJ6YgX7XI|4Zd^Fqil z`41{JnL%&)Y1L5j(up})Dqrob>1&z_JJZ7+rfy`s%$ra!0s_AAJ?*q6`n;#niJkyC zANK276!F3!&qrdg{4Qc<~V0oKP1FMm|M7a`2tp`a4<&CT};_;BJ~C# z+ye*4cP*B9+yQY-MOvLRmde zuMDkhRa8_+-;P6)cDeWa)Nv>m2|KL1m?b8@RR&BQG2#qeRA@K|movvZJeGPWbswt= z7%PBkTNBxmk&sAorSqs@XTKm&sLRbFayrut2XUq8)OZd4;cH8YSK6}%$Vehxu39}PgZq@c`vHXN5#rchAwPT z;&$mD+y zFUYP({busBm=ICTZZm6T4^kgyVAbelZ?Wrk!njW56~dHgD0Dz~X5G&tp|iu8ngS?YH}CO|03m4n|H3TR z);& zJg1X_nIcH8lWIxg@HC-=ort|=BG$8m=zg<-5X;=QennKD`RV#zl@y0V@P2l7zMq~p zG7(6Ii)W6J7OK#UgMD*gNOz?yy2(k$73H5;pq zQu2pu^UK7Pek@+(bkB#!Apr`DyY8LFP**|&R3SWedn>|Cb%Gp2c58)P0Z6#an<*|u z$gR@jP)FgSQ*C+Vq zfQ4w6oT(dbuJ-u-&AqF~3Y(HDG@#QR$r({OHR?Jgr3+F|A+`tZlFj%YUG+kjOE)OqVpA=MIEGKN@ zcDm{!ApcOZv$;ck(o*y29;)ZEmq>x}U^y;~is?C;Y|PhMZ5ncy-KE|3lF8e_CFHJA zai{EFL#$p>YUAUEYxc8!Y-FElCc(nOxQMMObkJljDeAKOuCOOb%mfw=QQlPAkOgIg zE3V^58NW%;m1PznWPpxJR*WT2MSp7LjiZh8E>gcDI^f6E8ZslHXW)UP$g&$Z(lyJD z|HKGicKVy<+fS(crst-ni;j)*;5$VB*&`m?A9xFVDw)zp!eMoxQ%k4iKsz^_C;Cj@2L?%M8@8jwcOpR&YZMfcXmG zf%O_qd!!AD{(gRwQ&S%m-j%D$kmcS=3fXoUE+0uRTRQ)aA94(=P?(D$#DDO%s<^0@h-5zAc zB^v$~fLzs-y8fN}@dM-Q5H0AjxT9YNZOIs(;<`tM)4MQEun4FKRT#;xeAGaMyBX}G z8$$z1iy;ma-_^yksG1ra#pQC#g%ZtIk)(#2{@RwM%IJudwM$15hZ(g%AA}dRvQ`cH z7|BfMIlnDbc8gL#JYmOC;1A{l)A{Yn+$ zQ2RkwC9k*J{o#1CxU1yo?!!4z?-$Z3Gz&nD&~0&|__x@hr;T~Mmgs#-y6v%Oal9Bc z{>2F_LRg*VSoO!MUB>)*L~(i)L==zD6UXrf&4g2TM(b4ZdJcuho=&;4yzddzERCJm z=-?Ipey`kTC>czkQkGZ~XMRBr$@vJEXrUoQRN z*GbyONchSuiAF-QBj9F(!)aGdHgy1&IY|Bfd8h*z1sAN@27Fn zk)5rz#0=45uEc}74a|moTqm$A(QGoYnAN>nL?8&NaXq+CV(axOVkD?d6@JtP$Xi=) zR!XQDne*uu*=N8`f|4nUXtwRcwa)z}FDl&&;Put>U(u>|ikPTN1DlcM6LS)=!xWge zd#*bT&o3LZ)iLu8;`;9mdRgysZi^%>$ndpHb%X82;n--;@Qmx66|gbw9Z4!DrrHWd zn{A8Cf4e(S%;JTpzty*7y{V8$ThtroxK973a}^J(WG{76o7CCV^OfnPPCmd(d7?}0 zSpLi)*^!#f0a5Tmz=l7pwh^~X)rP@FFvEcl@x1DdD6g$#%dP#(oE=F@zIPp;I-rKI zcUkS;; zhON;CZnNB1=H?=r>|vyjl{1H*AzseaF|HQ3D-QM{`L<@5dy04UwtM_N_z6eSU&OqN z1&|2vDS|Q}OXcb9o$342g6khBV@V3G^{=DWsr+pZ(jkkdLl*V8rxv+jj}a0QnnWOC zWZr!AVsEdp_jqeR@YR@Em}lMC+x{zbPFo$RvSG#YRux9SUBjbs?Pl~Osn{rS$YNCA z;?5W=!oZSfw?<|7)p>d^CjHvvCQZDbNW&1@qnE5bYkg7w>W$ZhR;3p0Q{2SX86?u# zfiNd}{o-be9u6w3_ za!gel_&^VrbZk=fApH5L+KUK&!JJlk`XOhE^F)74sU_585%0HRhi1y+ZgY;7L0&S& zu|C52#g;JGR01-c9qjOJF%pJT2+P6}+T+sEbXpc`1tBv@q4E*^eZ{)1xvLfPWtOwq zh!xbd?(Mg32$EdY1jUx4hIuOi@&Q0_fyEDOdtctuDy3thJ+Ik)LmHRCwp=5e=_^Ma z#`9}lNOsJ2OCyx!71}7ta8YVX%<2W848RZtZk|`Nw^@0N1afG_A{HTy>$;(EeG9m3 zG)0bDW#l(XK1sUKi;D2llTM!_GeiIVrq=UC`>DA(Ow;BZju+mbeh*}?3zSeYQNSJe z?1yD1(}t`XKFPfKL&@w->WlH?y|}2&I96xtaz*9rO05Ro z_;Ci`kY2Rq4B2oQf+bL;Vl9p_a-pWN`?TAwvsVnSDo~!G+B#KIQBg%rYy#i~ADoDc zST%yO1(I*W{5u{M(iPZ$%kxVlI5t0-uj@}u%<5`Nt8i=E8t!_Y`7LAkgO0A(-LsUU zIDfJcYO$9}TF>0l+Mhs3eD$@5t|4IPSr*MP%Sh^>yVb>^yQpqNKqdT-p>USLScNrJ z@=Lx~-#Nb!B~4s))o_ZoD(_;m#8=Fet|npGwyKcm{@gqP^J&TR$YG0NzQOe6rk-ox zb~+=9B7hRq)Uf|2^;$_ui8^(J*Rm-=b=Fl&KcS}CJ?}t0=hs5I*6c8<9VRPcH9N4H z&Hp)ymRj~*lV#XF^f)8emd$leo^OIhR8!klLqZ!>IFJxk;w~!ydN5_Z=qDRWbDp_A z)6I+1yL)=oXxqxtlS7P2_hReU1D=iDTk@XDVJ_EinlCksKMYRs)nDw zji;iBBQe$}S6uicg*D$JkS(2&{S5Ehvn2YX-3@nZKVCw&R^A+P$H47f8xb| z)4l~uG*sp6uT3}^OV?jfQpy6LZ6nphY5ocH;wnJas)1>8X4rU|b0Lq2yG~FW^W9Z< z*fu%M21;%ryu}y_tHMt92P7yEi}OU&fx^+y4a&4s!(Vz@4 z{JuLiNn0EJ58bGtx<`1J|2X>|ld$O4q3k{xs zWb8N<9*^0fo*T0>U+C$oc_R8)6FnMvPUxRBU_S;Qxy>;tS-ae4QGVEZKg!X>$p=Xx38>eM$VW;)E zrY5$E?N5InQ38SSa^q4JvRp+87@v>eAcij>NO2)$U&>^mVP^`#n7=ih+G_0Q6?jN_ z;T1{28NCI1))|5Cq71V&lSw>256QLvW$J!UWR>G8Ldsen>VWxQvNOE&-}c)+TW&$+ z*i-hxXLyujTCs)IJqPDHvTu#PC!<54q@*N4r4%e+PvQp&_EBCvW}Fgu?Bn1tN`70W z5+@pj`1m@WDNV6-1#9$$kD80hS>*BSt9dLMd2!F-Mpdsr-2`IH0=Dt*04bC`{Vtm| zFzPt`xL~E!-2rJn^XmOYfp7J6%E5G7>E28bV=&|6s@+^< z`QG%XZw=9YIK*UAE?eXH>$x;?_vC6czt+oCBis_t;@BOF;WXQ?dwA4jP8arXJC(Mc zgU>IcV04xlXwHL)@|lgf6)+|7rq?q&zj{>zvnC4N2Mi26rJd}v*VAnQPR@_R9BRSL z-LAsIH!2;W&RT4jpHe%o{oE1hs!=dwE}Uldwb z#WO+rhb>05;B)Jrfg3Dkk3!_GzeIX9)1H+Ms~9VGd^%CQ8!}?sfHhMjHJnu)=O5RLO%VPl3o=bmy6T==oU$&1{35O2Y|t{9C5BCCAuBu8 zjcMW!1(^{^$e-c*74o*lfSdo#2mM;w#8GXr37xrz=N$;I96^Hr(){m4a;t|yxnauUopOcT7lRpa{h7h6>2z9(Ix=N+Y!OI zZvAR2F6avpx~)pY0?A_PLg#J{_ghGolMBN z_J+}$O8ZXnS-l9*EbPZ>d~Z!^oF&a$5g37{{jg^((BQ{AfQ3Cq+K7sVLZ7K??`1oH z|JHi1pMl{C8Cjp^o6sQ$p)`k;4r8m*W)>Z#fDZjL>SU>32FNhjru4nCvy|^l3H&VN zENuP%wEzt+uN9=Fw{B;|-yO%8$Se!DWRu#AD;3ZbudAD@+Ezkp&Iz_zP z#;^8PCCQTbe}525ouGbO8A6TnOv&set0b1y<#DYv7W=F#?WgjInJbN;HFqZH)+v)N zG><3SdswlC46Qm~lLH+u*$E}%Qra?3Xblg`hCZ5L;0v*?6lieiLVn=xpkI)^w>o6b z9D9?jkiJX>aBc65fW3>GDLC9#W!7q*DwDvb!TC1RZPp9LqpSSHE`Ea0l#ysR1N#qJ z$~E~$@J-;gk`asHI^O-U5N69&`o7`uRmOG&B)>-7NXN_M%D_|frcdHI(owj#C~g>o zkKi*qusHo7q{<1@F(BizpQjG&#dIMxEfjLbJ9J@%tWyUZ({=*NRD|choq~7D63mj5 z+6ZUI%_S_ExWwJ|L$NE`&N*fU9b@Y(0} zbBDLlD>kZycpn)1sAPp)%o}9-Ox@PNLTThyul{O8ckG7T|-; z2XK!3bOty=QGFjZ=0B5s`KR?OR#*0d%%hc#$y^P{`X*0o62#d)`;em!TU>qZSl;YM z;oPwaoP4M1N#xjKdOB-E@~p@%vgJ}0k`5Xq!v0!j^~-VSZFzvyYVJg%qCtX=t;rYS zMxL;B0h}ZS0eb|WQk6keU2ktmUd|3uz1#wYAJaLhn}?AsGfiUf2Zp+lQQG#t~OZzKV+#9c+@s-X)iN?yGwYA5&>j^%>?JAJs#bs-hTebK27 z>OS*5boJ|W#6@k@7qscdtMta6UH3L}0K))aiRrbJ9~K%an4S}thgXGswzLfU% z<_8;MxwWc)#BOYJ=DE??<8ZRhpw01Y-Bxhyi@(An25)8~Yf*V2dg$AB=(_xQsx?_;(H4oXP(F{y#y%W<`-Y)9(}CL>!CohGy1gPiVEX2Z3F;W-6j{ ztf}Ta7E9G3A-CIebXLy+FNfJk)5`8a%cN=gK`1_;W}ebI_bmO|p{cOZq}iAbrN*ng zh9tQZT0EBOo#y;+PSfU_=LY)sPa^jMlZcodG9->FbHvZ!hXWVjwR`@zo66};C>SW3 zVKQ%?Bwm$$@IoHG?Nk-TENvk^+Zc&MefM#K&9f)#OC^aQhC`VExR`LUjU%5`?6(O@ zZ`7-QonD_=#qh>4p}i7$lEVuNX}i`~3i^F<^I>PZ_xsvM4??0o@NBS#Nbw~0wg=ukW`5~RC1@IUZ)@gT2C( zL9e92BkQ;YKFy4z_B|QYL{+y!MR9LJT;flE!Apy@7Rq)~&jSFHl~}=4Svkj_GruoG z7E0N_*9YUt(Cr-@@BwXcC~sgu20-;N51}|i_9*bE!~#I!IL3i*0Vqni0qjO?tBI&#CvV^5 zqE*Qq*ziWiS&N;%R^l+2PkK@X5uPL${PTc^lW^bOl^FO&**6!pT9NLQQaDmml}JQd zdf-qi+?c?Wx95rw^XOF`j*3db?&Ry|QIQFIdpv=wP55YxWpdV`Pkh#2H8$n9+PyGC zwDcihQ9A>1k?h+*+22KV|8|iwnEYyl-JYwg5yEeqkCj8}!Gpigc01gMQTk$bvP!sE zu$$#&41MhsKt7va)N>>;;H%lD6OtwU5#Zs59b6Owm6FBP^arcM2yqV&k0rYR_rGa% z1HhpO21w;ViA><`>uJ*}{S0}-J=1FS{E~s{DC$66Y|>#t8>K9$L=s#?t1Rs>NLN>v z@`fc3&JWUqbfp0S^{T6}>dY!FF;JT>wY(D&O7Lgh;4P> zB9g*IO$d|f0*XD0%ffx8n>q|@({M1aeiSQipL4O>Q$*jChkGEW0 zVWAU&gv%46QE~$VhZd?tpPSm+*V@-ZqSC(v;j?n?rkE;L^BD|8a2ar0$On(}quX}I zw}0-Ohr^@oYud2v=c}$5xW6(mFt`Gi`B@eN1io`?xfs)HMFeHa=@(BafUupOza zL{gcDvyZj$!c-+^`=e#jF2>U70#jIf)BU=NJ9Xd%Ztpy~pdXP^ zL$rSJl<&qi`@pXGEN^hyp%GUXTep{b8CQ!4>w{hc);Fq$S2_JLA4CsC)(xJ6fQL2U z{SBoMR%`!-Ctwy1H%(m}K*=C%(jb9eH2h)p%{}=g0AUgxK)-o)Xo|~mEQ~6L^)#)j z;O^+=?o+=RK=gU?oPp5IGQsA=W| zFI*!XX77cf<|x27PUDy-l^>!+KjU$kg?c{aK)mDrinc&?$aCl7=8F=&GKnDD&|oZb ze0;n_=5_9bHQG4X>!)mH|A(osj*6-a-yOP#P`X1vKtd3PP5~tZ=|(_6LWb@VDJhYX zE-C5mPH8^6TN;LLxZB^ocip=d=pT%%<2h&V{l3rpL{lXwD!Wa_5V)V(Eh?fw^FN{c z&uf{M)@}}~TW~AtBtwa1GP*|Tb;J89?vTzSr;;x6p)6;{*!WISNnPoGn3n?2{`_QICtEcO3v&3Xmu{5BGsN!I3% zEyuE7!HsJNZ*Vu4SG(VLRFQm$?#B^UIHZl$_cP;ExC*%3w4HO0A^yLh_qF0W-f)$B zN^C7CIINGSTuhp)SLEF?tDBpshz@W>Bn4hTUIUvr&f8~CG;#@*jDcF7fg}u2i%7vI z?5Dd=P%z3IMrcwDo9Dt)+luxYBsha3f}xodn8sDBUmd(q`T6&k@wxoQ!$>HtIxQY`o(L2I*(Y%6Sr;2TW|h6 z&z}N25}|TGO;*JYggbPi%Z#M7e*6*`5|D~J`HODRRFFlok`#FRj<)ko1$m8%Mck4f< zm?95hd%Q1sl0Rl+QSv;e{zaii3zS3v1##K$xqi#B}(6$@b2>ZqY= z0`CHVU;{$Pcnx@2l`CnSFd(=2O~0XGLMGTQdv?hze}aqsKHuszO%JcA8plCPg;e>s z3$6e7v>bHJ`p(~1rc%eD38i}!FWCjWkF~!LVzD~`*>vaLY^LtwpQ5QLq)yhtEZXm_ zOWH>hTD}G@-!UtD@2a75mwzgHEZpDFJ{y&Dc5tSi+pE%WF>N*s){?M7OK`fM3*LiM zN2BX*iPkziTbL|d6?E>OSlT*7E?KtZo0H*Ee1{@_{~W&T&8qLk6GtBNVd$o`2F;A%{TQd>AiD#={?@Q2#iu}m!j+05xC7bGgZ_6%L!AS zl-VjQ12r`=Ad9#K?YAW=^`xQtXwse(O6`SyzT(=}U9lwcw6khxH)6v=jMv&)zy`UW zepACoIeBzyR<}lBxm0Ah-pmATv$jNfS4a#4k|K{97seH|b-k55h4(moKmGV^J5M~~ z_Z~~?oO;obI8hTZAb>jXqD9ZpJCh><$iolH@ z+n$C1z%JB`5?dmXyFn1%^S+K{?B8tMHYgdzR~jgN`gS!hKJ1B<2;R7fY0plm?Jj9?M-ze|4$N@_6~ka1~+KCg?*I(yMxn2v(h~Knv+605+m4kL~z= zUNnczmkb2hnJ$wWtiIdQh!TB491|MBFOI;bN9$k-4+3kjAx{(AqS{!uuPX_&6pN}% z_aYi_J@}$lNI$z6(J3k_@9eVHwmW%s-*_Zjr{YK2Mj1)-dhw{YrLd%9J5Gy2QXJHy z+V_ag5aoB-fE9GsL#gUDKOer@aJQ|hkGMPCPEC;!BaomckT9RE$UTs0(_d6%dqTtJ z(Aj+1p;x*-+D*#%Ly>rSH`9g6e>fjZYdiZzK>T8cxBvyBQ@=ZoX{Jj~&2F z7YeMTbw^b&^dW~ED3)mZkGVGESdef9?KRY0gC2cqt5acbDidnlxzvm~wFmR*CU#qW zVb|W@`sk^M3pGKkNS=w`a!{q?2Xi(*Whrf$gK4o}9Q8iat7YJM73jeF)f;4kOH> z*i-4>Z^USqTj2L-m2^$CLE^*1SNcf}+Z27p({As!2#cl(7aK|UT=pg8*a97zBMaQ9 zJOw^?jeC1bpe&U8lMh*f^jmHC24)Wix{9qe??-C=>A+g`j;sKT<1k7)nH<7yT9196 zs!fM&n8(xLj4OV>osoO|0#%nPOBCfv~7{EO4&tdjc zI+p2aJtwyFWmh|StHqPt%?{6?Et@ZX(onqgD^)AVa6B@!xmmhY!3sV;Qxf=Ka_zvI z>z|j_u^UV)3rm%)Z>Hwb_kJZiER3(5jUNW3>C&06%{Dbd%~8R$K*xwa+VAqOZ9?0t zwe6e>rVVP<@A;jVCiRS<4Y5L(*1CfHl#vib{4(X{9rrYQ@|5|CdqoC>#wgM5H>-HRaHMro|mW!gXog;3u@j%0I|BiDV z@M;k=WV9a4$INkfr_oYzgmI(-h_L5WIeExlHxT4M+it@(zbFQMPSW}>QtEf+TC?OW zK>DHl^JACmF)#A-U(a@cbGqb5?x?ej{a@?3%G41K7m0~(s4uq{fTjb51hl5oPaZ5K zI){s@@w_)HHK7rBcNGQeIU}{y_>?xAp7{bcWmD)*wg?sXa^kwe$Hvd6NJS}JC35rh z6XgzyH_5Y8xbpeg13p&EuR^jRwI@IB>y_jTSRgANBJzgzXqpe3Mr#v!VrY<%&&!c% zz%*>-?9)WHDwACk;cRUS@g$tg8+c`H2jF+8aWLGh({|cgOFu-|$^8AByb8sIK<nIFh z6f~BXE;|kOAg4Q+)flVQ!9gFVQRKfqQzGcJ(*S2dIc;DQJ_P)dcXNo8p|~0MZAf6T^Nn>pw zZ}u?;$}O7}OQ*xoIy>ujw^fVCs9z5q^&&a~$s&4>N9U>$w_e*yIq;>!MKZ8_;0EEG z2H#kwN_)d1GLBe)KiRbe#1kE3RS3#YD}w1;{Vi{*xHD2I8F7&+yn5;eoE}R%+!2!M zyUrpD%Td7?=!mf>Z`?x7Vq~8)Mwsg&8ZdEQl7MVoT$&#J){tQOA^;3Df}v~TEou}+2j4W>X}xPz~^B(AIqLn zt^gKERL@aXo-q+Y_*Ln-zZN3b0Igolq)&(|z3w<~GTuK*>i$K!R z$E)>_!x^MJLpk?xW;44+JlIx>j?d60!PQjlsLQgqM9vovBie;X=!900`x_r(se%sIKrh>zqdA9x2V)Hdr1x$2OK&Ts9;Jc5**5KMho1*hZ(r7 z_r%d!i1RgszpwvVs&y4q<+2yMvZ=Ox3jgcHqdmezJ!i2{KD)FO3CU^!K)OS_fzcjdS!?zU}rfRbq>={LT#Py>v;0DHzJ~A!$w&Cc=S3U7BFzY!v zK^$I!=qYX*ZgBL@LATC`NWewG^Sf>F2f3$I7z*Is&OMm7UjYHU`sK*W*BdP5tD!6e zC~$=LQ9$pyWQn>|Q#5%wqP&;;Y&+X+H;9tE(o3)*IM{v`SZV!Qj_MHH%CH`xDRO^s zZz}tM(la7T`k5_I;PX7X9V7cs9RXbdesCW_4+i4O|K(a_4sc5E+?^6GS7MaQVxbvx zGV=ZySp6YK+r6G(XjSn>gItT9xal-AxNNTjC;D42QWRB|sbGJ!{I8v|O7O_e(!?V0 zJTFb^O7Sm^9I!edOEs=sH&EK1Oev(Wyu5O^Ug$>W2b=q|JPma=zBIJDQQ~@Thm$dj%!L#W|Ca3SFOcRUI1zU-T;@rNG*Q_?@&9Q%v2V z?>!flQ7!bd9ap@_B~?5SGX^hR$)@O6VFqlzTxxP=7x9PC=#?YSbG4AMczD2vS39-O zPCyvULG{e>!zJUwRFDh@y2Ui-+2L}OshuaKpg z9?je2mQKCTMz1AOB zd3tzh>U8gM*VIZ&y5NZK6)}hgWR}FOSKS<~K8S#yI#rkkK!3gls>SZD&Y9~i(=i3E z58GpM_E!}H++LszNlt7JT)yX=qnQ281x~adVWg(VtDQe#dmQ1oc$vDTrb5ZD1ruew ztgyGJVUXUV-p7_z^sf1N`>_Eo(*qRz6-$vwHa|3Qw@1Uc*0v2?+vjIPR}L4o;ajOe zrM6`SPD}2XG%!Ce6qQww96YdWbvEWc3Z%D5cx|&Ink=D->`rq(uU}{UaQs8z33S^5 z0RevrNRShng00gtTET0}L?j8YZZPi?Nt;b-1jB*c&(xKQ+uHR4DycJ+)tKe$n2Rw3V8hMKA4|KTd)*DYp6z(^TNZiLPA<&M!sdLvOApHCKhj=}W7la=%+9_RdgLc75wQ}^ zVqB>7LAZ751HW|$?)9M4ENq(Wc@tjhX{S5jUe?!ddD4- z_(G5Sp*$+H&PPqI-i&BDBg$I7rCE?cejMN*fkSFzTb^Sjb4COMJX@(ZX(aT z9S;(BY!3oAogM&!?X!YJb+s+W^WP%gqdyAlXjs@Dv=;E24xF*ewXp4_auf`%224h9 z95p54PWe3E=0}DbPnQ_50<3mC!QbEu4z3SOA;IJw-!}n8rPY1eAnNIF;6ZZ7v?seB zbc_ht$!fkd!NQ%ke&q!pp}BLKWK(o?g5Y@o@ml6YUzwU*isM#8<$TX=Z*Tc3;zP>z zVGlm2Ekcb6v_#IIq6Y=5>NQiKT#IlDIiOy{$u7P2O@YHK*<2+Csp$FBZ`F0uKjuo|*aAlX{>1d-ZB_i}4-6Nv&YHmv`_|o^l`s(_8 zdIXtBueRg*W_lHvbhQPNu5Ei?uBM3JFxDAzLC?=WY!Pd%STgvZW8j;d_hF`q-P(w_ z54-?&Gzd*LZBQQkD`kR9TPQqlZ+T*rv#rfg!2z&@&e~PHvk)z-vS?2ggEuEC5)Nho zD3(x{DnQ6N%)j*_^SJrM0S5MWYvOkpO`C;AfvsX%4nZeBjEQytB2a!BuUBTWrTp(B zDNWl9`;FJ;riC&Tes>I`!1wVx0qsIVt1mz6HjGTCkz^cbg@$kc z3ar}NymJMI1dS&yJLtcJ|J8-Jw}j#jsCIWZ)2heUaPw31vxDU*e>s}=G4|3fFiR%v zH-ld+KZ+vPQ+bKeUNrA0{nRdl+{;C-4ED#78C9ZhS`p{y;yp+qt&XXl0mZimEZm~? z>=~#OQG{LSe6~`5-UNtCIFB)O9X69LEjC8C9EnZL%@Zy(Q?9n&6l(pkjclxQ=WV*Z z$gHr@iP4`dQm0hOR;=dbdL>b z03l25xf~m=4d{jpMrHxN9dhBnvDDsPa$G{hN+}IQ>Hb|}sYg6N#;431`Frw7TI`ES zt5+x|6=__RF&eaUIqH4BxNOf?{w%8h!(HzFW|k~`=$3x!%mH$w0P$evZ9iqZ@u=A# zU_Hi^D~QqMF9A|yMX8R7LSw=@!E;ZHWaM2o6m{AdS&#Ia*c55B z?Sn-DuXt*R%DhZK5BA;eA>HJ8gYxWED)QKVWn^bfA*Rfpvfw%OmEl~Fewfw#wr-wS zGKM!$(kI)U7LVCTycTyfAYF2!`s^wE{ZHHD;!&2@UU9zd0wxQAgm));tk0G!!AuR_ z`DHVH0=+Kc$F zBXC>P8M|@mMsq`o{_5T*9E!WL={WMbt`J9BS{n9qp#2#)1t#6-6nd-0VeIDQI}!h_ zk|v@+Vs?U1*=THZ`;8>)GI%d^pPHg$6o+eNqYV-i9JFF*EnU-0&4_}sJ-i7-svuT5 zc^6V!Tl){P>0AS-pt6AzAqg-k`q){3OflC?8EE-5ShG~NX>|}%=@$qXjW^Ansz`9- zb1U`YKFh3f11!HkeDshvy>Lr6vYa#;s^vPuOgLGb6>%QeM)cTT;RGEn;w%s1UKl#! znOnWO`Xc!Ygg9VDVFZAZ7IR-j)x1Li9A=6JjHR8|p~K6>St0Ofd!&B_u3Z#E1+JEtecZXYs__%PJx4cOs2 z;i&l__<~`F?+3dkSwJv)VyV7tW;RL-oJ;|DuT)s1cUJ=Y)b|WXz0RxA#oubmb7fU0 z*Zo_y{~;L4wo5iwMVh6IVq%foeVB%I$Fi|=^GFcJt(1V#L0l5?Q(Pz>E}3-I{&B|I zaa-IaQrquf+8)qAJSj+{0Sc2)f21a-^GWS`Yto)!aax6RABsEyo3=z^cJoi9QR|36 z(kyQqo2hz)o64z&s__+8}z`WO&u_fy%R!a&!~6 z?S7$SCL~1QdGZF=_hvl5YaLFFK}IIw(uv+Vo#c-WiE9yala-73fXz33JYm^lZa<^s zFD_<;#1yB%r%a64^or)v&O-H@B?9xy?|;m=`T5N&oFQZqTD;1Aj@T9U_pU&e4b1xQ&0Rpb9eS~j8nyGQf(jSk#S|T` zrIj#?JgnA#dfoJ#URrl9<5@e>5HjTi_?3yP4yASZ(WEyr}aP2fXyZ%}1|A zNdoe+Q8xEV<>v1%8BYdz^GgiEYVL1UZ}u%#^~#JjN9^WMT?a^>LQ=?SWX&CjM8VJr zl+&&wG$<7+TKcXdqHcHn?DlNQufPt7^J_j&dW%aJM5d?-vUQUf=F@DQ>L zeMqo!Hy$BMy@=`>7`IkyTq}qPNTZ~Z5sQ0yH<*FJJIhZk_(hTRD@s6sytY3Lkd+L{ zMP?kHn;d;3M!ed1GF{JZOky3xyD~_m6p*J(PaJBz{Ee9P`kvL*X=P=1a$C%Y3iOmX zF>k(NqltisrAil5&fpkIemZRq6OfxX)A;F$5JU8ADnm(_9A^tzNpFAz>sMq5-&DgB zC`#>OPy%Rr()6Kwq#SKMV`DmqzrxG@p7XYCe}^RK{Qh)@*_#~b7Kz&h+Q_NnIpICvwmce}Q1e;ZAjQYo@ zL++IV6|;%a)YD@%#PFFY*vc3pt@p|eK^InXo(kj`di$UwR! zAgW^xT8~S%$e6EL_!nXopZ0!{7#IB?*Z&%0j=jO> zAl%`+K!bK3l8>%NY*x)1R4s1Rs3JG7Y^Ob;>U3L_ z;Z|H+&BnI}%#m*tiY?cm^LFpoKK#Ey=ltw6U}dZd!Xe6>7-#40U{xWa9?9BeMYDTQ z{Ceo^O7=Qf2$kof9sm2}^svEFH+IzP`AHik->un=GaBd=Lt@{ua_U>YRM{O!F!g;m zvfqwTpMnGtagc}+lx)zKbu&S>yLq_uzdcIlB|}m-;eklFnWN8khecmr6A-f~NInyK zU!+5di%u9S^L@yC=oZ){NZ}E2TL%RFtrx$>QU);I3-I^dBpV4X{(6TlUMddh8Y!6U z3y9ya0+RK5QZS8Fv0-mkG+`Iuf*9Q2yB+sX0#hZGV$Eb+d1O97yE^D*5LsNzXCXrH zhyN-7{SHzy7CVv6@9KT(-0EW&>EC?H%>vSfodY9@p`hRWEU+st$=1VIU*=r#OK-wo}H7 z)SfR}>2i;t=qR{s!blueK1&h9%j0no{#G2+Bs*W3n%c*q4RK4}o4FqN$l>&JB3oa=aUk;dJ9eJRJA#}I!=512rFE zdK>76%z(_`@MB{(w1-bJfbIprEI=G2&kNTpc7MUWg&^!xmxw)yQo^6e9?#aH#3pc5 zVC6NluBHGaG0?(-QcDR7?X&4G#_8Xmg{Uz%pP8w8i2aOvxdO#1MsY~pCTD%&u!L}-X)01X+v$L<> zk`6Jc=4qgymQ;VXG1S-^88%V%8%EE*t~Jb7TF%kaBo3+Jo!`Hl^U8{hL+*DWkgUy1 zZdh3(IPska8JI2*B@AI%Kn!F_m#YR_TR9KM!+!~Wr9RGwV$-jS%ki`&sVTKVKq2B| zWyl>O7*qTt#06q$E$zPZUR|H`aN_BYV^}UQz2Df_u=#Ge+A&Lwgf9ZA)$T%*i|R-i z_yE8tpzUQY+qk@jcg~P;USHIzl8$z+H?V%~tn|;8Lh4SVks;;cC$CwBgJnC_U`}!3 z^FpADuFCv^XlDJWFx>-Nj+Cn>0$)5_qB#;=U{j7}XN4J&@UST9wCFvba?g6*$IH)G zfO|_$DXmxV_1XG*-Q#}c5U-AJ@<~j!#e9X188t?nHg0>*jnBu~mm;(g9nTX8e`~5n z$gK3NBf#B_eW6~+`c+E%KZxP)MBIKKapf1fU%kR!Ohdj4Uh1C-L5GF*H~>_f{yMKW z;Ptss%for;x?1ZM+8O|MpGI{aU9R7G(b)BwtKtSGZ5#sJ#fHIOMVg;zCQ-kU#Pk@3 z4kpv?jEt;-ov?Z@K^mhLDi#d%!FZ4VbVsP+RJ~OCTKK30HiI~lxR88j7Y07wfM=ja z{`c)&yYR)!RX`|`I-u8C)ow!MZv#`R^AJ1|M^u#c?2?fHJMj`s08k4xI2I}~QhTG4 zt2fTwR4(1P=V0nT{USgPZXQx@^7+bnOaCG8nwy~prnb>e6rE$NZ0&Sj5!J#D?P!&E zhIS=7#r%w0V@4b%e;h|XtolBTXwPRvEN=yXzNH=vOwLURmkOT8#&ZUae?J!6{iW;Z z?aSEO|8ZiI0}bu#a|;{M4F9M7#t$lX_QTG>1ic+eC4(oE)Px=g@}u#jN!+=LTv30? zFL{upekvYv3mOJ>EQzsydz!+k7l5x z0nH}wGm(GmuXLIaJ21&9{Y!k64q!wB6+`%oY_H$zQw^*9Z3XizxKNN$8lEgH2ls-mjYP#p|=;^J3%HpD?N_;@r4CCTJ%Z++Ztu}zY52KLuh?{{LMyMd(0Vzj%>&G}0{!oT%u+CEY7o8u}9fre(K0U-os zE5X5sjErT&gM(B)+4Ww1Ojv#JM*{3brd9Y1Eb_od9Lx(kcKH5FO_eQsatHBi*kd3F zrNbTk*gj=t3DAK*8in7Fw%gi)BNBiQv;Tu6{LD$FpnlCsCR3&hp1S#e{;pKLFauO~ z6n_XHGYm}?0SAukSf{-Zw%1_#6YP8G3Q7kH>h$+m$4(Tb9C|@oBrgE5_Nsk;8Cn}H zs#c(0#v0SU(H{ri+WOEW$FO+3_rUakE?UA>4ugmWKlj8P1>12zquqH-jiZAldQl<= z*{(kPJri=q>dLJb>%iSqDXxO`;z%7ogx?$U?d(zQe|;kn(;{u{d$38g~T5|s_SYK3BcAW{@-DmfZoRFtO>bSw3h-}rWoSJl`{%FkHcjDBZ zpn>Pj&IaiPxp!ap8bX}kaL2r%-@}Hi!1Dh(%$!fvn%p^;?wJ*Qh!#1f!Z_XGlbU3c z8v2VRQ%L{jr&60l*byVIaM*hou0UMJ044v5|LJh&>LGtUKwhAAWUM4(Z*x|Zls2#H>UkWm*LHQ zp))U0P!n<_n7y1`Cqt98Xmrj}U@dR<_`=Wo)BT;$i#C(LJgEx1_$7AcuDqT#Q8;h-J@H@j_@s$rIb) zAI-Z2b29wBlDtuI6Pd%n`@^6_%Ru_=#rxoGNtGIueoqy{n0Mk4{WZ4mjt^BQ?t?8y z-mC^*JSpnG^X}=F*r|fXKdEntLZYRES3WP{awSNgeq%2~lt;B2wJvR^dNfBaHoC5_ zfcc;R$PYji8g)BeA~b)9OrS_+`@e6FZ226qXvv3Ny4Vx+9_xwqbXNS(TD{{)_fiBU z;n7j>I*b`bfH2gUK2aurOrpbng*nDt8O9G$^h?yS*bU(=>vlx)8y==F`7rH#%%!FO z!Hh*nJj&mJ97D6XRO`A8YA4X8pvO=P`oyCAz7u9$P$jsv?4B0!JM>wii3j_(#Y8)kE&EaX-oT( z+@J;*F62BZ07#)0#*i_2)Zoj5&P)&`3NRW@0D6Sm%zeE*Y!h#yjoPqGS zX)AN50rd0WD+u;UE_=qehx}@FlmLCreghi~SNs@tc(D@W*z#$qlLAS!%{WR+T`q95 zu&Sr}ubY9n2-4>z6k*QbuLP#Ca;5d?)tU5HEm3z@FzkT@#_c(#U2_AYxBCzYVIs-K z!pD#|S2tZCup#xxi=`hBRwk_y8%jW=-UCsiJgXgK)TUa6maHv}y`+sjS%7gu)Mg}> z>{x{FWuh{_Q?`G`Jo*|>zwIxDNPnSUi-O`Av(v%A%kwJ!#nn!n)>@uHav3lqDblIT zb=*EFH?_{G_ww$-leT|v^v$x@VBDDIR zF-NO$Ok$04S>hiB>anmD8B)dBO0|0ALwXPa(C3G9zpeJhO_I7oP5Qd+tjG?-YV4&h zRBkb-#h&I@fQz-?UuHiPy!-HBUAF459wXWHsOM}aFZ;lqOw71ABsD#hp~DJIbRz?B7A$0 zw|otZmMd&27tZ&18cfg}K<^i?#m4OUI#u_F3K;DHjbQz;JyTw;pCUSOt7C|s$>v+L z%LD0O^V62os_KZ&Wz<+T0DsKawnijyHuU-NBKzNiCRXE}XdoR$;GX+7m^4!YLB*}h zew)Kf1Mwfu1Mss>4qdask~-U9Liag&qS$=stgT(y zvoNwWY&Ylja82g9f;0#!k(+PCe(T1k&6g(T=T=n9Wk_DUcpdCN`B+nv23!X`X@190?iCw@>2Xf@kfzd-%Tw7rWmrH zKilR~g;mAYajVcVRE5sfIc{&Jg@c&|p&eY!U$>WoX?xNp>6>`AB$;pz$vPVit43if!oVV$Q4ZG!SJ<+}l390L#2M-Awe zs8BlUL9r$dyJnF@Nu#NZHJ$@b?m7&3Q5~A$yWo$FD{2fqXkjQ)vsF8@8Qrw_yzA|l z@}2W-DG`5LH=`r)Hfwh|354UB347ht3d!7vKj!l0L1X4#G~(~d&t6txSv?sf+DaFX zeN%khhie<>8mBOFx>7Yy*0jgTal5N!fA#LMDtj4_^)4Q6$Mjoiii`EeKG%*tmOg$n zo@A?9y6PF8Db@={EV?oR9-t=Qw{6}Ly0bn;ZP>jNEHCZbsN+cc{nF)V!-a0u6RfXk z-XvGYQRS`b9oc|`MT@HKJ8j^$IqictrVkxRQYr$>K#ZVZdyaHD_NN_Z6(3<+aashf zR5GIYTVP1GSxrF$J6CUl&wX-RRD1Wq!5A{Bj(tGaR?|z{JF!B?Tx-*QT+UN8*GO7v zYHDdSkAAtWx`9unjXU#4H``}TSIs?ynMiiJtmW0#*67U7#3Qrj$X&3!_+TM_fK(#_ z-H?J@68IC(Hf`N)u)rpkqXNJwgi1HQ_@Q%Ak-4*0f%{-!%YL}UdjsJOgljN`oT{^U|Gp#$?Aywp_WD3G#^D!pxHl`|h+k$scC5>OTx6 zM`u5sti``@vo84RpGaP{wWV6D4nJIKwuFMfLD7(iJ+`OV&OeA7gq~4BvmaL^H(U;7 zJ~=&=^cC;l;RESq?c2xen9i-%^GqdZY0n8FWO;b_gB)8fMfV%8)@Z)4!>RU#k3@>x zZ$4FlQIn)!W`beIOq9>p1kNUcVzY|8@b5%a`qnk~6Z~kBe!Fdueraj#TSVtf+z4Z= zGNXuCWVEO!H?UXyi;m%msf4$yvK(c%9C;2LTmN{`;1p^)Lr=Z8=?6=60y+xv*0!gL z$-LLFp7N4EeJ6+pHz@KtdE@5o4Xd!#3;s$;Ch==b;yF0iwsdgZZ(;BRS_iO{Ufp;z6H_N=t!c%%j-=Fzd>wHdn&8--bbT zhnN{aa9ls_!zvcpTb>{#UBXhpD7I&wrHPQm8^dm!Q4~w}XVBw15kxtdpOkq#^kM3*yTK2;6tWDn9$3}5}ono@L)4cQYg64X} za&W3Mnu{CX7t_89xkpit`y&r(%eS|ty$`}Pz9&NNsZGj;Ecz}oFOTzlzjZxci??+k z-;Jpb`W}aAgL8Lyr}4;}OQn?2e&`kEOLAB>#hhMk*7=ri3uYG(iTeI|hUtAh5TfrZ z`o)GM;_+A<0;wKKwuj%k6x{{;w)FyybA&c-gd5d6umo6h#`}6qW;_q;XFQIY>(&6} zhmV)Mu9)P)Zayd>OZDrw*L=D!sOHO%o|u}}?enI$d%X(~~j-GaUb&LyW2QOsp;0fuUdFTg6sc3v?EuU6N7esq7I zL$=`=3xux4S6mrbMDf%)vNT=0H#O_`R05;+^}JN`@HL5-p)(*P8qamXU#9vSaNDtm zALx4Beq)C?h2%s7O7X>!FYUDyk~L_Uo=Zz#)h<7JOE)2h%{ubI!P$8%(1e7O%>UsY zL}-D`+zyPD%S+RdNNR{*HX~z*Fm%}K>O;zTHf=k8@M`Zm>><*1WqXEfcYOTnAo;V@ zuVjO=zu=@7Sib)}(GW>f31o^ypaF`P`F=7nL&pD3d9DA*8~ZL>g3&EYk_(E@s9DS){3@_x#Tb9v>-q~0LGg6?{oiClNCIMuNi3F7t;9ZH4P-#$UcNbfBb_X3~o$+KN~W+_2^PEe4vX^((^;t(DDZ*!;2W(>UOdDd?-e*R;`l*)y%s{jAb?I3}xu8Qg4uBo%&zQ05+!} zrxbVNzo3qGkKbzm(T|`?=c$lIjM%_yg1sl{z6w>vege*9MZfRt6>Z*sJL1|bLeRKq zM*6&4*2SlHQRz_&Os0DnC1Yls>XuI9g#tuO$vC$3 zxVD*5;=E`brhPi?8=>)!v7DsD0j3mv>33Ma=W7}F8(3S{sY9yfwSlI^#p+~g&(d!3 z+YLx#)^;V0a@{S!1P53b*oI*O3lLXh$b+2t9KGJKP~mtlmruDPnVt}ycxuo7$Ak}A z$vNj>cC^%BfiGqcm=c%g?bfx&9l1(BX{cmGxM9`*mkW^JXoz2G5S9*jX?v}gqU!7R zv1|5T>%c-lgr=9*A_eead*eV_XTHTt%t@=CU_9%|Zx^)X{&TK{I$(@->fvBH%b>8G zJz*?TmZ#RaQ0EqR8}QsKIlWsQ-K;@I7h<1-)9cRO2Be8cn?FeeiOW%-;*aUAQA8`Yu z0w`@#u<*QLAsh^TJJ~LK_$JUw!Cf0K`kOuNZyT2at(g9++@qt3>TChtVoNtuwQCbE z^u9l?;;(|(d-#txcQ?oDZqHJCy!WO%pFc$ef$Y9`-$&Q4^R_9Ko&r8p*sG(IOMcf= zYwhBNE(aYtpyHof930Th_P409X>WJlQ_SGNL8$~*E^Ks>6l_520Qb>RcNH_f$memkURlpr$Ig`x)#mGo%52u_b- z7Z3fVPDJDmf+Bz`wsZw7g=e%{{%ry*G`;)tOF=y=bS9yw*jfgGcYrZ33pN8u*IHHU z#fG%`r|b^)7>{XxE-d)e6JyISu_-esI#uy~KtD7rpZ$bZds_klA{v z@P0qXEXw>3L>RtS)pJb|6JI@aQP(2tEe5X!xpWIvMh{4Q{DS5ocQ)SsuNrZ|_n6MxVg&`9R`}1Aas9!DaP`e%Nj{ zVe{SpxT%~s8x#(>RBmoZ@?pDPND%}Ggo3n)f8-yH53#wgZc_JmkdwX`@%`7 zocEI8nXIhP{R=o@1WY&pZFYVmX2-o^O&Bm2anBNwRQ^}CyEix|CN?>B+yIUpG?+&~ zz`~CKi-5EKpz ze47*VdVV8QT3KDc>o8j^ct{qkN#>gNCL#to8N=`aD!X6054L=S&4uME|H89H^w zmty|Jhcnn65_c&1*#@}!O9MDmSquCj@oLST4Dga|0DJFl<!_~;qyIIX>*)>Ge6dy!6M`@?+kq!Bfz2sHBeQB4yx4OuMoaDTM%sR=I98!JbHlQ z8#oj1E()?_*iKmWP3`69yvJl}{CfYhbn<%&Xt*d|^HRyu*;?dEq592Rw&4ek?w8bq z%LX^^ZwGQ#F^NMtSr*tv7M~HUAG-ysT#7L1lY-;E*o&qlmclq!Ri(iA07J}g-ROoW zX>SS%d30Ypw(uKg(%2v zX6?XQE5=^V;#>Q3A>|^Rw+4ekKDq+$Yh!*48c%`1#F6UMk3&VqLD0>r#m~toz@Ps8 zyHF};iXB9O=&C4SI0pplp|1C9Q=h|r5D3L5A!V-@|EjJrsCC@EJb2XTEytU?&>Hwr z=}fJ#4;SU`Yg?{4E%kWwW~KGEu@wcf;JWOcN`#daOy0Lbu^Mk+ZZ0V42dHG<2ig^w zR{oHY8R(aq`h13ZUyC$-9#W8A5r%#-A(Si(e9QV(3rf|N3gk`y%28(nrrVqEXCh4A zvjoiaEBE8xT#92qfve7Fa}#PVGx+G+B1 zR1s_P_2DM<;UF_A0)RZJ%AJl>G8A}xg&KqPoVgYjc+vCI)4{-UCc6+^FOm~zr38UIRwclPzG&}92%u8595F`Aw_SQq zC_G~#A^DCO2siVg>6YzWp(lE-TRCnISZ4Ui1|&3oW8fT~1A?k0V8owMi1Jehm|=_b zN;bWh6pfasR9JZ~C^cLA=j}zRb;_xNsFi%CCXQkDzZ%ztGuYBKoRoybPZI}E%;Gb2 z%lCS~ZB3e1>P5m{LF%HRwuDi^SF4wyL9KO-9ozKFa``F}U||VU1d{HGsuzG5WR1d1 z4bJQxSU#G+;28%M)HI`&wlWw>zY5#dtH$mGOckI}4kP2lB=}rQSfV~kL-lp~nV@H1 zjtBKMAQV;#EQenJmRP`&P{-TtS*9n>DdtkUR~2TI(srFP82}OVONL|q{^%$Hs9a~gdosuduvpt0CUS1RA5`CFBMCk`2l{bz z3=A+j9JApE%6COgc5lLd+5>^xA)Ylyq@Qgs6}aL1iS32em(OXxo$gD}wW@I@0I$Wt zq-QjnNDcM+!xLAVR3I-iE!?U`+Eq+2(zK%1IZq8(vZVuthAdZfK87Dy@5F$InF{`$ zVw=0AB_=TN$=x9C^*G<16m87lqiZ|=%>){5tCcUOef(_k86(n7zkIpQlPlUzNP7e> zJuAPst1izV*%}<#Hb*_fJ42Sze@9@#U6up$bzZcXdD`>qPDOS*Gt|!n zPJMaLCk%)VKd0uH+WF7cWWijXv2P!_czF{Rxg$^;QZD;RgvMx48#lQ8 zyJFT3%u?Q*!(WPzM(#zl#N;KxUg`3>K&5tU{NlCCFdzTTkZ*bDp|nR7RhIbKyf24#s!d zMdMFS?Ih}+&5U^((Yp#72|Q%j;Ts-&3ej zbhE*t>UP;Urd^F)Qdy@Iewt}oF#o_e0HUOR77t$k$MNLZl(U!yt?20>uiMEV79L(+ z6ks_WpYo$(;m5QkpGx5*x3I8vU$0A}Z3v`9DU#i2+%q~~OE3%Nqj0?b<$fNrnUDtX z1O`s-;Cabnyrhc(#J5GEA9+o6qOp-?&4uf%YJ*;5NsTE_b}5tnHbuUxYe*%JXdy~a zkG(G2`al*-b|HBky-wdg**v|v1>nn~r){mqswqqQ`nJ;d=;%c&7ku&AN0Nj^~P&%J`=x-fyh(Qqr|e&x0BCuqw4L+K`-JnDENI;7My9`Xmh zItQ}SWg^dE1WkZ->xmR*9Nc0yI5XUHCcdr6`WM;$Ih!z)?#GaeS?#U9Ng9Ziljr+} z)+@;#Eg}DMO0PKn&!}sKjtov9jkif3LIo4(5!5Zr33iCKZGz`Cr%J&v9MA>9Y2*!9 z;6QM^_&YU6tyIUn3*Kb8Re#8uFoC5nM`d?UB~BUDi_|OmjL3iabN2hf_EQnH$RNo} zP<*&A2hYdZqc`0&{0#GG0N#XPXbF7Bw6|%jv^YqBJ4=GTXUZN(I}z=T{E(%+|G#MZ z%CIQAF5IC*O3;@sX;5jT5kaI|L0Uj^Kx*hlL6GhS>F!2KO1c?BawLcD=4`%m&L4ho zsmL?WUVE*3-LbQ}wTJ%f<)d$Jm|qXUdZ2HB{X(H87ozEamptaPV&i*!_bt-(1Q2|6v0wJuFMH7Vm;DO-)$NGtq(5UV6)@t=rE{9Tf9;FNr2g>} z+%JyqNS$=IPJBVT9&*7Z8%oUc{ht3Tb!K2=EiM1 zPu-EKSdzYV8yzaSqXkn$vVnWQ0Uk#O{)b~B(nLt_2yKBUxE=QTeAHNy;t_TQ^<|u+ zIL7Bbz;x6A_H+(8P5=7Kf0>xO{G-M5WA7u>IV+z)6htf6ZL@Tj63rdJy+%oe2LWzk zGAfS;9KzUU{~V#~B>=1YHHTSrdso@xVhk*{M-*hA+a|@UC8*H$o{#~iIC%BgNmrIKtEq^Zr0yB&EgEqnFLHR{RK>VWMczjb6Q zR1HGX8HMs>o@9jf?yV%M$I%--FzJ_du$w*^Kr5nCKnTE7;!T z9a41L)gJo(Wteg$YQ+vIEPvO;F*MHfgWHOBu}}WU@_lmLAk@Ia(`KPvfW2-~e11uT zs&q-?SFWThzA?wol8YYi7ufzZzY~y%DSvheA*ju#FM=zt|_I z0j_Al>ss42b#hhQ8sF~HStn^gMXf0CZ9I*UMvoKikg(RiYW-q`jP^YhEf1QZYtJ7; z+{>F00oT*S9n3APFx={Yu7bG8#Rpf>Q}cDKV0>6BETuC1G3Q-*EvsMn&sBjp6hhPO z7)DvUpdkf)Blrpg_W;w(RqqSM@MGy?hwn~4XEKrlp}3BTJz`0U6#fZICT79WxPV|1 zXoqQ3B^X6?(;}MC7G!d8NQ2bKEfkQ3xEHDWHi;$Q; zp!X%i3Lvizmd*+~nZi>g?q_`Yq+#4|{Q2{F9HX`w7F)_eKomImTxTnu(Hs9l7wA=h z0eTo!wA$@$wX+otcv!d1_Etn1?qsC%Dd$&#SsSMMG6A^M zj=|yPRW45=kE?ovIuby3HBD7xdHG0c*^s?y4>50%MUayc$0sY2)~lP`RHkk7=mm+$qnvDouu658z-mkfcyd*$j`zGgzeCH+vQ2b>_Z zj6vwVpzA?qB~p?oQKzMdp>dsGcKbRFs#TX{oy@XmJ*sR^0t-&J%oO;x#IV(sCK*x- zOs}_3-8bmUZEb8ZndNpsPa=BshXLGFGi^R?9q)mt3Q}P?!7P=!J6Ah^{@0H{Mm;N_ zE34lRM7bDD))oI!E3?s6o)u`Kr|RL=G6=>8vQjRH77w@Em-)Ia;T+MT67^P1xN82y z2affBGxLr|s}C>Z{Sl|&8o;TeY~~L@3S=owbJ4C5W$;4H3o*%R-&>YW~6J^m`g<|FOrZHUjgUrAy@tNr;N6(rL=J43l5Hdm5rlj?^>FI-_~_L%Bhi zd&^?X!B2NaY}6Pksm2L3?cmNt%K@mzuuuSz4#n%!*18m7zlOweOFM9?j4dqwn2z$s z#0Q1j?>dS z;Xm%!c8m33Hk7hWQc~KH&L~r5O|0$aM!cK=pVQUg0(FfNMZqMfg;}EMM8E7jczxrf zy=ozW+mzHAagVMW*^yUX-ICCRyPc`E$o zXCw-A@YmRj7Kkz(26R=6_xXi5zH9S>z++cx2D7$NN#;XMuxBp)fG_xu>T&4i3cmbZ z1);kvUUiMEz{KUox#!X=*sbivXyLinlHjM%(0AEt4{_Da&b!-DDE?eSd?t*#*>&6K z6Ot2~;vJ9HhG6TH90&Ph0L zW~yvO-c#@`TgyW&?&JQMrNowujc6zvcpkn5ju8W&=bX>aHQ`{?_MQ9yD43)Vk1j7K15~#(IBLnvih;vVe4Fqh} z+zZh6k2s{gXMf624{cMT08XjkVrEDfI7JV+Nbiq+@kQYBXI1Zr>YW8|!v~vY^K#w! zvC&Y&TDddVd24++MT46%;w0hprq)f(tq!+j`ZC?5xWE4dqi1sQti-GrDv1F==9d03 zi1Dd=orUf#NUg~8iGAd4@HxgLr{U{)b(%P=)#h^j{5v;mb8=Eo-NYU@Ss#S0{=}+T zyXPwbuaB!?v?HD>h@E+$H0b?Ah6w+dErWzEq-A8hG98a%c&9kaNRuhssH)g)KQXS~ z^_a2DDP4Bk4l2}3HSiFupg7Zk7yV&}keehx0o-8gTuj8fjH-evf1kG3zT)LIG5v9F zSw9bEAsNsr0U3&O`+-wrr$2r!9!8+kl8*UaG4h1dO3oMZm!tpy1+fJ?Jci(S? z%G8W~dhPMT&CFg_4^xI=hSP|J=#)C6PJfcHxCg}`>?Tg0DPT%YTs_=XHEHi)g{+}$ zzM4|b3#%We`dgzjSOq+c$0HjL<1u?2$iTKa@CKy19xLb_B0Fo?2EU%qNhRPDUKcI&?D`AbEGm;eQnq_)*v8n}x>(8W z5IaGrKU*q?c+4=#buS%BuT*{h1oz}lG=Q4{vTfw)oAq&Abgj8rlb0_7y&U5Xvr@mBbPWQ2MNzMh5GGvIHT@ z86R(CAQzbVPS4dlSmx=g(!}e&?Q_s~Hs5={r0qBz>>{$}f137Q(s?VxIc!koyXiPGhTQA% z%p$4QuZ8pVUNw2hyF4E&vr7@|TL*%i9-ZJ#fVyjpBuKJQTh|t|Qzl!MUWD(OEqs~d ziypcWb&=e1Wv54JH+@M0-0$f%@)NJVqPWE)R`;^O_-?fgET};KJ01Z6h1&)N)6Zdj z`M<+T*9s1DF(iT!!P2N;hCdJ;8Kea0bR z``7X9eG8BlNg{(QN-R1^cl=arPItSc>d(u)(E zq6;uajkDh-JC)GnEWCqXZy!6^@-O2)$25iBbegBo#ax)hN{Nuafmbh15R|FMJB3-N zTnP7uTYo&g7;(IP6V(cQLoR-_T|5#6txnIVzSG#-iZr)a^R;Sxz>Ds{a z7?}IC81x27+e%_}3AuJm7$6CM@YVoYDo<2%;dF1|P)%W3Lp36P z{ajh%*6C(w=>{LN9ItB&3{pBkF1ufXp*MMchPUwIdF%N~&4e-|2m4WB#n2Lk?v*nUT^_!&3YD6L!}%X>{C z#LQBYcjxO7ERAY!YVDgtnxw)B{ccfSoxX7q7UHo zn?X8=I{al^-6T*Us3y@h+pi}s9=|@meB#3^F6SNi5M#(tHJtqLKh!2TN~sSFEs? zr+64Qum245knh-4GT@hT0u6;fUHjj^sX{xFNUfvQYQOGMODAH%eBt=XmcLDMm*Z}^ zqFT8N3;&-BaKw+nAsl6q_SPQ`Wt90E|%JBPN$vJzahex6EdWfE6F%%!?NfNc@UA>W`P64|116a5c zSQl2B^g^<+btf-xL;)^VTB5JBEPu4$-k2@EzA%h*RJ80EbGcSb= z<@^7`#Q?uI9>Aj^MpgF2!C(8*|LIk54*uDoKwPa%TMZ4aigFdlFqTFK%Lk4fRtH;^ ziP-9zLxP1fGIGQ7@G3E%Tf3^WsE(-CTX6+0tvEJJr6b6Hbc4m8YN4j$G$YbwJGlxT z)L((Af05p@H`%!At`QWFp~2Eikh%FqAGtjXtdq{)oGBGO2s5H-DJ>3qc@Z@?pNClD>J2iM-J! zeF@dO@E>>KGTF=~d>{Y;IG}>1%y*e=knER-Ck>i3;WU9Gg*Us{mpzf>EShS$w0g|o@AOfl8%kZf3tY8W!0lrzSb`e>GOJ<>*-+(A1Hz63l-8}fg(@}}Iq@XBap;`OjV}?Edc|K9CRGJ${k?Am&OXJoy=KEx~`%B2c2sidn zrYpz@b|@ElHp{s%W`b~}Y-1Ow*$A}O3Rv#?DtyOSe3~f~j>a9sjHNovI@0wTbVvgU zobP}J10)3C$RLN&_NpL8>oYL@?0T?$NgiVUP^yCgk@3+8*XHRw_fiC+9V@H;5?*SO zDcZASL-~5vz|l&*eysXRU*cA0Bg;YsFZ4yJ-QqN+(&H{?)#0b4YX7kgxD$3ycp6sT zsdv?vid$6XQMP(t7GSlqB$;`~`PL-SiTd?n?2L5%e-+Zp}eYR71 z+N?=|Rf;#3mVp}+WZByAnu5lCliu^epED4j@}X(FIRy4vo=d$?wexzxhxneSK%o-=w*3>zBKS);>#v3^BOrDQF!(31 zd2(5FV*yS5`o_lL!oK&pX2;jd6Zla_hfu|)Nc=oMAGjy;714k zfavj}`MzCM=9P+NMISX`6fy&%70%X+EEE;~RLQ{TkY$dA) zC0FH|mT${$tM@kwXH$eOUu-q4YCG7*UQ~e7zBAcZ3CDy4sIVfAa<)$2K^pmBBsie%d(5Br9hg}WJM{&9a?G@xh1&WGL_DeN53@y zmko5dOS&XQ_v;fMFss&X^%MetLO87i2#tfY?Y^)HLpFgL*n_iXONp;c!eT#2j-Ho# z?VVpk9IP?S1T$=2*qc@BR({D$8isq2SloVdw8QoH4wiGZ=wA%}J*ul27 z%Jgsmc?G0H$+C3gKIa6w^{~5gI5LpWJdamSsQcyunqyJD#5%^NM&C29wY)3-?5zTIlpuoaAW7cXDl>6p z#mh#*&t&A94W-0c-bSeRb!FOyn~bwg>3`sXgo9*llE14u5#7e%UdStX6hK@jj^nSq zDg`1O5hXeF^D4COZeOfggqLFO3WZZiiN_%Dob2$?)K1;0tE;Pf%yQKWX%yRE(*^i7 zA)^^fh&P~=+>cLrdZVrq%L{ExBxbbmpBJTRxEU?QX6A%i&;>gfmc#8gN9i@$pFZS% zE;PZ!V805B``3f%k7Vx@-kMT6;TQSjq93a>zJh(lw1f&( zR>s#2oK-)`e$1ero}}8t>u51Su6X12P@rF73(r3`H#4h%&hh{XBXFeL-@jDkqv+OM zJo*p({OqfBzc1g_qV=h|>B+D_IT5%r7@y@rw?^Q#pCqz z8&b19AQZdmZgx^aY55o^4^ihXj_DrZ_*9tbcfKM(Hk3(UF&6V>3SxDl%n;0|!Phhx z`hJ1OoRYlGupYwRz(@~5Ac7%Cvf1`1-4BUl*(QCJh}*52gDgo$eYj~4QNf(ve-eQ_9-+zaCK~K#}wC;$IITg8{t)*8$HIA=_6bsG9Xe0v}Zki zd5#5L0mRkv$?W!})&WUj3VxLS`ezzw5c#Gejh_gaS@@+^{tvoz-{g$^>deO;bxHwG zJTc*w!VTMYQC#%CW|T1f&0ODTp4_EearXrvZgdh}hzXO=s$STe>^FTOHfO)IZ~EJe zha9{pQeBaHlRB%=AH;@E#FOMUd=y}qC2G|Z8DwQReDkJs7HVv3O8^X(1ifz>=*1J? zHi8!{G&Gb9RTlP4&d`?p{qF#B>B(H&zm#Et_Uf#Uw(aZ{+4hU>-6EVlDxEp&^LRTW zjud8%?Y>)o>-t{G37vi4i12hx4+0dv7|EeDEJsI2)+e|#@8)Z*wps`DcT^r`vAPzT1@_@cv5jN-FHWwD_E)kcD+Xq6*HXaLV64n_w84Pe%yB*Q%~d7b^Ss7ALY zn=y^g=q+)KNj?fgd@-(nyXji|z-OuG>((!=51b=FGy{+W$@i>bz)*Pz_Brkzhc>0dE6qd{8plkJbi;QXT6d0ry1+eK>zGFO*cy8v?fbVBZ9m{ovgIDPnoC>6nUw zX2QyIU#7?vFxa0cu+qR`1!U6j=2gDa*)5+Lam-#Ncy@p8c0n#zOn95|=d<_M`S-;+I zJLd;Z90->B;x?dbcRHn&B6|X4v!?^zg(Us=2_egDC}tdcxlaTtWLHP+*uQ7mv&b?L zWp?i-jlU%=*+Z%L~yoYg6H_!9*h8d@Mx`IMEJNKLc?&^&@<9q5z^8*%?9 zz&J>HCAyIOHQV3PV-LqUsbvxDe!XY3qJJ?;2nAsg(sbS3UO(h$Q$3^s`idpH(g^20RuJCf8mW2D_l9OtsF##W4^6IZd{fOD^OT z`!U(i6z%#m3B^y$CRn1Q-f98a2W5NbCZFlh);}8`sMLJKHnm`TOU*I%TK{ddjP>3z4Y+M_B79g>M4k_@JFMS z8Ks3H7=?qyEErB&fe#O$F(KjQLHjQK6Lw)1mXBATi;>A6CWkjGk=e801sgA>d=-Ha zZg9l((SbMu?dKFciCTbK-S7M&LseLw0^Vm%3&|COYUI&L*&ic9CK@4nOc&mkuGw1 z`>)ytTNxsP8LM*SM%0JzyOL;krs%0=t@+-Ctf&-S^GD>j;#9^f(apCu zl<{|K&tYz}Z)48CEPgrRZE?+?S+KiuZ>3SAFR)jC%IKR80n(qXu~{esJbHR}itg3* za+56~>DB*+cNZ|0zFKf1ff#{sW)EObnb3N|1c1bch71K#y}1iax}%x$>4t`e=!t{r zqGZYJ9vVQ$VIeHAK5Dq$Yqq}wmeXKPE-wrNqne=Sg&pDH03a16l{|iW1$<)g@bFG* zQfl|(o3PCinm|3Q1JX_v&sCC{s?P((bunKj)!~3_-+J(kbNP|s1u8JwsRSXDe?5pUs5ZYQerXKD0k>+(T5olQes)_QN z@Dt?3>=lvhfe%wK4h1$u_D{4d82HQ{3Cwrn38&ks1SP9UnRQpFD4-bE$)!=Ea$#&S zzT1h0P-&ReRd6zT2{He|VpxG{WRJZDu~DXck_5fUm`RX8x_KZVv_ryB8IpnlX6*z!sQ@@aZDXL%xRf_ zUaKRTSXYlFRt~1^s>1X+7|VYERXOS;L85MG>dfYbenPpOqN?1kmZ7of4t1LDB(cUTSsx9^>{@#~-%=;onl( zpQR5v5KQb%#b9(;17(_!o#y38o3CbJW1+d_#S@d}+?UJpPnwn&m`M+TB)|lEELr5~81W zX@#iq&lIoG^BHBKM^M|Tqkb3G*sV4@RwHDud?VIjZlyapTv(Q+ckl%hQ9Bqm_oYl? z`^{8k(X01o(D6v*S7!xoA^Y#q;qJ4hPp*Gg)?{onr7gg&fpz8taG!bea}*InRP7)R z3|jz#HmJS*b7ZoVQB7!C?@R34aQoh@ex^~b#xg75>l(;ZwII&NX)%KPIO=B^ZRtp)539BPq6T850N6DnRtmTOxEbO6J}l z%J^x{(FNPSKo4M*=`duE=k%hmvj^7ceX#iVu5Vv8D3Z)ZAVm=L;16p*0LH|0$Okb4 zgb*^hyqr1vtSFZ(aiOO~W%_W+Jj(RL?}U#X^3sqW9nT=ZBEwx<&fSCBVL0y3d%EF4 zX#7Y8lAhyI#W!7+aZvCB`%}bsHn+W|w9@rSp2pskQ+(^&^Ac@nN0%dF7<#7QruFbc0m6cy5cv_~T%9HX%)v9MM>m z>qp~iM&sl9?aXZiTt&f7Xt}BEW7{Nc2)^hD?^S5h4(NJIiorNq0%nU)p_a6Wrh`7Gj|LuddZ zfpa*=^u#h3!`#cLO~_vftRkkQCVgU-pvCu^}6=6#PbRU2#rGGA%v zpVHZ@fQ_2-2g2lBDys~ibR=ou$=Yl0Wi(n}WYa@cySNa1*vqH@$L{hinlC=r^MFZY z4`$gUza@atfd#fsXjoW>J=Ft=fsoL|$?3`K{F68089qY+=YE8q5a7Zq0(^MD9RM^7 zKO8|=%)=rC1>$oNJ3?;9@HQ|!myl0IxkfIdNg-<=eYG4UY{|DqKX8-HNY zxIzqXx3!dR4a1N3Zx{E0{}u>DMF4a_8w}Rs_m>ZaHx(4XHaya>s@)3ImacdT0)Ns{ z&fe!l!XKRVx$j1|jKYK|#QY`p1T(WXZehjsX1T1Ym3`bsW31y_Sp;J*l;zc{!uX!! z+F`p28q|sBM48qk^P}LPPbQ5%CqiY6E@JG5kmY}E?*K|KEB*=bUVC=}3=KLNp4WYC zraYEa_pwm819sEfh+XyQswo{&`@{@$YSU=%aKs7KlWfPXx=3HGAcX)-ki#C+M<%6A z9O0-)o||e>qr+pEq=?aC%36WxCoswAjUcj<+%V`m_T9W4u=vy3J8cY%cf;EV>lpNR}s0D->}!Eq2H!23G~K&saRocj>=^ZU2I zy?9_yP}Gna{$&i90xLWCA??1VFyn^X$V@H5Y6g34faS;J&k_NnfNj2OUlQSgSR1ps zVgjf@3IN&HeP0neK(SbqL+)o%Myw5!BwwU4 zN#d{aGNC%DKCXFs^&@qkwz;`cdw{=*>B=YZ52t-`vb7L7o&6ONU2s*e)Vi5?B=*AI zSS0xD%6vU@Pr5>mgUQti?}BE&d&F+Hu(dXrt*+0xA`V*7Cxj1G6G#I0xoa$F=*M5O zq)BLiv`spQoV27SG0w!xc)s!LLh48U5AQdCk%6clgiq|y8?mK?PvA(eIS5rRBpnS! zV>m^UL(FIk_t}CNMcnMHTMYK;zd0#t{^y@rjm8JEuJm3q5C@a_>+EtO@v0{=0=fpV z!@G?!&lzLns^@(fo8#Fk0}>#3bt~p_7m6w>l+Dz*-v-GJe?4tg{+r!JP)WKWOhs^x zJ{r5c{5d9?ieZ~EoOZu7C!%FBxH@)O&Hr0fiLhIt5y{&7jd1r5yo)mibNo!uCj+dl z@4a&B-t?JGp+I?UwD~CbbF%6rVI=!ja>fdHeQG3xr!11 zeJnWnV2m^QG9rk;(=gP%WrV|&1b`vU$O=l~&Z`aO(`@Ft0`4oJrbKcj1yXWy2`X=K`?=Q=+H54!&g*uwu4;arh!kB1M_j&=C>GF! zPpErG+h|$LlNsgi8ehIYl@n|eEl3qmmiq!RVSrNsRv@y6Bxqt-xu%i&JiuZv<8Hf+EZ!1{vX}OYu_W| z(g$?ZV&~0Z>#OW4!}{bmu%dX`_>UM&o}TN#YlcPQQtn~XZf944b-+Z7|lgrwlc1g7=$4Udn>vc%O98}VhzvqCoeME{*p zqdH=U>y)e4M~rhtZ_-Zrz1Hk=v# ztuQ=xMAC>UBq(U9b!l9GI!c<9qEjGOtL~ko0XthcU*?_M@0c6o$yCf4=V7_;$8;D> z893OkKEgVTwbc1B!N5`GgfsV z@$~Z>H0~QUuS`Vonx@mP2Iq`vBEAuh-KAc5%5XKRA;ur{`5S_?Q$Ihy^c|;^(0}Jp zo(vl`ueZG{AkD0;t<8KOJO1s8AS+6NdmsXkM=Q)nXm%D`=2I_Hhs?&7mLgVG9{AHK z%MfbG;RIqFr`CqjSn@z8Ghm~Q(suKF0Cn{7d#-Xioj$&8;$bleNsWo`&|*|Ou|Aac zS}JYW<`TE7P$G$c2r9dD?m?isauI_K@O?AeIMM0X7;?mQQC^6@G19Ao#rhL?kK;~r z|HUS}Sh6~vBv4yC@t8a;3MwE3r0_yEkX(5spO%=5sn7*`eWkbGJp|IlEduRdHRPJv%ng7 zKs=}or!h0+vSN7p8lR1g{m(z(^IYbv{7%G%n^`H?PVk0 zN38xIN$}elZ89ls2T5W)VzNkWkKV@vxdZRwUQW|yr*#fF9a z6H{MW_N!AjQtvM_j#D>oE{}B#45p3jB5(KCqEj^a5pa(okHZpxE{UDGTohmZ^eALz`vX-`QvgDJ^Ion7->f5` zVw793edX*rCa^>=X((!eAt(L8w22bc?O;&F&__AB*|TZT|B>kTRmOZIZi0y+@?-)2 z%fzmC%T{+(H?(xVp~L7G^xMcsdE%cU%?o8ZrPE-`X&9w-m4Z31t`{HuaWD!i@=_H4 z`Jq92WnEn!=w4nAnenbqRLf4db-o12$(CkjGD(Ay?X$b=h)rpMvmc7Cb_`Tl)}sMR zG@9#%4dlZ{AOc=TM`!$jgZ&^9^imlZ81P%57pioDemi%NB#PgBPAK|jP?9d6jE4MZ zIVh(5CgXH~fLcQ2tB~lqJW7cK0uJ2BE&$dCjpx_O( z(8(Mht0PSt%UPLOFtJNJR3->3{uBCTI$yfiH@|=6Ee2mo43*_Q%zl#a5EP|lKJyQ+ z?7FmjrX=k2wcyxwdVCO2g$mnIbqog+KO*13b+t){ee=S>9}~yrkU${ zC~5R`SeK#Ui4I`BGx6{ckyX8Vl$rk_-aLZn_FPeKlz_z~J!Df>PVt_a>t9lt zvZ$Mp|Ass5LSaRoS1{{^m7{Z!+30XB+^fb5 zN}elCM6ZkJMaMb0j}K;sV}v1;BoFgB%75FL(bPzEX658_N>ucBj~mT61ctGYG{nAc z=jPljrjcSd2c7Q!qTa2Re069nxxBoj^ZZyoyVLQX0;Gz>YEzdp%{N;vGFO$gOE7ZF zKjxbT!bEYogV)5;r%72mNI4H>l)g|K{^!}1KlkU*RMl=dDf7(ig0)AZL7S!}_70x- zM|Z}Rf^`Z5YjK10sWW^GQ}78O9VnWzGUYnj%YXLYjiXESO;YP{Dw*RuA^fkYg7$W@ ziCBS=uyn+5a?GXP%k1>rm^sa>j^n?LuxKVGq#lc##8wbe>|S(=p-?aP5&xHkjAdys3R<^RSvB7h6ZP7&)jC|fI zmY9ZFLd|k5ldWcYY~qN+^~J`faB1Hf276yzTs*h51fMF_>V-mFzcwD?Y4zHgu1m!p zv;a`sl|^`}PrQOq`bkr?+w$cJp=ecgbv7W7e7>_F)yBt*?4vTP2S2g2q~z;j=AeSO zPsJ@9hKA_T$w*Ef$A9%VGb}7jkSx`n4iS3&=PwNq81`&pIqBExgtg`-nY701VMbXJ z(g~68Sx;sl1Y%*!*0Da+DpIQX9kfu)5$EV2pD}7rLUkS{^N454p68Fwo*o6lx;%wj z4;}db+-YDW>gVU(E*~8_lx#PpHToQMVAWPtISdWs^oIWmQkS|Lw5lxvHNEapfYBqH za~_eJ1iB622Q6aA`UG|08KUI#0e%x}$`JUNEZy8ba&U0iTTn7(vB$}qq69e3?K%@> zmi++5^+aqalLim-6N?)`0zxwZ<+}-#^y;Z%071J-BtgJNIzHZFFUz5#NpIn%x;V@C zfDu_G3umUt%-=#R7hFan{bpQCr5~*Eu*O_i6gM_D_{GFZYiny~y1|~z3!fl!VaBaK z#Znc)TE#QP={bBp?z2#S~v`&1L`K$HFlBYxS< zd*-=cVhuFG@lj~;xnH9kj!Q3-#Neq(Ol!vFpt<+ocQ=~)ZO0;Q$88H=5y%VSR&Ue< z5e(%_`JkjHzNmXH=96K597ZnT^m&*d;H14NX0->M!FQtL+%knSjPDVo{a=!vvQ=fb zNXE#!LabD1t4gWZYY}C_xy`$7;u<3wW&9i*FvVLp~CF_=5*m zS6A1b73CPi$UpI!`Zgr|#k%EL-IvGzD#ZTKr|K;Aygi9~@zFP(PXV6xs4f@n?`C$) z-#=syz0+T?^wZN;{cugcdArMS9wBoXQbWI{o`kBtZX)q&HA}tNaI=&-v~!KLi8D(V za$7xGyOouDoQliR-H2sQafFf;}H-2C^0+Q zUHn^LH=BgOSbnd?F4<#`kC3%FE!wxUR=0Z@m=m^yNnzpm4lD3lT<$F{8caSPHYKPx zd}H>{p^;3t{+-}g^jADdij$wdf{REV-1{HO;gk$0o(iqy{Du;i;J$%UG{Mte^l&h_ zFUaH|Q^c3QUfu8-w2J-B_@->H`+Hxxp&2b9npJtHq1B!kXFT-WeQBJ3cun9XQ%xkH zED5bf0*hg%GF2nZ3bny-?>@|H?Uu=I#ZRs$^fihDD!D=mc>kdrERpRfD(KR>r617a ze?7rMyuD`o*sfzvO$T-zDoCEzgT2EcvgIe!G&m5~GDvR^NuHK}6n_nWLiyDW^eb-Ahi+cfq(< z(uI#$unGdUd47}a?d@SE$>@qsz~w%&1d3^6l-WJ&g=6#V_~F3u2g%Pb=DzB!coV+P zM`C!sOVPOLytwvAb3HvBy8f85tgwSa?zSUn9QrHm)?4B`H9Vtc>@*3f16K>L)&6lZ z0vk5s8XX^xE;DE;0{%yp`psp?DEtG$4(y%ZMqGeqPuaP?Y**n&vN4!u(gD;ebkEYL zn59UeLrdppXElwDg;P^g?YFt=a=;1Uapv>?ejK*i)>AfprKsPr^YabVmfEM&jWueo zx7S@cn}9t>40wf-nsTC$UjcEfNc*p-)LwTJn$e-~HHSvMNvENWW3>#*>tQkyqovu| zvHt!LpeO=-FVjOf5(c`Kt^PO;_zWAobX;=O*4x_vFynPTejGbGI@0!_)@{aX@N!CB zwx0E(Fia37Z9HlBCCRu8P+Wn#y#_4gHoK$Ux3u znkJ9viW|roFuHQX%@h5OXnHn8rx@_Aby5BIBh@tGH_ELdk!H#OJfvXsX|#kk`U5(Y3&eb_yzR3OLMKU|5|YTM?0vDF5~iBTdweXF6CU zA^qo|@Uo%A%~xk|vgy1W8&m7*>pNF|E?6FX<40NU`3czjhXzz=S9m`=we#GcI>f`i zzm%;W*0a67^+tDy%(bmAc5W6E(E4Ku;^v^t|dFr$^&h+BN3riOlEznbf zmojPrfyBzn*Lw+og}0H994P&%c`S^LpP@!VSELCWVm3cEm-z8QD8L$~ao~ z_n^(T_Nbxuc~AQ8?plS@!hzHm)i6g{BtuFVBwNVg`a1$Q{5q;SxXX}hPa4*9Z1)TL zBGY!nuVdTk5cAe%B^Qwa-U)6K#Xs$9Z)h9S#O+tVmNoA+3BGpp@i7EFiX`ic=g+?m zWw%oJ> z&TRGE;^Oo-5D1o8JSol{zm=G4-NhXd@eT2G?gg7abg>q9M z6|G31OY~%)PzB>I#Kpbt<ZuRux=dc=RN+Gs`h;X8$1Nw6e5hGfle&?Z4C2$(A-{^NsJVjyFDiN8L( zun?pI|Eyd<$7_)PDu4K#ld~7awR45*->esZkC(CW8}N_;Ez<-Uw=aCT*~ajHh1VN~ zzwbQSXI#lu5MWG9`X^jxMBC>6;UtM@E1`maDPh8O9Ahb6m1mMNfCnN8b6joP$gZo8 zG$(&NNBZBu?^dT0_uZmb$-h!-=Y>h{wdtffRY)o2dM-1|MLeR1JU61~7mmEFvFAz& zh$SZ@wjf5~NjHI<<0*5k#&S9>47meRYw-4f;taaoR&HW~&u#CMwac67Lm@OG{8%Xi z-A(&=GJ=0$UcVUM4*6ht9}=4L{G9wbdGvl5YE47HjVH`qJJNfUqjPo4C@o%tBL7@@ zIOw>gTVV^}~1-fP4oywVhUtJJ+ypIoL?T<}es zFu!c%uj7x0aYvu8X45MS@H*k;1dS17qH^U{bvyPjwHhvhZRhMxW*Os=c43qLKnpdG zT|f86nBN&L@8gCp{Nd2G%Jsa#>!=7a_SMM>XF&=|uBxgkaOQtaO41Tb{tFH$F)=ZY z1;v5UVKW$kAufhjNL2K$Xp7GjC?bF#qbh*o-WVH?fCUh|7-?^v8lz|6DbhMA$-2vjb7K}`B~ zrI!Vgd*1o_8rB%`A5axF%C~?EiP7r#IyyD=3Otgh-+!RWCjKrj|H!MmI%C^lC$Db3 zzy8J1ZLDQXX)B7uCI;VFSXtaIw`FJ;KDTy;aWD7Vb7wowlP$cJLyk%gx!f1qB^zl& z553QCJ?eecP$ml;Rk+qDf_VQ$j@+NmEha_wpsW4rf(lw%vO|; zCJqk#)7a7I%Mtss!|T*1(=I9KP*mxSJ`A+xW;=Q=@VmjNU^_jz`U#T!1&|&wMNN}&T;7km* zp8W}a!5kf#P!{s$H^M+NX8E7HteJ>JyG-5ck7Qse(MVp|n@uaYS6}I<|1p2I<6Z=_ zSX3?L;@oLQ|9$dr9DV4`dNIx!8yg!5|Eua$FzVC(V{x_w7|-d|Qr4_I*m#*e7{1+a zIrD^Kcy33!lM&_r?pFaeLa>Nj%%r>j*{q=ptsBNuzOBIT^3;fMl912@Wy{yW2ja?j z?@R|rmOqpdq^+(?op%juyj~@BH?a3ZAAKP%@wK~q^9HCdtwD58;5V+l$N5=wx#1SU zCQtuIzn#VSmzGmeCWg+&YgN1U6dvh+PNleIJR{fnYM+&sS%p_!;U#z-Nv<;){{ck^ zsu!0kb_$ogw><%z;cIDyZJ0b_n)r}zG;51edk5ii1ng8bHm zCmV&7K7F(>o?}tSZWc3gW413+ ziPN=e3XXR(w6lT8oTA*duSaatt0pfii+gF`6UdRGjJNIV?Ug>&0U^#86&*pi!q!Tm zL+}Vc*thF`QMF!vtExCu|B2GKE;z6P2FYl-0&$?>2{rQHUw8e(stqqgCtw=_U z794X63MdSQ!^X)Q1n8l*);Ca&tVq1=%-gw;@eW;iwoH6z?Y7BBL6=k4wvj(VmriXX z;R?oBgo-%6?r$AYa9V-olqJ3(%SfS=W&HFqf8_dWpu52f^77wm{7kdK_s`l~Ux+1t zdgBRwv}hi(ACJW?pc4OBVc*%h{gge+QXT+q;LtR+KL(`BE|Dp10V; zoppcx1$SkT2?siaHz}8Nq@z78iqockx({Z;Tp4)3DGnbOqVtmJf{w%tCf@lFX^b?Q*{^vEr{ZzUqUL$=o z_nB>87b{j7Aw|E^a7V4FocvJCq>JRgblHwbMTaMqI|j?mq$y^F0LB)ztb@jxIyf%- zR%5y||M5v8mMMq{F|z(fzjf5Ty}i9ab@@G$z$Qry9o`;+Y@>9Jya?Dn(PyO3l%|xV zY^pG@fArj$h6=Q(+f)Qw2~+BIJ&E(IVs`(5rxjnWQ;Mw(5g?uv>0|Q8_fr+0Q;l3* z3@2=2K(t-hw--ay_=UZU&$~JU z`DIqku)V0kEeemrgA!iH%=9cflmiS0L z?D^tfb-4il#MjH6j%5=!j;&7UB-d0qSHy<#B^-bag{}M7uEcyM3a8lw!N>{&zFt8S zmclj=-Iu96Q<9SULGcE1y6ZBmrR6C|d!K&cw`m%&D%5?M(cfnx5azYUhaLEqk2{Jw zsrbtVe3ALSUU4W=>|$1$N&qsSw5@IHs23u{=_!ptlcvq4V<}NM3OfgIx`LbPB*0rBf82FzT&jVqk&QB&nXL7*1LG0t%YtA0>4C_ws@H zgkXmswXD+{YAlWlFb3_rMp?eY)ae>q94(E?nBZxm2Z9}AD76rXxv+wa<`Ed;2*eMs8Y9Y*O*e1b+YSy6pmJ(q_k_Eyn704) z`!|dF-T#&*iTBXU5R_NI+dzI;f!=diy0nw@^$0^QgRyt5-=OGxaJJ-pZK}aN?V{!T zPewi+C`rm5QC!9yylKcJ?%41&6YW{;?UA_dNWziduNmCVk)6y9ap|v zoWH1i7mh^Y#D9MNlxkY#0tyCNLYr=0j{sM-0sN$T%D7^xnx$r*BByx! z1e#{%2CuTyTK#tPLOah`06G%&zbruT0U=rNMTJilMiIh6jUYB79DMY;jg@i^adX#J z;9*g-#|}B{nMVS6s;nYS4Yo6hNRd!%D@%E=lb&ghTya*zBUra~&6DIy_hZ=t`RT{7 z=xT?&{S_v?D+IBG-e%HA%F>C6iShCA4}Z8piaYeKgyZKdQfAxLhv?faabnUBJ#F>? zw)XvZJ~NULCBwJ`ZQtVlRid5q*3nT5woBrcZlvPVweeX3^G$vV>i|asIl5 ze}9NE1vqiOHkQO)D@Wt6dMjhnKD{1sG3xbMBkQYR!b!q?E9LC67F2s8!onFE_x`6q zHaF)anXwgPlD{`z0rKq6pYH-EB+!I-3pyI$99mnH$2;_@(M@AHVEm*6o>DI`#D0Aq zl}v2jcXk4Z*XmHti#ZYa+*0$cLrd-!vFA`OY(!|Z+WJVzo8N4o9515vMr3&$mrInG zJ@%pGAIzj#ZcLv-Pw#nuDFNLU+d3nC{f~^D$U4hEkTK!UYEKWnq~BdsUV%S1$L3YD z1X?7U<-kK(S4_xBp;eIEP`jcFw;vNSy6Q6YR)k|c0%vP$y86zQajV)Ai zLL@~0VpaC+tEdP)8Ao)&ng#jueew4{AJN<_Jiim2{_`>%UU=ecx<-5nKm;tQto%i}A62G<|?g01*QV@?0V*scWgYww6UMfG`K@ zv5$ZRAo5H+@W&25zvZis-+*GHn*vRxuG?RElp#6P%Sq{5^aP6d6*6vcDdZT6A2uZs z*zTe299!Ez18NzNd$&g)zA;87=zx^Rt2F@qu7q)d7hekzt)L_Dx|jiHEkGZEX~c9b zne`H*14~OwTf=y;TT9L<(#wG>wbVBQG?pWA*|R|vv;W#@>|BM!Kby`>FCk&aLVQ~( zUO&h;EzXnTlA_NdSe@6BH2D0Z3*Zo=s5=aeNo>i^B2V`!G%*(Lwby6NrklC9(YNQ<6$&t3&oij_4jOUoDjCLOwqj7W z)UJ-M_;5K|_J^Q?=WtFSls(~Ns0GqkrORq8cs@UOAUQZgseiKj_1$g1Gn*Vs1HBm+ z^h!>QOQa;j-OX(XeB>1s43`JH^M-ucsg7tgu2~|@v-Kmj4-cF27j|h>0H!*4!=iUe zzOg}Zn+mU~Vt?Rnu4~vF&|`ev8C>p++r(EIfgK#?q7YDrQ63Q$pBVAE7r4gH4mCDD zS@}D+lOAbOV-#iktaEx}V*>;{(V`&m%9>*80Cp9m*fi&=y>Nf;Z(C~V?x_|sPxjXN zhslZ;@v(J&;=7BblS_@5@%S*rdHu}5)vi<-HcvUxn}X}xpx%tNWg>O$)^kbx)zX`o z*3l?OTCz1h93ltP2Coj zP3_niYg!2cg~j>|ITHzTx37d#C8Hz@cpaje$Xg6N1uy<<7C7!DIQ0BC!UF6!lqobK7DoXO6)L z{QW1ywGi)21*X(aBKTil;sobdg?b7D6PnfMue~~82Uq}S#3!)pCYZ5MgwcI$sb@g` zy5sZXo`92n&P$QUkF!A?9%y5nygKgtKxzY7VD;7e36WC+JkyW2Xd|;=0uDo6I{DUb z^H6n5%Vf9jf;Cpas3K9;HJ*Ou^nG<=zp`Atm8{#}!6s-ccLHzLaF*U|YUypRqLt7~3ggWxrR$BB=g zk($h%`>7BtQ3{N*V63{w%vwz;;Nd`>1lnf!W|FPz^wiXCf@@g~fEW1uLt_(DQ=b$Z z@Z7-DD8%I}1*UO0&O0!2Fdh8BN&Zh(v=WJK*|fMm3j*BxZ2~@R!-`oNq-@mBHGLzU7jLmmhI#qmo+tF~&rUlIs!5hh7V-C^`^2g$ydzqa}ML^R3`>q7!sNaV< zBeRct0zJznZYQ}yg2mArVAaR?)YM-vpOfoLe(=W7@Y9`#@usVXULf_@^%u%#o_wJk zB{m!FdGEICdV9GXLJ|{s9gOVDnp7RryXe2S=`pp_Eo!R$kW6&P1$jo33zK3_n%MWJ zZpJ<#cEszLHDx)e9Ahf~*JRE)5FVjQwF|Z_H&RObQ+lCxm|aG3swNmh z9km5N`y)LORbg`5i5*9@dm*fH&zPzG*}b@M(apUruZ{Zyk#1)Qk~)78#v586Q(~8v z0}am_B5%Q7lNc3}OC?X?IN~~*b?o_PnpMEQ;0K(Z_A59*oQPXM|`$aiKLQi zz1$ux#zUU0!W#IBgq$l3HW>FFX-x+*A7LQfSkR0q*^04Vq{J+S->^USL4X2`D5I-3 zjwRw&aNdGxSqMrp#$LsDMsD{u$pWam@Jr$D z%IEmvtwE6wkrVi6I|1un6?MH*o z)?vx!wyG*}MA@fpQ)t`WECrWU8G@@cx-iZAza%3B{m8ItbAt0@4rg5K?K}hKa?^Hp zgUf>A{uPt;I;K}-#CY#Ow~?G(zQLO~NU|jL#vJmOLzFvON?MvZ#v#A#hRT0BzvSO; zZf(7@u;4!Hai;%sEsy_+?CRi6ebzkE0K;+%(|%9bv;xg;z$ryhuPSGtD}R9NFo)!e z7ZRjr)xk|Eix6bu4J1_Wsfj7~6+V1PNN6J~qV~D;^WS(bl=jeFMVoMY;<@-7eZZ1v zE0k<*wBJpojRp_3>(eTA+n&-VT@wM%tlLlOVu%d1I^B_Wuf`NReIF;pGZ zS%E;OWeI$eet{lTjRi$Fyw5CEmkz`+`7n=5f!h6-ig{Mno^G0Islu`mbbHUdq4gC~ za=q8`9{AD9tF!eI5M+LSiGu<83PB!v-^D4gGzRk?9Ur8aMmH?Oz=-UKcHL+OnpRjW zBV`;Yi@&C%L}*iNx=Gf4jN}1XER&fC<8?3R(rCE`G;`eqf*mA`SWI^PPnpQ+ZKg+H z!DM@(KAFwc>)v6?e!5Jy9d1tDq(5A6z;i7^FvFMVQ8cTYkAQs+XZ;NZun0_AiT1hh z-*pS2Z45#gR4=7d8UAbw?8^hTFaitE*SU_+hagGJ1Njjf*Vx{~yOQGKVjB5wAmdzL z7f?XJcf}lH)@aKp5Cf+vnRLhB^bM3N`P4_s;~wVWF8(3DOH?djT{*f4Ee+c5MwW?e z;Yl(q`nwx$lzuLSTZhY7K-(EZ;DK+01Ay-X6+N4CMALg+_0+q!7*uKLHuusAj&2z$ z>%bRbHWi=`RYBJ}9L_(()8y@8DU(K#q&8CQ-$vTlU_v?3BaPSj)x3-h)y!Ed(FGjADgz923izTB5E$ z5D?iVgbyc(hPV+Y}T73 z%O;T9o2F1UD()70=H;77E)!kQitYF=W@G|CFYl`U%-NS-jAZuI)Kt5KwCh?t;EaF{ z&w4`pq-bK3Sbmde_UPz{UWvUUta?L4DE5Aae4ndyvNkZ| z;^yuSK4}r!m-`h&*|$R#0Nw|B8l$3%l5BgY)gWWOvnU}HB-?pr>YMH#Eqo^=QJ+7i z#cNMa<=tanM9PY5nhbZq>C_=nWxXSbO|0t%>BAL^2ZNX>jGsj}-p9OrL;p7Rp-T!JlWROf; z!y82tPW<}UUwXpQ5Azy?^))WUzB>`J^%C1$XXLBRIJ~>=L~kEE%liY|Ccti0pd63# zfXp~W3G(595br+o7Z$w9>@ihJ<*f|@xs>kjo2jIWnMsneKA`8y{xNlGL6I}^-X00c z^@$+2fWaU3wPm_GUFWL@gcaE@A zQ>w^ldoyord<)Qr;GrLypEpB}A~ZFh>H|By;;Jgp_Mi#PkJf8AIURmgs_7IPeuv3#y(Mb^eijtBn%RdbJKvp)lTOiT;k1!O-$IbF;sh6G5 ziVOC~S7k%i$BxGsDj9dggPn@F+wg`J5{i`PevL~rODTniCUoT4lG=aYxpsd$)Nr3( z-?W_e!R*_v;m>F8OOL--FwA)wb zqu|0{l9YD2VHNc^UK1DKxl^$xy6%R>@%BvbA8syssu5&i-K}~^b^VRTTjQmc)d(}X zYpl4%J=dMW5t@!9+efp(>oia|ED?8xOb@N)F%{$sRkNe^2e-$ zYf^zg!I?OFXhFJBWCRR=DyQso9}CdXvzNHD5V_3{;-=Oqh5tn_7%jKss0nC%LwsdA zEy)3}R8F@yjNUOJ7;l4mQ^uU)Du|9J#Zm#FQ$XI}(Kv6hYIvd#q1{VK4LryLxJKP~;5?&>9)VEGJd7OfJ?aa}x^W zaannY-?HTpt&B1C1EMczBDl;o-tfgq&h&#^jiGtEyIUjPB{40H!Z={IIIfb%jfklz z^}hP6Uw^;b!$XH-iRvkYy0?jf>UV1;391(w@CstE+2>yEiTU`gV-$p(KcC>$y?oFz z=N@kkT>2aXcx7&4QH@i$-#Wi?Kq5Z4N+hE&b6&yGjnBFPii-pg<6~*YmU}E;Bx!*4G@753%r&-m zCNm1s)}hAyTh1pwr@dsuSqmgMybHC7`SpPgLs`6N>?EBdrg_x6s86eO+La*T{PnXC z*{kgJ!~^O7!Os}H#qaNvNXATOq&(Ro?DJ?Xc<5Rm@bE1eq!~@f<)2`6rg{@M!CA2N zs9Z}0zm{4PF1f`8mPCeS9(&b{7AY*IQ5%k#t>^^>$VV`m49IdmArD;9i%eynXTS$_ zM&|>(;(IU{p-RCLwGd6)-wu`lDj1byLo3BXxOupvRmy$!z_}wvPdGya|Mm?7`D*de zbl)Tm%SXu+NeV2{qG_+O4^UNo9a0AkTGKyp9L?XV4gh-C%`?{A%lP>vbeZXF4goA2=cq)OSqdvcv15i(wGp$=$7 zxZcR^tpZ2>{qT!Fe!i2;B8 zPvYP`=-tj&nM=MYP$NA(((hlqTH&6nw5p437E^@Q$Q7^6C(Gl^glkz&KbaP`Y`iTk z?-kLnvg+HPPPQ3Kpu)yCOZf~dX}EyIgV4$J;^o#dd_PF0%4*}jru!n-_-tVtm7E;g zbk+S5R;AF6<1vk2yS<$ui?yrUE=6f`B=;!o&@ji{AV>`8M^$dhWy?RW(m?rtC2ddiNE?Yb7p^<%Fou>v#Qsn9mJeoqSFICk1OM&YJ;f z8PM%#El9Lm>o*@bsh+R0`X?vCrBrSkhEN1d!bv+u|ESvolKt9L+jVPF{5CNf-gmIr z5hvlitT9SIOk0{Z<+JKBz&Z{W7taCF2~rQfg+!xhuqBQfiq3c~b=qt(bO;}ftiQV- zv-a$GN!QzGJg`EsEkY^dzC*~Sl_n)60TY^H=Y>JqwRy?K{y2{{^w+uZaMOVKBKQD6GLmLW=%Er75Ve zz@wmM7!xlSeuqMa+GG}NQT?)VhhlbzC5`&HDF$X775RA*hZCmwQjz*3-`V)TvP^}E zg|ku8H?~FV-fgP(*qWYcqXSPhZCT8E+dW^|;|lC$`%De++C50Z`YgBEHU3Yc(KaGV zr$*gEBKRff=MWs;-rNUosCUMPfH|A=h`CVPtP8aA6}z>MO$AyS<|1W7tuPlbu1b*t zBm0)g<_gXmQP73}N3#Bh9LHO`fLeT8;Uaf%BL8jxUOofV3tssHDhS4#KG}tdX^a|N z@Vl}J^Q?z(jm|RZxm?dA2niE}2reB9*v~xnBu8Qx493}nA4C;O8y)#)F)1hY>3Z*f zgj8}N319FOvloM@sjFG#l=boRB5c$w;T~>L-l(|%pTsS3C0q;4RQ226{^Sw`L z-+ORd!4f${r+8E;9mv)q+i2+`k)QI(1X2*C>IuwSn1M7pS-k0+_y@9i&nutlsEt$T z$v;fABTAKW;b3)8>)0L+Raz!q(0opqjh~$kGVW5AUc91_RhRe0C0?W4gX2yR+Rv$>$Sf6>vjHrBkLhA zk~*uqvbrb};%<{yGq7S^IJ)|9ych*oZyzt*Vx@R<)6UM;HsZ$XJ{wT$JxJ&R!%pV< z@7TXGn4c8^`fPu8>{Ikgtqfb-$jC?=^!_kl0Fg+ZT+ zCvjdykt6w}e#Lnn7y^F^$9r%*XydT~|0$zO(yr^LY7>enH(|Hprt{VHf$%pJHzi_3 zp)ADt%*pKDk(iT&2t`z3+}G5eHZLm~sFkPOK9`cUnh%#e_f zQT*WAoj-~NnqamL#73%mIS12ch3-UCdUSx7v#o?U?pTAY#PxK~!uQ(7pKJ#F9H2V@ zfq{|neFN~Hzy<(KMGqoRi)8egjDBz=OLueS{e9<%X9)DNjsEpR4r@*f#c+{T$38kz zo}y3(te2ucQhd$!I8yTMV|vUTeWG_ckSSX+g;Kpglr2Pl9VV9KeS`;}w4ZnP0PGVa z#Xy8>b-NARVFAhtu;90VI8;|xA33>kF|$dIOW)YuwgGBFYm@s90Ia_BnR9 znja#_-Qi&!A}rg_{@?NG>62`Wj}<+E=xe(X*hxcp5`s|iWgZc(C4BJLN;w8-R8Zsc zsOEix*SnI~9e+ay_7^^Fu9=ze0IaNc<;XLx!Q*S=ZvV{fYqxFL@DbK)D#X>t(Aks9 z*Ifux{aNHk#9&yO}eeZ5Kb~^vIV_u2R`GisO#& zRtyvNi@F6RtfvEie6=}?8p8KF6`x>snI+{ORt!biBZ-#+*FoGBwNUt97GO`|J4L7h znA5y5_e?Ih&~k!j_KV%y0Q2R3jGTKwB!S=72}j1zDua_MwbGAV`l9W>0d zl_Ra6xb>r5c)YYOnBE*1(1v3unOP2aXg?M{jo#2?ExQ&NhNhCXjw#6b=LHJAYFNfZ zRtVMdw<4GjT6N|wZv(4|#(_xZnBG{qX23csdE#>d~Rs3$xQvNEvN z$pW1pNJO}mZK2N5F$Kl3dbkvfGn!E4wNQLTs9hKo*@lC+gKz~z80gp>%0sj7qx)H1 zUKP9c`k`068HgcT055+lGEm`+Yh4tN>rkA%#r)AW1rR6zzF{OIj>#zoIu4wv_wk~P z9oK!}83Qz2&gap2u!E<+bzb}#tA5|DNeH#YNqvAHiZ;McC#x_=;>WI?R*3JJk$P+C ze~71I_PQC{Zmbj?U}R_!a-31Q|6aq9lK;N|h5nP>{w)N5gj0ui%LRXa@F`x3~6gj5VE~uq>omI-PoemW|RZ zS#?W85z&t%2p(7~jq@ z=g91md7d>L`&?$0rud2XcUD~rFOm+VDG0D*>Xm0diwFSgemGD_<9;F>Kc#TQOf??z}yl8=p#SKgDm(Tg}thp54kk?wo{)5o-IaWIo%_kNZt z#URs)^6;=E&`nZU>q|Jedl7gc5m*Jv>xZxNBDiJB`5cq4H5+n(@fnt**n^<6R(Eu& zW%%j1jzOse2I@>+xQIH>fDvNQ1O{}|`Z#(LTrAMlz(C>$A@kY7cO?&0!30l?%k#Fc zca&=RCL#0gBd@yE*IqkT_#OxIvp#I&Z)dcdt+EI%Okt{Qt{Z| zojKwE4d^g z!#v`Ra8RR%=g2Yr8M8$WnpS6LXLE8)zbly+ajW%ydBnA8?!#uY@-Urrw)s-(WA0FV z@uJAH5z1)>B?T76iKM96*y^Exs&+nR&$7CGT%q*B*^qaeJ_5vh|w4Jo>=1UEUp~M zR|s2)@_A|aI8q+3po6%{vmJmcFi~eMvu2D%7!mZ(b*B(r>QMzv-`d=~@hvEqU?)-8 zy4v==)m=~8NUJ>$m(L{!urxg(*sMwG&UratkB12Tq`B^uO04n+t+8lnG{s>eaBlv?8l(* z0DzVvU(600rQE%m2~n_|ARF9Gk+P9+32NV1EUxJ^B+Mmw-ew?N^GdUW0{h5GJl$dI zr(;F0GbGjTqy|BdeY|Vnex^Mz+VOe>Kbk0S#?TEDjiz^j#8_o91W2`Q@=Br#oKrzpxR^}Pi*$I-XrI!Wo4BMv*gdM*Ee z?9LHy9t7F=4&=+ud^NNfr&aGVuF4-SjB1fxN~|s^?Hn?pdj5xCSN^)?;1EV6^0I~ z-qbDvBf)ldyaZ{0J$!j>`RDwE)v)B+yMWc_xh(K+zn11epJg!n**f4lKu;K8r(s75 zdx0_HkN~gZyr?PuT|APj=YY2Yvk!}S!(SJ~7wM#%M}Kg$MW5Hy)YQM+I?lZM2!ogN zzmHl{70PuaSnFmDWIMpanp{$ZHtmQ5kh!?9kgAHZ!RiD*cN1ikf!3|w;8k7F567Pu z7yG|^rw01bu{4n4T{0JfET|M-gESW_?K$N(fYu+N?L+=`oZ_+6 zn;U{nN219+Y+r0jzJhcrzQ^)a{>Ur7gf=(C4_*B3F5wpg6Py1{NF%4ymWr0Ks;Xl& zQRQGQ*dkVmHOo!1<(B=3U*iACGoEuECL&y)0w1_@2)5=Sr@kpNn0ISU2HcJiInGkd z$sFxW?P4Bk*?%jPrn_^xy3hM(+Gby(gOamTv4L+!e_aJGPj9C%fe3gBx~JhyjZyWxeu^L5y&n2YVS*B? zbb~G{m;|sXQtKGb4pzSxM+%8@+~YNcYeR{iB#}_O`K*>TiU?)-UfeuB{`Je3FW-se zL5)SIUrv|(ITv-%2bh72OxKgX3Trtcy~Bu~G$wzR86LyFCo&0LIZCj3>L$aVt#kqw z2UX6dP+iL|FR}qCNq8|9^1KsCZe#Z6_e94{@(*1|p?4yTfI@nsug}y4{X*V3l-?C> zS}L6fVxc~&oE{6}>tfW1gJLOr$SU=^o&=W%WF6dSGUhl+1#O4>;KZ&GnBgVYUAZ_ zjNS65NBqb%+{V_{e}KMnauQk|@1R+X;vJ68gJ&y$I@D4WJEQ;3${akcMo2|eK}Smq z;)I#Ekl2JEjSaC6TC{iA490;e7XV+@E(gx_A;gN^x#f~XO$NKeIg&890 zFK-G08l9;@wDmRg9~8zYld%mAkn|siz>8LZkT4l=D98A~#W=`YfD8 zFpPR@Db;}Qv5q_RBGAXH{%@DU3FDII0ky^g@?L3@+n_AP2X9ofdXk4+6f4a6WJ)%U zX1`^eohtq118dOco+JLYB+msKNDg<-e3ggV1T}+buX?z z=SB8B3JVkyFb_+dMAB=f0R-)9?uayV%=R4^@CA=HRairrW3@PxWrNmduLI_Kb#YqX z5BhErzGua>w6tcpFXuN8Iw<@sK2=QPFhmLs*VlWU=?UWxoc(8Q(qhMNe%r4ZA^zS; z8h18b7z`UJN3?8t_XRcIz4!v&JW}baNB~m$J%59f{p~5m_=#YZHi4f zb@9p;;=t|=o$G0j{j`5RpbkB2^BM*=F^Bz8elLNT;04xmklk<-*x)gr{SHPnt#i~p)Zz@0^-0uW=!zkN9L%3C+ z@>B5eVp2sV^yxuIkiL;oBu+a`hY?oJjGABBk=%4Pxh@4a)TtzfavppMphAeK*g@;z8M5?b+Y8o5T@QI)hj=^!h8@E7_Jd~9Z`jmVo%CMI zp$_D}|4Hv&R--N)vgAzcTb>^zZq(cB*+ zym&~E)JeoX1%}EheNLT_O9^V+Jy`5IP?*46 z^L5nmuCo%*b|aYoD&~Ff6X82#2Zk3)XMOQpA)jg`^1Up?sw-T-{q?)|!r8VtiVhM< z0rv7rKMM_jXRtNehog(?QsKwlq*u8Qu_#%fAaXr@FDOBGc|&Wl2(T9OY}dx>k<>@z z+Wx?X=4v?*4^{vqQ+V_!fs0sZet}XurLr=J7dfEY0ov$4eypo6(+dIX2HB#n$=dSE z^iM3PUA)BnSI7xf9%P6Zd<+xYYcDCB)WrL9RWha85few8EWNUZ#hq`&1{O;_=)!Ds zY$Le#4Hx^nZpBzHFUCgM@g-Efcj;JiVt1B#jUe{!^R}{r1r={3nreD%dXJX_VtI9S zl>}v42NG`u%ay7L5wI>|g_L7p&E{*~Si_*5m3_KIAkKXqE{{~Cf6QpCd zt)oF*V^8O+Ec?Di`^Kx!MeAbU;DGH|BS6;g!&(CWshbh`@sohq>O%DUXbiA4~e|%Rn9kV8*+Z7T`KS+Wn6DMFs=(Nm|vE{VWdw z8axStuv{M4E;dz~Y3a%Rq(Wf-Q6A}6!Rzv9wvzi0zZ`3U_H@x$J4&2ke#VwI>OZ{- zZ*h#8@HiH~sAWAmlYM&T2UN3b_%!vn8V7hhZ2EPSq>$PPu&>^2O}Kb@Y_!Y zlBulNsy<)B;UrGxwee}^YrwCM0rciy-x8IW+z%#i$RgZ^oQpYZPh75E9Z!Yv+z-s< z@&4VaHwn(cDjq@X4l671azr>ZtMC%xg0ZcLLboQOhNlPgPJMqU@L>LD@%)Za&fOj{$86g}N#`YlzEJFcS2uxhOv&j(#LS`N9ErQ3qu0Y!% zf5L(G0&gp@G%M;gn9;&M=B8qEzZLQXUKd?HW&iqm16N}LuNzP+8OcMhgWLP2CNg`M ziK{DlO+6LMWy-zgZ~<1%AUzgclyVenYt!M+brj6QF#8Evp=G}nfO3Sg`bdjEVknA3 zZKc<`w6KwKp$X3QS`*;pePo&->>|;NiKA;zfIvNEkl$qU2UoA9h}BNvpP?$WdC;7GxI~0MA5L3G zxX&iO0Df%5750aP%kHq;YC9RXt$^JPkzZCPAY2qd z`k^pSHAHMzL3o^ouoCM!% zer!q}2zlnNKTjnY5&_S*!M5{V5RO&HW=yA6*7n%^6y-}`VGlHw*C!6vh}L}wGSUH<#{YehS0!~G!9 zOFv`aMPc6HN51%lMz2wd+Hgez1#A`oxpr;mV{9Dd=qf$Gr&2YbaR%zTt7w0J0eY~8 zAxAq$arG-W@l}ZcK3K2>q$1n5uqu!PUyr{u%$huI1;#KSOKfZf`Bo@#(1_2m?XSNB zz`*O(Zyi@K+H!*@mG~X=gm|QT((cTl>(|&KzK40Tz8d{^t(mlAPwqcjEI(3a_xtxO z2DmZ^?^l8aK7MNyhX8H!T2(jx56tpjIXqrEIb-L0{Dj^KN}_76gm+^Lk?Eq6l7-+T ze$2g;Qh+XZZ2ZD#Ds?NHL}5Fie_h>k`EKu5f9!2@r92o=bp<{J#cQiP2Ogc}}o^0!G?6ZBPXw~B32loAMq9e$XM`KB&8I^7|La^K1# z+?YSqEWB|oblVt1uDg&WZwhOm%Dh0+J|(pcO_&DhiDMY+K4J!JPP(IKY+cZeOFLXd zNUgV%>XxamR+{tvI7*f|8&{pdrJYI~%`o3O5gx>OPDCqTVWmvm2Tkrey`O>!M~luM z)uU0lFahGlv=P5$jsRj))XNFOkzI13(4@!Mm&@nT=k4%d{Dk~AL^k!d)7bah2MKlJ zr}NG@#hY#<6^jl=`Qxg(XKl0=!{|!{*l2{5M9eZAX<_jc7^nvy9Up@<0qvq->>W$89*f%r!eQ&$OK-RGeBWip zB(8KwN9*}OJsG!A{p_p{dF+z&SyXR*t7>Q|ID3?%<4eW0){8V|ppZUt0@}%iss}y> z1_@P>u2n5x!MPg{;je%}^2^VG2I-``qR9laP5$rSPt)qHtD_3l(2GcHC4bvCz-s`1 z2?AKV3yksdpAT!z_MUu&#Lf*mY&sDu#Gdu8z$6$ICYTsm0JRMCUH5qmz6;l=r?a!L zOP2Zlux-%!*KNBLGuGc~gFZcyxN24^?=H{(|Csvfs3_a+>lr|X96(fRC{aR`j-f#i z1eCInE(uXWx`*ykQt1#dKm_SVLb{|ohmawL8tS{|dDm~PZ>{H#XDwxfoBO)XIeYK3 z_kw4FTmE>fpBrKxC)g&Ya(>!sB=;;20~QQt4~pH^ndXj_>Ax7C{xTl^S2@RGqVpbH z9(+FF+86@s5k{a%**GZitKT>P`-t)Q1lt*pwRBJHpo*xVVD^i;#p|BEwnn+aR()t- z?(^T59Mz1i(`FtA0bc#!vv|E~<^{F@Y|s?plg2NX*bYy9W`M6cZYNak8^BNStH6!8 zuZ>@Tfr)tC0wt*4Al6VeA2yP)Y>{r0^(?LKM{ErnUmh5bVX@^#z=how0CB+49V|s88J$j!ZGiOK7eHKJ zJ9lp910ruJgU>-BJdZO$a&t1>k?a!2Z27QiZ3VHM?- znt=NtcS2havd_aMF2K`y@mN!H^M&uq3oOiU2j^% z3zYT)F1~Po{GKtKS)XWps4)if@u2JAU&%!6kXBNB< z8K*w3kR_j{jk~;q``qS9yD|xh%jTocBHlqQm_+_cj-0R8sM%$KF!V)!Fp&Nb#sd$^ zD?J*tPh;RqBaxTzfkJkUoa-D(rso|858oVSxsFVL$W&mvfmo>ZeKUB&6l9*k9WY9Kh`zX0R_|YcV2plc(^jLbS7X2Txu+cv=m0m16eOtH6r`T&Hq^t z?qixE%QyBumO6)$FhJ2r>OC)q@^~*Uv3Q@!wHU6qCI-+6h-4Tagmr%_tGiirg4W_2 zKnWrBaoHNjo|o=1R<~DXT|>g zVqD6~$_n>p)3MY^ixY67YVR`6dJ<=k+n(6cNZa+Dv(uPh+K8;s`<~(_R4A3M(Zf(d z#5EPJR#CL{lpXVpYa>ONwW0V=Qr=l-d%N;D^_*Zp#zDo27rh%*2+qx&A7lAFU+J!G z*yZV&B-H7eO;7!7vB*Gs?GPq!*-33aucnz>(@g$FYUbeK`-?l6vu=I>{_3|8sdci);!P==2kxc z+UBK^AzcJi7@;hl55aKK=MLfj;c93}Pdlbs{Au6-&2ACuXek}1!f(51^`NS!_OVk- z@|MGy+-oW+kIqJPGT6Crtx#j^+!bB7CHLT3ss!MjudnacfQT_wCqqAXa`$!NU%mgQ z1puR|!m(tr+qu8S!J$AwXBusT?BTS^jAb9$&PC4fOFtvtbi>yPYwG{ZWHa&CARu~f z@i>>BLRqvNdN50BtF;)Dc^Mv?ZsAg%B4*b&5i_!P1Xj%xIirBoCf4nv`>H2){lCH^ zHFu&hUXLoPBIXW&PvISVRkB#RcXP4@zMCE>90iV|^asFM4pFx&T?N%jU9A=j3dvv(^>J=o;knEb0Eiyng#ji zcvuXV>~}(U4*o)D#_9AL075oEm=U0?hh&bXY2V_%r~qH|hVbB~&)E{|7`{CCfF#S2 z$Ko@2_^dedU*9hd?Ju7Lz!(SM0y_O&ykWoezxNDyDB+-mu0ac5SY0m9k2Xb1JfiW% zJUC1CWcdRyAFCAs&jS3&U*<5IAU0|Abneo(9?*0xHQnJbs(~?e;pJ(g!J1`M{f5(`Vz!B=Elsl{+&% z-{TC?4L{BaeV zOkm_`kMx3Gqt_PiLFt#Is{2h$)&pqvcQTV6*Jjm-pbnhhXVXO;kOMpt2~~keF)V+Qs3RNl2X6e)03LdSHStcD*Jq{hQ1d@$c^#0y8P3)1$cG;a9iLy1KeVQ^KkNyEI)!JeY6s zG$7nMa4en6JlSPa%o)(GaG^Bt-T_yJ+`K2XGw`8gE3-8=(I27n9G!}*Fs60gFxDUB zHC^5BOr)fT`vQ~EA{G;W9Fkv=m^F^AeXvqQxpRK%F6%C&J^4nOtQ}yv?z!*sdo8M< zgjCaV$CVoElD_Dkv9@cMd|TE0)oTE->z$aq`zgXx`rC8wARb4~BWred+TP(lOhThn zGeR?s&Lmv{i-%o-;pc&;&s}uK3CzTJ&a}1f`fBQ7Qum7B-4I`}qxdm1a|{3p^Mdq* znW2IJ`i_^m!$Xh-lu$zoI;{ByV9mD02x#Rt+nMa~9pkNa{QtaY#QkOS^+_M#Vm(T* zaAV#~hJ8<4Zj0IFYe$`?+BXDVu%~n>I5n(_gH_fyVy!p!CQ+`RLli|iecdHfE zJCr4Q%PL<-8;I;`;iFEURt|xA_-i{mK8Ks;ks9y5DVlVXYG8@-Et}@iNx&I%yuLXF zcyu5QDBojS`8n+q2x`HdZ=>xU~14aOxfPc?H&px{oA|5p(3?$I_ zsRR(B;6Kkl>P9&#EFMby9)Hxa!TjC|_QQbnh_q9;IGhD3pLk<1XQ1Q;+7lo% zQoy)(NC9KE+p3KxpBjt6;X6NVysXW*JX=!<@&+Dk_&;Bqh^s-e0-(!rW69R|bh1E3 z(}M8V)Z6;4SNy}>Mu$HIZ+G9XJ3pKPK-VqR#smGvd~kj6gE`LpmlwOdPRn_W)b;>= zuD}mmVAjM>ASL*b3~)7pE@!z2ckxFqQ#O+56C~Acwv#6RqIXF?J~j%oeze zq`S8JqNU=Cqa5$(pjKbzzW@Xe)POPUTT%y?zv%6jUepfXD%J zM78l(f_ew{SVKr^eO3P15WWB7_Tb7XX8C@28|hxu!?}$>r+JOrZRaw!v0@)?L%8vt zQNJWS z2(G@IU4K#zX(0pnh<;p4Kq_yAbxMExVmqD0FH<<{((p6 z6ctx~N`Gz_yz0WKWpqsPtvshrOORDHAqFXW`$v_5RZY6)K__rvAG)6LW8NZ-wxXEu z*lVLMJ9I`&{kDTkg0j2MJM)Js6_#8!~EM8D64qT{2-<&(RJJ2s*w$7%) z{um{?T~5iU_hX%p9`$>Q&l?4G-&FF~g(@jjXWhKX69|1O@;QO5F3XI}=hxLI@j|6{ zKA9N&&*p34gI^e?*{wLAMl; z{@j<*w{ElTA~5n~5IDX|^V6HEiXv;RMguUjVFZ?}LtMB%U2oR53PR7&eUb(%9|pM^ zMcd7;1uOKq(mf6-M35q8Yh#1#G*i}8&V=RCX>R-g4~>QM`8{$EAfA9$UMiF6&v@~R0t=?@|mOOOcdUJqD7fWFs zoqkJ#W0mrmF%6O-D%n3BNHjae6jfMVLwmJSilgxuP4!yFSNtk8FiowQ4l)3$;Ay%X z{C&YCTQauU%v9xf>HBuFoTqdYeC#g!QN7;x4g9FH4JNbSUZw_M1_Aw~ zU+Uj9o7(1i>;}bjw0lCDu0R!at`QB53&L($jZisG1(#)=4KYnI4|=FZPrX0)bgmm6fSbOZ~i(fK&C zO>n$L{E!dl+$+w_5NcjDWD44Xl&r612|chS7_+i;PwKchZ};PAWV}c%9&g ziDh~y2no4g3s&KE2(;;;o8aJ5_eSf!*gH;p5(I6y6)ZbQ59^XUmCZP%4~rTLZfMsC z1*+zMJ-o|jc%@9Wq_tYwaAgGI76`E z&XcZ`8x<21qSxas3s`Bmvw3g08OM7%!fOr0hNT*%WmD<$J-pJxx%H6EK_2OY+CF2C$%k% zan=%ArIQ}(CL9otl?@D)47%+jE);6m^un#S@kIC=!@W0^gr`ibSwm40a$b*s7)rL_Px{@APCSw{ zfj@5UhhVBgKB6tmv%KQ#7n;a1N9UXSXb3~EoVm0h>W^?5U$zrgPDnsfQc^@#wip0B zVH$^F&kk?)wF2(XeQan*jVH0RwA6u^WD|A9!p!{am)^4%FOmU_N~_(_>COLaUXoq= z93*jPSKQl|5D=h7X{s`^u#D0*9=8SgZfA)=zK>zsXx8UbrtFIQYot-1r`iAE2>Ts; zM$^f9xcUhALm$|13-QGJO9!$M%aMm{-9ccAZQZeQwtPIu%s%+SulfS6$*hfr1>LZb_Pal@G#_LqnDz?2}5x1>(z{e8-x zRq-{%5LAvBI2G5nR0Gbdv+tDzK*Q1hBQU^J7^$!8wp00sh2nsx;ZOeJdL{C2e zlRH-M*$HGFIXsGbzg#ubh6&75=38T7Z>x@FJ3Phc=p2Z zy4rpBTF@f{S91JY0+J79Rs`Ra8~Zus_vi8=3jNtz9~qXq-2QmJ)s8seDYC69FHd+# zn)ICG)~-d%y!PF7uFPEYeq~@F$u%NT6n`knA=V3RXd2u6boL$(N@IGdJ-?r+r6ZW~ zyjd`qeV&F*5Vf_gVdq{G|94`dC^a=Ti`((7rlzI)@r=A{R{VzMbPUJ`CsVa3&oH zTgX)VK9Vf8p7$Z(zNYOe$`FVOSMGl%^Es+^&g~fM>R5aWk_V!nL+st(!`(1eg^&|yJRU3#eM*S-q(#+s;| ztB9!Zo;W}N1COPsd#f`?`Ap*9phX`NF04N<5fGd#Jn3P#RUY|RQixd)s@oL40wVNf?Nw)OH6y6|DSY8go zt**|?Gk#&`_LIPshH^E&z7sOL^2&Xh;h`Uz-~4_o8)KB)&m^T>_GBJ)0s)oihiRpy z94Vsy8Ff9en^zl-Jmh?C-TTyZ#~3I8f&Etx!bl=mQlq zM8lXa-P)A_YFs47YB~C7*hX$P)_XO+0}GS1hyf_k07JGoHE&jVqjY~3kd))Pk(l8u4( z8m+Rv5MzkWXo%N(>?R?yFV(8p(8wr!Br_!ita_=X2``*=lnv|Y>$kH1KpM)l(8&-p z8Wf-;B3f(IK;5 z52z-|f91oVLp*=jfpCh_kU4mIkB{#^j9e%+3V#QI3sjVm_sSlOm^k3)q_xP%+??M- zpE`6-Bo?rNV>P?&Oo|_uzgNzF8PQlFYOx| zYrHt1F53NC@o%c~Yh~pNw^@&Zi)GCVC6G0NN8tgAkcq|)Ys%%JCqOi_0V{4Gv>e>H zY(Rk%AB*l0?jPYPNXx;4IyGSNyWC~-IkVr{E=WEZWOkd*2I24NPJI&Z^ShA{d7 zQepqU=K>y9<}BElw_WQ?$1PC#72;cAKdg#h9>8l(F^$G@fJ|`4trvW4Y&7m*@%kov zzOK2+jByVII(>X5*ychg>nyVKpLk(*N=?8#i<=di`xSRi#w!1JWm2g)brEJZ&ig4M z*AvW2FcClIPo%p!JOy3RTm-bYe_!`XxN&pjVPfmRvXSQX56`1LhdAmh5)!0k=mWzW zkn^2h;oA;W9*Bb=A^BcSoC@}eG6zbM?AGADyv?>j&K`1tX)6Ce7D5U|{5K*OWTPxz z++g5kOJ;JW|5%Kc7--gOSN4>w*HP)F^gB9h$1bXjo9SRr$(8_kg1D({sZ(xhN|aU(P|wAJ($_q<)t&oS%b>A~qD#Y=9c z-A%jRv_zN_(WNAlJf*ayg~hEr%bJ!=HsUkL5)mQ!mGNfW_{pkQ7qhW9M*b&L#n47G zhmsw2Vk?#MwRVs%>qR)f>7}K{!kGZ%2%%ypvw5*f1^j>m{hv+>{MJZ$O6c8y4hkZ} zvfC{MmNbzMiz_R|QR+KHv!zv4g*rv$?b&Du(O&DT43+OqbC9k18Tw4$6q7r@7}-~T zQ42a$XL{J%+LHg$l0i152SrUa=eR$%;ZsK}yA)&x%58VLG%P!{dLfQqTOL;{20F&Z z#)j^3(zm_8DiqXkJZ@MFG!?xy!gq*E4cn3KO*Oxl7VO(wa8CCIeYVG)Vc+_BH$etm zT%qaa%0$?qX1qcgykZqj#&)Y$de~gGFuPljbp<_m zaz&B|Le``U1``e1?etHd$bU&oNlFs%1Bh9pQ$5EY`WoVL^lz#FNUDGSK%jwmx;ZTFcKGvS=nqr=n{(O17Z_*!^x)eDy+_63;IUm3iBUX^4*Ukcw*O{K+<^aG(?q(< zw~}rs7Lp9@By&sXU~4SlIzNJZnV6W!VwL2FrR)hY?=T*-Nz$IXvh{b&pH4U5K4fpY z>J@R~z}$8q&Uoth?wt;}MY1(q{rnoi$xd?E-kmDTBQeU-91xyQE!T_i-@STIqbLb< z5Dsxn-elFG-iqz6&dwnAV0}=9l@hLS^KocM2*F#gQA#I*W0ervv%mgQFt=1iYwC}t z8Rk1Z9Og161XEO=94$-@D7%Q(4(3Ww-vKe&ys+)uGO5UQ;obGfaW%B@L#b8`6g4e; zHw>wK0o<~#q)!AsBqk;XmpVaH|2gVc-#+lj{|j1yKBR+{3@(bW2C@tm2H4HK9UTQn z{&3nx{|fG?hOhULV&Ta)ohUF%Xx#|h_2guSRKrX>4^yRH4YcA%_or5m4dont7k~b4 zT+%Dh9_?En@;6JSEvA*QcNVBhE$d6)3Z2Xl%;FEkOL_~PCBHW}EBu?S*T-M7_rG$KIX9e^eZ<;QZ3ogHPxszyuq>pzf^*c%S8w5>j z{uqFLo5N=`N!$ zvlH4M&>7~XrZSwbXI|LsoFTlnNm{eGVu7llD;g9k*_*uMaZK?hvaE zIc1(2)US$`49Z z!d#Td6HA!@N{&y}hX;oj0-1Kyg2{sOOKQgN|t0*kXC8Glz&6 z(S-4It1LKegFtHusnj+RjA2IQP?g3nJFUkLzRyU?!A?z&vx;<4A-09hseF>3ZpY4-KF!VD$EHqD-aM4Fl(TliP@dY{pAM z3|I^?D0}ca6w0J)lqkW>*h~Y^icbHh1sKthbF;SQh79yktxI9I=OgzGY($^^G%{9& zaTy}0$C-m!ik4!eZA1flsUG}}%QceJxDzGme(yA1FSnBu6#x_%qM=09f-5vh8dSX$ zeBx1yR&9M1w9t67D2~i1Aqzy3XQRnmEJdVcSjCfM~SheGfPWd1*6AnT=l+&i zo}-0D7WKWEWz~1?#g4=nvrNudS#aI&0J%&L1}3KAogIgq-`a@ZipEgy@EB!&_6U0Y zkP}F!73KtLAH&pq6qaUr*T=`_wY@zRT&!J9V7aLYg*Pq~70n+U)CTP(L(Gn4vIoFy zkkvqoO8*2*W98%4-<12Wo&~j1taSlnh##lZ@c3&4>X6)pDT~Ya?B)#Uw~!K@b}|XY zxIq8~06ee7>18qqZ`N|<8YML|THi<6t+?6=`>x@_8#zW_88k>?BGZ?>F&dQxL*Q<< zmrNhkpWRD>9O9?5k`jK?H^?j%LZXD{VaIr(B40gLCsFM-$P@wzoIyXT&-S`qPF9jb zFB{Ph_|>E_n9B>ySY7U~U(bNpA+1mD(i;E`8-^Iq6N7pIZZf4+@5D3?199 z*DOZx;+?t%2M4t_Lp|^sjsh7VMXas__j>H*ajZ+P=$N!ALm0T@K4?g)vYw821l&~Y zz5daQhq`d8(w=IrvZ7)GuK@h7jdgd|{Ur8QjeB(6S+B%vX484%RkDq@x3oaNZgnF7 ztIKW2iXlBGrpg8Bt{*SJ{mVo02NXgjR(#4l5Dwzvz{`jaDF%SEX#bpb|MY6qAVWFt z6K({HAZdCV8($V<{|=Td*4LqVAtJ5(3pak;YatQlI_RL(BVvhnQmVKX*_OrT*jTO? z`Wu(Iz8D-XIa*^012MB`w-fa#gEer0x{stxOmqteL zB1QNe8qp>xAbST!hKaqFcy9<`^mFan>r_t*QF#iobl%S5D8kvSa+7fhLqS(qMV+ty z-MnmV%`3_@F1UkEvxd+N#I<<|Zgy;c{d%z$vc8n%VjF3eZ&bo{vq6TjIoh|RzI`oY z6&?R40S($`MrP)};5yaXlh%vzS&Dx(wBi4z=ev}n7Fo7}Drve|F7ri_+IMAL?fZ*G zBI55qL9fjsEi6E%y0o;^{1A{l^anMIh#S(<(umh==JKVXVLK5Dkc=gvfX*qvY@1xG zZYJT6f1Z=&Xy!Os9VkTaiiL5c7xKQim^iiDA-LJv8a@wBM|cl0E8!W$2*S!C6yvkT zz_Be&&;xc8D4nA1$OKRe1epbmv&p)Z5&lNvSaXNl#1!$oaPHH6X6plP{xNliPx}f5 zipRQ$9}C_O^;U|cX=k?vd%agTN&5HKcKizHEHYHu_M|h(Gqj7I5;Puu{EQ7$bT;5@ zTM74u$A7Ym!=;2-hx#TZJ%_I%n3*Y2Q-DJ;du#Z)rufSIyl48R6TGjMqiF>Z6Ap%{ zXwWTN0Z1aq>YW(HX^781ZCj%Qo(-D z+EUi-V)3?Gil6m0&wZ;?qrlM#u0ASnLvx%WEHZt}h*y}8lxClK3^xCD`<8QhJJjcp zbZOZM7u~R0H{l_9SVR~ab$w!?nR(kGOu_#0pJbw(FmXZp>_jGNaQn@|OLQrKFTp*h z1ytQdPswgyVT}IEMum=(P%!3{d@q=53k+wj=;IB{XSdi`wU4KhdoBMC59elNWH=P+ z+S-0S+@1kP5r`Ie04+}mhrixm?ZtEcU}Cw=gSZhHBL|%1x^x8Rh^&xrg;>%4Ea>?@ z(t@^eg(z>Un0Z^HuI9Pmw6+T~%CCRFD66O_TE=V^3C;{#!Tmu9NO&1!yb&3SW;);d zW#Qd949r|14IH(D&*piN;i>lSY_Mh;Z2-4k{ds3*!hcp_Lgvl&LnJJ5iN4v_j7m_9 zz^zWMcN7 zkN`{(Z-&w1KSXr}!0>#heRp@4dM4?Q#r-?6D&LU0QCF9gLsbZ>bXFsdKy{)1LVw%n zf<001d!V|Xs^O~9O~@Xtqq+gVJp<);6bk6qeY>g%^t9A1r$q57vuT+KP2-;thy4?sL!ax+ev zN%kIUz+#}^A=y`H@x3pbW&n zQ{Y|d_|VUHows7ZX4^~rO~L)(W~|_%&*M~eEX8tYNh0Ar&)ZyF*4vEQDyc&l5cY<}AeUQdRq|N518q|sRh7hzq1^FuFh_W4!w^EqPGPJsuto+M~+W_&qoJFdcz>weHru=mc~-! zecnP`*yO+#7BH>IPj#|r9vroHp?UqUPX}H+aOQG}4d+%CKXekBUbylwLOK-?)W^r} z4wi3b>s|t67`k&0_}YQiEFl-m$X23qvqS8?mBCMClylz;A47xZ?pXod{_c-DU;iNN zBbsMStAoK217HTb`Z7(r`&A<*H$OjLE0RG5YNe#2q5>IY;N4&LjKWA+2YYsdaT0v; zf??;?Wuhe@XPT^avxn>~jCES7Wga7u1{1k|!7V)hZ2Md5Zm{>=L^V_6t5Id3F?4Zp zxgrzovM+4UovXM5-`pstyjR8#O(RVqI8z?mISBR5GVdV!IN{b%x#Y9aSlzyI+cV8? zP2|r$`qQR2T!ce7{!}ynyekV6OlMR`&R@6l!ly_0Gk#1vadBH1n_Wb&9a#S-M2(O2 zR${$8?r;I~**eI_KB{SS$~|`#eev0#C_pvWT{P0&LH^Gb|Af25m`8JzT-OK_UV{NN1v5uAK_t1cdg7A>hH+B~2U^$UgM?t=_d@z`@^QfHxQvck@d`J?T`snO&|G%}GoTQo}8 zeoE^oliA>(+wIAO%LcT(BeL+JhtM6L27{Lon=pb9;H(u=s2+=23-!4Yw+xdwHgMmU z{aHD*jtwEiRAxczShfW8)AWp7Z(d}tvb#)yk^#bJky-8Oh=J^}wl-a?p3@FptmncH zwZmu?+%84eb`$?%p-cv|6wQ(j{kCodv*(W1F;vdCWM2}e7C5%w04Ro>FyN?S-P3P& zL0Dp+q{h;%+2E8lo4GFC?awb>d?xH?-1FqD8pVa;6j}S{m}$o7oF&D=CEcCbdxR$L zNgTWG8aFvdnYq2SMFHU$+kXQSWHvci+x0GhT4eX<5>{!{qDhT#ZRy`+`R%Ti#fJ4o zMVqyE3NxD=J)(jU$N%!BW--t6PAc~lpx$qvT}FLz&+u3S=HfNAwTfy&r{wiTAce`% zfd zZj#?l1OUwmo_%1>dKXv*US6C}Hu^OVtviS9I1fyo+{tG`%)cv`14$~t3s@9XU#!3? zWx;2{4s;pHV_eceTvCz|k*8nrW)KWEuYY|6%h<)g=^C^ z_o|1J_x*5d(joP2KAo?(kcU-cldl@o^53)gojC$rn}17xJNWsGn8U|FI|pfr&gs$7 z&wu{>nHRZY;vyAa+DZi+JX(R~h4b7$#Nn3XMU<7E=V#(gGQSqp7OxrY?L(ARtb3;8 z`|FVp?(vscz7~q@)KX>N40JT%cXo9pHtacyn-Wc6$X2YM;tDQ~`U*X+XGo4mBSwT`uxnS*kPZ<-V`q2FKasvw7| zU1N(17b94HKne|W;lFG10KiqT0Ou!|j?R6Km~V56h>NYqaBHGiO1T)D#{J(V&?RWE z(mbGUCCFCKBgX*4NYZRHTP`a#M5_}4=)brwt{MypY||>9|b3b}fnisp~)hYwUXyzQs<)oP-IcQq#p*%gb;mLY|P- zjiT@Ub2&jl8VZVQ#;}NW+OGIat)2{!#FBVBR?ECE^L2Zdve%&~MX_b*IUVcwr7l1Qi z5l3zk#=#iijvbUfT%@vq^Mb_V`C1K1=qufVWL#EoolGK#V(;jr^G%zxvU;s zr&k;31Jec)_EEYG;C%ENnQafPKU3kC%!?g6VZ;%`$evvF-@lTUWM&fPo75!z&Fa2@~;v+t(JZ0VAwW^lF z)WT=L9JDM98Xkg5 zqFX~^f;g>FgF%&@Y>S$JJ~!@FrBZ?xAQyUPz00dbccARjp0eIbh0R zMyn>=5M(T0fw7$dG$ET?>T#P|N^GJ}qDBD~zdQE=q~d4&xiQXV%N>*TC8o z%eQdEm?=(p#1dx1cdA>tW*hr5&nE1C2wJ)ozbh#a5NG@oCO3!SlRJ}P8Ki5RQg{xt zs1x<7nA>bBldA9rZ+baU1cLVi*v_?-G2dOYZ)$OGFbK&lId<|!z{5KFgE|PQ<)tjT z+3XiGAsj3Vx4$cEN_5`gK|%UdW~hTT9JQKib@frk$D)04Rd<8OI9DfF+P3%G8=xtR zo*R0nj8c#v<>h)$Qa&uF62c-t4N>&*fXKZrBruW?P<4fxzv^@FWQ(0AjrzcCzMO%1 z3lS_Z)%<>_Ly!G*z&3f+V~b|J0p5!hG^T|q$xsKBma-TveogKBhqEk`p{%cZ0)=#( zF5!x;M%p$X|7M>sa~u)C6vS?k{#-+9QOv}RIL^k-b_knUCHiSN$&ljaS=w7OEM@3v z{h4EB4pZ!j?u)};)_^W_ zaVz~dZ-07(83Q{pH#XvP`@Pbw{cb?M4~G!0ol)=B*3}`J98|L}kiXtf$f1`L(gHQL z3joS?3%BsI<=|2|mu5?0wLg7qJ17g|Tji9mGYAxO_p{==)qGR>`}+Fk=Pfhn17rJL zD91Pu(hqLL_x_!nWQ1sCTCIw?3P`fP10k+%uSetW-|<6l?yDd5wuY zf-wNjk{(Xw{pD@z$8l?>x4AO5pM)R5jPfmTw|YjK<>fUJ9*F-ispB@!gMb}eE|iXq zsM;up+wM-zG$gAg9&PiGL{B`-0CHlpL868c?&6P^8~Jd5ch9YsK&=s4MRULBo*ef$ z{VjSU@3j!_`^>M3%F2Y@&GAy=r&n62{bhh)DnVQBEm-c8&66{8t}zn?3zac3G1S_O z$w3f@CK6YSua{TtyJ`dEAbo2GB{l4!^hVq8^K1q2MM1H;Rb+qDu_=58>DC&4uwsO3 zb+e=PWQBM$r#S?sVZ3|8;U;q?dDV{1r>UX3P_r$BQm2u8{3|~sTM$9FDNWJH22{u{ zXh=GsBk>_DfNB(!C~T3Yj~WLDM|fc&udvoCKQ10oE?$ya5o#P5gKft^l!M+Yse%CV4iFo0gIlWm#0{ijNZ1Z2fa z?KO){i;)Y1Vq|ojE__Ghm^?&gf>jVg9t#}&p(&1QNm9dRY>77rfAQ6t%hCt(Z~sty zj&$frS(13yDv;a_g6W7j(tkxmnb)GDT5}V_&zvqunI+`A&)Ty*)VsU{>%f0kSN@d^QJsPBN_G)<_T{BL@pRIl)`2gO-|kVE1APGs6-gE(UPfl-wr zfu563bPuA50WqbdCc&KTBnU%UciIm{LIoY(!zm~VjY>jKtcv4QkV_uGQ}!J#?v)81V?gZiSK+Pnebx{jZ;kmFx~r>X&8sNMn62trDc~UZ4(jZrfUlI!3@x}q5?M}Pbkcs{(wJ{7nb-^*>hyA)D*eli7{{(t! zpry$w1KyorRV-i4iJ`Mlv-ZT65AgPl&f z_*=sD){=`itAs~ih0S65P5IJX%|pK!({A#P*CJ;!)c(J^%a+EJzTKusv*u}4)i++v z@;TBWfF^gOw)BB>lFHMZZyhwbEa`0D?;zc8sgaFc=#2|O%DMnR!cI#RYXN8F7-h|s8v)UdBrcnOCeePE`S#&ERHGXQiC6FBiKwaNb$qw_1jtG}ne2v{ z4Z1o$JL@}8IMh1PaMEkPp>B-Rak%P;`U8|pcngW*&4u#D$I&v=-++;zXeO9(M(J0b zopQW^cPp69z|Il@_ah>@c?Pfcbg@!X&hOvTH$%exI*xo}{V>YXXSZEhB<2+Qno8mf z;cq-yJ^Z%L7QNhNZ(2<^y-%3GUe|Gw+D+$ILI?vKJZQ?Ab=Mj!QAo^w_5Q(utQ2>M zv||?Cd{?u9vHdE`&fjiMsO3AV8Vc{!U5WYo`;H2Y09?+tnQtNyVJxo9QM+YxKr{SzaF7NiE9Y%LRq+Kn}I-&ha z&OSwhx}+kzt?}94fro6q4sR$E$OnU&+%Tk&zgobl!S8Me^p&8!0T(d9&_4_WXLBvn zzPz_RFHaYABaKRwuqTVw%~hVfR~}isA`W>C{%MFD%09PL2X2R%t;d^#D5l%P_&r?J zyI+5X%z-XZOQ(6$KsZ?`mbOQ}ohiOCx_u*i4wA-F-#@$S*vt#vF)v^&U#d&5-x{kj zc*U3Y9O>O#Mq+N2H^spRNTR1XA(Am7HV4wgYP&m#H~d{jO^pt&4mTbGcziDuXzz91 zyj9hx^%ytM4xEzhUl2)pCTzDVskBM> zNl~I+$%(gb@5ezZ*2<&5l*nSIi5vYcTP91PLZrn{euGvp;(`#TrPdB*fGwaSOZ*A< z-nV!;qKCNp^X?P3s>G|ZoJ964+N(mVzb$Q9KwMAaqwz z2?gp`w3L$)15ZYC5f(Kw@CJ|0CWeh19XO#91#xNa9-O$}GTZd7GkJs7MDnR5Phi(l zxaMAT+RFRQnHQTwMLJ9b&J`MSFendTheg^rL%O0p`~R4F3!p03E^K%Mk^+LDbVvw_ zhwd%`QAq_vNklJ*!3F+>JZ|(Q{znOpL%$zxM7-o2$ z=U(?(*Sex+!B}5(=WsG^-JG(l`Icci*-j@Ej!wrKB zV5P$g!dHmuqunY0h5CMDm6C$HAO}%-W3E9{XJ+Tn{}LC1`GBoV`bS?j$J3`z2Y`%< zrD+rmm}Phw>(NN|7Sd4PWx%;_FA#@+4~Jq_mU;t)LYYlXAKgi4fBE8@mn3y3e#&LO zI42qv?)xcO%RSf9-u!bz!K?;UehpX^+QN58Br7)#qOAW?G$LD4M3xp8)jEsVXofqDjuC8EuIxh=qNFD_NSXGhYH$i6w^>g?`(b0ACWRA3ncF}Yp~f)lwO zc#l!0(NLV|VO$&!wF7H~&Wt?43IUS@nk>~5Gr>Q1D`J1S$Y})4P&KID6>{0vl=NHRF9XN@^%~>G`Z`rJj@HfqH zU(H$_EX6Xyu*N(!GtUM*X+y#^TsfDFUatf^U7hbgr7}oEC0VIEpCg4-uMi}dHcCx=b8U>j zQ0m^iZ0RP{qD>mutAA(!i$C)!@{G#*HF?_ZyBdemS$yI#2OXrI4BAf_RsNog)WYY$ z_-@eVi?~k&8uxUw#@jMg%76~pVVb1L_H~@@K^dofT8Lx`6rz${9L%9^mTgdZ~rqZgz#YdEVd?@oCn-yW^RxG_F*t$$yx7!;F zFE>UkQ7bN~gfGP@lv#)$Iq@e(im1cQPx#1V;i}(FMGwFYV1jvJZ~quvr?gd>a$%L6 z_}ZaN$!4?6+7N<=6uRIYfLlBP`mv4^b@|t(^NdizNZ`oS-y(~4>&-qO4xW#`Sfx!BFbmJPdLEJLsUDm zoD}hVX?Qp_exs@cJZN8|#Q8M{WloP|13K%p_01UVwvKkV$>wiH-`*5fh^bVK$TXqd zjf3&2AuGjMN5n$DU^bOIlH5uRFFrlr`CAIZwCVA70_|6wrRGXRZGo$L-Xir`(fQ-w zT@&$(D>9}Ps>g3~ihiIngaF~4kquiJ0pg6(S4|B21r?H! zLE4aZg^^ytBb~2$mv42^V#8>Fjw*uEv*ya63 zpeca?Dy(l^;uX=cvp1pgf$IxKHlx`tjpDDGECx#R1K9<}0jxR92#m^t2tz*mww+!kpANT zKLXO>)?a8M=Y&L8jnuYe8WOD8d|`0Pf4UHQ2XVEB&tdp#!J-PW$om{id*$V;*iXCn z(z?W-L!589KWSCc%5d!%#hv5<|GIqnGPIC4UNpR}xXe!&B{SNfaO+s{l0fL^%Y2a> zfzKkNfSrh?uaJ1_>+3g&&!Vp%H&khTh}qj#alI1Cwi2tJ+i4-SZcX+F&@|h!tk;>2Q-CVlR+(8IDIidLh!_3S%~RIWtb(IZ~@Fpwz!=MXNXS zr`<>vNH&bYZnx;~Y(j4BS#s^b#jz>!uPdYflvupRJ;Mne(+d@)fXz>G?>PL{qq{k4 zo@%0xVgimfI2Wooo;?DdT&m0RtrZgS`)x$>gzi<*v)*N}h42Gy>5xb5iSa#>W_=(H z5Obwu+~+LJN1KFV+1eYcRNu=Bk;MC>f8zECj}djQP@pyjy>@EwJTJ zSTbF~8%7tB;5bF69CcMARR)&yoZ@m`T$046DF@$q#kqjhulS#4okrGx zxEU3zzM)L`z#Orha=Cy%i`0fy&8%S@s#rXKHG>hl#SnibY7qz>Q2UdDrxp_x^_r+3_SH^ilq-r%+Ju&=pL>W)M^@QYCNiy45M@!pE33YhUBgPJLq1lB_#RguwK4(29Xnr{omWIT@AZGZj0>K zT|VBRob24Cb)`nZr3DOv;^jT>3?=d%!;RxJhBdKl?UkdpPdm4NUF2L#a%$sDuz@+D ze?C1ejXVq=_vZbg6AFI1ng;&^B@C3p`9&B# zRW^GOImGlqz-i^X(D|Bg_7lC>kO7nrKL&U*pj6i4O}I?x^5I&mTSsX~^SOTjvu|g% z6O-!ZkyEO~$1{OeM!X7HX2M0kj`c(k{x7erNKs$aC?i9AV6UwGFLoyDb=Ne+hEFeY zy2{N-ZJOM2+C9&tv(&=_Z~Q@%aU;4w2}~jJx|g28aQ8piZ+JHp)vplH`t5{nEr>vg ziLXRr+aZ{Q`J13|rBdM_NXy&Xp=%(+PjSr=mu!!^LSsnlYjQiN25QaT{{9P)dji06 zW7!Ux4R~>ob#SlW^-YvH&5S_!!)0AKIB)cUkyc%!Gn=6Fo!?+$@jT%SXop(pJ-!m}7*Kcy_pGQ1jlGHL$ua`ER zks4Ba8jWdltixX}D+x6bq70$`- zNl8g^M$Hy$RbWFL_jsR*AdqEdOZh)y$zo-c#6!R7F1~PXYumG|s9C=SzZj;6VWn6% zL!iiFVgBKjjwP7vcxw)4lq4^0j`Sm%s+^s=f7PDZ%j}|+9$w*B3cW!yu^3AoX(aZh zN&*wgxA|ZpLU^IpKQ&;X>Ve_I^ac8hXw2q+0mWjq7zNW9#y1-gZZTG~;Y?lYkCf98 zi(4{*g|*qB{?DOg@2>8e!Q!QP=-%F|DV-*|<6csd_^z?-b8+B7TS>ZY3l>Duj<&Y9 zEZJ~e=3Oex40J2o6g*t76UIcO{qc+$`Xqv+d)3&;z%M zr6n!Cp=?L&CvNja@;r72AGu5VC9%d6Q3BJe1}R z6fw8krA!*P5f%n0G)n*ydzJ1L(;AK1Fs!xFyZZApae^Yq#%A$dI$?JbR0`-VKs*k- zN9k++Q_^I45o5&bb~`dNI1H=SwS&(SHV7w|GWep|4r#Vo@ zGrIN+85^){WLSGLqD7SZk9bx%@zxM4W6JbZx_@R#s%zd$1Y#U!UCLZ+`H*)2qs1rj zJ0$i0Vi|ZB$JM~5pLB{#F-@%*wh#zASSJ<$ze}3thU%O5s!`@0j_o51u5!||Vm-4@%+^1^x)Gp#%a$CcK@*{!EcfsawUHjaCc0VrqVGhB?5XjdZ-lZTX9_F`brU&czPfT7-cCK| zoEk%;kRJCiPZ@$1k&TDGQ5JV&DypA)tVpyle(=PArswK~+9@Cgi*NfEa%DV#%9s-h%xFO@_hP-=TW4`kLrd|;~p#kU+TLN05nXraru%Y{i)@5wnze973 z6IjRiVP2i2q}|)Y@HhDl&MO@D!g_*biJHw=o<>(d{?G~zYu>BtzBuScrfa}>fJ>1q zBRphg(L@-PD~v;#SL1<&{yMZ*$K&+c6ShvpB?Ue|Yo_bt+`;XvG^wvFH?rCg$Xkpt zscBp4XX4ioYP~XpQMg%Q^ z`Ejnyedd#tV_RDo2cBM|$(DLi@vOrRuaq6?i{D9&lJkzdV_qKPTnnb_|8`z}!kJv! z?c?#;=LxAXJ>O19->=3>d!cxvOn+R4bs^kr?&x_$e|?>)?N^;u%ngoH#H|?aX?nsH z=@;6D&nBV8!tPqw=Ke(K#C*)qRJNzM6+Erfgd6G#NJY<0WeOJx9PMi5&O3mrtA2%t zO3MBk-Hvy=FC?-*){MQHHwAzuf6N*o8<8a^jBSi4hLh~mc z9qnjZ;ok$=%WUAdy>^f}+q%&PfJbxlk1t*>Yu>9Ez49rx6{V!!HG zPt()&v@8yh-Sq6jO$OqMRwa<20uzq1fb)Zzi9E0VG09g~*l(4;u@N)XraDmCX?v>*l5D<{D^t;AY|IndY{i#`s+RK+^ zz#X;m_dnNnp=JCsu!8m9H$I*ht1SS!>yNT8aWzYzqMJ)FMS<#h_FJuxgC_oFyk1={ z7|FkTPaea%k`2|4(QGc7MJzNUp!bJ`(}3+z)J;zfJGFX?RMUDqraQr5QY>}^cP#iN zAC{N=EjM@4>!qLVIiU%8DsGrrD~?O&zh2eNRJQw}Iv7VY&VKdIU9L=1-tPQ@^-!Ld zLCA2ytARO;;gHOoi*3f#eSCac3lV4|Lqi?WM@@hcd|_lr!R)o>@U&fBnzk%7Xj%hImBdFgI8IIZ}4z`KS@i>lmr@=K&J6k#kb%ErQ`& z%%t3(>tjkTGnKnr$66zFd6<&cD}$s)#);cbD!SG@hlt0cL-XoqEf%;fB3m|QqZAfR z#}piBOgyLiDmUhn9c3AdG1$eueVIrnnHr(?#NqDo^R7p^kFzh&3F)y>z7dWTh;z-- z;!a1yZy-8$|`shClKi*{Gshqb~Y%Qao+j- z<3mol9ap7&81m(O-^w1tpT@X(Kdo* zhsT8aQxCWq`>9(2M~YE7>_3v zZ!kyWxj341r@TeD!)(Un!u2<_wwO;M$?Bra`0%%%UO82}m zm7wFwPTc}JuCKN)7Oxx~)As|f1mcLb8_yn!0Y;Iz0SbsLY^hsjggU{rrY?s z;7#%Yb`n{F4?P3qoc71(CmZ@d42`qF5+FU(DKZvvlX=P9s9MD0iWT|4Qc;z^^hl5hhi!oKN1aH9xnK@#z5 z$gNt~kqGimxW6PAR)2Y)`A_X^w@ufAv23#oX73W_U^Ca?S73s0d%3IE#1~V|CLXUe z3-XdQx*dL$#PD8NujpSXyZ>(~SN}(xvDdL( ztQNntANjs06%q4~R{~RkJlz`ruZrwK>e|%|)-?H;FRs)7ER<|NfBw(Rmek)1Sqn18 z-A2|pJq1e-txXesHR;tdCquyeF36WaP;I>gmZi@OW=l#0{6J;i3&{ePK~1vs?}Mh^?fBk< z+6%v^$Vd)0;8>F^s5vw_!(0rZ@r#Y3cJ2EaybDa|QC>&j6CH5zSAX}r z>G=hg+yAMuRheObcQ+q=JkHL}U_ytbpl^ds;vq$~Bj(ptumA3uo*WP5INm>A81NEL zA!GiJ^QE<}`+U+UR?gj-ECwFrvS#?5y6!?7dX;SSo+cYK~ss17#CQ#XRjsU`3{qfBCjXDY8 zg*aav^*<`gs`aYKg(%tg&-&qR)G3I2w}Z&vJ64ytBq)Q(0<8o>?M#aoHHXY9rcLj| zW97Dxw*oTkE7U&?u_0}ABJS3^t10tE;OI;u>8>k?78rRl+u~rcp**622dh`gvxdd3$JKY)`j)e_Lj; z?uWJJy`mp+&h$Ti{VK-s_6oJe6{e3;Ug8@>?@=Od61qTb53z`n*lM-4@ppFKdiUZ2 z12)>D)jl2#IAaqNUssB2{f!kcpc}nFW35}mTv$5lKmPaB6*3%(c^01*JaRo*`?XSg zzEXSDT^SDSPlt&@kE&TF&7!VFU0XmK!66l=JfJY?HVm0hZ^!HC>klcECQIAYmzpfh z&jWq60ASg=9cYAIVS&F=7la48*FLNdHGrj`IbP!>mZUMS#B|EW>}d{h&B%WkzPEDP zm}=3ApK!F^zf&W*xH{BAZt0QrC(!vz>ERhl7oDa-(N3`V8+vXPA3f27%}jnaORY!R zcK1x17T>&FcaBO>hq^fZ?GyOigWVFWbM6(9GQXq9p#77k#)yi_rkL2ALzDx*lw3Y@ zo#Bm)x?E?U)V)sUZp-YF_suabZv|y#WG1MM8ozDEX~*rne*GFDEGWv+N;u!wpyXh6>sBUo0iDO{P-eF3Z=JSj5p!=hOf-Ur4@<{ez=zTbJvr*N^$ zKdc>^X25aZB|pTV9j3-u%6%0LVhm>AO$DqbYr)IVt#p4N;G*!OTv-ZYwpxNoQBz~Z zm(U&!$D+%BYvj20Vk3e);^pFVKGP$={kPqNy)hrJcE`sd&$X+1%I7-`lzV zKQ6#q9BThmle~+=$pgSG3iXX$V>y-viv9OU_%13ra)l)Yv+6T5-EQ$sBVya{Shh_& zT#-G@z*@sYk;(@`8jznQfttQILsM%2f6Dd^nQU-=wy{xzs*bJ58WMw(Lh?C3_I4Th z-6oflaBF^+;I%NBIdp7Y4AVxkUzp={E=>l#SQHlhds=$9aYzR?GMV?CWCWAdw1;$O zoKLEbrDyVU{#{wBQJw)H6yfQW6b5p73g^p#GaACS0|ITd`Dc-nfn9aXTyKe0AAqy< zRJL{OR5)n3fJZ~DTH0P|z*~W{L1@jk;b%WKHb$l0<-7hp$^-1+ASjvuk=$xA&tmKZ z?He#7uqdu46v!c#9B0-kT4F+>l;PkYI8tiOOXX$yFv_}**>>% zbL%0_ncDty9YP3LG4?8akg<0|Gh$VH1mh+@l-A+ zl#R;yQaF!r=bS-APyhcc`yo2VL($PA&r0YC!^W+P3#y<(-}U3574#`4IizWm`&Yu0 zTj%cOjTp?B9qHETAp}b}$T|`b$;Iz8;2%%=Y*fSKB?<0tHOum{FuUN~SB&}EN zXc!|qMKp^B$6!ajUUTA*>b+cm{kf~ni)k`GyKhZT6=6{C6X==d?QVwMII7!!zf^Lk zLul`GLGEH`0+vU2UOH1FIu=zyFD(YVXR_xV;fpa&P-&@^18)bb@%aDKtZ7t@l zWix)HM$SVZCLSLj?;g&^5IS9-6-YI?hx{jOA4wMZ32LU<9j{j$1i*sQ&eT#%;pnQC zJqMMAmTozWfw6;&w(q%dPOa9YNnSUnc;DuAZ9Hue*&nZ;l7AJFK<;^rVcwd4Qy$QK zWe2}gy2uP#0!WQmp^$!{?&Njb>r;>uGzIgs&w`ohAV|%>pKg_Co5f ztEtd3$1Fn!ZIb;8TzwXM@AC~DEuP{9jN}*yY&;3=uf06v zW3MWnH~O|j^Ahe={UJ!e(IsR^jEwV4 zh)K%Ah`#j$#kIr^?cj=X=Wr@_%oxWj?#E^~00)!|FPb(^fiRekVQNdH?g#XuaGySC#`$ z{2Q$A$wotocF_O~IfF92hg@<;5pd|z@sBxvXTbuC3&M^nYcIq~K-B_5`sK1djXt1x zGJE}t1!4xuu(3f;N}N@LPszE$1uYZ$)RV})Hm^(>%;YfV0&iIDIEKe?{~ZX z){#^g@c&qb>XgZGrWaTPOy}dRn1Iu#0)tWeazo}?h|ma^)zDg=6y?vJIe|jYNR8z7 zJ}n$C_4dAa6wF}fuOp&R> znoR_f%}S;DMq;EgY`wY%{5I9=&H%*+($7(Y0drjU0-jcwSo+p`)bgKW3r*ggn5~90 zkT`%BZA#a}rb}i=mA}Ma>s~^U!_4 zA38KFQ5j!oF6paMRTiOdGpr$>`W+n9sHmQn(?w5}I)Bo9B^UYU4Tf1_vSZlN$N@fZ zdO0)|a;o{~Pz92LQPR6IYBX9nExpZhH<+eM-VvsTWR-T@syjgPE;2nU^oR3V1S(C& zMebY5K{DF2?>GsQ6Jw^Qr#De&CkJA4e&8|yjs1ISLHxtXBQTn?vk}CM&z{s`4>7p@ z?*R@bq1}B95d@!Pw<0ucz=1^Jia_1K7q9-xzNig+LbRvoMszBf?|y@jY5qw~A9|nZ zYA$CL&$S;Enh9dXj+q!VYgi_dR-!Y9H)q9M|5%?J#ptDxnl=`aRlIErg^icg2^_GG)qP6K%_ zun;TUI|VB+AW*OhF$&K)%InF|5*IHh_;;==`z~Z7!#>I;t zg+O#cP=G-Mf!FL4L*B~}7@6Pi~!Z0*@c|+l(14^k8{wgMBhE0c4ndui)VP zm)ghg&K=e`ofCG`oId39Qtb-Pqz7TS7fW}<(yR07SMpYyZcQ{a?oPy%YecCkL_ zVI}&t6>H#@J}lnvn9a05PjZKVh;)cdg79+AKsW`BvTqmCg7cA%V(h<+t74u^n+@L- z3kd6)%D1WYNh?2ojQ^klwFEfTkMCS>v_^4vcXV(kcZxntLI&Zz8--cRRdRw_*{zX= z^YY!KZvMi2jOvcF&*&83p1{t<&Q<0m`Ed7eAbP-rN{9Dea<`=*PF*S(0|34WFhrdC zS7wa`R#Hl0@R7kX$be3r6HoOuq6X(ujwX1y=DpSBseloBVqyY55cmg&+8xo0|1+c$ zsz$%lZmW~cl@JWs0_~UQ(&Qg~s0DX65U-`k%>TSTuQZ=U@HA7b{F`+KtTmd6UR>S0 z@tuGdho`j0`37s)22R?a!-692ugr=q(Y*EGKZ|?bdv}Wm8-^9jxkPWK{7g;25ta{NG&>;nQ-s9A zfZPxN#UB3);mxx++@M0dI2c(86Ng~(2y1%3!DUuQ)6 zFGY*4?>wM5M75_KYB373eN52*ORy>N9S{8r_6G2l{zqxIifYfK-DMXXE%h6xyI1xU z^cq!BFWWL~VT4@`0#y@SNTG}RV&`L{qlz;AlMx+v30hYER>rz1tm);cy5e;^EG;jC znX8!r&3vGQ`6=vO79W|6lK3-Aae0!{X|4t^b}x#?y*7K;BX=EKlD_JN@WOIise;gh zLMqV*G6UqfHjQ0hl|Op&U_+z(l7f6fD?TP+Rcf%qHc0l6Ii#yvvnuRlJaZ~`zNBg= z@>ZTMF6Cm8b)sjPupgJscs5Gr&vC>kI3i8WMINB|CUW;&`oBsef9#*?pI2w<8y^;; zhkjplPplj}Oa{b7_jXo3;gh;}K8+mQZ@f5sw!|_-<2vux=^5BJ?Jc@`TfJ^`9rQZ+ zPpVDU0AjqNJ#Xm&a&;_gV#Tog$O%kmih$pTMMWwEcR4&uS3Di8Meux#MHSx;$CRvf zoozn9mGr#Tx`d1>U|mCq(A(Jk7$eJ^@TBw8!JjR>yc4B4-Of=VlHF8b(qS{q{4P!~ zR}{A)sI351y+5k_s>%M>#Aoa^2h@xnd>W&ScHZ9)K$sq-qI3WTu-M2n$l77n0YJnA zwr?x%@ALM6JEQBE{V(`#RT50R3uF%}x^018_CGfZY|t5yv#`JMN}H}LHW(rqbNU%e zcft~aEgZ0`vs5z*X zJcH#_clrFMm)NxDF~?e1W*cMedtLur(_hR1@2?y$>4R}3)~_2I&xDmqVqqN6Vy*lr z_WKHdsNua{nwm}g3GbD!FehUdJXn{;oo+c(SkGVs+CYP20#pBDJt0fn?#0N-`k{Cc z&ziLgyX_m{WtZ6BI1C{V>j=c`UfF+IGBZ~XCl0bynqt4f(D40UAld4#Cu&bvaTFu& z$%@`A%jGnyBY$qsNR{mNXSms*{N8ur>|6BlNnW*bO~}0}{cQ8U{zu;>&zHDf&igsa z9Hb%Bkn0t7un&udT8%gDM04XTdq0qD9hf^U} zHo-#px?|1JO~e$Ky5rWI&hgDAT0{%1J;>EDC^5&!TEv^TzPnL=G@nd3-l9OCbFL<4 z^z_z%jl78GAt`2PQH+Fp-hn;i@2Sfp+(n5FOF;t9sVxDMQ9M^wt-^QTR&E}W)>W}Y zsTfaX2RD66j;u@nFGKvMd#!DU4Rsianp8vh8>!cTE2m_q8UU#SPj zS`nv8oL_QsE`dX)#7)h#Ra`qUyWv2QmxE^O;}wbg&u|&@czVSsh`aDsKt2`P9Jk|^*;Ti|A{^I_3P#{O%XTk`&wh!owxqb%uaY<{(KU7sby-q z@n(1_#(=LSQX?HA{b;cJoDmDpc2{d_E;x6grVy+<3>>ukv3h}Mg6l?ZR!micR(rR5Z!0N zgtu-neEM6AeUeu-8%)rQ+sjsZzl&S{y8(#P-52AkyAl({huH}}^Dk=Yi^pe0!iqcZ z-)W4_nq|(LvlgVA^~E#$hj-wN(nc}JlqmSTI{WtgJ&N!zDRa=3*NQ6pmZeXS&+eq> zGIDU^xJo6l#S%dRM_Q!t7yX{}pC!aL(9-fjKOH+$UjPQEtnTZ!iVO;>rgSou5Gm7YAIQ&(4ir^eCI z#`j-{S>-m%0e`e9D+PZg-o~|zRV%N5d~Tw;rmTD~no?0uqRM8G-o(k@^y`1)jHF!t0^K{hw+=;KzME*et&N8 z%?#)EZMmnaOgI?3n<4O4Nof2i#b+ah-nCgeO8poR_B@6Uk9os;f9F!#weUv_>O*@A z_kda!ULnuV$JhNY;~bE}aIc;DJ=3}ii`zUrLLQ$fxECZJ6Vjo-ZWLsPt(eZS&gndR zmRT~pi@L;_$~8dKKREOq^w6WX=;d>d!$v2U9b*BjFq^UUAX2S^H1 z*u+=AHDYt1=_uw3^3q)HW_&Ry!7a7!ZiY0>Fp!Y?!pfxq(l7=5j$NxD2Er3;b)EM| ztY-mvl9<^N#~SmVLf~5?XM$0%o#@-jO3Bsn3MvLsJ9+rp0rZkVX8w@}^LYSFYr?>Y zjmQ+FklwySXmsE&j6VbDP_T}bQED8)wI{!88#|JO$TGa(x0-jQNF3H*@ei~V9LbJM zKmEt$2@z|~t0gVwaL9R^X^GCx4{BR_bMKe9%&9*}lcobVgd7QPas>RF!~ftnW*V~F z8iq?ON}e?m7=eQ&(IwnOF-K;&tG3{xo`rlNNk}0gU!C|(^J~JLVS9V~n@ta!k=wvy zaR6wyR!h4-5rMhC!krl>9f@&AYdqGC{xg1CXgizi`}Gi$-qZpJN35)LK7dR(bMq z>x=?vNC_xO3CJ?qXVWhgNHfP&2uJ~&8ibMY>Phal)S_fKA}X%ybR(^;7+1+Cc$8VY@tFoUzKY82p_YqLUVfvkJT-;JCu-6aK!St~IUS%h{ z-bI;8^dcvgMx5|C;IZo??Pt}IkF1h$ezCtss+zEGd}sctjYCS0eDr=K;IYH1K*<S; zF(pn8QI!v#u5ph~F6&c7A@v_UdWB83O_U1&n-pQJ$usPU=rL$3Vwdom!%&Q>hjKbm)57lg%rsmH@W)~E>cA0ZXo=ud2h}=T9Fsj zP(R`M2?U(`cBIKLBt0PD1K-pu=wdM)Lb|a=0qaMmCXri)`g^!_;$Lxt z5b)VU3K?m6yPCqb_z=pTHpS_b_;AM%M@mlg5uNdBJ7HJj5rVNJO@yIKXktfWGxVq{ ziN|&L+cWHK^Wwz|ewTl0)HE~<*#%kOafLhNP?X?*hLU-f@o&qs<4@LXbCi;^bBP3V z@k!SDf6Iq`>=^oM`QKXz#EZoS|mgmT}HwKX!?f`tsGnMmsxHT7hlr+ezO48{l#5RYZw zQfSSSF2Qrf_$cIkQ|W)Her@?TBcarD`j+$)AwK*^gpmY9i-x*k!~wdd=v}qSb62vG zH6y7imSD-!^~)o6gDC_nZ^@-r`40--Il7)nLYKLP?Ys0rVJcR8)XCiC%sG%`7nZdA z>Bxz6;+@r=bE%CgD)?K(S2r8s#^@UTf&In`!(4;9$o9y1!;-)LzIAcCcv(}Etyn5Q zKcBy9Zxz|C_uUmDLCanYA2ZQtDZ(KMZ_XRDEwI@%tL-NCW*q+;-4#ls_~d`Y~5 z&z}jDLP-TAmG4{^`Yykx4aYbui!ClLj@GL&gJ4b0>*Idf{JhnZpDB;eLXfRBTga;i zk_=&eKbK{5^JrFE%|^uwKiF*2AWHd4OmAO#EY@2+tF>56vg?+DvUmq7N$dv-Uw92T zsaK@kx^t%qPE|B8j^h#%W?xZh)D3=p>fAugHT7f2q!D{7I8I9AHQ#yi{Ss`sSOFDy z^Y^bh1RyXZi#e*??2BLZhm+lERZ1)Cdl)#@*7;5BHvG;f)~T=IRKf|cXpW>asP(TF zz}?xd+;N>}yX_$T-X*`u<9!=P4MdC5E416>sIvG`16@!Eem114N*e2@ez>e(`vwyF z#y#IybtDG$WUDqV>^$3D>?vRU-oAOfQf$$ab@wKz-1WDaKYw0_I|fx#b#Z?XUn!&K2EiIs~ za82VjY9I4LdU;g)dDxpuX4`+0O4%V2^TYlRqq}Rg&9q~)XP^xrEiYWtef}V*#pvYP z$>+3(_~MVads^Yy#t)M>v&P zX>i3D`)N^Bm6lTZ*RlY}3OJwDc_42f2-WFe2f=;&w%`;$QhzzodHj+1ODVgIh^agh zzrn9lx1#9RF@<-EX3Tu@?Oz)z5YE~AqgcaLdJ3-QsN5LKLZT*LKK|+ARVN`@XfTH> zOI@zlcyFw3?;#=(^K#7ffh^e;t?&t5Ov@Jdqfx>xwGQNzZ$Eva_mpPFKK1;=*{@?V<3h66EyPR zW)un+GjlWVSaF?yz>Y<+TTS1{NW?;#4>_##>i)HT5U}oIL>N=P2Htc7B>GXpu;ZIu z`^4Rpq|845BYd}`FN^;`6)Lgnq?g|7*M(;-YIa^`+ebl4fOX_w9sSXca9uWYWhC5L z=xl-L@mKhlua_@p*Dr5LiZ84p-`PX5^kcG6gFEwr*UPWdJ%`w5N}@|za5v=|kRZwz z)_)7QuNtJd{Uqe$^Vl4|@FIni1n(TLCS5ToSe`X7Qz?uMYHCL0%h!H$Qj!6cU2ZY` z9*1dUfrWU1J|8}21_~XJPk6+~JRU3})zx|ekp&;GuVQL3MmPHzHWs(sx}wOYZhJOw zyVVYg-X4afE^IENs)lUtqj)+yHJOsTZ(b$-x3Ivl`R*(SPy5K2skQKz&AE4Q*n`fg zEl(q_MiCKeH*z>NFi_$PxuTk!kn%%A$&HM+A`Eh!_Wsn%l^1vy>1 z17g=+amtml{Pb^^`RlG+w4>xkJ)lr#?<*!Jhsk+4@LB1HQqb5n)nSy|s!Z#%hF z*EYhbU1u=AJ z8M5xFV@*VMj4XZb^XG_4mkV+ZxgB|?a!Z^4#|4OpZHA8D)Y-{ptqnzu+bwg!xaoV4 z;>+Ar!eKk5ib6DWzt{U>5X2=5AnQ}*QxX^8>pmM7zg-Sy|spQG6O*;OL>TNqlP$if#3B&Fp1aByzO{QiCWojm5; zX1TurB^nnWpETQaVf;u-D-gJbd*Qy$jD$Y>tMynvcxDw%FE6j+xhQ%O5~x$C?!<1i z)ub|85Y+ltochL~N`cx|Vm~HI+RJ+8@ouf6kKKrRaQAd9Fz~jGD8+-^4>Z{&c2dC~ z+_r)RYuY7ka0-u}?W0eM^%DQvW)pH6?SCaf{_-wz!&QSpI}x$MUe zcyN2-lU6*P)M?P&x;2HW+`zH@X^ceoew%h~4i3h(P@~*@n5)ygX!r6ZOpi$sDf5X` zU#yPqw9hU@H$NLoYJAsxGYSni4D$Z3p9z1daIT+2t0dObK)A~gyC?B)-8|Y9Zs)wjtzQwPI7ul^71kpS~Zq8qaRYVt33AlzR zv+-BMrK3yfKNm8_Vq7~8pH^>@+#Cz-=hA)`N4<-v1g^=X_hszVbnjk-wy)Q!Kj4R0 zpCAFZOiKv(ML$RuC4&~T5ri9?Fa*(qdxcuA4mWf$5X9`< zbC>2us>Un~gAL0AMOa|N0$eUo65pdb&cl6pa9SD~6hXa-=$1XXBYV8aj&}@XiEEHy zMFC8ySTzo#z%;VcQ4OMG*Nxdj%@lFU#;_~k8bN5{y~J5oRt6IXG?UZiOP`b9rKiV0 z)G8(5VQvyA1HJ>VDACfTq`dT?1MP!9oSz7v1SzAKjJZfYGRduZe(`Imce^MW6YsYA zUOrq=-oo6+Ldl`aAEjaj9~SfrS0i3UOqLCq^IE6Am(9+IvA?tQdwI2gYk-QT^4D!X zZq5Acq4_@e9F2dwXI4~)?(ing!2rS|27|DXvz6ew*su0|y4s)`a7 zT6BG&=$D|qm7Bm)@{m5MYfEo3FXegHllk$ykoS@VeWLL3(Vz>=GSkpd@Hf4Gv)vWJ zRFL`dh(lZa@Z7ZPu7W~P+YpIs`d>4ap!MpwGxHqTKKZ+BlGa zPHcBe?xktIlCZEaE$gctC3(5zwJwV<+NOoc@4Fwzlw_;8T}+AR>jpn}t`e3^I4zpG zgGfLXP&SHg7HQDE|9qooui<>rqyUF#lxtf;Q(`3AT(;4F+0dHqOITH6!chG6r4K12 zF5k)FEp5%RT+prz6{}VXtXyJfK->RQk3kB3g*X9Et_ZPXR-!{oN5F9@~mcAiF6bV_w^g6za8Dsi+xL&@+Aaw zYIWsf2de8y=`{Ak-*Ad+&n0KJ%43N+IXMl=Y+@@k z%~_j1a1&l(7WT=&y?D^6rL7$VMf4erS~q`W4y}mntKR&uG#%de_IJ>F-L3V#(+5oY zMy974_B2mbOYE6`OS@?;pH%YU%4}Tz*8W4m_WkEcJOY#u&)MUknt_3V@{{%7IIg+( zhAZ88un}#na5AvCK_JQ|(Wsd?W&~~VfFM$t4GxbyKdtif=bX?yyKhWJE%oJP7Z#EP zz^YjQ>Z8*3qg_?F03@ov;c-6J2|`6!%T@;cgz2|ZUjKc|Y(4ZR&VaK|0jZUFQ&Glq z(=3LYf?4x>!MAT{?*F_Q3%-8sbfb2EN3gVWb3)iYCb?x+fF%1it^6;Y!t@@SnNQDz zak9&I4N~S0vuE07Tc};+59Zh+UrlW(k%(SfA3w;K@8c=dX7tv6O-384c;nHdM~Pzv zBBsnZ)*^zBzvY9+F;#SdY_XU1V{~sTt5)4*BY4mitZ)5twi*xiEMIpoz%ZwZM3!E@ zV<~gzt-45%bMP$8f{fXDRa3Hem4JkHjR?03tkVt0_K8+v_3=gRGmCc$V^xk zyWX-?c`F4Wwer|09;s;3zkMjZaFT`YRNj?kkuWCyO&3zu6oHfMEr3#SGjQduPD+E zHtX6?pT33VfAaV@s8?b;<&GFxUnsvYF`xvmJ)kFw<&!waB3D{Zo8N( zVX&4Z1fmnP_btvXOkuDNB!byTlqM{nT?+>n|C-A{QTJ7Tgqem9|BQFTD`G1XXpXhD zw9KLhtxKPjIwJpjnUnGG6OUmkYvpy?Yk#;E9;RoglF2Z8s1tLo)ZxXv44~ttJe)ao zxnmH6*$`V1OnOks_HS?ZZFO&OajGz7XXuvhO+jWPuW_uBl;$ z!9ixeV^GMBbzq()*lU%mo`(UgD;2mBHAlrd5J#T_#ctL&GqUF_nX=I6WYlEB!;R5v zIefNhi;H_?aB$wG{Ch2SIQPh2ri>$uE3s1*XB0iM+ha5Indrr7Z`G4+iKD!|()zYP zo|?m*kr3L6f=7Q_ALA~)Xu@;qq;k8o|JF^{|HU%9+q=<(nQPS4iTTdUvfk!zqp4KZ zRyaS~Q88`y%dEB{x8E)k%O5yfM2+5L$#=+|{Xa~-WmHw`_XfIYMG+7<;3gF$6{Nca zNu^U7MCnH9R77b32|5vDdriJLglgxXXHt zc)TE>wn)>cVP$^N8~w??m~vm9aqp`=4MEU`8_#lm`bj_}eJVv^c>|xaFDWCH@S=bd z%&E^ba7ceB<$U8b0cTZUOaHM2J+?ar+>#x`1{8((v{;4!nR2wyipr61Bvm>xnSy^A< zvvga|%Y?2M&q&Dq2PzhguQq;7V8u5bx2oXGt%&^W7(I~pv+mbWyrNgl4>~UIZqt*& zn{mo4BIL&f*uMUI1tzngXlh>W#XS1b8OBvV(yZ3{0Gc~w-Ww`5iE6$kdKESY(SUV- z3wBecgM!PVC6d3gbZB@Ose6DiE^07MiJc8g0p^Fi99^lR+%MJ*?ZzvJICP7|=IB*bUx5jLGh^DAOPVF#VYIFnl55+f zl_;1YTrI)7)p8%pJd&d&G=wPL37tnvOUrzmNLV*lh0)K=?F;Q~)sJA+nR(fM=R`wG z>q(>4xK$?U$k^ChDTbN1vgTc8?|)ObUB)fHipNC}+RI%|p|_3IqD+BH=(DfgGOm-Y zS1EV?j(oRQM5w}M(6wATyyU_a{(p!5+L!49te*c)nJ zp~^T=bxq>;?_Ws|e;H=}+8>7E)?sqa0|x5o$3sQ_-&PB~W5!Y7I=O~arTPFpYtd?)H(3WO8(Wj` zQVLGGsQ*65Q4uIC9cB}1K?lC0dy0fA*Iw#TdVYcv05Hp?*UePIE=6kk#0fRxp;&9-MG{ zZa+x@-V2_;2W+lFriKK~Hi7F3;XLzI1?n?hh`SA%U_B=81Mcar_eTXn;I7)=`poPcA%Ljfoe&r&hH2TFOnXoXQZJMQD?ac9 z#C+u&8_Zp(%Jb0}mBFNTJ)n-u7UN`Py@%pz0p$KuRu&!xp?#`>PiBy!lqe=n!Ul?o3}4gN81aBAWR5+ z_~j(Sj7X_xIzIth9FuyKw7veqv6i%IOYUA@74GdKvd6eSSTnFek@s}|;3T4-nVc}G z@p|?b(|d$F!|&tV;yY4KYZbU+RpwwVWYgMwUY)D^)PwY|QVhVcp=^z_KdhM#)*- zR?V1jyM>J?o8##5mDS1)weZ;s+nxkky|O2lYmK>Ji*_kw(P0#bUv`OZh=EAt53CWE z2bv55#F|+t*8=2SF_>ZjM@(BP+MCPqq)!vZ77ATZw!IOf}SVh%~ z=vYHvhFxeG{{T+c3_h3=P#7Q|*vj`hWPc}+0UZS}|yn~j!P{z?~_eMyF|bq=GQ zO`j3M^C6ShjX34^ccg7?Il6?GXu@H1@3kUlNpZsdkIUHZ<7lNLJtDn;H%RstX^Klb z8-7V0JpU56zZx)e&q6{CE%JjHg6?Bc=x-dGW)H9s1auxK#P#szi!uD>Aju{WQwio% zNDCRLQh%Tx<*hb*Tk0A8i~dJRQxDKA0v@>^s@W6nsMdWWSFvMBn|%=;ry-LxLq|j+ z_gzgtLq6$y;+m-^-+8XxrYoErE54O&mvV>kbf%u>II1xd_LuBh`uL7_a-u+$s!^{!x5@^pv)fr0IFztA&xQ#Nr z#?%P)a6XRE4o~t@S3zHUX?p3eYVDcW(~OYoX_}vkdzJa#4Nx&Qj3~Wg?|&W_UeSav zZHE`UrX!<1oHFNzbB@-}+#6k$*+DP89hmcBRgjj^iszcQfYs69ZOqE z*(DFUTl~*Ac;nu6t*Do-ckDEr+9U6kH}Odn_vQqM4u*V0_ln2#dbnNZwTbS^aTBqp zNk-76xnkVVy$l^ZoIO4g+8^O!EQw9xk+P%KCLeQ2i);1+)^~Nn*BAb#$ljWLXN}9# zCKKmeD-=GLxgBlM$dl2V%aIiaa~Fi5m%uyeY94l)&w%YthL>OMryWw>85wzvmott6 z>bC5^vTG6R_%nT?dRaqR^Y8Sv^U`N%W6l|d&-t&CEG-~YWBo29cZ)px^W~8kFOCPtI(TCaxen(7svE^LZG{Lq-f7`E$xh<Qpy}}kNmxpG<-a?PRnBvr z=ODH%b(j&Wg&EoJdpYg3Ts(c4HjDkhzNb?1&ga6y&V@##!2s-EO%*PjQ8}3anwOk{jtr?1)x|y zf0a$X!zSZ!E55hzSAc!06VIT+{>(}+wmE-#F4%|oZ0Ot%eIy1xOwbz%WUHn{YO!0o4DSshkmJK-zRTe8;(_*L@YyJ6 zi9l%azj_HMPkMfS{_Av6u=$iY&EALa@v_-0p~(kw7WS57jm|*_fk-ZxVih6wvC4s+ zpeDjEeH_(gNdwKTug0wg(vi7ec`-5U9(z>Pi#IW9**wZJG7*n`(+EG)+wbYzb3gv~_1Uit2V~ko+t5o$kEeLUoaFnnk@$ z!6xkpo+n-e;*W1!#g8EPfFB#gi|gR}AXGhI?AJHrJ3o$CqB}hYF9m~~z;!o%PEjhj zHY+3&t$eBysJeH3X`6k=8@dZq-+jXp`hRKmBY7D=c(gB9GXAr>Z4}RRSBB9d_vOgU zD-mipqWrSv^L&lZtFKOr2&2(fgdaytZ!T$Le8H%B(y2d9Pr7>>_L7BW4IzwCq2ysAoKUFjttwbs{qP3_-WJTh)?$B^rJP{?JDFdB z={l^dlM)wKyfh##*oWz-@XlZ&8w@Ug{?wS zkF*@k%x;Dd(?^0)ISdg0kp_QBs5fnvEqjHe(*k(GO?2{v;&j9yK5#}fBir+Bi*aaL z?{Fp;nij*tUp1|~X+N{L;y$rc20Bc3;di-7RuD0y;#9<+TsbjM<3sgW(5usF^iVhj zC!?*O1mjdlD-b*oqZ9Owqpi!$^d`F~ZoG3*(XTfW6K*qa{e@WanP`B6{>+ZM$@Z^H zye)t0)8C#tM3Jq|idnbcq(;s95xPxIHwl0G_|xzDmnWWu@<&PCTNm^C?FuJ+FISvI z90{MUKz`*<;?syBJj55#6)-76`)eH^o zTz+kP1{qB#bFj0A$A)*g?WeB3^~pVc9Vxy?HAt&%VkSahM9gk0+zpILVk*1Phl)_N^9OC`{TSXeNEa1l()hFvc2H}<@Y zJd`=V$u@L9Kx-Fxvw6mP=`+Vl1DafaJXpNXx&tX*cfsBLJ6T7co1|yBVzufboQfM8 zygwO=pAsH2BeDk=^57dIun%y4MSQ;OvC!$&Ki?a6g5ta+c6;s#t=(uD9>T`(c-LUn z8g@NNr8aV9>LNPwTTiL>n0rJpY`lb3^zB+eFfgsdZ5trc-t&D6Q{)8`LzDgN^c)m}XHKj<$uJpD`B>EB3L!2Y;QOp87Gq zvV)V{Tw>OIT-Z=ka~$2SRrV^hk4SJL0ETh%p+fzUFVM$iNb#Ityt4c^r+o4k<{l{mRbRN z^hBh7A60UQtUfW&i+}cI)3=L?B=W~`Fl#ZG7ynq~V|i={TGSXtsTUugR0Pk&v8QPn zYxVSv%zi`Pkg|B4@U18JOVkvir(&Gp>!XlmxhI$P()F{TZTVdhiO9LcRt`V8srhF< zX}*h8WgGKs)XQ3pvYyH9Jf1ofm$i%Z@Q1NHW7f94zG2$*Rf??4@YudQL>HfS>4bl& zH*8NTQjSat`d-64c%|s=t)spERyZOSx0*(N!J;IDWZrzrK(f4tP4eNAN0|xV)stIA z_7VFoGz1hB6jie!)CjT&M@e+O3MW23zG}Bm**m@=89T&xWh2{`nntrRyK-qw6U(u7 z3xBA{=n8N-R(v*x-y|Co+_Bev7AA;gK9Rtka+P5mCeOPD6*F}QQ@k^7+S(Kd;shEI zQ>21@dw$ovH1S4%eFn4E=(Dq0sYH7vrt5ljUi`rF1VeFc%Pbb&`cX6in*}^sAg>@C zP|6!Lfvn|Kf7k#FKFaFhY*JzHni|{6e3v0_v<<#CPE=z$676>IO zd2H3Y_mba7;tzdN-=Vo;%${TYfwfXwr}WNA?%e|oJa6|%xA2|q?T0@kG4VIfK0=Sn zD$7E+*t$4xq_ED~MVGQ_%C_}bbq_rS$pw@&IP`Z#h$5B<5LE^1o| z=Qdw@z+98)Z6Osq-i{#!o3oEI0$d8GndDI|Mip2~^`L#zHFSPZ961QOEzsz}hdoEx zaEOP9`P35UhQ?_{n279pj+Aox5e~wk;p{om9)d49=ks@WX${}k*WT6N^2MrjHCcND z!vehfI50W>1R(^{;|Zw@ThkiI-;neZ`vv?me05A-UK>CDSzvwpa81Iok3L=BE|Ftn!i^e-nWfue3?W4V4?*C~4CJeik z+xhY%H=qa)|0Ke_L)*fQou(wvB#dV8>Wt~`5BO7#K584F^!g#^4^Nka|AB!4HIQ+n zZ)C4tYD&?yW5JVXdGC4I+BBa;d+sAX0pmO2C>W`LW0748X*T2a$Bh9~k$Tr<8s0HI z%qZWO66U&4OS>fDy36`tNsg0lW5Stcw2&_CoivM1ZnHCyocz#&zCSxhS2v5~Qnu@Y zC@a3(cvsnDG$bpfjTX4vKaNmNspYxSvz;esTwTl`o|-#~6ldO-AZWyUxg3RUhTd8cifofF_{Fv)r|Hgg z{jw{z!gw}i%C^E?SB>jm{+v1$XKIFoR0ES|xuZqWl&N>;sg!)G!2+#l#DA9gLA_og zA#0z+a;_5NVk52$5C&kq7xDwMi=5!RwR)rx`0=qEF0HV)wz?;(uP^t-nm1AY+!m!2I^wp$*s?&kNao;hlV4Or7r1 z($XBn7PNq35g-mkVK&oDEXg+wc{3IRx$3Mi&BCIHPPTMIk#Yb9DvK_3x?-nr12@10 zh`5pz(Nbqbl@im3-v)4C77e z{$6@ae;}W24Oxe2)u%gZe~X#xni52}ZqJGon+ZqXf1tlofv^~37XxCd^J zg^cdcfc7#uR@5XVu{D|i#O8?nq(xm%BAydZ-V-ZSLdL8>ohG~;+Z6SoJmw`okK$49{&h`K)J(E`WFhKR!=c?@;--ERWV7 z(=n)4zo(0d8zd>|&~AKXk@>cAKi*e;#_$9Vtws9kQY^_)h{co2N#~lzzxLx5W)Qw9 zewB%uZ~n2x$q5eTa^K1^b`AM>NC>_dP!_px8~OT*gZ3Yq_DyhhnEePP1-1gp8h#@( zEC7@IkZ#qmQJYhP@xCNZK&t4AKhx)H(@vW+(m3}`JQv~t#eL%`kgD>bBm5ej*#C+Y zaDlFDduM~i4M{Ckpr`__Pzro00NCF1+O+~7ME~Z<%gbb&pB;U#ph|p>Txz%5IdY4O z1t~wWwf0hv;de0B=W&tm@v5TyT?`H%jI)Sglr_6=OA^>p`fvM-|k9>j(3?QOh#hhNpC4 z&|!6e&wF}+4j5%sd)1grCil187l{|A=O0wOIkSkn+d=%g8F?Dem%eMubjIayrX}M8 z8`;b04S5R-3|8)qwmg@pIVq6#Wx zsXO*yo)Ggqi#rL9L(fiZGstRewR z0buMuLB+ZWB88tq=;30M4fIanvTDr`w50a{t3!}eL~>sd35<^ZCl|Y5*<6O3)iu zC^=e})&3#QW5IZ~U5#Dt^Ga@}Hol^wqwxK#d|;&-nE7_;%=8nd&RgI%5p5DRGHf zI&q9EB_;0i?ZRKVv?AG5OoLmhQIEemyAhY!n;X$jeBcWW+!){K7HBc&My4Pk_LDw+ zZ;W)$i)ei7=yT>b(8h;+;BYNhZ&Z&Nv{KN1X+K*Wa$Q;p&7x(BRn;e~X4>mb*m#@D zj<}T2qVeNGu-PJ#d4US0XtO~VjvSr_&Xj-gH@h+a0`O7?%_uR z{#-t#cII*61h|?JD`S6-s=P?59Bf>R3Z)z`K`JOvzC2Gtt;vRE9Dgw_griZ0wjewK zU@co5BNy=-X*=CRk$0(|aHNj;#UUY^G0pZxuc6JL8vyPramz zAsrMNsvkYU6#3qc7rmo-F?1$%pgYb`PHS$HS^66tXd}A#uX^qq2vdqM#Wh^kzAI1q z_bhSTfxyZADE6teu-g1`$xf9x7ncP!;gu^9hEFB05E6DOQsT|K(Fox`!~;8MZ(pCe zOIRh0j|6uX$go`3xDLGJa(3?1#q-jzPzNj?j+Z@jr;mTeUcknZ#39O6%<)+ov@c#) z4&(t|_7HPWX>uZlY6KrHw`S7Ud7Qj0vmlu^SO1x`GUWxHF@-|bj$VM2*mGVuHlUlrtLD3EL7lR?O=;6#hi0 z99UQE8)HeA>SCryrKXVX5de004BT)h2}K4&^Z_l3J#oxnN%3A`wfRDziDxNQbl z!|BA)0iuK{V!bBRX(?GK`L$D5xIrs^DEg zMXgQk*(|I~Q)UWrw62X9YF$BgD!Sko$1D8RjC8YnY(m@!bG5)v*!ozUgi`GOeCfG* zf43f^ID3c#xG%B2)O*ez&l4gXufWbMX0G~EmeF<8cwaigN{;#OqaB-vJ1+ow<_?|P zs=DEi4nWi#Z*dzf)u74TNo6;wZbbR53q^9*k23$(&-FEZNhA&KWo$rkuPQQL=ih#~ zbU)C5-)S&Zogq8~9}}&u|HLGhoHg2N$$b8BEQTBXyC6NCJvxOeqE(_>CC>4cRepjJr-;UGqvZGN{|XbXXTTxPB=aC)38wCDn$k8nz%ac>p%N8_U?*P z*Pg*}o_PJiq(8lrzb@_m?;fxk^XE3rdC=^rd|cvL`Em`f$$m<+Phj=&8b_ait|Y*$ zPM{G;W))^1%>?r@n%-v<3vt|Cd;MrPxurjqI7y5*Iuwt(6ERRhD90e<*gUx3n-D5X zyFh18h)@`snXA+S@W-wZk_o7RHmORXsEd*FfMrVa$dr-9`)tvtzO8#?%~W^+a$Xkm$&^b z*p{;_K;Na&oaD8W(mm-CS6oP3cde0mvFC zRm<1@arq}M)gvaCk7lC6%=;5o^ez!~LFpo|2U2T|i=8`xY{y)&p|&m&ROdkM{D431Ew%%om^fDouh0zAEB%^^h1@aXKPSe7NA%|e{JAUPAXFSUZ*@E^|6h9s{>ceQ21V7lPL2my znq*Q=dx{xRe)Lwzpe&_hLXe>m*=(gQ>`DxkKl7y7idB-l&3rg0D4|7nF3e9k_}*{&YSdj1&7!74U%h$jEP3bcMnX;g_W zJ|7@LP_Toi!%4`_<#*opuiTd~jYB7hCW*!l!~VcYb@ zYK*XI-YFbDvL@SLwQz^Fr{A`FA7Io$!jaSwMK0E(pj+|5l$%RTqeoZ#58*!P$m}#t z19TUFuO_|_k_#WPtR_!Sz8=gF;N>@nDv^FbQE}%3ehBtgJ_&caf7B&|0W(={G`d3% zG)NxBQ(!X?y5z}!m}@`aW0!9UTgdIr%3QFTFC8i%yfUNWp0PKQo{l!dy+Y16Bs`xo z!cZCnO#^Ae;|947TPCulS9_bD)C04QL*r?sD7ObQh$KGi3y>dK%QbDH=r`%Rb72~k zAWs=0NoD8jBj4$pw_(CveUV%m%F&~CAo{UgC-`%Q)rvjP|3*b70S0lk=2rIqAfs4X9 zu7}_by=s@+Ft{zh9b@+29eNgVYW9VMmOVK*WsL)H2L#6e9KF!E4h`nx>lKdE4pM>O zqnEwaYimNF^w1k~f<^neMt8GP1PklM%P^u{7ymv5x3f-x0Y2KG?XQuTN9^>lTwauh ztB$D+|EvA$0BqZ2dfEVv@K$}SuH56m%lrC!tVmVK>*z+0d+9h5y8*&WDU+dC81F%L zhy|l~Bj_17Tprp!IhR7Iwm5g*{^64Yx{7CMzR#ohdCh-ZqNM6LP*zeZ@z^p)nEJnN z=#9Dqy5!{K&cnTgsXzhplZ1qXr5eL?Bu3=>t1G{0UbwlL!g60kK-r&m{xUn883?ze zrM8QCc@$2Kf{JGjq>_NpLP}a13z^ma&!!0ZupBU_%%r$>H37)^n@(R>7ryXSryNrB zCI4lQ{tBkp-{d zqR?*kmD9CSmg)3r*8)!eqmlRM6*F4Tfs5FOb)GiA7iHAVko7w0&0e zV5>giP3>iCr_6q9veEAiz7lC|iU}O(U^=7pafTl1rlTAEnnIENb1uy9RX^oRkzpwH zUa*q$RGWOIPu95~D8~Q&#+fqazBEBZr`D_kj;oIx=3VaYGF7R>0%c?j_Tgi}mLK@C zT5THlqywo_b@A*+Oz_ACLI;*vw4YjCvYn4yo77F0SB$v-D94n;h_KeXZVGF%wGL7y z?if^bTH1-fVZm}+nBX`&tnT3aRybXTe;*w5KWEKRbatb)Hvn&zSJ`fybKg9#IGEk? za1y#kfI|L5Y@`Sw$_Z|Y8uF)+{Eq1?m!ynYMjEF@=;7pbH*AWL>+O5cQf{uoL>PL1 z;&7`$806#>rj-}P)s5bo0fQxLQE?_2y{t%NEF$q)d`E3eNO1|bXJP`;uplTHOoqUS z2RUaz@L2!+!hmn4phj@h++P=RU<9vnHJtLOh_3NLV$<~UR&A>20faaKR`3JS4%!ZL zlC6#Fs+g>I8~Ovjgs2vgP;oScC!$^xWgFck!>UeD~l zRfofM>sCpw{ERhIDKVkx%9MOHeifI-!qjKVx20=@f1Db=Fygq=Ri%yO5R$uDQrlaE z**{_8Xc*4b_WfwzS2OCco=`)udf`qxq9Pp0Vwr?qyi*Q6QYXRAF?)ctgzls)?N{8e zBu>TD=eYNdFh{MLd2!An1=1Z2{CluT^S%(x^9OD&QMa5rk7f_c{o2`!?&6iS1)~fP z*hwy>bCLn{50+g>p*cMBgNuzJ=^<4($@Ii-!qTkMAt=f+;v%Ab-J{ zl52d|tM1p0pMIpf7-L+wK!2|Tl=NNfm3#}AB9F?KMMNuHN`w*x5}#BEx6v(0UYx`4 z7D*O8MygYURR_MYev5DUYiDW@zch-!Eu307!1%>?pj=yC)42a@2e;~gmIQz8_pS2iyNi?A(TNJAXhsld^{jbPt;7$O<|0jW9d!EDQz*nbr_$7n zLn-C3te>Dev}9WMhw|0G`*B!x_$?o#P*R(IZL(Ytm*}n@^86Bb$-aTEIpbaImCOmJB0R|yITWMpOi45*Lnr_eqDd$e2x{_gd# z?jT^TXP(e{)Lvtz9i;v14S}N!8{S59Cww3AQ3+daYhQ==S;JzM1eOb`CHZScDDIx! z*S+yUz~M)4EX$Ie?X8cE0M@*9H1@tb<wxQZ1R`~DorGB13P6lFs04q2za-S;;&}L1?gmF+f^D4G$ApB}2udMO>rM`D#5tr~TeQcq zRh=KNde^RQRdLl1RQT#pRy%WLJGUGBspiTp&ClVtYau&eJTr(8@>Qi3o8Wa*Ey40S zYiKvXV~(eHPcyHp?h{?6dqVA4!TU(nVc9r`p`^m-fDbQ!ZCU^Q?>z`4eL62Zp5d#R z6A+o#uC-l*T}l{f+jXCoU8@iZf}uGM{AV9fZ$Z@^H{>L@vHxM78F?cDz;8$2fJAMrKg;U%mASTgRc; z$)iTKCNpX)b>W{9v8{p-G?x~aSP=|%zLx+wgFV{}6#D;*O#*afF|8{a6d`midr&Dk zTKI#ndtsopgdBs%ynp~zL1vy|HOAJ~7Dl5}x{Wl~E@5$revA3Yx!nSpEvC!X3|;#G zb#Z>Y%gXA6RS5H*xJ$x*Lcgx3SZo{Oq(e06kc80F+iSM#yWLIgSR45NS|02ssz|}q zfdt<{pmr2|)1@?jI}$+_gf<|QQux{2&}o%5OC-eB66*Ju8R+SkQojJ z^uw(=Zog9x@YmLY6lSE_l?C|3nK8{vA^UQjH|&bH;AxDOKbu1;Od5AVL8G%c-Ei{BZX@SVH}cz?YteMo9YjLnhec zsV!4KNJ`7d8ReEX(|aY@kXHHrpB8{kjWxw1PMGEzrnYv1sX3=twpkE(BbUqQzL6e` zCt*9*daDKdEcx5;ne>}L(34!k4bR942|d?wWSyxe$CQ_^3fN%VfUq0nUQ|9nBEU!g zi}lmH#usdbBdQedXp{*Rg0gC>WL#C99o&jQPT(2x=41_H@Q*Uyia(AmdQekkGpaEW zoqOlC#jkVldjcSw4|ypQJp%d zt}F_a2DMG<2toI6+OXlTacfig&)VypeZWh}XrY$LT^y6q*)k$a!;h+r)nc0Xjjwzp8IVNS@Ohp9Tk4yDruok~+~pV4D7$Y(5Z8^e-lj;$`cD6|w#+ zaWpOe^N7)39JUDk31z$oT5EV?X4fjG<@nGKKpY5D4X_>h<8DJ(lfSe8&OV^62yCS5 zv26YODye!ZtF${*e`rU4emCo?Mvo4c9&Qar*X0I>@9(rCPrPv9rxlnMd>{9XRtkMg zm-Yuo1s{_@&btZz2bMlt!sD}Y`pp-Rih=duM3&@4$y0%V&9Y=a&|Y`uede|_mZ>`- zukY)ilDH3W#WODiio^>M(-??vH7OW~OnAEF0+$S6{$d{=|Kbg^)GMYess-io=`4&H zhqRcJLw~u?|AB2C9f4j-Y?*UTwYoLaxOGz~%VkWWG^6azg8J*SeigNbP6#)AX8Y_} z4#(bm-?nIxiqUK5I1a(;jze9Zq4aJ|QB{k!uI{%!6RR6g2R)WjUm%1S zA?GK$LF&|-wY*byTWL@$RSK`!tnpHSvHmJ_GF!X(PdGj!;b zXf6nx{3gq=iy9NIC3|I|Y9QxMFuAJLP~uKn@#=)B$uNF6K=c(^!|)92pt{><>roMT z8^OQcagv>>j^o$uTvdAO#BYV#vwKsc;IwCvLd@Ddr3LJN8fyCN)ejxe%yy zUg^BCHKrdtbkC{fyWo+Bc(um3CCbD_+-In z^1wtE)qmdUoZ^R3mbkL=Z}|rT>cceC^w({vrOv#KqH5v2!992w-B}JnU9PIwC<2z> z;+H@A8twS>O~h^>JKHGJ~^WGy^#&@IqSltsY z&#A!@TJ##K&q7Cn#X@_0_8mE6mg|>&z$N2vuk9zwuaTBfnW&aXn} zdz*<3kr30)=fn0axG5b=iy~3eZ$=0v5BPL&B3BH18g*&IEF3G-&K9}7lR)2OM5tjPBx(X`Fd;`zexP)lO5isv#DD>18tc;t=m{t zhe4J$qW}1Rd1};aOX!fujpx_~Y;g4SQ%IvR z75;Oz8XnA?L z(YCk_0;61L;NSUH1n#+pAG@Z=-y%(LwPOf~gYYVlNOZOdqo9Hi14{fbI=p@IeEn&O zXDkwFbF{OB1cyNyiU(|zLh^boyb;zM@j`FTHY5EA5; ze%v%9I`GcpFRVGIM6d1(!4^)Z0d;w^y_G?|uQu^-oCd|2Kpr`AVg)h{AmBHVge?e! z*gQD{^Q{nKp+cZ!e60yrO!Pf=!w=^bTv6RIYR>E zysr$4+4GLoRDAxi?bcATCuP8*B{9@M5&l%vuI^PgTiT{LwX53HQ(qfK>u>Io6{%CN z@Be?3k_I1o&1_<|*CT>myYUVFCpp%?i(R3EAm#%n3XUvkoVkP8`=6mSXwH56URwTp*sBgd|%`k}sFXZYL0+vYFzmqo(g~8%NxtRX0|L^|;-DMh5St zu&Rwy%n}7F^Jsf9dh&4y?cKsB!5oFn`?cfONF#&gqH|qx2+79h_V&}J0>!>>=>%^k z9GqRRDt>Wqvz!4fRISk8aupi{S%g~Wk%>(WkAF5?H46yDdL zn|_9I$(<9|MCwR}zjj`|TRFpn^&U|w4q8^h3=6CcAn|{oF$VS<vMd zt9(zMBWXQ=OFw|fTSVOc7J*`**u08ilt=Q1|95&MFMJRHliqhXhP%^~bT;R=S({Ic z*ApY@+wD5*+W&YJm(&!Ac=>bPHhRzQr>YZb<;Fav{?5+jCh^5SZV!FCNM2^}vQ0O& z;sKvTx34kg75QPA8|0itnk86){h|m4}Zqo$kTH&PwOAe%tW)6#I~Sk z5b5DS6S-KK=fflY;Z*Db8je&-ys8n2?NH;c%ms}ib(M0l?WiJHKe*~y!@|m16e&4m zA&;{vw4YF3AqgwCoUk+^=hCyX7B0#Trkpk2AB-LHmw)Sj_Kd?44_8)7miX=Mw@T`7 zbLD?tzjKsVY97h#xXb_McGGp4KU;}b;q_<>VfD^13cFmrcc$TTF*PN2X-Si# zlS!U_{#S?VhFv%Qaqhiv>2hrFIqdw`Dc0>e>{wmDAdvOi&CrYS^WP5Vwaab`H6`x1 z0g#?G{kMT+7$5<6(kAT$cm-ZzyMyQ-C_@o+bjP)P5Q?3+f=D%y_gQ2wt#-BmAD=1Y zcpX9ljZJ%lN8OZhlS`!NhK#Z9k1NSS3=-YdtAu=UpGk3H&)q2WUE#ee;}15^Z@+i!z^L3jztX@Nk$HEtY0P|)FP zWrscTzsj!@yKoK^p&V&1P5hbAo%I}SUd6$xiEzH6nGo~re% zCLiQSy{;Y69wk*YRPH549ZOA1tY9RL=@khFu-CPygM#v{u-CnE1Ok3_Tep_b83FdY zH)~bJx?CW4TiRH>R}V{skR_;s2_00pmEA~ABqS%8JF9>fC>J>-b<2u|@YTZxzSOvw zqHw2A&Q08<@x-EIL8L`@FpXLkA7!b5ovy~CyC$RR0o?;uuYP~z_Y_jUhvix%Mw;Z> z`j|4=;3`1d!B7e2Q0=KewzS>Cevha5v_xVNUD|Wf;$QZU)t3Uj>?oGM#^a)UMPAqu z49B8l_8(*3S<9a|McO$9qOgc;&mz+WF+T=-EWPdUTIsH6za7P|P&~*-dxR%z1jnvr ztG9V-JJzhfN_``;b>ssYQrE19k~{x+m#qlAp@*=KV5C@uLj*p%(1xz z1B_HP%^-`%<8M|1#9xv`wU9!5B;-(B2ksTN+g%33HIfnrrLlRqRdp0!j&hxC zS-CogpgcDwYcAcJkN)t}sVbIBI)|w_wfH>2Q zQG>){bG(f)y^dv!_u(>t!>D`yn*XtdD%>b$U>(mDp|s5dBm&d|gK=v>Su>Z*@5!V_ z0Yq~x_)qQMk2**1A!-o}BSMd8Lv7h0!ZBJ``9)rTBEz@rCf6di=^ZRo%8R?|_*Jx- z6*xbQTgC)`t7z0oS$-qRT@0&dW^KLzZQMa^muT^lx z%AmXAG!2>iE!^>hN3X_>4e{H6t0&;D?`>Z&doQX96#-l`v{rt(ebnV;dW zj=m{V0!GNwvkm_jw1wYz7ib4Q=7aYeTEq?-4QxkNjzp=b=$G z!7)F}J=s>^^JMh^)RH+VE`*#7r`rz7MgS|^j8RAjrKS+w|HwclfUoBX$x9D%AK6^V z>+GrP+EPFH?0<1CbbdGoLz&&7j;3a8K_nM1ofpp3i;&$rl-E!4_7x@M|2z7&q90fK zj~A!V?T*$^eyz5KMDC~%jeNb$(48g21>uId4YzCCZ7#muwu)W?ug8)q?tU%*(vt32 zk3A!*3@#cxWP7i;{eAj9b@)S>(b#wC>LU|fClGvL>yQhym++6JgZqVsN-jN)|F0Gb z>s}1KkG9i0Y^8YBM}tgiO6h@n8+MpbLPAD@8}7{t@;&&e&N%gQnW^+~F~dh^H!WLWa?v*7#rLipH$#zZ1u1S{_nx$;K# zd-$Mp3q3(&@WFe|2OzHvxz-U+8!FfWzF8x0pBHSp#T7er$fVQB+r?*5?$mpK=d2z( zRgtAz?8ZT=kIA}zM&cO$-+Bg?56Y@%quqWXAkrfl-B)?#_q~*?WVf!4%=)2xKb#>E z$&^&@yxd$VeNSN&K?CG+fZ;Qoey#--kYM6<8S*5B7WIh#YgnIINH7*iFO{SCe~5bP zs4CO<`~T1(DWbF}5`qHK9io8JB?c)VAl=<6q8vg%P*Uk`1SCZ{fTSRu(%oI(>zViO zvwmwi^M`BJ%y>A@b6@wq_I_=6O?(o2HB*m!BRUh6h~E^YCP^gmSCs4_Y|Er;)`H!4 z({wxPo{Nb^Jev>{6m$nA2<03o2G)AQ%Yf)?St|F$)fTNxR@tI8hG0~vmH-7|CE1!u{y4ZS+V1ygv~5nt zEy$X9^3rubxgHSdgPSS%9(SSrZBHmYUMuyDsZ&86DbW4>-yMgL5iMPa&L-~5GWe=d zdP3eHs0IO^gvgX*gT%_G20>OW>-#L1-vi>4PNue?fDDaBa~lOXH653bMh7olnyv1+ z)1zpFcXlX_SA8hn5iwc1vKK|On~SO;6>zH4j-6W1+ICzKe5NuGv_|`PK*#Q%TlKy` zYTNYYibEPt7p{>P@UeK>h)+o$xG*r9tc@j+eR4|ZR5Xka?i(1G9;iPnABqBX14dIs z{#7>RFq80j0Q$)VXKs##LuOG_hM~8wzCL4;_tpcr`k25)6@q8EH{SzHWAm@Bp)p*5 z;UtiSZLWD9?~l5QivDsYS9x*`SS-L|s0k@;am9L14!ms!*Focht=~MGuqy8pyaFdC zZoM4nk;S^KmzQ{w#~dvJdd~QXhvUYfyN91` zjVTvu$H-+5ZTsAH~~ zs2E~ne5usNd^PN}SogZm`DSVIYQGD)j_x`dvyZ%7uDV>yKhM@6lwnVKc>f2!TQ;G_ zlSio^lKF|>YS1aaH%&AQ%;cOrXq)FR(R?jHt(QM`FQZG5Qt-pylrOT1ywU8we^N>U z2&C942;<%|^joH3;v;`5lWJ0^2B?TvKk2=0Nkb_!>ja*_-xRZ_mhRcIvMdVZrpC98 zeJ;lsjzm4Q<0WU-OpR*R1v4&Sr8PnsFn8YQGE>-(J;OAHasQz+$WdQvyrCDr)L2eR zb$hj8FK5bJVXcT!`(xS1g0Nso;Tw3kmlD2WXS7`&V8>|7(&)H5=WluJCH-;v={m!I z%R_qYllQ}{itz0k{*-l4(-Zc;o3JYnZgw_)>pB&x(RF5uYZ9G3O51GXpp@kOGrx^6 zGsXHKvBuAfgDN_Uw<|gi`&=u1GDQxVt~jL&`nVE@80mk2tC4?FWuAt#Qg_ZS2_3^gQ5!;Q&KzMmuFh)-G=i6 z)4R;CC{X0%?!Aq#OxT@0*gW!W2!+5um7?oGU1(`%H^CKLU_M+ujcvK;uu0AN;0t1|9J8ntc5`ImDv1A^@8jZR)fzL*aD4#y}(AC z-1Q}_1}?v)s%4Cll*zKECG7s%$L7nCw`Bho8cLT+IV*o>(Z|d*t=AoMLooz`_Yb8P z?quaE8PfAtm6Hn+)w&+vao@%Y-(QT^nP=o@Q(@H}1n4?YN7KqZd+ZPsfSU*x?5oZ)Lj(Lc9JQtqmoixfxBbFPFqWr}v z0iLcqbc1ugTBMafz!xd$#PET`Zn&mQD1mI0Rmm+`nP?ojmcJ!(XIgUN(wC$c8{f!-pynyt+k-|pZjW9;P+Ax zbdU_9@R&0dED!yiIc+*@1{6)cqlHN61PI{*+jh)|#oA8r$ouFf>?e4SQi4z@2wEt> z{*fc}M>8q?=GJfW$sAFpTRvTlL*|J#e{NN&5k@@a^zr+$JQlBpy-c>X$m%r^~hocA2| zEGRG;G}k_O(xOSUXY7<Qo7G`*OI&YxD+ck0`dMrn2DP(QsDux%B(J+skhS5G>F$BUZR?*{kuf>>fh*nP1 zSb0R)JkeqUt0cG1!hW9R_Qnn5YRTgey7T;Hy+l*Ye}Qn2|M}=#y0brrVNs(M-k|g8 zkj=l(-8lO|d?4BA{A2R{;h5PH%GUmk)0dkIC!Ma|Lj$#2OI&lbhf5vn?!kCnA|i`F zqx6_rAGlmBx70TLSp|5xb+~6HpHB4SAQym%%E^P9;kFy z$l2aBNL2`zzkeSuOmgorlJdgACu!&qo=Etnji0FC{juOeNB5}KbD_N9zjO;fC6#Hv z^6Bp~77i?n<;B;0UY5t;w)maB!|%%)Z#dL4&(0sgvBd-|u~rZ49(t1FZN(7e8vGLp zBZ~f4PAs*~xf@XD)2HCGBmJT8aY>BqDVnr7>w{v6WRUC3wHSKzB`h&Xf9)1aLJr<^ zru!9{0Jvm0`a(?inihSJSWRAv!(C}gCH=DvHz(&^0Xo5l!mnA;80Cyo0i2PXyXvVn zp8{Kjay1{kj*sNKWFTYygaF&ud-g!XzPG!7oh6bG;B9Ei%$pw=_yg;}YyiQYxuiws zVTO%n(XSf6d;uVkst7ugQ}>0&M|8PM#du;$=H2e4EVeF5RsEML%djpO6uwC{z?5U& zW~^!EJ>R@*6Uf zKagCvi)|mIb}XrKaRXJ!1YXrGWo|m2yPxQWOr`m+ilhgpZF&e%AHK6^Ex?{Mf`{K; z$_2;xW!_DS=KTbPS^Cj!P}$uX!v8Y_K#iM4k_T{>XPTwlTxr83wiG2wjj%eU2p(73 zUjxq)gs7353;^rzrS?eX>}E7?kF3ueWn1M5r#jiGyQ%(|W@8A>*2?@>y<8wi^Zg3x z$Mq)??Q0Qo&lREoN$p|6hyH(p$y z9rk^Jj88<3r@5Vp=E+`{-MQVmBx$>#z6bkzpQs$ItVt*SS8IE@S>D48`R=Ug9-+>@ zYtda#QflPUx5uFokKX7x>AYRtA%4ic>pbdT@0qBL$V=H~evk5t#Arzs`)0`dX?DTO zat>7wE^!l*Ev8W48!at-I4F{XhaO*!-X=QSd(!1_t?=4{@_76D;Vnk#iuYTB&>;oE z-K|UQoL>um>_<=F1`tJXWj+6`vL%FfkEq|NW3d$I29Zl}cLNez2G7dXQo$DbOAY_F zFEJ04w*r4Tr>CVFU(~KIv+M-7x42xo+K({Qab-{_U$k8+n@V?{Y#}tXPqNuHXF6{A z-g<7Q*|X-6PC6+iB_fWuU#cT-FURn36{Sx%cv(glC$`@Evv=jvj<-79BD6gUQ+@(x z$@Cp2R8egPKJ3bAO8mkUO7(LvoaA#!nZ8O9`hF8|b@*La$>2|Le)y9Lf#+$c4+@T8 zTE$=)gV)UTuQ6VUK~Hl2rIT92s_8%j1>RzLEdza6;m0`aYMdmeiTblQK~$LugLsp( zxgDuC`VV%WCYpCznbo&3&Bn+V;D{${1| z)%XEO$j0V2teEst?0|j`Fzxrr*rIjPP}c|Xx8@C}PGhysrxl4^k1|Pua4rp&hmh4l zBUggaOSPTLqP3+z+ld`X0uiJqnXXx(mFqvOL^~0>(g(z4{2r7D6eVH4Ji1J1pOI*^ayqTNCDHqLSzXxa#&R_PMc~L%w&$us9zG(c)d9??@KQ{YA-k5Tb5|ux$*X% zlT4O;iUSYFWQIwed>yvJAxSK~T{ThVB3qGnfWEx(OqK@CCo9Ue`tvjH6oUDXa|lz0 z_OjBUzk)>x7#YaM8x9Ys!XPzzTy98>BCoI+dw0da9ZS~$52@L~pRC@m^TKjhH`EO- z+1m2CY$M^`VkB~pU>|R&XND>)(cfAnvvhjiZJcP-gI$ED=}ygnmyob;N1ElI_3=5Ku{4{@XdTKqjIY zoL~1%%dFh_RiN(4cvydr_=*w6_#2Ad|} z{SO|}1_uVfZZ$bDAk1HA2ZEn47x?x-HjFfxQ4km>3cR?G)}FSaGn7>mC83I?SrO07 z;SvI=2^jzR>zr$rPSl%)g@wOgFFAO~tYy_rCDVUV^hS(qPJP6IsH_vy^~|0=Pg2Zl z0_r<=AIr)Xta@)}%G{a{^M55)D@cr1m`X z5FtquG0!v$__PY(ngJ^l$XIL?K#zLo2a@;xnMvLkkvOf#eN`R{ zYinRV-p{*%-w@RQ@iIc;IrwHJ@p$WFkk#2LUDJC)iI*9;^JU)^9Xd(pm(ju#gFQzl ztOYci66D(`6h=j)6VG?)NFBpu*qTi9*XlR!S%t8^W+Kb*8CiWv>PkbJCl7>$W?YOe$69)fe04{Nt{S730! z6%!NN7&1>b2AU55TpU|7YGrW;Y|c_8+FWfn`Cn9JvHYpv(Y`uYg>U9wQsCfNz}!2mK^yEzN3vqIrN`qsM|OBezOYcI5wT~M4`Vo-pxe=}_mz}7 zoS}kT#s4Os5KRC-2flWviDE*rluoyc4y`-N}fQtiUYr z*u|Ws`bT+od)R?c4h={o3?dZZxC2oa624HYGG}y=F67b@@fKEM`sK%k@22HhA}qfk zY|wKGZy-L)TMS1ILL3=jfB0#?UpUP&E{tVj6I$aTXFI%#cpOT zwG#R9!FO*130DfobsO=qYyIg*btbh2q6%nP#aW3L=v*4DR=pOvV(9C>?SCPiw0LII z{plUWdgfvaooxDae%B<;MZHmdSZVV1P|uJ?v8y#BJ(qAC)f_G5!hugCY|DTk2ubOM z5Yov#vBYNZFCa-hu+>aKcuy9VTUIqFw>~*3s9J77OIJ}IJUi3&`JR-X5s>{SM?#sp zH-ugJ=Xbxgr*-~*TpS)J4j7iG1+jBtx&^lx9dEUy);+KsO;XR0T|>CE4$$L_(!~PX zMR167lTX8NVcp%+;c|`li|Wmohgfb{%XMdTpBO2vWVln1 z7bsYT^`8$lrNJ4sgecOF7&VGutH|zD<3H?3N?%AN+8GcroM$es!?(1jt+FG zmcE2LR~j9w$;6puqktU=J*X-yS^~tnSY&u5gv5?3B4N>0@Kf`xpJ-Vz%1=fj+>!;XCYsxo?viEmj{-yVs9PA*#r=PF;a1rcE}mho4|F_*M% zQOEke8|alH|(aIyFB(tr!~=E(yW2(@z&i;&)}sm)vh|K3xip8*v?{_S?_0@ z9_Oll5qn!3EV5p`evm`?W~oS9y|dq?^0M>EmZ(S-8DT}PK~C`4@DXLA*w}sP4^ZbF z2zQ#)eTZhk8j*9{y>wnVQSw@wVfa8P&V~!G&#<$p^jhC>-FeVel=K1C0?i7##mZl= zW58h1d-4P_QSW(b{CnNJongfIF~2>fdq9nvL|Tx6GC`*2M2eaOIaherJj;*Y$^ZBP zOT6fSUJyJA_z}>|fHjVbBL7TBPs!Cve)8fEEt2P~+`i)W6+E+fhIlJm`AWW>UD~mD zqeIDl?mOfSsbgKGOD`%U5yCWLEzHPhE`Kvr2h%kQ?8CgB*#MH57SMUpOSO>e-QwW* zDF$hT1LAEF2uWHaRiL&5#|k0cUFOz%3$Rc+AH+07Bkp<&$wD9tQqyk>0V7@y>3%jj z=t`w0Lxshc&Z{_&++vOKZD(htX<2Iz=Q4c~)ttFPz&oAB~t&m2Y}$KQY=tSq)|n ze7x6~O37=w@VTy|Vv8>DJ{{hJU%D(7H&5ckaw54I=%oN)^}S&k@;#<}i|-anWR=mO zU$4^<;_?EberJ7RqAxc$I~&CB?{^FW^t9<%e)uQYvoqVqeq*LdfI>p`vA#ajVa!4< zUD*p2J^@i>QBWiKDJ^IyR8!W#~(LGgrNu;~Wnx!vHepCkpTF1=*__H8j0iZ+N)zYFu0P&D%1ur+k zVgiT41!M~f!wbM~E+Pa8=za_WC?=9S;Wqi~)ECv*N{AJ9bpVg?8vGW*#iH$ne;gb% zFxBYl7kg`PuME`ttWO{a&Qx4h{iJnMMkEIVNhYohmjOlGf@yCF6-L}Wx><9K_cG1N zstUP&o;oG;gw5sv-U9(|TZnJdH2>^Mhj{tv+P zO^-vzxVpYb&F}8P@{;cMvIrSM*QR?~`pP+puwsNyzcd>ZTKHqAu+bb7I*Y9ivh9ULHaI6(Ji*g{ zujl1zSquZ|bd5&lRgBuMP#AkijatAX6gT6&fam(lH}EW~$jUPc*6b>R>NSRb?#h9& zZGPYN`w$!BRWU_@90ROdaFx>5(lXhR#mnoGTDI1MmX(A4Z*_mCcfTtwxhH!5(M}r? z|1GGTEX4TUaKZ&Mxh8SG!;fOt6&`#N>D6DB-HTXAUnI19bhTn=o_p;n_e?Wju9hTBR3OFG8*(EnLSjyhBJk%3#! z*TZI>_>M&S4e%_Rz&QxVI09sWdG^07I}DT3bqD`0z=%T&eo|2NA#kyQ!=gCn{ zy~+6kgT{QW!9)~vdmLqA`z!;o0UnuYgpJnl3t;~CkQ1t2T18qj5tB5OPTqlpMgovQ z;S%#27BOI1Ko*7GK#YVfI6~?}S_DWyTve0YMdHEG_JB4|@<8tCNbS;lr0)%Oo=6p; zUet$hC_wy=E&}WT_~QZ=>Suze6GFejLNU2dV!`ta-S&v*7HLl8Hz$KUA_;`A0XOgu zY~He*F+U)d3keh?LXB|p$C!XU2XfhWRiU7=*1fY$H>hesekw5TJlMn;1=vHI@-!Md zAd;C_?4q~P4YJfe!Z6EWAv{THa?TT6slyQvUK=!38gY#-(WoSve8St)>Rl1|8}UOG z%cQ?~+Rhp)-;YWijhPmi^v3~^3}OXy>`g?Wc4j+Qh>nBPuqx<+r=JRGZAls$CHLKCt>W;M}BR`T6Kx7Q@VY zJ}r~`we<;dI`#(-i|(#>m|GHmu$js2vGj_tVScp?%-)Ite6&l)lDWX22XvI_s`ya7 zE!I?RXv6%Lxnxfctx%zXVgIiVaFudlWOUTJnH8k}ZdA+tt#DvY!8exeYh0Tb*kpRv z0FVgkC-U7z^k1_|e8h;R$cl%Cv?&6{V({7NncIgz3ev5Pv`U)t4Y6_#Kgw9FTxwk? zCuP1k|Hh=f#a;ZaGM1=ddsPLSO2R9ooMqy8e7{;^Buq$Z?ir@Ra?u%oGijJ9(N5~w zKI@??GeyI;I}>W-?09_|Q0mxgc)rIY6JMdh0YF+b{seaQyO;4vX#9hkXTF9Cy<=RawmO}rQb+yYu0_Zxae+cJH06aCX{GhgE^KAOKjUr z?8ET>XI)n`VDC7B|Dm%~zIWm2Ol@CwqtMV~VSyoDXiV_Pa%(^Jifisz!)akk+}aaX zsezAI5QP!rz@W81@ZWBermEQ|)AGPM=}+V^oTz)^v$s56Vb>3<^}Efu)BsOR%*dTF z!1(VoYX#%~kv$Q_k}03%0XddISiC&G6T_fzo3}ib#P8uJ_wJNnUBhAAepy)g30tPWR-bgzLl^S!Z9W->v@a_?Bs%_~zbeP<^jtuEt#T zBWG!=!z+7Z+*dz@BhW;XCSA!_c7_^4QNLJY^#WJe+~_=o;(y&1o(LSV{ce*iHPJfP zCU*O28R4Rko6s-I%%nH>c~)+(31wjJG#;pYTVY~KUs zn|jLi9=Y9<`l!r?AU)xHhBF>!X~@|n7#!nooH%t&y=4h&n7qb>s`?-fwxULL3V(u$ zyl25*n%-d917yS!Wtv~uK96Oe-{IYPWy>+_m(_bioXhJAX2K@<8imNN^vbexI^dPo4r0oOJpaSr=mgr{)udiCc7)$=#O_*)U*W-oA*xZv-}1-*3ED?dLm zAm^Nyj4>Z}#g*3bjZ*u#>{4O-H9+Si|29Fi+Ml|C(|lIk2W{qVF=yE_6OeBMQ(S06 z{rPcyY7wtn+Yx-lm!CJ=)$U$KidvA~6A(oIi{F7Ab9x~)ycrx@MHW5R6I_Qa4|WUv z&~W#LPC@eR`7R7%x`Nv|+|i6yhszIkdewSBw}iYc11zuk4T6)hfH#LM!I2JG1fYY2 zvP)l(7Sx}40!IN|SZ`T~Dz!U$<3%+{Yix=a>F=b`nid@A}N-g{tJ zrli27z_3C#hQ3p)&gY9sYu&8Y2LU<^evXcD?|hEK0OP?|qmVIkpErTmt#N*Twh;e2 zIj&z4pe069iQgr;uZQ&505-1?g2Tc8b732UCAL7I4S|g!UL=6@7Xxn3qW@hQx#tG!w-_-ohm;W#Z z@2)P4Z1YHv*K~{Gd%cH}O=xW;0hE{A9@qXCsi!#h=5HmQp!<_#7*4~yWm4T%%Vm7! zMPDeaWErPVa-UZ)J{)EOznx8DK-afIU8%g2^n!xUUxiy(Ryo_blv#X14RLL_XK!Z7 z9>?-ueqUAM<$eyD8A~edkbITe*lRvDjMgqGv+m^^iK;AM4-ve}ezl8s@*t9&Yfz0@ zXEz;DBBLHaDO?B2d?kEfSx_Sf0$w3&P6SXCpSv< zXmpe}?$hDrdD59trUqx*ZA#!&Xf-l~9YQk_nniEmP2gPhI8EblBEzEy_z}6bZuL0y z?k3xv&y8q7szoq&SphEkT$fOf#`C;-@LO$)p17dBkMJ>F{jn<+4)hXj3c#}{DF0d4 z?&m4Bu~YZH3=d@&aD{QcioERl)u}Jx$DiHh3A?G8y?i#8fur_PEq0wUJJqpyht|Ss zwH?kh3ATT6^*Kh)t_8s zA;U%T`lZ}j*_Qx>1j!%-Rj{4(5+@r?$UPgV%|*Vao_SBp z+x$roiWH!?fCyE%3Xx-Q07`{`y=$oNhbRcD|COKC9k1~#uY)V&9)y^uc0C<{b^8xe zqD@fe@(x~TRnfQm+gFf_wT~RJXSQZmr1`@N%2+k^h4q~zPTZCq{!b)u_fXQ9-c|mq zQ51uHpT)0CW#^q{ch;4U6S?Zo;{^f<7L;juU>6D&k>85XAL0F0DQdpGO!OzN#hiK2 zk|Wt?@6#feEGyH8uNrB%y$~(}fO6=UHUVb&G9a?SK#KFB^!7`42Zr9oGORk9MI|#C zD>lB8_{e5!@j_!Sn$z##hX*zMdnoA$VUK|PsVe%KS7P?RFIFE-gBZv18! zBs|jla3+s7^IEltrog;gR{4ErBdK~~>ps3ioi#-q{*Bake_M)dn zJJ9nQg?S8qA!Y{n7f1K7A8QedP*NR9-|n4(N1oPzEqs06^er!EN>ge|UK~ zO%CV8a5-!Y7JJo};VSWGUHhu~Gm#Zvd9d>~p8gi?g9;M@`*p7Ti5$w}mn$Rqv2F5r z8I`uy1T?aucnOzC*pfSS*}sc-#|~ViFgezF@p9ETzHpY`C}v<&QWjfG6)J~6X(eH$ zsEYq(CnWCuqQq2a_Gaa%VTFhBE8T-UR*K5YD?y^Ig(7yae2V6o+-ATym_@3yZ9hdP z0H}_anQivgd_Xm6s)wcB;vo2OqB`{q4ek7w)HzH$9pRqROsV3FneTO-o)_}dW;cb) zpm!2$L8ToH12h|=&$OUQuAjsV=eSXnwUV?_mNATUBxf?9V_GN7F-iMTu2kA~i?7q| zMW^WGLC2@yuEL=U>6mwv;W3Cr+lCG_=SdwU83zx=aMYT%Z?YATH1Y z_Xz_h7j%H1_rbL=ku62k!i>`W*Xl9{U4E@GQ$;}!TiBxwITkF%r*?H@yK7~icFG&t zjL6Ok8rtwa<)`sieWsLZvFeqT_`@s5slzsy(dhYze1+Eg)k!C7g{$i-Nx9o;M<14G zb4symm)j2)l8JX}!8v3PkvIe@a*r*l5x$WKFhI|H^H+w``4-Q4Ab98s;0r7m35&za z>FMd*EEe4Xe^NNBNE$~ydsfDEr6TnH7llPN)D zKfo69z19{O(e8Ug=5FSSh=I$3yhVs(JD{>+AH8lfmsdZaEq~liLHs z*x;)5bUj8s5c{=u!)mm&AX6x*mF@p|0f-`A3cMrzkjK*BK}gLBqt!IV@@-J=C(3Uq|b{E6}so1ZGtEhjyr!oXv7QL0*-?yZut4g@NoNs zxxD2e$WvW^OW3mIk)R}xwOMopt*AW-cAhx7ch+)GURTJcTWS-||9xcP?6c?&*%=j` zmzQSLO}ZbYZQWGOQS25mji-(I)pbdGz{`orh86SZao=0*R86#>PFYrWc2D+x_wuEp zp7QL|l~wL3xJ|3kUD{LdsfL z3wd-nWjBoD9)z~4<^9M}mlWC(p zyL)>N`Ah$tUL7+_sR%{P2aTK?vvy1BS_W3%Ui;|CJn+LDZ_%w; zqOr>lD++KVvBs0AMi$K!yc|hdCr~s+T8R!bpQ3kLP5(sS#}?xcu_oaCea(W=_(Oky zZj#c_4fJFVaoO20en+QFdaC;mxiV~w<93dWj7)7GDvNS0X?lv}w$XLw zFTG??sz|ib9bjZMa(4BqHQ>*H7x~;MivE?ZIp=Y6c{)M+lIK)FeT{+a6?p=MRE=Ig zgRTlkwPHW-0@61{`qdEe*8uENo*n^l$#CbhF=@^L9R(f9X0nQIt6gESkFGb8R`r%1 z1Z$4@PekpPtU7n@Ww0aJTj&LhqfMq_OF}gSN!K59gSY0+T9MvjvYOP{&-AE^{sdx) zk$NNEI_$=}b&OCsn==?fy68n*|f8kg&nxbjnu z#(&(u5OBY0V(qtudCIb9uV6)CY5LGNXl25NTa^M^q{Axo*hmoBaSv_tT>)hSegSjR z$?p#PzUI@XFQux%APx{xhuN?u3IoF$8hDGctKik`*RDgbl@Z=?5Zz=`x&yfupiliu z-c8X6E5=R-vrCucIfJYAk72HDX|_fQIT`dhl3rOy_+urRsHt8U*FG3lU1KM#K8x8whMn!}m^O)FnEv;8OMgQ8r>e$O3s zxwmbSBM))d5q?&AN=ieY>(=opd}bClHiE0AvZfU=lw8nL{9&o%77SV-&vU(eoBZt? z(s|kF->l3^8r)Ryw1$`@XL8mnkP_Hu;3{htF?&MLU}Ftscg*0FfEP4;0yJ@`YL01Q z`&`-PuEk%EQkBu_7f13=d)EIdmel^raks*am5B(%_~aoe^){(B#Yl;rlBqM3Ia6EEvP1j z&$BtQp~V6IAtWRPdSw$_yX-+=_y--Tf}OOpthm>|vjnnL&&h`~q2 z;{6;h@VR}tBi*DkNs=BC5(x4Lx$XmP07TAenOZPVBWfp1z&~is69VAU{~W@dNIV^E zWUC*rBqg5(BzaF7)-6+K^-MUeUUiw#IGB_p;8(@(?pRz7X7J4N@Plh^CEu^O+n33L z(Kv{d_6Y0}~yP${-Sj}8xKcmhj%L|c%OHh}l-{Vnwt!4d|H6qf=2c_?{XXAGiH+|balz-6$F}XXBHg3sAii|gR*COBBAp$@ z(9g?Si3?zxxMhkC@Oe2q;>&ek`?)Ze)L`58u0op_qE@`%^dL9zYigX0)hB~F`&hx3 zydj7>+4r3snWS?vqjOt@UhVY6Pb#+RoqLe_S~ob-pZw!PE-|ufuo!|#ZomVjfXDTm zB*ZrPyGbo0?{!@@cW^|u)WtpP#r4TlN$xb94(0FU^?Hn@@3o$;c@u)?$Qt#;4w??( zLUc2C8^eB1*broP)#p_cCVYZxJJ0bClh)tkZ6CFv=f791g_gzQ!q)@z`rmf+S|5Iq zDH^`97cf|%*WC7$puiIpFYqpWftv$7T8Lj} zS_EYCg(v1nx|H|o2My+#B&c$>rR{h-6n7dbjUP2_{K7ZGB>Is!u=lh?`}F&V#c*Fl9gqj>i3&`5AfE^LN*j=ptIT#qoBmgW@!9o#YdpI=6I!fnuPfeoP9l_Ko8PPk5D^5Y3=>hC0Wasf@#jo0Qc#2QK&1)8qksJvyrZ2A0NZ;>2wlFQ?jQDJj{w9|6YnFq;pXyh1 z#R~V|?`x>XSp6MO4UL;WS${ypO1H!y46u9n>>0qMlcCCGb&A;Lk+=k~x{6?s16GLE zMAULT<-8bqZH&jiBUae3Pr-POU~OSJvI&~zbfMpAF6~t&Q|PxqPO4G&X*8S^(7Wm# z06;+#IGO>q6HmLIi05N-UxJ3@^J%Sd6F!34^uJl%e5pH0+E2>Bd-Fb(&sVFAZ;D)j z6M6$+wmCRjE<_$kI5CXQPxsvtiSzs5AVmNS2t*u7x=#2WPr*t>UPT2x#sal^vtN?c2;FKnR~6pKO#O1clz%ZaG_idllUu-t?e zACEMA6rgC(^9@qv{#ui57{-9(-koRfHyj*9|$^vXt`pGZ6FXu*rc%$20o$^j zQob>b$ppG-5Y4@wmfU9S%&%}>&y?!!z zJ?kE z2`m&;kcT4Ya^)NyN;D52wV}9nzce?N$8Zh1X6Wj8?0J>Ez|xaM4ercgvW-Kx{fY40 z`hCfoV{?Mi&IGgmUrIdnuY8`okX!tx#NB*ixxGJh>UF*I5O3blKWvxr%~kK^1-q%! zdhvn@ti)AWQJY3k)OeO~9s0;0_hEl`s_Fu^X3w%;&rc*MB10Smv69mC#N8 z3bfkkGiuk77A>R51_Dwn`Tfnbmvma%dxCTUcadog(A+S>akFRzNPft;tm)7fEr<;v zhrUXaGBT_etI3SU=?}BRi0U&b`aVZ!b3h?1Z~|1y$jQZ@U*ai5xY4k6{7r#!tkDga zkYS#Dr(BBV?yDN4%3@DQ@@FC4!2l}T$jo8N1T$VU3glHF;3Ly!b0OqqwuzW2H(nfN z1g7PPWU1>0y*(Y67__=&^aqO{}|LDO#_C&*J+{^cv0L-)nIV$md)_~ z30fNxeFb%p-u`Z)ie#i%vOk0SDd=fmpuqqx7|DKTRa0L6;y-lO$6#p&zOw{72&YTw={v3>}G*1J`}`zt1rdm#vW$hvoI_v7KK#FPD|A=oQ*>R(8(k zdYe9w8>(6KTWHuiI5zCcdit`=`HLrb{Vv~R4ZLbrUA{C#lh$PGm809%=F|(dJk%KP z{l+TxdHwn|zA3Jl61BR)O&JA`7Rl!dT1Zo?qSKacOl;V6<;$(o^BE^5wNA=Q?|+f_ zr6}*iff~f`;yZL@FRFp3yGpveq5#{M?tY@`JlU(+&uMEWnIilyj|X^uXCY)A&$ei3 zT%SdYQ2EpX&y^F>W4W>S4X-+d8*P_f=(#PWXl53W>J@d-$rjf4tWd7e9!ubl(7wQ- zVes3!yN9;oF)XVW3!si3@M+x5w9!DlUT#a$9U~XA$Ujz26iFMy^GUQWFxZBG>VKoe zP}#8r-mGXvP49#~gEL8ufn6ahPTw67v#m>}AN2W8wgNhY4$@R{m*AcjH-Emom{|UD zyL?)vRTDwR>xlW4{cNKRvr3ZphF+xXWQYOEh=&CU$JP+t!m{tFLkk&HJ!h5J9(5_LHQ-?baSw)} zhH$@=>DnWS7#F$pnV)Fkaf^f%5auh9>amSRg7qCA9rlXWaq%PKnU&igHU0!SBZ`y9 z#hDIRHGzda;|4`*f9h&ijN7JNIaf3$V!lYaLJqSQKCb2=l5FnRDVe%wR9CT1a@y-( z2Ll;QdZIv#a0JVF3al*Q-%#LbFMZS#UajYLI2#+k52+b2z+Xe$BCzy;43}2y2WK#q zOoL`E41?LpX2J0oys-3>G@vz9BURpbxXhA+hX*6MKN_^R=ZXxnux8N@je*LBf6-d1 zU=8784p%9C(eVR$V6{2_TD`lE1h-ekZnC6nG!B=+C`2;$=*Nm8_L)4EY{mz5icLwY zkqph7T5jPQIiLSz?wj4S1y|iNt_7zI9abJHA)_}tFr8Q$O%wP^;NAk3S-qg<*t51v(^S?@p+Pt-vImYks%q!c7eX3((H%*dcbYgdHe<6(4`x9&V2 z#DBn{DB1;ER8S`n4OjoE?EU`wud+Xmb4uFp@Njd#!Sp_1e=-nX8@5uO*&It}Pi&Dz znfCAC;6uaQTQFuaqKAVsKD?KIX-F2}@^a70%DS>|!ThsISEb zXjoW_H^JgSZ?T!UhEkw}QTwpLCuRS0-JY=z2(z$LwXn0plv(yFFRgyP|9%5vzf=A= zWDQfnS8b1^0L<^iLq9n!;-*lo*1{w3nY?8&84`ERK!gQ=)PF^6;N{Frbfv4?&9^g# z|31P8R7N|DIY|a|E~QM5Uyp0{$@kGbYdFp!5w{*SJ~)Uf(2!*q(Z})*Na*?HYH=e2 z+dz-MLe}iJQP^ubnWgsPLLF55oL{v;jKa-`EavD{lu?0Sx04uI@wi ze-CH9W=W%`KUaO(?$9kD5{rS5BOGP0wx7yLrzd_5IUA6XHvwN5Ut8$)=rFKN!NuB< zF^B)&e%+F)jICYp-D@mCE&G*^vaf7}Vv9u#ego4giyy6})$)tac=r!`fdmF28~9DF zf{;@qv|WCEE@e0swJ?>yDdt!ATM=oZY5T;Qy)$`qM*%?Jv+8FbCv z4$s#{Jdm1o4vHM6ZSpu~MAfQRJYBrPHM zu;HZxVm=7LVC{g19(oT#xc=!g;=qZCh1)&e9|j9_hV!obOf}mDL8UJeUxR3J#lRcu zDW9dGJbi9yu%FY|itUcMU9?@&NX1;+KR{*1IZ?Ud?XVht!+ON*r=8bkdDdT{@#*yw zFl1wAUg9lxA#h=+I^tT@_^vXND-_W`vc4we{ief2)UWO8cEGr&-E8^yhhBI)K3UbC zcB9R}pZ}r0xv;`Xefjd5cGVki0n?U6CG1oQ%-(|?r>^lD^J=!2(FJHG_;ZVWL%ewV4Erqj% zlj2Y~Ih*OO&ek9|or-4)5sOn+8~}_Ey00htrT@)?6nW8OTH@E>k+!}5Bx}J_g2`lK z!{{4acgUQlX|NIr@;2-R`>E0#6oZt}7eCg+g9u?~fpsuVf!7pNTJ#GKo%I)%=t^P`3{;rht>kPk9C7Dj~WF^-^W7ig~o7ffNSA&!`-svAK zVpod-48j8FDu>y|l_YztQv(%0f3(Eu7)=%M)|S-@`r!Ye0*%ko`}%LU$&DXt7p-nB z9atRt!@C6WeY;dPgGU7s+&)VJWwKq?R_~kG)!KkMI@#ZMAPjx*?>!HKp1iRQ?}E)? zt3pH$Fi&uhk9847x-+0xZo+$;)V6X8pX#;hbQU}CtqOMMwhxh0%>`bm;3~t2%~iTdj+M{>=Mwb}5B6d5`{obXs#Lt%65!=`P{5zSUB z%X~CPZy(TM@Wj9pvgDzMH0C`BT8(69VdhCli@0IEFYqS^%PgZr31m`Jw3~;sb8CcU z6`q-YWyo|=#WLHnxjjF*=}v-bDrS`d(T$Po*0*~@or3b8(zhSOOg`fS6(q1%ds%V~ z79%A?dD&EXg6^~)S%OYPWKrwe%2xs%oq4IW|L{GU@d@oux1KNmoY=I&^TOYO3{-w# zlOxhAEago3h%gT7hKB3dZI>Ffd~<-WQT<3exa2qc5OYWY9-ivZ)!Sa_4blDfb7zm9 zkT-0|)VkGGpI7UOx~|kOJ*qe<-Nhdf8q|L-gW3h5F%Xm=q~H}SxrkC4sha5krQp{t zzel1kjR+zXUb6h1A~@hT0$;+7OmSk5VJ(DsR7D=R-K)x7+4ot0eu+{GGTt3%!hRsmFN*XXmVT|{7;TOxIr>L>PovkNx0DkF-ExCQh*@6MHX1>T z{hYEk_){K5hWVDTCojo- z@I$HOY>fdrqP&Ni7cGbapCLw{Mo8bVch)1$Sj^rBIgVkT~eS zoIw}dF-XP#7=uh$nBhaTTV3m-bnOwZr|kS$>pr=mA6L z7`UYFIQ+Xe4dqA25CH)`k6(ilPwgx4XM!D@8=ur4V3aD6E(`>4^g=)p1FvN81Q!24 zp58ht%D4UA9$INdr9)9vRJwBr0hJCBNu?V^8U*Bn7^IR)3X%d+Lzf_(62s7nba%sh z-p_aa-nINk7r0>Nn(IDe?_)!}8RAae?{=>Z1m95S7hx&@`oFjzJZkz!Bx&*2U)sOx`t&xH4!wnV;wB!p^36_CyZ$!AjO}8%&ct^O5j%c7ltPG(ws!e8 z{`i-Nl}6ijA9oY6w~QZ44JSq_QiuEFQ`xh}MRr+Ggg=YA8mh}ou#EwudYO9G z;Nr`^o$SgWX1pY-TaTHCiJdQR^pSP_KP>?HvoBe}o3#U%MHClJep?wcvl2}}#N(|A zov$pa6F|IoTFlP;Twe@+&C3t~06bwzC^nIdIixuUl|E}XXcs*sSjd^hERh2mllun+*IZ_DyZ8K+jTWG&7*ZZ(>1iQRHC|yv8P2D&W5HhHP^nG9Nm4pBCy!a zo8B|yxKf&f#rZ^=Z84Q@+5JXyP3RY!3r@GPB#)>1ecq%z)0!8bJm~gwr9sphN^jd! zGahWYq%6G~#>93%zH;v2=F=EU4Yg})nHp-^yV?6ZIYUCTR#CWxP(pF~NLijR(&$8D z<<#k|1M+!Ag7L@I0v7`x%0t*05KrmFUx(WTE4XF34?HeEs8QJ0Soq^Rtf+DsP(Kc) z()5KX?{7uR>Cfj(mCD@7h*U_^09_+0vAO8=a)M)+V6tV;7yNN;I?ulthV|-L{2?ZO zL4(V;bbe`T-P4Iz=N3U><8smhtqW|Fz>TLH#j=Mt=|U;ed_1PAsBIcH*%uJmQ?C`s zV@w!{&+FxBpTY(|_AE1J+7O<&0YA8HC{WaY- zc$6gS!tv&TuOJHX8QjQFwGBf+StbqmjgGKifq?^~%RW;}p>VJ8RPlere%A{` zg0g`MCqKSxrta=O3AH%5^`LO8t%sWj8pnkf?_mvYT0Mxxrd3vs{0gs-E|2xXH?9a5 zRRtX*nD$_2d>(Soc%7!uh`}u?Dpl*}Y_J_|?`;}y{7Uzj)?&D*pzjK;?w#9+KbD;8 z{@zzuEVJm-98Ym~c=WmiV(QGps|FP zz@SfgIToKYB<}YMtbk+_|LFP_vWp^@M%@lM zd)0#Ng+}!>-=pwn{3qAkqnWNz7treqi98y=afuXp#f*J6g4%kYJ)pDj9UL0^{MK^! z)6)AxhEW9;gwYk;_WO4I3kJfZ^SgX2aV{*RK_Nb!W_mxzIgO6Ol>YS`DzQFr%wAyQ^hDBZAe!tmO8 zy7?Khiz#~17e3;Pl}1z z6=xP1Ao}R}>}`I4)q+ra8mt89x>FViJo?P=1tz85vLJg)<7Ei{!<*oAeBRLPC|@js zJ@TzBxn0#@(w$P7Rw`8atU(&qp855bV_@sU>N0!Fh0nd-qh9~5{8zG;dU);;4JfDqO zpo0EI9<7K+p^~I@Lk~*v_!-gZKYK9Niy8Qtpc6y%Xt0*v*(qT$g8J_Dg?VMUZ-3@D zJiuS3EO3`SC4N@kym@Uet+sZ8j@FJ_hG4f8)(q!lV+?vf|NKs&l&UrpT{knv|MRWi z(vue<=YI6X^?TK7Ywn<#CbTY_=94hwGu^>Y!f2*7zvt9ER+hQQh|-xuVKX?@a;W=K zut%e$(W{qrwg;z*_ej^QGtF&B_w7Pax@c|oQlMqN|HzQbL@Rkt>8Rx9j!!`M$e5V) z)BKd1Bapy>EaG%uo+59fe{KfKU6J%+KhH4k=l6^7m0qbI4=ZETwuTvpCV_E|F? z%{fBo+gRh~C5X=B!jqI*z#sPvin#E>tt5F@aB_H*FD`juZt)U9rI@>m9%uqcN&^TigSridf|FZI@WU-RP=7m~+w%OO25U@P zACOL8fLlbPHd3hxWi_C6uKb5k9mTmjaep^nveZ9{msjVz_>S!oDG)|KZ#RF!gwZJNE z?xrLTEQbMviYOiP_F^^kD* zxwlqB;*Yj8PJ379#0WMe{2F(Jr&g=h6fS$kP`SDs++7r3Ehng0G4j`#5j>GQg#dG6 zMUmY@MpW%-sN;Gl64RbZfz0ed9TB$n^B0xF3Es~-N`T0MjJ1iqAI3JION5;s{DE|B z4N$n@|0l%T5m#bU`eDIRP54E_gd|3~>7s~1RnRdtil~L!U-2~CM^o?ll4fa;-Q)y@ zRa+rK+hW8GHQH2~`Ko5ohNxhN|48&W@5c2VW)j;f3jbOH0W`sOMfz!ixc-Gv^bd-= zxXAmQcgOJ`uK(8_P`bID{xt87onv(B)t`I)5q)xO=dLXY2@l>$9WI%kK0{b^e*>@G?ElzKPr}WwbZ%`*(Ru%bW1%B$tNS3fOt* zE#Dq%0>%qO6U}H_qTheasnLndVoId{wv1{&naZbx>QRuM+GGghSqMHIJol&gfSiGr zTs|TgCp_w`xgLWXAywXF5mfgg@E>Ts){~p|wc)&Al*lA`IaJ62sFIosp6}NFi8$YV z5R?!Jtq@e?10w2`Nur8U$pyM{Uz*6ThT#R!u&vp3B}=nb7*GQDRwvwB@3Df6{_cI| z4<~rO(Jhy@yCBROF8y?e$06Nt&CgP4;Eu z#B9c7PH=H5Tp7lt?G|fOnHTH9>x9?Zu?D)EGze+(+izt3;kxvg;I8$RgfPLWu4ZZN z=d)EqGBe^?k1jLvU&zXFCe4rr+Kh*2(?H%GB6qPjlnKj$v zM5{1oP-=lX2h1DRj58N{NK6(8@oP&0N+by9V)bI7{~0ZFR0MOArNQ&UxSQ*8RsQI6 zfrAN;hNv@CT9%bYu8-Z2t94=`f%*|~LIJ6M4VVHM2`W%Y{$40Kf7fNa*8x&{GwzYw zWJ2`ZaAD)H>1Pe9mrJ%5_eS{|jpPRANQZB==D4BGh7!dvMguED)k*e6_Lo0y#=foz z8tJgi3H@&SUtNXjwm9RzXH|F}c1eM$U>8&K#wkW4b0qi)Tg2C@O^asi6ZJJUUxQPS zjxk~S8LNWhr=f4el`Ag9KUcizBdX`Wepm-L-XBC01}XF#HEX_9pkY#zJ`p(G&XkUC zA|3hT8)+ylb&2#@XB;n`fE6{Q2H74q`cq?>i@ys}BNl!gotZWXjfA+TJy_q;tY1r=;P zxA(1%B5cxfn13E^3lrRg?6%E?Pldbp&MVJWpSk;R{k$+$wGZm*ys` z0>uhQOz5J&1@jlgz8zhD5w-sN1NU<%1IrgIrXV?oA7jWyJ&z45MK0d@NQ{OrYl@R6 zrwY@b@YB509OfsQqoWu6C!h`yMTxvYMJ2 zMG7g-D=Y%f_X1RvtgW-1@nKxKsBw+ZI6nHPSLrf)*%DuIhWg4iF`Jx{%jqsmEh54K zT+m)f>};RQ;JXvo%vo%gH3er#v_2FbsT%iheo{Tp%pXQiWi#!w;S>Xw#=|)9xQ>mH zqd5BGPh6NXTiX8qqY-1U3xAzM`ZFh>vxu40Z6vH_GiUQ1#p~O3wlRekxwj+8w!g30 z1`;zc>$1nZ`D93=lib2O{xiFoZnEI`=PR6vKnt$>=`-nyJl%s&@m#^OFLy<|Va0aG zn*1Gt|C2vRK{+@!5m<=OzN#z3I77zXqeo;2lN%=7{5N+O7XPubJp4xK>1Y4Lv$pJB zCM@e_(dlrQ;IK2moPig->+sM-7Jwje;9EKLP70%a!2bv+%Nww)HJz;W6`74Qg|sfZ za);BDZypjLWpn}!WJ*!dZ-VaZvH4tFHh_q#n}TO!nb} z$}kvAvhd3^O*_LM5Ol#f(*xg*si(Gn_T&ap^g!X?xZ6Fn`0j%jrUiwlb5I4Z-&CvO zJ&HELq6^krFC~4|G}Q z_`Y;`Egmezts5pLCN>jmR>0zJHd6O{xGGPq7bwR)USkNU&tdRA_5F7|T`HL1(TC@A zzTVBv?b^k6bnE}w!yXmzQh-h@TmAiai$3MiH_g_W7Z$pTy1KD=dgnB^)P=)xcMa_c zMiu@zep!n?vodxL5#c6%lAT}LHspR>hwtNq!RX*=6OrsVZl(~s?<*4}4@$B1EO1Gx z42V3jad6o6SA{pP9Gs`ln{78uVPURNa05iMq0=Ie6GQMg@9F=_cpW zMqUdy%=qXHJZGYj1Y}qXtX9miAR8^$T4}Z~iMTdi4d!12yQsKj-%ZgKywaeye*W(G z07i#$JkS+*hVNBY98>sE zy@^W5aJNR>2BQa_HPLEwu-^Lr3!-nbs!% zN!wW5o9nQ3dUUfmRHP2bAi&aqBr$$^QSGq=(@n6pvp)=#gt%J%&pR0k?>6Hp!Z_({ zw!WVj&5$vY_bCZ`_7T?#EWKIjBR9YVD};y{|I@?VFU#M=brMdC@0^hC+ZYeD_N}d) zZApUoHkkZy@%+ZJ7EA;oh-!wO(f(#{jbwtJ+Zk@ZTfWkg#rpM5B8%poHTr#;B(;tOt?a`wu=dn z3R?c>4I>f-fc!^}en*T*_7%{8{s#{L6|to2>)U6C*Jf^ud!z_}xC*?)6vdW3&8}F( zV89KGI@U3R9JqWjCzr?i_jQB}Uw3x0R%qFibV4k3`54RV08#|Rqz|@D14u5Sh;Amnyoh)*5dZ)U zhcXYn%0InTga0*^9vjb#&EuNT|57g|(u)~zstKeu6T2)6c6n>ZSRc(hEjZR>Qah1t zOJu#>(rpzTV2!?AIdu8fYN%r=>!L{x%>zxGiRG=)t+dS~6LNxVCU$&1a6ipE5ToK$ za!pA+ivJB;FptV6ySur0Q6_$q%b_2rHpY|RWZvQ5feAGlc$+X|s7iy@AaopgL*Uk~ zw+Rc3LH!Q=RPsG6=1WRmlUH-+wZ|lh;_v9<+?YrZ8^jR%+59TqX&$1xJ`@P{fpS#RC*|aZ@rCal&=b9-S=A{k zy=wyXotDG95nXCbcV_Mp4e#3#UlX9tOMie$uw+chSov;0F{$~WCeq@yn5tBVH|(;8 zOKoX6R1>WB^%}mw^bi4jLH!Gj5GUf%iQl?W@>r0D(<`mJyPIW(8G-nYz3f-X0x1*_ zS6N=|KPz@9m!doOS;YC8s_4umXvX3Lb+84-Yi%EgI*(*wjWn1xTW7%smJ~#Nybp;4 zUdtaf(b6zoX#04>0~ASJc)?!weklbI5DgkT5J;h6NnU@5a2BjUa>|ZAT@D5Z&WKjH zD9C7-V|?;QJc5+$tp;!8%)#t|2Vzcr=EOn5dJKEH2GG(tZTBfozb4}Xr8n|dr0`;A z+&;jZs{gIBtJ7Wa8w}*^-=W`~%uIF@n|M0+7aG7RFSVG$X%Q0gef;(Ld!w0!Coa+S zHkQNh2v8y8a#gX1_w5y;O?Smt(m4)OKbN4Ndkc8p-#M3@x3_!cyC%JPS$K7FmxT(Z zdWCG2`~SbPZe0G3=_7q=U9unQ)q~g3H=hZ8PX5AIQmOtN(ivN@T&`_h)T+ zdE1U%6Fo$XwxiaepdnHbIBF3>U)oof8*(FDnY;30Uxb5+s;gGR-+@RfnzVlEi>ur)i(b zu)rsCB|)P$>ysmaft$GfTrTyK_OsE+JGcOfFU#IpWZEnwfif;A>K(>M*A9FRUJ%~x zGFfX+sWw1$c<1?6AH zpB*E*LK+0SNM4(PTg&5Bv{2t?9***LoltL@kpH6V z_&51cJ!w;KJO3slvVW58c7}>M!mi`Dsk28XR;EHISVqNrp8WnGz82@~`D0*gY`JYw z8Z_4kP^!_9oHN0>nI0hoB9=SfquuzCE>3JkuF6V!Ev4Q}w*Ye$)ZyfeLgYv&aiJ;6 zP`=>@AZ-(H@QXP8Jb!ZvW{*hx9=zFa5YcUw+lnk-{C1S+*1_S#dHBI*uJrJWETn&0 z-)Lb?1GI+e7nhT)PDnsRMn_ev18*`;#%Wv437$aoosSvDQEV8=Jn44iOl6*TZdT{Ug;F24<_uuNYzh43HQKBe6>` z&)w5_NtYrwXo!&-a4qo98kr>Yqo119B4+3@?~LM z*BO;R;nH`b1^+(;hOJAwY5*rmGdl_wUkRHB0){=jUUz?DD}Sk2GsZ>?d-i+nV%G`^ zwFk@!4tZ%jvjL1_nr(ZfWo6#vuf!C6xC5?mUT2^S@!9gVksm(cBxF(FxIk^^b4Zc$JRtm&M))Ou>{@C3ygb^-7sZQ+HcFcAt-CpmK0A#C|G#L?B0{nRbne5Wo4^ zJuWVxmA++NW-?CAq3af`6?ytH)|epQX`wqTixC|&ozJ+QQfW813vvns#tV~}7bwn(M89rtoR-_nrap<$PC zpLjA<5-Lf|yK+WT28~Kme%!9b_-|S==gV?M*-S2TiH4}E=BsJ`R&EB9;y|&SOtOH6 zYBgys`s@I9?;5!74_@KFgBmZ%soc1hR(yILa5}A8N6i zV{rXP3M!2y;~`7R#8BmA)XLLMrO^yk5%XYTG_Ih#TNRpX7rHCv7CdzFuq4AX-8W!~ z$ta5M!A^1G(XfGJ8YM#$ab zf$p!k@g|6+pf!B6REfB=7N|}lPtnFB2kD>^L6|QvOym%cT#D(*NbIS#WqV?N%Ts+x zoA%nE=)XW9QT@$I3j?VQ%0gKuX-5b%7H!foKha7|Xn~ zQ~9<{F8KIKWvvt}ex45XO3 z)mYw)Wa9eGd;#54Oia2Uec1j~RReDsphCqQ+W8w5L5C)zu9!~kc&ja0M>kVP7bv`B zePQgHas4^ebGtflHG`M#xsLg7ysXO{d92 zlN8*TynW8vapm8fS8`%Q+LZ0pX;t80O?rg8i;Cg18SAD1Yw6qi<4BEGWrKX{S97;Ow^an_=Ew=Vx0>;4-cq zlj!eWA1kq@ai}|S<5wd*UJf~D-+0P&#Z>$luyznYx+TFK+mZV9>ra9R=iFV;o)tpd zgyO;ZcsV+zd!ao)ZoZE%dDto9IUOpz4#rw9rYob_^BwV;{!!B@r78>iJb}wd0-UF( zD8h0^6f&^}FU~tu%v`C4`N#f>qo3_zSF+rVMf$M9c5AGwB#Pl6s_KeBc}Ars-cNXj z!)h`W9!hp)I^*Acy6bd?E*&PBD*m>;tXw3+eG+1}6`I$tqoCn-|JntZ7ww{wOA~kb zNl(@*?y{nNTiGxyQ%bmBV$(LCh6B!_I843+m+YFSfjgcxPq!Oky(AQ+Juz?4b1|dEk%=28-?>s1$t2iB2AbRWSPI)xD zhwus_J7$(nHzUNm9zJILZx5O@&@*~c9{&+39J+(O#2++hF}3;)*#nf@#@so$Kd0vT zn4n6Ggo$QGZRA~v&MBYDriuR7D!Le>+bDEPB_5P6t#k(VYqEL6a@UTS0 z8U~Xda$G#$KL@fku%rF-p(Q5&)FiX{Z*+Hn{P7K!2cT5Zl5Pob5#iLBz{ zely&QyYA4M!^G#3TrlM?7!tp??$3AzNq&gf7ElE1p^iQTaQO>O6QbnakT-xz9x#&c zz}@~Fn!Yz`vZ?CH_5A!X0S@C&V15o&FgvU{vvUm^L|z@`Mv70mO2xf?q1FM*Hk zSJ6{DQ@{Ayc5MFAH73ewSS{Csqj$b<4GbpbutCP#W}XM#!7s>a?-X06;L+A(d{+%# zl9uW3#oddpH)*h)aMlrF8@S$(@@sqYRmR9&AzU)Ai2%$);Q~T}GLQfuRgpi0J^%y` zhWoJAx9U9QC@OsKeF_7Tu4y~YwykGCoH}u}K>H%@2Ejo%0P$6y-F~W3x6Y_7D zI<@-y?ogne`>@QOH77LdMc-=f$dwVH!NSErymdk{0eTBRYt%M#3S2%tH*h94sXY(I z@|8(SsMqBKR4n70mBBTLg|inPsS+5vXDi9;N+|H@9@R~*@uKwh z9^&b}$|R}(VHSx0(kIg*>6Y>O)7RtLC7-W$vbH!&#B;qAdwDl1yw#obr!5ERXePaS zg5|wC4L#QK>t*9Y;(>~u0g>k2nY%5-TIIxcEuVd|sD2}!`YqUHm&cXo( zoTy+Rd$qt$2C$5;w!Tc7?5&Q^7XQ`zY+zE3}hsgu{saD55tStFTxzQ6uQLE)B( zVti_KZgnd9{XHybYOY8XQ+seshRf2og!MG^Y`7%wpD=}A%}t?C&Mu0+VLnXU9ct7f zNR(pSTNcqk=|MF*6<1PLHeItfAqN)Bfnt)Q|gfow&HzEs?9j^( zGkfctGx)4zXDn5nE0(`XXkJ9Kn-Z=6n2{D3$A@eHdnLBS+~^*d@m!7mF~?a~5U&vozimT52}>qDBMmongo;T^@~qE3Y!9Sg_Jq`>U@qPXBD-6cY9C^~=R8p%VhESQayc@J8=v zCLE^)V~S43C?BCmoGWcZ`5JjZB+thU(>Y|RE)$~6VT!7PQUE%3AlEb0BWeR7>J&CM zxTg>|O!geOVM3&4_Q)rIAP1Lg{OMMN@C+IB6z4A|QjJhY@jpF8&BweOyWO;*IjTr- zMEW)-6vPa-(#h-?(RI4sGFbA0!k)n1z|~9TsjEfUXo{TS0FQfW`2XBTnU@{dPztk! z%wU{KdZEH^*}d%Cqar;19~^RgGZ3(4j7J456D+OmDnu19K`M4Ql5PBd`q>|uQY*lO z2X_IF%|O;`|5Re@mmyYKdkQ5)p7x;i`(JwnDPT!~{~%rY739)QL+a@-uom#x4&8+t zVPIfj3jXE(-7Ad;bIIXtpKh80!S_kw^Po&Sc|Q~_jdc_&4BN;iu-IbYA%&iu)SU@K zfi4-m?d)@SO}`AZ3s5y9>lC;JZ$D|j1M<}BY9`>$KrxmXsdM*1ruiL#xBZN`S{s;} zA~X=VbCDho5X>xLB7e_mwR1%(ZCCaytq8TpH9mOi7`vubkt#i4F2)j7QL-{0yCmYQ zN{V|T7K35xOQCU%7)h{mG@hy&@j&nC3EJonpJ+46jZ%5oPX;E2|G%cItVCM%9>v4F z3yMW}+=5XHBK%|u(G(QU3R??yS;Y@c-}h;aIu%7di-m!vij{wMBnw#3oxXos=BYnA$ap)B z$YVzq)W^t11`zdRlZQiPP9SyjM(4{aR56_V8=Yu%<3xtiK&3&BALzQ9fS<5jG27#J z$`7#P|Dd2I1k5%E($#_ZjulBi1vh^%38i8NcLV?8-OXJ7r z3Z`r@h=M0GSZXBnSrfQ!1dw`TAznqGfEz=DnlrP_cf+|Djwz zQ>gCE^nMZ;ZrN}fU;V94_*|QtX8wj!Q+*D8>+WOw_VbGtU60Mh>E_LxWE-B05EF{y zD2c9XWow5o>%k`xrXyhQbgBR1a5T75CB{NZcd^y%i*=xLCb|1HXK%@)oRsrxwhj(L zwu#djxDuf{CrbhulT|_!j+^c#fGjcn02j{JtgKd4S9^!eXnFopo73R#i&bsf9K)3Q zyw{|=7;h;o@#k|)E~_GQVtWj&r8D1|Z}o*3d*91e?G@}gyR&Xz*Mq^XlzulkX<(AQ z|NNe-RBYA4A^Xs0-S(Lm8B*McgGyQNwXA$%_bV{fDGML+K_SY>B%%3KyP&sxavc{S8EJdo8158=n+X*SqOgRyo|7T1 z?a=oIM9u?(xejpTV)LK6hah4&M3MlfAsmJVYCOMo`J=YC zfOWwv?lwi`w@-lZ@F1*-WiHuI3YNOa1Iq-`5|MTAEh?Cg5C5>jF)6TaAj_V)(07eI%m?;Y#JR>-{6T+Yc@RmV|-3RUD5FJe=5h_-QQE|GubQ*4Z6fq(jG>H z{4`uL)a+e)%)lUJ)7sD5`;iRoF3BdiZa;%Yh2fePkDWWnC*^|fe=E>G^p}{r4D~7C z1nTI&S+Fi>Ly<%^U+=8m8{eZor^5d=y9sABH20OgSuEmnWJixk&r9t=>l?RHO#E5K zetJ$-Sq(%A=qoT^3QLyKryzFd8S$HUpeQM3W+QIL{80 z7h>4r3Ar@S?Gg#CabKY8Jq$TaTomc*)ky4ETM1zu#e)fO#%kpv-v8Q8G^qu()|zIl zx}!Qrw%y$1u8e}1YPD)0ebCz%kIH(ta6$Nb%f+uU_98F&^w!@l`*`FdMUZZzfA0I1 zc(gldx%F9gqiZg2S&wGzq5&>|W#o3XG(>3EfwX-(ojwDp2O6SMRrgZASBGz9d0|}*36y?g z`o!w~5e=4-%DbF^F(`&>ZiGd#^rm2Mflwj7u~7XZqkh5MNnCvTp~GfcO|eXJ<6Q1o zI^|!3oILXa!{~8B9V%kF>!l?n9w^TwnL_EN@e9|7e(H+SQ3mgkZGTe+S0x>vnNs-2 z%VE>o`*-7&;bWZCINS9_vO(w`EnYpLk{A2ptIe3nHQ_2=R2=ysjCGXbc<=&AsG8^d z(h40XrGR=f1q5B*fLoaqL8FiR|l+8It& za=}7_A}(3!x|e?~tlljgV(#j_249hZ>!3~?&og`^4hWbMaTl+-p&L1(iLTd4`#o`j zZ9NdY79K$%0{e}~HZy8Kh}ESum@q!kHlBBiTr@s%*=dWP$MYa4cuJt}OL>~dXVCIs zg>|M>cBOxBga000dQZvG{o10s{yA&Zr*s+VQk;nJ$&Clw3c)w}_W*w)mUYD9HJ{qJ zafsXw48ZexJ?Qp(aKD&{uPtmK`_H2QwU&ngVXz*7=9WNUbDc-9o<4DIuJT5>LhdQW zOUC}i1kHu)e$zV$bc5+a*Bg8jOl;0qZIg&M*N>V%ml3ABGR>EdjCve6h=sgNdUB?U zr#NIi$orgwHd>nElEtGwrCHz3oYdkR|8qw&KVpgV@uww9f+(p`T1$GxIrAcSlEKzi z9G$FhW6y?TaTKHYS1j9iJi%lWCY+q-lDjt?M(?T2Z?;0NWRxb6Ir?Pq!ko7N|M!T% zR*a1vnW3qT)g4rKk4SB&!CZ#_A$|cMU#*9*YZ^D3ReBTUv!smT^nWhHXJroLjR1 z)v)@xw=4G;`)6+-eV)itpB0~Sy$JJ6q!s}&2NdsM{ispAXI7(lP|Lj@ZJW4486;bN zyxGAEG%p_zmLMi@kdi6ai~^nuakch+y$>z2ID(h~fQgoxp*i*s%2$VKM3vk%qNW4Q z%=?-G)9=vZn5t|`QKA`s=`eM5dJ?ALpyR1t+rbMzt9~Xy| z`cBV(-qFI*Yr|AT4mhgQyheNgqd=EUKpuwg?mJsO^MuVF1XF`le+VoAnZLlN+Xto{`@gtf1;ASYni@|V z?qUkgY3-Kn!7$mqo%^7VhlUPx0z87xaIZE$+fVM@$E>KHf*}QQpa2x6&=$*u*#7

    je!`F#rwcnm4MiWm5cUe2Y#9Bf4D;(WO@xY;sv#962Nux8R%WT?c>j- zbx+M;vamu2{dU!)8t0UW=E4+MWenkB1}Be#t!@6VdVMe5w#qcZm08OX6k8{rn$Tx` zyk`7_l?n|izQG2p+xx)Wl-pb0OS`~yevV4SmNj2t+)ozh@P-zP4@bSn{OpfJKFgGz zX=2oyJq!&$Xf8R(WDgxYAG+48<%ek8;JHb4^DC&pN8uU5Vw&do_1;6sS5E~Hj@o($ zbv?i>`DIB32ki!^BZAN*Ylpi>_xgD&`=o-qdu8tW*WT}&zoAIX1$XS%*qHSi=udV9 zS0fdlu=LGuCpC$=S6LW1&*;E;m>(tD*x2YpaU4DqcRM7OJ8!0&3H^d7c8agzk z*eHM&N%_8>ww?W>F_C=bzf}HE4wKeiG5TsuN)^Yn`-X{u;{?MaPa>2eFK%%2jhQpR6w~kc5mI= zg>eI^^rFz%F!lGI7_Pbu@5FtB z%qBdV556*XZR&Klmi%ACvm&F-k3Sa1CM|YotUog6?Ck9&=iwg>;=iYLC{@x4s8zmx zK3DTiSmji6?AkADPnp8DKfikGWlFKA?z)Yd^uMHE`dxjo+qUMLVNd)2cRsZKvsbrt zz*WGa$|AW9O^Xtz?0}-Du0)qnAfi{Y6|Q{q;Oh%J~bF*6mqF6=ao0Ab^S?48yaMwyf*T`!T0T^Nb(u% z$q+A1>=iEna(nLQI%qiuJr%y}4DYw^wL~aq1y{p^-$FpGi$eE?fdYD+invi^vDa${FIS)pJE_sZyHs7b-SnPU;H_$&dHf+rR|40lgQrph@2a zP8I5@5Zw>pJikJscd%9#9e1Gw?zf#)C&wF+D+^z{3=2X`-NuY%$ks zytF$61Y`-$4;jB3evH30eY}esXA_^F7P`89sHUbC0JW=#q5X|wCQ>wLq&|kpPaxT6 zbQRt;v9~Y0g!yGdryp)>`lXK4W<#tnpyX6~-bG#gT@vL{)Wwo_&AGlEXs)!Td9{l2 zAl?<#p(%m@SP+yZCHL6(kP>u?^@tM*b-uA?7?YFCh6R9DV*(3%p!p~z7}5YF0x#79 zo9k_kU8VC*;-%N4gW~Ytxo(RzNRpONa&be;JC4gJb#ll62+u)5xElLHAY$mEM_%Gn zC0aDiTp$9;)dW9G34V{V*G>$mXJ_BDm{T;IEnM-V7? zu80Y{am!gv$P#B~?6$$_(sReX5sQ>ws59JvjVA+d!@Q{hfb_5#m! zwRj{fS;VeTHMzCWYqgn(X@z%v>N*@8FnU()javVLmUbJoB)fGqfnT&glEUVM-9^ByZZ19Wri>cXJ;A4uC7MMZtX z73PB9_i-j=A!g>;#&ikA&dV!mJ-HoMiG2Ecs?!z+>W^9K!9LM#_Jw|iIr4kj&QiR*y;>qf4)%Ust?2UVH7{95kZoTLjby;20L$bgvomQI|;-l zxa5S|eibJ1l#w@1Frz30o0| zcF@JSXeIJ&s8M)1{f-MEEIg?weY9PxF|t=vX#|cSfGO0SrLD^iX(l< zhf(FHV)^5nh@&5#E&$~#KxG4Dg`-YReBgXx5b(xbu*eqB+c(59g%ZYGRbOHR-aeu5 zMLe~0mc-)+KNDFPzvtFJ`KBp^ZwRp7KCP4#mND=3`Y^=K0hx4UfQI`Izt!Sv5;hnD zcmi53C6;0F(wJjqPZw3I&d-jYFk4e7$#e5w4=|Ekrz&^}?*d4`g+kpM+=ya1H2V7c zgP}SpMfhWVJ!52KBq5DDkSA5&sv z@w^66kPkM5{qS(3f8)haQZ|t{Ujncf*-`^I3+t|c6a_jeKLTL*`_@0ejp1-|};_-DZx*MiEGPWmOm&)vF8j8yk;HT&Vt_bjaz=l2M;Vs|@ zTQ%J~*4^v3Ji1CV{8RXUa7NmgcU(_9)S@z07e=E}7%vRYL(v ze>WrMqGl=gpM%Jn*!}5A)03@K;Qc+)y8S^3UQD!-k>|858dC|q3k0VBoK9c;mX?-= zS^b6VR zv%zsU$jsnfCz|w{h!Y-|g8em!X{G(ZD2Xv3Jd1^re)!0c;u?e+l-1oe&?g+SZozKU z*ROA1AHa5m3vJa+D&rk;T~r0eK0>PYV1NNZvKI`3lBytnPCb<;9xjdmf0{H{y> z)H)II-cuUg8Qu9h)AQ{k)8nu9#7)Aj)vOMrD&SOHVKd}wdA^Fzd)m`m??)DL+0uKZ z*Y!{Tni`6ZhJCr!F~|8H)=P3&>IIC`$YSN+O%CE%vd^(LL>h6l=X0w1(Ii)cGVo0- zhpnE}fw6;zP4fWss8HMHhsCR=xxZR0ra!6@$j`RTf*Z@BiS8o>-89zOBzb9XhDln7po*(5sI}}Fa;2_*#I2F70@-w0M$ZPBkk*Z zx-06M{)_)9*rKwctU>alpM(7q%vxY~K=ccqd9AeX@8lG5)0$8z3L38se0R0Bd0?L5 z2iO2qSD5sb!$S`xt>L%ZmLvb^0_A6-Spehz2e#K!QIczNfN+u7D~_ICHaM4Xs!lc1 zxa^=#^zM}J%2bE@M?zGJpNc)bk-8l-0woWFo| znSoxL*T7aono)oU^NrwJ^gq*Wy&_U#JE#dXg1RtZY7^d?|HHz$ff!mU8+N&Oc6O#} zCr^2R&>VSF@Q>6MuE^?s8;cH1X22rgx6?guSc7E_Vg>(ywmg4|;PFdcGBoN#5fw?R zjBC|9_Agc4U0g7LSO*WhsF{FG1>5@c=gKgrsh?#ltE<8ip?R7?`li84u42!2Wb^~6 z$9@fXFFV5d47(S47w+_Rg8w$WN3Xh}o>}9J`YO?fY{$GB0R7@e7Pd*aS>`N%k8D10 z$*3T3RHd8%l{oXiHQpOyCW;76!jHI~KF?7kMPTXCO?q^qYA8xYoB^~n{D1>bdwX7x zhu{>VfT1RoP_zz@u;Y|{s^dj1NqR9pPN2^y8~*UHc~Ct72;q;5{nPi}2>+`q!)E=x z8($XOa1|=Y(bazQNh=S4xN;lG7(jf{c-6XQ*08bICSfWYLNkJ8%&1;sRY4<7;F2Zn9)`K3D z_p5*I`JOe_O;_tpO(Vp_g2(|sSAEoUi%bo~x6Z(MW!-TScAN#jJ=v|4&51v03qpfi z%Q&-JuC?oo^={aJmn9ofza61DKV1-=IbJD{-Z=M0W#ui{2@iIy@eHz2!wXU9)T4Xa zmBa7$_E*Ea3l0uW{`u<)?*eqWQOsl(Kx02*; zJdWo-CnQMw{=#^3+g8?RCWVk7LS>3yMgwFktzBJ?-VeE@Du?eDW_Nz(-0pAH%fc0) zugQ?QL`ItQLdM5m6i>Y`bk_b*$W;4os%pIWn&^Jex@rfhumGnW)uPO%z`X}z*X1~) z?FRZ81EdHmVHo`1fPN&SBkgH8(aw|O%@5ih1_s~SuI_$@jcG;_=`Wh7ah9OVQG^!r z_4RdelMqCUdNv8uH8Op`Fz)v=qUbgh-oI&IHmA>o*f$!-aT~w>uW*&Wf||uT5hO_m z`Z=57-LskgK&}hI#dJ})xDmBj09(~1uyMdp2K35LunkmHGJsfkQPd%8OH0s=mGgRR_q7yeZS5|3!OAbGIa{0Xi0_jg zW4Woz3?paGe3IVI78wEqnv)pogs%_X9UUJcXB~Lzfc*+zYG7dMdKubl88Q)26|q!{ zKW;-%EXzCf`~__rN79TlGj$W4URB+2gP&##x{K#f#*e}aZ(OlJAXx9&y(>;VuB@3U z-;DUAzjU;gAmuO0m437lfXaL6Y#ziT15Pcrhmbi|l3D=7Uokz1Yj=c~E)xhTrS zFg^d<3~(j^yVYU%nn3KAE(a{gB<;6U+o{G&9}bioD16?he|U4yKIGn$vX^+uS4!vj zsoJM07F;?QN?`H?WdcNgV+i8~7ITwN-nW0sO=XYK;l}i?0n$5onE1AmRssHGqa9MKw~;a|P1%#OY)|I!=bpFlo9^1@3ERd^3Su?PZYsVgs<&zk~XV z+AT&Y{AS3Jd(|NAbI(mP_yi)b;Gu>*9OvQBR{_M&7bC$UXu{j0nIdxF5B7n?7q=Pe z$p+9`cf?tln1};01&;&V6I*a_Aig1Z5Tb;fIggKzkwp8F>6?=yPi6@Xgq66(8uxrs z#2&PS(`A^kEi{90t|_3N_V2vQokTm%xAs_jT^1S{q9a3pxaZ{w6NL6W8mEwSh{J=8 z9guhLMZU#bfb`Gi<{;>yj^e4Vziy|Y5nox3etD>cWyknbw2cBqldBotl=2}!=EC@d zSTf2zse!E}6V0>w`Ei4ouh(%uqy-cXS-47s%*EvCj^Q(oNNIW#73>U4R}tBq{o5d5 z<>dR_#qa0sZ6AKTBsLNMhhk9>(XP=y?O`sa+OA@@oxXKhg0gfuVoZ*jTw8!n|2lhB zUMGs|+DcB?mKc@_C0=%>dEt=CGj66uY%Hv2vZ-;VA2|pkpGC;whGa-InQe(Ch7FYj zk#X8o>QEDUyq|=lAhj zm`*y-1IkfM%X~xt&q%q4K>VtbqS)>5-%&9EV7*3Wo9hgMsyEF3X)FCAirn4Xi;mF6 zSpz17fT7)?ysWIzhK9!G=T*c7hKdqN1Y;Pl`7n|YXlucwl^Z;0k3kUx?EPSYmX+xI8XD1=<>3e}J zZoFUp@%@?%h5KSMgJ&vu0}Ql^bFsJ{w%*dS(0%s|`_G8w=yL-7YZb{B=`!;$@{(S^ z{trpyg4B<0Kw{0K0gVYKOkeqs?}*>dRU*?;`<1iX{{2P|nwXDCb^E=$LF7kCKse|WCQwyt2L=`82Ayy5#upLzTHRBDh9;g6?1%o0|^7XOTuol}DQ zeiVT!l_59HD(MV-^W@>=UN)IgOf#@|a_M5_a#O*ftx-lmR%(zIzvSeA{St%qJVQKJ z(DLqzPol|v<+{r+m;d0W_d)#p6#_Je=eZj)L-?+3y||9~p3z&+?G6mH5I_W#WIr-D zI4s92#KUY*2>tSHX0X4XM&)b4eR^K&t`5vEcrB9FQd2 zR~xfJiJf1xQl-%DH!@nt;y<9Rf{R}Sn^U| zMm5U(0VPXNKidX7X}1c9MEm3f2|?a~^jISm<{-$$sz7WD761J2BCbV1aLDV=_X=cD zAI%mNekdE1dk1m~Q0B_Edgx6qygke6pg$RIY4>$J4z}>Kywx4qemOxRL-NBtU6gO_ z4-s?l8G`%`zr}{2!WgSnQ`g58lyt}+VF%+D^89)|$L5;vGWxL>kZQ#={Hrmg7MGGl|qdCg6Ep7R4n987T}>N|(mQ z;RM97O@{T0hF^u`TW&7&!31Cf&6qc@ebR>Pbf+nATz1!ebAB9cIi-uOJ7MF)&Ad?nq*~vFE#U&9@^ItQpO_(8(s#UhyT}5C6PFp-r zaY2*}M!E(??aSnBKhMuj{)=ku??-e8kc^jx(HI*Oqb@RTU4HG1u8w%@01Istx?Fh* zV*2M=Z}qBs3WE+dCO0rC2Qmh{0?+eq2Sv1!5}>!P(ET8U-ByIlF~726K^3=8X`sz{=kO(P`#b?LvP&hJ5rQYRQm;4!j2m<{=Sg&DwQsTnOGY>@_`);Y9;nJ0+O zw;=glNV=`(5gx;C%mVu zZri~Fe-_NPfb}-)bcu$55I#DlZOM)*me+!_-A4P6%3@Sye*gq*MQ%rLhtv&@_ca{< zewaL+e+X9$J^BMpHwU(2+_gVQ2maF@rVX)T{z9tYp@f6C1s44V}x6cCt;ruL+gG| zLwQf#tf46^A`1=_~fFO~6 zwDpP^BtaJ<;jkdn-Db}WFk2R%Bo9n?j83fJlAg4X5}G))8sENOu@%5mzKB@_&K+=p zVW7yvUtzH~G$ar=;XT&?Kvow_$tI92^r?sgmR#tDMh>*c0oRj3w*X(~BUo*lQBfHFX3j3S(fb1tgG=-`ATrUzld4s;)SG+3#(hv+0}? zANhhyd2&fA3GAGL2%oIaweA&jT(3?{W<1YDfTN1lAp3BVVBC$%%VUb)mqNE_7{jNQ zbhNQuK_TVJ2eUFXg)`e4Zvj;u@5eTdKeB9VMHVL`rwMD@#SiS*oJY7^?s+b&Z>~n}tMx``Ya=SdLv&-DObIE$OjBs#td zhl6$`0vM;U{=UyXHj{ke`xPw5^#hN9Zx%nr^a!`WC^<#(!y|=gIkMNB%MnF%wDBA# z{7zP!DWwJ6WS{>;Kl`+%_(6J#z{@7aiAMagK$@~O_8-Wcv4&h`;@D+JhW5dFoFa_i zkazGNYeR@I!pT4rLDu^Cy{D6TT?<^f_v?&``!O8v%V}#9a9Dhu@k4n-4j9;ainJTw z`B>JYZB{>uc;o!7Kra@wwFFJrY4q4VI#1Jis3@z|sTBKb5Uel|e8~W(638oH^n`^C z(Tr5Rj>ro7-^2 zN?|@Ajhg0%iv@zCIh#Z1LqI4H*NU`-Ao)7gm$|n_|{7MtRe6- zM(j&|3nRzNFV0Q2m##QCI?g}^(l4at4UPdsC6{lz@;@e>50}aRwSgG1s=C@{t!zja zJ{pO1k8CIJHQoS!+edAo_cW?VTWD+v0LI;dDDLFCx(R#Px~8TZO*q(xeS?koxuZ$U z>`qt_$>-%=3p6{J0nRmp3`)NSDn|BI&I;%YW~0y;Xx=_mZ`@Hz2b2s}r@F0^)+h^p z=jcYHyEICo(b%#dKyg50jFE7(-&Xv7A~X*d;8=$U+7%+e)vvO0R@P{)1%Lhm$0ma{|9@`oSOz z_c`K&0vrUX22md|l)&(3RX@nIQcfH;e@)0Vw$HPXBfcJfJ?{O`#b(`vfDHA|7gj}o zu^(bQZ0M{T+T#JUO>J#${#J_a%B3?+aV_fBIjIn6Y=$Qi8Yj4;-2|9?v79Yvvo@OA zR1{Ah?XjFZj&6t}!CiSscRhUr#$cl58VHkHupak7Bwx+?PqyCP9C%XnB~?Jh;k|N~ z0d`DTNW{0#iHRG!4WlSLaaC7aqKN>DlpC2@`udR1B@Dq!Oz{)X`#xLv1>v*74+LsH z$+c+z-K6Q z19fP{VoHFzpi)jrhsZ13sEe|A{O%(6nBY!5ex^e~CB-${BTI`ru`O9IIuFDQl`Jgo zLu0MF@BI-Cfdf0sC7K!Gks%s0-iD?PJWhbN!Lt@@sQ)EkGn>#OBHC4{=oT)$x)<$zIYv%P0Ob zPydW>!Gcj~OrLrTTTIoe8nzXvjc-AsLVyX6Df{4_)-`pTCUMnKz*{H-w5{OrlfHGW z5yDI$kj+<_6(`9vPd1}(xXg?k94sAiTW_!VVToBV)&tE1-D$-~Fh>0~l%3zYw{|t) zmrREd`jWkpe6^@WkNtoH6L7f5gWKQVuMLksh^hEs-$8PIfKGzB7g7hC(y(@@Y9^=g z`9}5x?Sr%BcHYM9(k>d2Qg6PTE*Tb>7_>d6+{2;VA#gGM>)v_!-N)>mvJG?L%&z?7 z*PtX#%+GV9(_mclm>So4&8&f&wW9jw{er^e6`H|o_@f88w!b-~RSGaUcys)RdL2rH z2{5@%5b|>I?qGU4EkFhVz`!L0pzeA*3)DLtm!y}OQSb5}@((3~3K-Z(NEdGkG#uk* zmNcXrdR0GZ)f;Uw6{Y9zFi>GLgV39CF3VZzt8LORq6QSf5_vDFLu3aN-*I)=8{V&E zh+6~79@3|g=;gg|;|VR1pK#+S;5u##f|JNcZUc2uso+>jJX{tELi_+`jC6-4KPVW|H6H+9BM20c+{1{$ zshz-|yl6D<+Y&4tfO0@E(8Sdxg0h7Lc@HDhPXW3n|r>GwlAnrp=NO zHk$16dE{Nh>k>m9D9=k+mb>{HWfRtlV57hS<`gqO0IW z`tPnP84aHPDWbX72>`1#-zuwFYAm{UBgx|hI|Zul@WTT{g($&7G|{Y*EdNcP*cEEQ zb6mcPaPLvnE1k6;XphaE{_XUzjXSUUSz^@HY|}#Phtv!}Ghm1Q0R8uqHz&U@TP1CZ z+zMJc2Ff_gCZE!S_b{)^g`HDnLI*iNL_X`5yfv5Z6Or;fcvEQ6{D5&f_i0+-%VN>Y zR?=JL;u1mD*%*&MBz0D$M|1wm(vBA?co!6CX;#IX`mF}tCRgZ7%Z{32w+Nb|{gPjd zS~|R1qmn_fh#L+`X92(4c%cs-vJ(4*Mh@HkA^y?W@jGiT-@st7q&?$sEV?;6j%W2BK7Ij5attHQ+#iOr$Oz+i# z&ycU8X40oRd7d|RY&Pn)O%0&O?m8Lu#-mmWBOsEH9J3^#9rqil7E|-2LD$0)uV>xXlPzw?E$FMR6Gs1q*FIfewtl zl_AFP-`emD=5s5`F6>;ZZhs7gA=Mjo0g!r2aV6-ULy{-gFVBkuPiX-2k($0Zhf$OK zswfxQ2~Xx8j$e*X(w!j{$Cr>=K|>=5fFGE_5Ju3i_%>qKB1vjAMB#ZsK=IrFdIlt!yv5;?!LN5MZEvUxIp?i z{_MLzAWajmnnJvQtK3-EACwvxqgjeeZq(8cYiAxzOH%M>vF?OYT%rSVPOZA3=-h@&C2P%r4UpJ z8N_YC$pQ~{g*lJm-K#WuY7)s;z_x=}9RYKJL1KxKa3Awb{1<#aC<=|WNthtuOF+&A z7!y&)(F;J!O90pe>FDt11Ox?p{wwzKXl*xq_ioGSG}K#bloubdKkGuWK7iOM3%=Q- z!BDNGbhoOaV)(IdlC^DKvLxQ+Qt#3bL_Y&Bd@?LAZVoX2BJ1WaQ1i4GjqB$_J7}Pd zrfr(`y-y_jF>QNDL1zWT9Vq~3h1ez`_n*rhlA;TtxfkI)ykG`ydr%+9V>ZYDwY@M# z+HCOCcS~m~9khoaH-jrB@<_%aB3X6Z!821hpBK`T$U$;UFa_tL zZ1-InqUz%Z(1r_{U|Qy-<=4d31g|8v?QK{g=$Q^E91)*_53$Hc0M75Jl_O4#=J|0D z4nY}>AJ{T0j}`WQO_K&|SQck>C6(WGH#zTDq#Bhf*dI9_9?Ua+#q^&PlL5vC7@EO_ z0ivS~2DPzu@&ebzEl|ef=Sp{~?Tdpf(sj~U)~tc>+%$AwTmSzvs+l|b4??SwvN>NG zb+&D#46n+uw!`X&h2qNlyf9W~x<_SBOsmhfj9p)vrytUbH?slTNi5z}cKDx-vI&~8 zp9|d{3h69nEH;rAD5=*kkR$`!X1k|?4~%2z-M0XDB?-6fXH ztc?Nm)0$wVU%A?JsU7+5%;Ciwc}jPqzp85 z4eAB$Wqd_b`r*kjcga+V`d2f5(4UPN%(Ac_G}E6X43&>H*!JU1aU5Ij@k>3!U0Ydc zg8t_wUr~;pSI6>4U9` zfAWQ>2-o5_oOEqa*Rc4_*eV3-o|1~}pK{Th zztjWFSlHS9e6e`AHMk;IjIPu}1dL&AG{6EVJf0mC_z22C{N!vLFoN*Cs z0+24S;_NG+HKajj)FtX+8EL88{dq)6DAJ7N#GmpBw$xE{-R0Q(Ib9tWrL4a0HsB-%Ur;bhuF0v+mb;_4PQT!@1Ud< zjv+j9r>V?mC2X1Mei)*7g)YxYZ2xGCXAVX{#)0q!NuBL-U$;fFIX=QZeGPIVF(J{d z&5$aekax*z#S#XnKuRv;#75*yu!wISxgGwzBjOEeqF7rOS69Tbtn$^OgkG-4rb*^C zPK8N*w}Z}!U7%B0$MaX)wgt9!#6{BqFEJx6;fG9XxkHD8x zufa0*SZ7%xBwZ-#{zZ=1B&;POiHqzfy?o%%sa$7-2}c&)fC^{}Ta;zo;#&^Du(GH(BGemv?`^>>>aXm#K@>t|0|8mKT#o1o3L5?Kq z5+{zn{wpPfY_vYBo^^NjFqe>lpMI(y;ZmcW&EdAS!h-d>*a>n_lr+{-oD^?-MIhEc>&b>d{>DX|{ zUIxC*ueSV|ynG182c;}hh~X}D`VE9u!s`+=+!=hPzE~}hP3s!fVUdx3+x~A+M5YI8 z5|0gTd(l9Ny)K2}pZ5w3iqST_PiE$@Q4OP!gP0F64yCP{ZP*@GI1~ln)}GSnd7-eh zzK(3t?fe3Db{zx9L7FM|%qCnxljsDZGwXJa7HHds2BRdHnE~O+pQ-$$21!X!LxC9Z z`un**mI*3SmzHzJ*F#PW1-ZI41`OY$a&M2dh$JA-xm|I&m?Ed}}?AfyPN!Lud?bXUO zFvV>4ec2rkb48dZw&{7MtG(^@c){b-D$SK6&6WI4i%~>B4^4SY-D%WOHZvT{=A5Rl zG2eB~9-IVOexuVD5tQAU-I|qH3YGxIIdz zFM#VKPVUMVxiV>746r8RHBw)i>AxS`SHGkN5@;|s5K=S+SvlwZ`0)s4O_-S_Q(wS; zh@A+=P`>lS8CY?AX>2d3(=sv;SV9tfS|AEgc=?iNwFth4^z>6>PIKr51`#Fbd)v1l z@)ksU%*@PU5IzmjH0%a{NP%{z=l!}14^r5(Z@wBNQg_Fhm9b6$>+qR4gDs%Ybbu9c zdhs{B)dMsg$-YCx&Lv^o7EE71Q9Qf!KF7VFu?}Jn-o=0cG+g-`ls_Saa275xK`wvl zh)i&-3f9DH>UJ7vM)LfG^do^(zU7YS(Nnk68TuA*ZyDtO;uNHEN&yVI=@R|32xr-U z&)~U$UJ;AIOc12Nq>go*58)p2LR;8i>x44|bTu{*`8b8dJHh}R^l;)M2+{iV%`q7x zRl4snm9=?$Gti2Q=2w&E8-Pq20?Wm~PL5QeM{0SDe8ZK-@6UOlKlT@UWFWZ5IcL9Y zO)rzssY22x;!VaYd*9&Ox4E6Xt5UBHT<-rJ0d6-i&5kV&RaFUqLNm&dhf2_ZIW*2S zhM6T0Ltki?EW=dDh7~irQoI4#1HVyphIx`&;+LU= z51Nq}D?M^4Mgn<-_)YWkT<$oJ}Q}ecI43R*f=tk_nu~uIRf)=wt*7(o&=E z?ADH9kkfK$?kK^@<~ghaqFW~+k$+75P{+(?8S}Mncjoz4Z=3EDx_^dbAPG(gq(+r2vOxUrr)=q`5)6xoF0As-e*zg3R7jv<`Ug%TwzsVU4gYXot85ha|t> z`|0g%gWQXL^d1xtsb29~^!K0c-DVi7rzg+XCJ}7|a&?uJ*@rf13mR#rlm$7<-MS{u zP9X`#V~iN2R|w*mVr}vrmO(#k15$=$xaSIuhvl32-}cjIH(lChagA|rKi@xcLq2Ax z*uhSs&qaJbSxUItlDKcVQ_iFd+dJ8{|A@rXqSfr;_unMGyvUx(tLl1g{@2RWsK9Z5 zRHnAA{&!$mqYU+I;YL$ZBw^Gx%>eQKC~ur`;z;8Q9Ffcxyg$WX`4(=p+_AXcDQz%o zWwqIbsGM+p<^U#|? z9_CyswFlq>!m8Rldn*KSnv~SPZD?S@`UfQmO(0@N!~!7%IS(UOlwa&MP4#n8+=I5esCJOm~YaDk$I}gfR>zJmARK1fy=nCQIJPHHi5?Ex?($KU$^j z&!5e`0#91Fyb)dyT9BH>=SaW`3lsJWP;){MBiQL8Yg1gTD;zf8Waq2~vTBB(AxU6g z?!M9m5fbu(Yq;ZUtGc@urW}7V`;Hzyswp+9ZH_t58`?XbXlvHi>NeDy|8$LYRSdg} zG7qS4uAz60Nn3kSSB*u9?UT+F^9(3qkuw1&`;ldaMP`)Q9m_dtc8U$;>46HT_ELe7~-c=O40Q z>MqH8d5}JBM>^vv85%Vch{29_0Q@&ATKX%o=z_0h)ze5ST5Jlt@1_FAb~Trdw<<}K z^j+;z%i!w+4lorO0oeC|pam2@6vhiUsKHB0aBV+a!$oW|r{mV##<2`3X9N#}*lj|B z)&Bg>f_I7gQHrTy4f(9*b!~v^K}3)4c!iBGUdK*!xuA0Bqn3}tDr8ZE4PI1U_zkQT zIrbE19`%&C4kt%-7oPhQf=kXrx1Lj(`2T4?I;W^t+ZYjG z{JrK;d1P|b!)X!?Jirn^osGSJ;yrPC)sPjp3I$KN8(jwo5pcu3y=EHV`!N~Im4w0e8WRzR+3@bg5>8I=cVvVXLyy6yier(etGg%{)PMg2rfc`A~I|E zsV3E5ZARErGQ;0Q_uW7+9uuxnNX z2@C6O@*_UTHM9SLd6c;U4@76$H$_yetxt`+QJ6pgKmFoV--Vfe_4;~0PlI#Liy!+u zqP5agwG`Js z>#u%p#S-)uCvt=c^E$S!NpAK*g6}s>(N%Iwtrrr32i*;`?lp8!7d$9SmB>BF{oU&S zt6gME6Y8YD2=ctQCmP0_ydFoIN#)&A%;OR~( z7#cZ&ty`yEdij-(Mxir&Ov_H7QJ#0i8S4}|F}JN~wc4Z}cUj5fJKb#R*aJ@{DZ*Ud zS#0zJxEMq_2x9Doa{fqblFL7Gemt(lq2Mut7v<#|I#fa=vZzh`;5*^uqi2QhK9={r zBl`HLie8*3h+uVTsS(ljfSX{zE88^C`V6*`nXhV=jf*|0MG#lt#fCHY6bqx%)GO;n zweyZ4Qh4CBmhw1YGqU~^hg`$%DiU-7#N6rmL46DKAo_zRJ(`(k>{Ds2zRwAbXLTpG z&xq)_0ViQe7ulu(aH7e0nManRB>`+B#pZW=@!TCfWsxa}D>v&;kAr1@h zRmhGEfA@18tD1l+*p8uu7Tcmi4iClRX`ps#zYIcOj*`!E!pdpxV*bWv<5rB+E0ALl zkILj?Tylv1LjpERVutf|c%AxbtsJz!*ZRV0=e9qI3YwLXs?&Y;2wa%dV!@2 zZS6hb_4U#0L0|$d7`c!g))ktc%xF@DLY0*MX4y6luAJofEZf1G@Sg#KtCJ54NIN(@ zn;@L1hxc6>iicVbX%hI!$*{&Xia$R6>mVyoL2=}glZ9)o z^iYh2?eIZ%zR^(M#`i~@e+Nx2754RHI$SyOz5jp=m65yKXN!J*p`5fq?6HZ3z=2RH z8^0AH4Am%fT|ba#6vmo=j`b(B@Vc?pY(7FXk?^H7LC+=x^^(tkTA`)DWA84akspF~ z$8|7u{-<-8dy5q8spP%+;0c@YB7iP%^mTW4E3hvF(Q7~*10*_$bb^UPWC)SD{MWp_ zB=6}DTdDbIDIU_j(xDF^nQIZKERZ~%VQBP2oXa4#n!9jg%e+CA;>oMn^hW$9&bu{Z zSF>3u{@NtU(ueJr&{n#!PQB^PTYSIx-j zhZ`JyYUWB=%8AUH>26ajC4pacX!mB7UAopTsgP;b`0=~Z-l4Y;|JIFuGICuu^?!}U zDFfU;&=1b2k7iAiI7lOd+H z^-#Q{E&!!b+#_44dbtLSDeWaFg#IIPg0hC#nmLT1vzq~Hiv$gqZ?S|n^E;f-e#deo zps|oKqU&~Lh~2&_PhWk+eaEW)j2A(}xHhDp%DT ze0;9k-$!eVr9ZCRfvlalx4C){{Po)iH>s<7ZA(%6rE|pn#LN8QrHP~p(^fI_VvR)h z>qTyLA&L8LN((fTIfM4vElpg{Bop=T7r zE~UR61>6od#m8pGo(aZK^*+G=yfO>e;B}NAvp-?mk{oP_5B~X<)lE0fb^8Zc1{EVZ+s6UTFsoU z7~km4TXO59;~KIT4z?SzF9LiE8ZU|RW94rYLD=OKq!vg)FAC^Hl;nj!z^a4VT#Pvj zd)E~l?r8l$wGajL>>ZKADXdd?^^h~bf984?r-h_433B$vPb7EmhR#XVLm zz^>W;RICFU=?d`VgW+Q9OMx2>(pecK0+x9sVCbKf=LxmLm<80`98Lq{-~^hcO^DTv zcH3qR#}C_=02fB)i&X1waooKkLD)Y5R<(w}qhRfwd^ zP8x1$Y}t{u7uBtn8|A&CWQ%RTCxLv0D~AzCiqby0opBN(zmBC$1X!L8mDt>Bp`Qtr zAZkR;HSnG3!c1rA+V|tbWt%aJ@6%v6mI4qDv=%;)nNEe82c@+nu;cKHpf$SAYd#!I zdWs?w19F4{mz*jcg0K!kJ`s>F18o)n@V;-F7ST+HL+i$mmUARuE_<+%t1q0=7qKRh9}-xVpg+xojf>iUTXIpe!D5A2ToqV zs$d`$et4OM)8)ZbM|5sj$p=#M6JeT%U%%}<+0X&w@9veW3BxkhA2z;Yygs+Ik{#Sf zzK7lGu-Am2bZl4^zPJH*858FFm7Ss%dI`@L8G_+ps_DHmfI87jdXgCb7z%+w_u>yh zi-f`!!U<)ZD}}F}j=nTXQ`>41H;bj_Kb|^@(xbA5XJW=ktpIs=K><-g;)scYO9sbi zNpV#e=WyMzJ^&PR(BYjDOiB1ds8{AhY~f0f(%)zTZt%+l+Wp5?n zZOp|<_9=l~+bQEo!ic^hm2EPHzJncMz{Q7ktQS;VSMYb3*JVawdh)-znIY690lP@r2B^@&Z_Qaql7_2Emp?7&p@TSY=&tXKo=2rAfk zUS9Ej{qAqBE5jA`X7)Y&uhbBf*V8j?gKsOMP(ErVVZgP(-1n@~azidnoy`wI>UCyY z!}u1HeB6ef!ngu=HVB8|{4P`4*1gcWxo>l$&|K|PIX5vm&ArfETl-fSKRxspaOP>i zB@42|AD?eO4-^hwcUXkWC(^tZ8fJQrLl;dkVlp?4QaKLgV%^nU<& zTqmC}=52?cZ!kemfPSH*q-UK1TMY>kg~PA90h~movsrqfTw6_N%?bFAT|7Py(*lynSG;&5A=iY75dbqOj z=7v~>f}r`CPjPcO4$s`RAz!H-)5)CEm(sawViVVoGd`;zA(KevJ#yZGx^o!r3magO zkX+q|?QiSP_IG9#vvYGLVXsLj0HcUJ5kw|5BP|RNzl0RlL6Q?F`4O>Q7^Cz*_qv=9R3$hk%2!54tUL5dzW62lPX)srfXP>YCI4Y&5C;YVNNk7y=*O*QsV z^W6z?yX-nKFX_6p8ohxUcZiR z*#sH(yOsIx6ktYHG%2(yO)x!O=Dp4Oh(;b~WFT`uM8%*D9b})d6|*mF5GiG7qHhn( z-h#5mekCh!_Mvetss6&nOBOxaOV+0SkyJYZ2i%JB?yXxzsV#?bgj9eXhSR+dGcL#I zG``Do=sls#826m}kc@Bsu-Kj3avwCy7^&oUSy?xOtlXNg&~%(@SAZ&1t)YNKtHwj& zI1Tiv00yoeJDPY#r#)I2*Na@nWiuJq+t0zh6ufLXtiSCw;!Zkjw~z=Xvf=YnKcD1j zM(F4~r1VPE8NJarmERh&lFUW)%goc(=EtYnqo5N(f=IXF^F9f#-`|}sjh=cY5;rtj zSykddK|*7M`}Ryio25pdT58aSM(HIj5cQv)(URLPwC|Zeeszc3Qwd9KD2l2zZs)nC zCT0!6l-apneotdLhb~t4C^7; zQxu}}gKzfqv3baVMDZr{G4Os3ee$9~5Cy3V#~KWl zjR1-lLQg0Iz(e&HC-o4L`VldQBw;sHo4qv>R5eeESxa|sNFr7f9gx2^_eCQi(L*6K z?z};hT6=#6!=*sr1zZ3eZ)cwX3QFa7*Mc53-=Oft#7(6LcOa+S?>tLv64;M%x1A2u zwq_VmNE9%A3WEp|d9AQe?St21|84Q95Apb2v#}{JEu|pVg*ga3ILIgj;zAv$4nbTC z9Jcc^T_!1lj}V!ur6sSQ@vt(S*|0#;Lq4(y*j|uL5Iz$Gp=u_3rCy}8%q}UxEm^C^ z@N(-FP77~?vdxxK^I^5iZM-MY`kZ>}MQiV2_s1V#W=kU1X6*Y8Zf=VuefLY(daumv zAAofAYOrz=UJ@wAN&YH=;1GO2soXh3FTA;fp3R>a3uWmHz;|?CtsMA#N`^jO|B-Z{ z-cn27o_wR?mT_)yl*> z#`5#`fb+-rk}SrcuxVWi^>5cBHC9i=!NhP2L4r&7d6P=ST@#U@Vr*JP5JU3V^}NO zWbf*{I>;4gvUBo(0Iuqju&$X3OLKby5A}0RI`y9%3mf~APZO0PP-emStn9PTjscCx*eAz@#wmIiA%CBbBXB9PVuxgET)y(6rj=HB= zs6@}>UK?>i73}cyu$?Jxk#Z7T{%v1>JUVn1Xo+LB*C4cf3qQYi33rz&NVaJOouYOuR^=3rM=84{p@sx-{Ml`rPZ0+?l+mQs|RL zWI`JN!xNlRQvf$0LPcYT%uV5#jn{KrZ8{=S9z!2R?X8XFbl#P-wkXdp#dVvZWE3#= zP#zhb<$%ql9w1^i*VQ7wC6av(dwSRP;`ROj?nUqV5+WMC;1BD=)3*Jxd=s;m30$Ts zUc9=Iwd3bL($nJ&=Sw(sy!(@QZ-MXcd~+{vcBMQ~^0&HVC^?TGUyI~}7! zDl6H%gciZzE@F>`1q9OTnrTd19Ex%qz3TpaS9Sao0GYDXmK7MFRY5GX2)d*V3N2*v zMWUVbIVove7Lx(G;jN|+1p>m>i)t+W$ocFEErnY;@Q-j@@IjCnuH)!Z~f!w(-p_AOai|%Y$BBfI3vKl~bq7#rwkygml)a);Mt>K?|#r zq70r!@9G3P{}>&z37k7=to+z0O;pYwTM3;zTB6MLL!S?)nKji-qIK+Lw}C`TEJ)l@ zoV&bs3x%GVx1HTGwJPz5;2(R2pjm*+`#*4-zDyzLa1Rz(U>*VxaTxrfSRyb(BZ<8= zFj#?s9Fs_BQ_K#WRN%BAfrc@}j|DGPMLvSA+CFoEy&HHH7|7&I{>$ct>29bLk&!up zE`;5ATOZX>(j^iA5_kv`7eQ?Q7`QZE#3F~NoL2=CEF1JGu<{9IdF#5Kd(~y6gez~c zkcz{-fEk8e66NdFlLN%R`QyQ2W>R2eAYFxU@wu16Q^wakpQUg@|FZEE(quf`_Url* z5rN2(u6;^^R~@#KMZi9;vX(dgSW6-m$ezXA>`$EHN;HZ$Zr$p>gTJW2?5S8j!#A(} zkVoH{n2hrsCI0oVU%o^$-@z=x9vJb!+~q#K)LbI3{8|yCZQu0PRkBAfZ*l+oYEYOD zG#rREDGaFABpTwoie=tOgXJpSlUtOlMT#+luaoL;%8pkLCER-nO5QJfrX2Sa&DeC# zn{5m=r8SJQotA_Y3RQ#TM4QA@Co)fsB}4N9eL({XCdTRr#dIob%m$tcG^)_!>{vwX z>d}Y&AOUA?(}d1>a7iGxnuv%gOm(k2*B>-P1`)f?inl4;A07p7Pq;Uyu!xa1%_w#b zdi&AnrF#{BEu~xW`1l-G>ZAQScTs-usy{qmmYRB1E%GmFXB_?4%dK9t=n#(vUe4;- zzcdFN)ff*M>8;@(ciFK-RcvR7?g`ocVaYiB`s-3I)Q>bw!R`q8cCdOs<$>&ma7Wbn z{fkvS=zQSYN()ELrWOPQ1iVmI$8Km0cu?b2d9iQhbVf+Nb8eAvCxc@$hf@rLW$p#5 zAQVt1UThmpJrESBGo2k?iAMzzdTdwItD5epe@$M&_X>MyO2F!sY%sc^KxZ)|+sL!_ zibv{5T3ejZCa+D5h?ys)j4eWXm3Yj?G*Y}J!d%1T1i2hFt5J0&ZAQ)jM zQkWl61|Sc7)#he~v-ihTfOUgZB4kL~#T3Q$>U_C;%`|ju=jULC@`R$ui8sE7Z72HU zYhQtBp0W;1AmZz+!C%|)b^Go=$w!^ZdhZ(WV)UowCGt)TYn5NdDdA9#7z;O6cpz+g|X zdqI%77_u6-e^0B;R)hSmN^S$fV8R_4%RC0ZA2OBwiC`J7apnRU>~Vke9>pa$!+JB} z(?d&8#PCa6!{qg!a2~c*B!?UERAZo!c-;w)6APeb5o0x7%RjND9KNA1@<>=8MBssy z4m^R7IBF<|I#O=~4w|X;S3wBb_^qzhkp889fUOY}yaLV~4wqeH0%~4@jJUV>BFBr2 zHG6|V84{q9^7Abf zdc>b0oo+~$0Rqy)XVv7q5buZNGoT6~B=i(Q=bKG3;vu%%AI?w2P6iB*;kEz%KPZ}! zC0FvMH=LGkD{7OY&2-er@z@y3DpCG6M^Y#6;#H{h2O``5$J1E=Rk?@Ve$$Agz!7N$ zDG@=sL3D$Pbcm$VCEc|F6;x6}8k7!cDM?WfB&AD0x&+yD-sk=9{qBr&X3m*8Bk}J4 z`~26l)^91{He}omr$rl5qReSX0~IABp8_wKv-eX_D9PS9Zj@X?kh+K?VKdz$8mTb< zg{$^9#HD9iq{0$P)pOPXF*tD=YD=21NRsVh!EiD1g&{p>L5X4wjN-YEOPGViILZ}E-j=WEwgeTIywre|;ee92- z(HQ46?t^?=oslXs-ZgJ^|8+(GnX1#|smlc=c?O&%i#~34iMi?f?(Xj1VV0{mi`SB- zMCN#EHQ zfoatcNASA=3%;Loka$VTjj?_7C44;L&bBh=Tb>#tA$!E2n2JYoR$lxv%tPOOOEi^* z{*lFWulOU@cl{P5b~H(*{{4CWS!+L344W-o#2s9lhIOZNC93^U={K<}HKi0g+EK6e z%Nvp=>SV_e{L7aO5#+-G68kHu7a=HAz!^3jF?-=UMnA}Lyx)7B*=Vhr5Jn{kLIuHD z2(~LwSg-Jh=TCtd^luH897SGy`2Ch6z#|;u`fsyH-DdDy(7x5BHeOOYaYSqu%CkbNI?2>d}tBWC}D zr^syqSyFG!wj$3hLIZ@;A!n-AK;~lu;Ld>+Du~0py3T!fK6O1{5#OlNimEMw=`9QJ zcaT*Aa@_gCWf7eYjY(|i8E6g_sM3M62kB@*06S1U)K)c?nE$Ls#jQ&`H*d49cul;f zk7InS3nyJAH#{@4*Xj+ekDrzFW1{#%sUekn3nS#GP2G63FNRgmid%$vE)O2sj~t)7 zW;wu`0qJamp^O2HGQjLZc;-tqKOgedX7##&ELe3I08ce?Si%0X5Yi^XtU=^Iz@h&J zb|pi;>B6@0x%JQ;S=K9A;~5DdIaG6;t`U;|{#DI{ENOc@8iQfkF@fN>a?4|o{!j!) zw!FG}2NE|B<3R?W#rI5sJh+b?8cBxZ*POrSjNf`@pzFWU7}Rsh(V8;YTcY@SvIW-UMMX6 zbvBnvk3-X(WE_R7UH!T&old-E8XQXM-{8XD-pZ zOwXz1IQSnZ1d(LHU-%Lyj$k-iyn9rHUY_K(t!&v%<-_K^azh)+!Vj6vR6k85sPt!b zzsJ78JAN?WZN;o2DWO8EjN6csTu?J+BC@0TeEKSUf*N}_pN47nsXs-2 zKaXt3>Wf)lR|U^y)m!$gi+ft%KWBaBR6{r2zK`Q8%hHW?pC;zjR-#p!m9V_)$$sfy zRu1B(zBgSTlarg8Pq3nG8cnzo;v+eEyjkzVSJiwfAzw32t%iBK{mkt#nzLJBD+J6|6*pksA!}rrH*HjrGX)udn8N zza^tN?)LbSb~MGOE3apNc{+1*<}^hYwr8>3hn;8U3|hLx_}d}O@463~H&a6I57Vtx#$&5_P6J$hchE-vt zH|*6uvqdAqu_?aw%^d9y`BSB2X~>~2r}J^vd5!o$L#v( zf1>(}$APu%P2#G58Y-=YuakPkvTRp<1(5l*t>>ptw3)0Y>7snx%$y(V!VEe5)T^Rz+xxx2`>_ zZlH!_U3~Avioiip)x&Bgs(EuhL!*c6mtcX7&U2Cc5){vPE8M$phdL!wr1`^XQCnmB zY?g~ITZ&s_9!?%sZiy4%LxmyZeCg9;ir$!)sWF;MCGhH20dB4OlQFw9$K*RidF1in zZIQ|qA;QIhVvH;138zI7)Wt60I=|d(vG1_Gk}OR?H1eHR#albU_O`>aBzmKBPk>#i z>gw~Dpyv`xm(M4jNu3A1Rj}McAHi_7G+Tc%vNNpD7Zs0b^*I!I}Cr81BH`)oh=lqxbesaNwvVI5(2#kKp>XQ z+joi>Lx*nP6n;g5Q^8I^?kVeq)ULy7C(J+%W7OfF`%Yr-al~+7lS_kDESWj&%oMpz zlks8fHs+2!-(7!f|C!;TFZ-pywYs+2)qT=|i|{Oak(zg!cCuEf2a4dnm2-F@qj{rm zHm5v|`?6NV7>aV>x_QMR4e5z&FOi9?rmBWC#%&!`%o%~ToVv&$BE}Km6?704Zq5|5 z65u~hYgo&s{IQm6e5tQ0@X9JZuWEbOu>QtBpa6Pb|G8MBqod=!$X=q^V=KK;xAx_* zsMA${YinZxCu?XfI13 z6e{}QcDr+^lasQ{vNk!4eg_r!>5+-Re|Q*9iMS;c)w(%P*&U+9f}SKOOa_EMV79=q zfb|&Y7R7Pg`YX9PgTbTN=@wM2_3MK8vxDk68E9mLYGN!BGfny`nHu(uz5iqv1~q5= zKbNj&KKfq!O}IBT;0fQzt+f%rIhp^Ae>zm4y(s=ErsrNxJWMGs>tv8%I-uGJK|b{a z7XlenX{s$qTQQrwkv$hXnHt)MMc184#CwPGKi{lu&DcaJ3v&^Y&lTSu z=6<*Z`Kt2(-KWUX&mA{9P@|u)-bmWKoZihOSlL&FV&MW%QzYVhZM4`3DsnhWt9Lc^ zhEjYANTbTfiZ(wu(wl#?Vi0CMP$BpLf*05?l)qihWXl)&g)&i*%OdwS7BC1=VpT zoMdzarGpclbpwuO3}f+->!;Ib^(Me<{E1cmz@!!2y4x+4T z3j2HNw$D=>o;YZmxY-^0_ecvTd^UVwQ?qj5RBU^=Cy_h%OwpqY@gW>#!@|ZGI?EAW zUs9trysRH!A?><_K#U-=2Okdb;t0X!8|m}hHk&|q%Te6{9M9dBvTphd8NLtOe==)o zKXWsJ2CA-9!OOQA=N*)G7i-x%t zRWwRA#iQflt*5XV7qiDfGNsgULArqs{&UHY;cR+(6lO?-Y#pijabWAn=-b!ghl+>$ zCik)OSat?>DxjX>@5ja!GV*i}F}^SBw~>|cmzhs|jXMh`OUO9lC(;xF3KM9fqyUU{ zQR}xOsX{fN-=GH%0#S7wJA*cH-%~U@bzOB|#Xs$Jdq?(dtlV%D8*_Xzh^I>v6p__z9KZsvV0{pA(W{6Cki1LzJhXqp?3bx;;fNU*Me` z5iQ+oH)Cwhy?H%herdh$Ot(E)ny6OCb%cBgH6a4I-d-KARgpc(yo>5*a5ALksjk!w zOz{uuX+`$!W(2HzoUPPp7{07?fFT@|0Wt@Tv=6>P>Gio_CkKlZ9{R|p_(@zc2X_V@YV`NAzRlQloM-%!975Ny}4 z^%7pH>J)!l9V+}cNTrBEAx$i>v&4NM#1(9-b4WBJUC|PMbsd|V?nQqp?g#USp8okG zNwX*EOL3zAQtNxX9F{m1C)LLmh>ph0COBchxS?D84Q76Q)1`lurUdOw?Z`p?KP^5W zoGX}`X5LqLDw%>g8<4bmL$!Bv#045xpv46PZ8?2|C2&VVH1jhs?ILz3L5nUqKxzD~ zTjN96gGi{#3A6rYYPoZh*h&$JcZ<91z1@CrovhSkJPiUmX1A^9StHsXwjuyJZ@pHsXwWOYzSxJ>ZemN*g6_v(NsJf(zFVg`HcEI$7;Go`l+& zE0GBSMO3K+{{-KVn=8+(Kt2=0M|+L_I*PO}^S4&K;+9ez9qqbrBt6hC(3kW1EzYfyhcZlL|0SjJC@c{lr((ojN{6F2^!*~H^OZH6J~mtG?_7}_3d9|z zzxlIKXD((#*HJ5wVAm6CBwX}ZQP_;O@`I%TEkA*)o1Nu*&O#&-OpBK&Sl<8J0} zi0p}uKQw)E2)>#|(&G+e=lbUnBj%UY0Q7~WGeVz$2EH<;Kz#?a_?1iLN5U4LZx8d4^Qx>x9WljIOV1XNsa;tqDii(@)`%;WPXy59dlo_IXq(6ypAbEQE$$j z%zI4z>OIzL^ye&-5?(+2(%Aa9MbMpRJ zf(SX5ZJz$I=P(|o%%s6o1(H`T1jwo=UPNXB8N*btpGu>mO(j!VwE8m&2mNY}&<;hoi?qV|!?zD&@s zH-QOBCX3g)rA|UiD^Go43aot=^%hV6<4{fseba_^IZd)H{wJks)LQ=?%=`#)09N}e z^Hwf>`Mt4Tl|=qt8@F)89&i78m>`{7a@U={s?_`wE9{tx8ABMSbrTi;Vj@QY+l_=C8C1QBS=?)$n0-Hlbd+IvkosiQjdxPBp4p|6&W)9e<|;Wyv$T(FtRi@ItK zO60u2XPm@(biinI8GY(QoO@{1jG_NHe5=Vy3uda~E(oJ`e#5zl8i0)?1@TYcBCS$x z*D)ge*VZ&BBl$uSDO$g9gFo0Lyr}5wVOog30n#*QDt`4orKkBR#+RKV{NVc0e;INqcF|a(EGhfsA5BBzyu9iCXf40@_>-dWozE15QI-=PLiB-$vsxX0Z+YiH zLL30lh&Nu~89pjOVMIv+VumxA3ivd7~$`8Lqb;ui*b5dQPv_nW)b@k;(PMD3w#R^SZ$x9?%lb?(s|VW9B@ zVv~4|0)FGJV*B24R@(8jJLcbrDMGbS3F@q{LOFkZj*pTm`=2#tq(fSAZ_Fr6uG5p- z3@Gv*$$bL@*M1V^N!t;`R^1}5f6gSd%SvJF#7N|_*fVzBM9@q0+~H?Z3%#ce`whwm zX)0=unGAhZWZh))H5E&!4sh#x?h)iw@`2#P&=z`iYp`;Et?hT(hs2gZkP@oRM3XOM#gDIX+Zz*%^wnWjVU zLvKxmwEIr^wrE70bWWX&n2!6E)%uF1*AkbNR*U+MD{of$-)H&^Db`*=|J|jd{<0C` zXG0Wrj!(>GU!Qg??fCh-aZamkrR`V4G6j@j=B=OPcl!+S9)RlLViM0%Tl^MYB8yQ~ z8y&f6_-W(b(|nV=;C!(fF2OxAP?Ws5b@T4(76C@Vl96OS@|7HTBdOYjTQPT>^+!%j zUSnfVNJka}M)JBqhPVR1AF$h8ETdGFK4gFM=8faGVQjpL)W5qiIYD2p-{WB3O`FJGYFana?VK9KM+m}T{SENgBAj|w`E3g12D zh68bPf4P?P4b-Z2yxh<))IoUJ34zo+hyoGS80Lu=> zC$B1HTiI`O|8Uka$Z@Ma!K4V2IZ`mBrmHKOw+HhQSaoNBd-N4#-!;8tJo_mJTiZ3f z^WSa*+G zej3a}Gs#P77iW?Wpfn)u)=d0KJE8&0f=%q8f7m%-x6t@1b0lKFfiDEKOGOBjh_hWF zd8fC~ zUron-xNgbdsZ$#7a_3Om?Sk9jswAz_z+rw};^BEp zL%$VtqT;Cog>!Gp!?i41Bpg)F(4aRBKwVUqe(Vxz6kC!iV%0Bm09N z=Jk@JKm}^tpW2)SnecbM{+al1qm0q-v+0}A`Na}2S+wx-aj0p8^sr{zJ|w$>7F;|m zz~h0uBCh7T#&iA;NK$Z7S@YkQ>2q>Su;lY5rgNuwyyim51D2kyuFV%~c&s{X zI~lY#HOE}f@%Hg3Xxt^#WcOl3JA-$bN4ht+k0E)105w~Chuq6>MpN&Rrae;&lGwKU zqGXRd+!5aat+DVOPEAdvwXSM4m8SOC+?wd&?eREvl%0q#>man=_@~97V_v`#In2a6 zzcE-*WhwRlkAmykGWHhscr83MG-3lAeg%|;<@WQ$wiF=}z04w^>JQPs=Kj|UaAU2g`Qt{kRwQK< z*WR2q;qRAiKZA8Q;{C*Vf6XSCf<(pYd`yMB$AwAo9s0^KkejqpgJcYRNJMUIHUFE6 z|8Yt7m(}Q5Y#oy4{{Ds*?%8+X`9vz?AeMqeFWVkhGF_BwlqKr?l3R-jtnZh3_Ki4< zK@@31op43j!J-G;xJ8@Nhr~qi?95sX=S7Fc&Jh$_yJu{MX)XOywN4M_}D8i-yI*hv+*>hh>v|qpU+B2mG@g_WfzDGCJ)%0*H z#4kUfGd z272Bms|>f7grAa~u%4=O^_z}qIyQQxi7sqT z$Mv_#8J#89>3N&7UmCkEZWK2vBjHbx>clmvRiYvZV_^N+tBIwvJ9l$6Ajk?yr|Q7z zrZ|>A`-hu|t#^0CFl5u80(c{mVPWSyjU=eYCkJz4XD_HxDDZr|!HJIP$Vz-j!ck~f z!IXX!FuV{hI*nQiN#~ovXH@>mE`=fD--xnK6V4V1Y$$fM({3Bb-12%kT{mfT?OZMG zj*R_84au9Mm8E$+srmk@$k>umkY91U?bBetgLH@bx6FTQe6f`V5Ka!utaB7z+(?Mo9fa2;_}`KdjV&vIITfEdF1;@#y%!#`j_q zK}&%K30z3o@neD>!R-&JO+Z+^5TWrZc5`?C2t0H=cB0@G94z(iRpzZAZIMlI=(HlV zF8H5An7xUSt2z89qs?NV$Z9D!%Vkjb>nR-nzQn<;i5Rj(6I~{g1(w zZx-YjBx4OpG!9kib4b1*{81R>KSG2UE>Q4khJ^^7uni3qDyZw}S#MWqzUmj_h#CP_ z+_e{we9cy=%`)LQ7JmN|8B83bds@Kvp(;et{<;@>b`lg6H}dTC(T?`pUlIjnq~0~H zO;)hEX^ED3rKLxA?3bV75B&()*+Pg%s?3jqd_*4SN=CTqf1dIejLf>p^KwIdz%9>x+Rp>r3fJNuc)4SuMl@CX@y;Jp;4-YsqVvI&4R)1^fj5%cS{|k5 zf^Mu5NrH)C(cB~%g{{W&__#ysqRemFiS?u_Md`!8x?#Vx2-PX?@|>wRf|Ccl^GQ>> zgG-fsV1*TiePfVYf6#s<|2-i7>cdDC6BLPe|FY^Mc!Gm zr@iSJC-kGAF(uTFjs(TcDPt~Dd-zMc=Q`g6P`q`PRETm|!|k9l4jS`7qdR?Z!`_pa zC$^UF=H`1{GsyXUB7(GRFTbYvjWE`{{&j1M~knR4@Obe>QQLf3j4!R)PnMcygl8 zkGLc0tUp!71U1rM|9RU^L(jT8d}QO;{!0-AK47+mZ}(NTOK!?uJ|T7f45`kn`nemAWdsJP zlL$?i9|xB4_KGa7dkET^@E~WH(0~ub5i_!4X z0mv*+n{b-v|C;VN!kZtSC1f_I-i0AV0H&jQaF#u;bZmUqRNKdTjB6CnxXxf0G`$l}xi9d1vlhEKc#-HTv+6@Sy-D2MPCgJ$a_(0Ll{1Tx_}~ zIhCim5AlhhFb;}(Ao4VRd6lmfnqc%>u-S;}TgDE8F92z#_X5~qXRp2$`m$K7X zDLj4vxS+3y4&q>cdI);AJczVc#PCpCOO|OZmw|L6XOuR;u?l^$F?Am+DhB2qI9Udk zO%30JtFOMTx#yvS1~S%NgVQxlOIdE(cWTvYE_Yl+&Nx|Rq@FD4ot-{Ma(B{{57yc8MF7pnAW<9epC&kW=5{W*8ZfTl0dD-tGojVB`PYcidlnr1?F*OC$4fa7%^& z%|SrM{$2IkZagU@GjJb*&jQ_by5*@$iWZ-CXIxH--*D6FhrhXs>GIKInV{};rtMmE z2qWpYAF`ntYp$SoBoV{&8z9MJ)rlJauYUZp2&P*Et9K@#@q%cETdaAH+O97}jehFu zG-|WT@c8s(s<^`VMNIsHW#vR$Z4glbt5y0DH-*Tkb!6f2J+itxGoOav`sMA9XA~P7 zulRgEeNt>ZZIf!hWjJlwOT(*96oPmI1}WJ8T!=s7 zcHjl}!pA`n4Kn}&ToSPCVT8@dq~{#6xF$e2zOSvLga zrz@(C@cd56&-*^#ZM1es9v0b>7BNYIwDBhPoCz$}n(0>8Mc)%?WC|c&M|ls$YRiUk zTfO7Zc_JC0hE_Pn-=$k3tHC;^;XJ4&;AM@3z*P@tL9^g-Bvl^%-?3Z1Mr^OF^I&^{ z)DgsdzrZ`*!@iB**#NIc@Bx{c@yO1fCt{<~mzQ!ob>q4_L+lgAbDi#;7FXysy!K61%7*{*!lZR(jS@d`ELrge|MgBg)4h_Ev{*7r90Ff;tvqw?-`28Ile6yKd%+}@%>+=$iK z8R=ElrFzo<7t&?o{@Q!2WWcm+rc9f{2Xv!)mZto$YIXMHJThS0bcWN5lZ6QbS7$=k6eq5q?oPj6b6$15cWdThhUlf&bcUhL zCAeQfG6ewQT^X=_B{nGu;Wo>cXX1?*`P?k7xrC4|64@ee`7<6E|FBmkp?&E{-qUjG zvbn$fdEVB>Wy9uZts>w%{Py1(ROq&o69$W&)y(~iNk73SVsh<6W!teho!Ev*>f;z+ z7NkhMFqs}8D{qY3C?_)xpGUGgO!wIiI~46pMPV8NW$-Rjx_{dWigD6^!d`48D@IMw zZYe979)y2#=^Zu1XA5ZC7^>~Yo&|9T z(Y5lm6JqS8m3L7SJs(d?j*`Y_{P+B>>N~TJKkeIp&6zgZe+@hp@TV#{qN1vuCpu9h zV?`eA{fj$O#_C`+OFm61GFWiV{i+=2}me&01QWGXH zT38-mjC-oTJW5p~=g^};@JRUfoAkQx5r_R&FSbm`HrT@Zv{kc7?x zLTR@BE1RMl{3<2FYd<{l%5vLE8b=6)wOMcM=5kr-E79-fcG_GmZyC6=Fpj}gl|}W> zdNh%B+J3Rm=p;;VeLj)JTATjSe59R1X;1S=Y~L%@g_Vw!-qcd@m!#t(TS*Ai1|iI1 z@JKZF0@uJ7{CaSoZ-ZTxG+|zkY>z&!$!Rpx*e@{4fLoFQX#%gb9za@&;7$DpG}TrI ze=GyY9R`jq1Y*DlIvxxsX>9n7EMH~>U5=dV!BE1XoPa^H{3vDbP$X0bt<7ISpmAD= z(|raGKv)>pte5|UvkL)~o30LjDx0q$38IModo5MPr;$4JTE?B=kw`=bfuAyx5`)`( zX!{&;G|8MDnBu*lz?YivN*m$^xdq{eg8+j(21u700GqV6X>kKjh8=NVhbd=cF?0Pa z&8u~M&uh*IXUZC-hjM}GhO#bhh=OpmEy`chdUFkxTsG~B-DLQQI?RQbs zLU-@efB)fjr}h(73*bDE{ywlwmjUho;fO=*)#4MSoR(t&sCY2wf>aIHWQ*i#W{b|7 z2Vu+uvTnbe*J){Pd@I>`a#dzB{okVQe@n7BQs_hIY5|YfT-V|xw34SuRohial+xB* zZ_aPFfq;DCW&GHoz@p|48#5NN(2V%$oaBkiBN!?Hu1?Q-XGv^?cP*>#ZO}l<`xAgR zSP=c^Mi+52kS&K2TCC8J-)x^xUVNO_rD>ABa(7gv+qN)+s{|{#RFLl9;`B@_Z}mx$ z14O)=Z?F9<7t7Tn3JE69^y8f5BDYZ^ZCis}AR`FrrgSOCTBRa7$&;F0Syo-Qth)D{X;FG%l|&Sd2M z?;fyI2z^w3umlxs{@O3}`!F+PqQn+q>?x35EH`n5ln`r8QH5?fbC?&a+BF)=CH!UT z9xF8Nx%fdaJaf>^aN5fBQoD&FBeTAMc?twr5m=4W%5eHEC@q1@+{gNQMj}Q>6abVP z9))nj+#1F#O%LBTSh^q?RH4|eA$cb?ha`n(g??~){e0qfb(CM5lFKKGrK<68f9&{h zJB{jA#im^d;l|S;c^aTukb+Q;PU0m3?&k(j=7g|qr(b_3;F@RLHYK(lu6L1u1g7J zfq*p8a+*K4Z&5TYhMLO?X>ttbHN6(&VZ&opGEo9G?GJrQ-1Hk^2e>AfCj>IC7jvH5 zKdp?%o$#j90vM#-zhS4F_$lR&UWPdx`~S}TIxe!jVR?!&*l^J{AZgH~r9N(0SN!7d z-ax2f?zh!-J z^=KxT!tv+L>Wu8{@2HzXdmDM|JsW4S4nemK7z|v5@~(Ih&Xe`+?d=6MKZR1hHM#b% z=3%)E2XNNr-lDsC|D%g?wP!^au$P?vSh1`nnc-_(eRfD9Q(ak!EOC$s0)n{%A{eR} za+e{H&!_H(D-LKCuMtKMdx>hvRDZW>}(ac zu;Ie_jVGsS>?z@YG>}fds+JrWio&H3n3v)_&*?I$EG`yKmK~Q;+Qjj8sRBh9M7R&o zQVqkcLL4Y7(rxN|@25YiCjJKF-%-dBD)0{sBLe|8R#dKcdGjHM49FC%p9?ARmJGdX*sy#R zzwr$Xt3}E1+yoXRJADrLd{Sy2Duq8s5gwQ)gZhOmd>^zpZJRaOe_mHjr7*a-ezEFj z#K+HMUJC<*PBf?mmJvdEtf$o9*BLo~zk74%^+<4GdSpoPanTV@H@C%`ggdHi25H}&|EU7Q)5O}n2A>-i4SNR8W|<%lI&6H zfT5H6X_v``p6f%0;+zm$kKX9GhG}fUfl&pp)uBi@ zimmM%e2w03@E|6~S{p3PvJJVKSJHcv)R?!>ku|X8?be7b)ySdYxp`AK!&1tf%eHN+M0q>AUhYvQotvS1fra4>8Zt-ceWJAOs z$g#n(;^4T#Q+3Hr?k_%A5wZBoo~tGuGViv{hFnNG)G~C_&1>he^A+>oZQ92rYfskc zKbzYnTCYX0F9iE<%bCBIa6G!mx*GZFmn7-`RY8~_LBc#2s$Q?vJVg2I8&%xr|A&JB zoo4@TZGj20Ab~4CI)d>vlsYA~I=J4*z_rv0J^X@3FW+zF!Dx9cV0j=7zde$_l^Ikt zaa~(L{i>PbmvQwJNPA+~k{(8Hswup6d%8n${MLSem=0IQ4)5pv+yRTVGg${Ur+5rmsgqewq?IO~&k&jKuJr9Aoh54}P0y=H zBOygFec0o%m3_gTF)Igqwl(#h{b6%*GP$vw$th zCFlcVz!*g(yF~9pxjVHR-Rrx6f9``UqkE*IU!Jns%!tTWnv9Xrqu60Tzrnpaj&8SI z98fg>)A|SGG7C~|MN5(_fZ<+7(3McWcn|vBa3Iq~ECXadit{;6&0d;oX$;NBZj*Mo zuhRb()Fn=KIF~LdHe6=_7T1KmAMhUcNG?@F;y#s z*^-s63cL?5R;_ExnX3~KjGgf0@!}bqn>or+ew)6G{*FVVXjX*xwYk~k=kT>`Q1zy) zlKCpFld{Kp-bsruot!C^aE=_$Kl;_Jmoj-eAG4UU@3*&PRDA6JHzc4UUF!k&mX=qR zdb_jGBV260fcINJ%Q2fG+hbvkwlpFVUg76Lx5E|rwDYqAHJ&^nN$(8-->lqmP!KM> znGNe(7 zEo1C?y2Rz3MdwcwX@cm%)g;ZWG5<)ygsKkrpuU5?+jcJ>2J&>fR%nZg_<}1(y@NWWJ7;nIg;;WKy1V9e9K^nehIn!24e- zRO4(R?J$t47T93nEstv-5dW*SSF;Hw1*A3JZn}{Pd5)pOxF4Kmzy~6gJs#_Igh0g% z1IUfLyNke*f)Vu`G-P-ax1KvT{jV3Gdm1vE z`Wyo;vmP-6$V&5z>Ok%9n7&qD(yTpKe@VtUcn5Ki^_L^TE2SN!DO zw8$9~{0(IGcZBfx|MZinsF0(>=?O9}W1f=WMYadukKyva@$o_kW^8K8mc<1s10`5d~%i694inJ=x{6>0i zM2044k@)S#4Db%74374ecLP27$({oo_Nrukbr>Mqj>V=E*j z_R?;8?8f5!9HzO+sGD*5#lq+sy@}751A4gpWRSZ01vK&Y6V#w2#N~Y+Iw` z!@bTsm)bM4p#t)BQ)u;f)#fx*ToADx9Z# zx?bD?gYh+UJ(7WvoA~4lVtjIe*1_$`Es2)9=p!T7*?U`lW&1B)r_Lor^a1Y~?(fic z1JgJS4GrDt8|P?QJv}|T@cz6{`QL3zPDw`mreLr$D?NDk{Z%@zVHM4}o>xR`G=JK+ z80q(QBxM_l@1D$B{ji_Lx`;|z@_!5tmjJ~6cla1l0RlsbJIgI0azu4%MVYMA)m+d)d{{mUW@YC0y&j*DDo>@*{v zjOxFBE>I*F*R2Bc?te2~nH_bbI#t){NSXV~Zj1i;Z5aSX6tCwQA=W7H!}B%_F=MDo zxc(xmU`UqYNFYN9GIpMyoswg0N*}fohm~(aQ5ZtJhGh|S8HG#x?4d9?k1y2Q$oz!; zE@(o60l>!i(R`No`SVa#8G`$qMS##MVzc;gXaGIYRyPv;L3w5MVKK6$CRN6k*m! zwsf6oa&JaXI&Ve56&^`-2d8i2<1XQ%5E?6t?(JKA+uWaw!-qjV0Ku z_Qffb<0I8iMGZ8UJqBHr#PGBp(>M+wI;LXH$`7bvvIkF z2`S39e|OixGP%`h#urYiEnSsIcgnb-DB1h=N{#U^)wpXBm6{hz)M>x}7u8c_bEh+d$U$)!fgr>j~Y5 zzsd$0p5gU(vWc~|cdl{Cj>sY<+%k2apVEW4oN$N!%4Z|O-c$Q8(t(~mY`oWV|(F<8NcNoW4n>h zVch#bUH%`QObja*m_A=Y?aX2oHJC?Sjf|KPz7t%(0W}1VED#K!GB?T9yhz_m4>-vH zgGa#hF#0EkdKtA{dHWp!Msu@&#+ky{6)R2<>N4lLQ;$G{l0XYFtWfZCK*U^)JKxBh=ew5K1$vEtInnpoFm2kPIUooc zMgoGAYWLM8_cUhV^2d?hse!*QJ_i(2z<{Uu3xRVEN=5!BEe}sW>_^qcp*ZP2v=L48 z62F6QT+s-?=X$aMK2i^91Ivw5AY0WM*5sgR+42`_7Kfl($fCd;v!#ER%&)yC`W z9xV?S81CNwOe*SVG||d+eS%**e)rIl9CJv z4jPg5Bx83W1wIMc#mCSf3DqO4IkHBE)=C-0qgoZhx5OW)!#20A z){s*HSu(AU!LM%?ZilxmdQw(An?UPpI{1D|`7VF~Ah*B(iV)-RO-6DGt1zq>TOR{~ zv6>n}qe!?|DB|$jj&JnB%R6G=C3ON&MJ7O6kvm^0L`P-b@2nirlZNJ&eL#J02_`CY zn3h2}J~GCta9D5|XIM7% zCJGV>TK2q{-fV~5TeM0p%!G4F`d`m%({@ciAc0BBW0$Ij=6YN-x1-}a^<$gf8AoY} zsPTCKQJHZ77-r}*bq-wq`oL`rxkC3yulqmgiGKxc@j=x`0aF8YBa=$U*%5rAQ4@r) z7;Se)RONRF3#f)rUHKykHX^CM89q**qE;&8U zsTU(+&KIGO^lH(@tO|G1j^9>2q5RDQIy+$Pn>5Kfk@@3PgWF-2Ryu8n)rU5Oc zs^WH$e1$vhfeR@9{y)!ICH6(!Rx`5!S2uj?@CC#27mIFsDQuTuf`l8-^TtC9m?L0KB?zNdw!PPBPtS7S zcX4HnUHTG`7Q`H9P{^1$j>TeO(V?!T^#a1s$bkjap)YiBD62nyY{kexI{%Ck4G;u) zi6PnKiuC2jS!q4g9D}y`6w4h~R{z*E;Wlu-fyER}9Xmmi{nq2iTh_8d4<1Z>G;%yOV#}gAng8;nk^YxA>G(cnKRCr z(Ib1W^*nc6*YCP`K?y$oCT-Y$6CyE5;-`J$g7;fhj9=6*0BnbUu!uI65tj`gy9|23 z|07>>MQ4;9lhIu);QD@#i_lWx!m*rQ;=l&07kJP~4?hB5%`8!?`A zEUA2)u-pBby^_3`@h&JVRw6aOaV?mK76&{T%Ru>4yIX8)isf;kiGE{ydI)+v2s3x- zb+FkI{CB;zVs+J8=5}l=75~QPR8$(#*X7tvpE-xsh;ZCvoE<6`+ir;xD%>srgEFPRdMv)N$=n>vUO{};*nWUjD_-`>{?HD747$4wPxG~MtT zv7ShWQaJoRw9b5Qp$*-nl9CeVl-Gp>moS{p&(4sSi)0ksub91h;4StOBCxE6avy7G z+(7meFko;hFavNKh}V%@W`+66MZ(2v^EJ0CT6n!|?sD{*D~qLcVb_fdIu*F;o|B?4 z_{svoKsv47qqR`{*Bi`O=i{xHXH}tJuu#Z^@n6lc?bJCIScc0hu3gW=SLww6!H27$wZ{F=Zw!TWS%V}rRJeCzoX{6ON;bQ6_ zMhB-ygTfr1cOn!u!E2BMg>h>hQf=?T#gYu;NpM}iY{xRYf;DFX$Skl`xkjX2HfrTx zZqEv05uc?=Q(;M|-8OR5HO|srd;uoz1e|Isl{MSFee+l?G|`Ta?V+PQBojEz_J%Vi zsgISVl%(LK$GhKpH~VJs-1|*qu?Aia9-f~XmIk9@fXZOD47WOEdh&`if$wNS_Ep=6u+tg>I`tQ74yN?#6ovBI zhXr9zaMMbxd9Q+)4h~wE zI|%NQY5fRz))=L%!n1l%MpV2kw0rDzUm^KH-kO=SiiSpXOCDhzmRxo~_8Wn1Sr&op zZTZG-yg}YO7twJ(b8b9om*le@IyYx@xNd3nxh_%}X;c1jD~6N^nx!lL@pr$1%!ZMl zpPW%9{E@G(7(B4FRuK5p@@RBmXowL60x9+F_?g>W6pK&)sCr;+2Vm8`xI^(iQPh z@(E(JkS%r-;Z#S69W~R0&3Umq@qVWG@n}kjg77a`oY666@o#m1 zxlS*oCqODjSj{HPB~ zQbt!Xq45O4jZ6asZ7TR*29vx)S7JnzQhe3<9Bi+58&F%P#Cyn=_{GXh;1Fy$(v*l2 zY>oQo38n7{yU<+SC=IZpHKV>zN?S(od3dHirNUMsE{ECzG?*-V&Mg45GwQPm)8vwth9L6YXPzh__?z!&aks3FA%DLt$Ht)H|gM4<+>n zo)+u!*;@sD@|NCJ`*n|9^}KW}*)s_H)+qUakIPy{rxngD!H32DqfQC$J^K)Hqr!Mt ziJfeVpK~K?273YP`y|y6Waj{NitsE!-{zw1ojQ-dR{2l$u+nj^qF`W`@4jgyA173T zanti$x`WVVpc9_w8U^TIEVY9nIQoo7EI0wSx#>g5}bQw4;sj840gW4*+BtQ zJfyJZ1PXYO*e@uaOR8SXcR_ceWm_mdGD1^XmUW zB4gOgBiiamgAQsT>=%KOKXLm(yYgazLV|vB3h!d%!To@RJpFYn)fdC$s( zQsHFm-zpmxwqsPyV(rd|As&N3@EXBQ4i1v{`4{Q($g?N?=;?hAZq~S5<^<_k@O^G1 zHfJd8nQtvd=QqvUM}&)6ogUZ&FokY5?4))Y>08oOQ3-@?7q&mkdx@X(W_EUVZUVO` zMU2j0I@{m+Xy5Ey=3+5}4-*PJ>#{Y|Euqo?EdE$Fem%61d7jl&7iribX>AY5sl}75C8gDaN7LKSfv+7`UFR|lfTG+Wo2(JwL~8K*HG`RO1iPW-ei@vY*FRVUP5Hau(U}Tc2$W}Lh?3&mRO2^TB%}`h_2!u$-<+0o9gc7@C)-I zi==v@XIa~I4{k3?yna|~_FSYeQ-UGI%SNg_yuC-v(&Q_Z`Re=mPsL$YxVJ{cdHE_j z)g^~A3|W1lAfI&=yI~YBR9cdfg7beN1fj|8jOJ>#+1c400>GXal$?Q z{j(X2*9eFx!WyeS>Sz*3JJ^~*5;df?O~C-C4)QCk38iZ>cK2_7gUbDE-tG(!z`RJb zC&2WkLxjX)V{51`5!X@R0s5FC57rq-dkBm2>0M8vMQ!NDKnr{W#z+5QSoQR5=ReJE zy5r#{tc|r+>*dYRN*kI#x)^anwg`e~gy8(L{c8Y>-A`6(&)A6RM9fFIhUYv*G@1)8 z;{|B}f)J4s!EuGKe?WYMM1z1+3d*+-o3T>CTc7sVF%hsJxD`1)vF+U5+iUnAupIe6iZcSM=Qg{7Lg8e58f@he;{I7 zDsUMz40<+hWqXp~qdA!;{maInXQYAW0;?47y^mMt@DJmuOe@oy^FDJFiF)g`Y5J?o zW$bCDgdK)r3$>~aP-aZgj{Q03PG^X_rDwPP+GTd1T`KOqGXcs+725)%72JA}pE7;M z6vuVBu3vDjTuIDHVO3C5S8A7E=oL!vVUL*JXoH-V$ zUW!jh$k96OJs!$kR;9T-APOD`L7|^QDLLPVk8+5@mq$wyRJ(^J-xE}2E99)@*Yo_N zEIZBf3=RK5v3HgryfRX9W=_B+%9*=os&C2Q~BSAXK8A@f5JA;4z|F6!+BH5B?{`kJ1WK=@eVB zt~xf`hxu6XCRAo0ZE1!LEzk8K)6t{q;(HWI*mbq8%(eozt_)F<>O9@D;16wey(=}Q+9FIAXM8zPjJTB1cXiHo&& zPUrb+p>4!ux-f{B;nKNU@KVfH{R2gXJ^SyA&(%9GHCSFN|3tUl zYT|jTJHhYFqiU!3X?Uq4F$HNqy+w`YUNw9;;C>8$st4OK`;93{_`n21Wy58W$a{Fz zVe|#4TO=8XSji&aI91-Ie&N(toC#*u2(TGGSFJMJxE9KGo*SX;B?|%QP4}J{A$3PQ zhmCCkwicLowVK^WFZHF*{C&?MZD@E?LFk(M6@u6H5L{=tK3R>J`oX*rs3>;$o75++ z#iU&s9nkb}>;ESmQ0`y0SnBRWT}VoEYqwWY zD76E|>NGUJ7)zT@7Xu4Fh;2Y6LR>eb(%uK5(mTS%e zeEQ0Ism2cr=Pr2=9$ywnsogEc9X&;_Ku`NHXM3|{qx=UoaD@$4Nxd@+pO*1_% z#acyQmpVsLfVg&7@v-5Ge5tC&T#lGs9&L2``ij?{`|wfv7K51C!dB^icB{i$M2^{q z{+NzUstoUmyrYV6`Z%W3AC^Koy-y!k>v6ym^1lQ*c)7VNO`+=miNK6#hv|B0I!h7B z!Y9qBU~nk`EBT^I6wH#BcP-Vt)C@1{;a@45@aUtk(uOt{2Rz(gK*@l zwI_2N5JXI)P#6$WrQ{L6EC@Fq#C-U_UDlbVa&apEP(J8)&QXh2FK;a&igCt6a(eZ;Vd$D}`Jl^?yL3z5DQToEUhk-U;M2iD&zeYbzu>+}vJW2{W z3HGnHB~vA60aM%clYUiXY&Ig*_m=F0j75#lg|_@l5eB1;&h!(Irnw zsHc?pm9(QDok_2RQDRQL7jba>gfTmy7PWX>2RG-L&93EvkC=|%q{qQgG95|%%=y{+ z-HtBw>moD8{SWna@7MK9$f_8cfLPdWk)XrDH7{eLk$bNe~-318(l7w-;xQxS(ER0C)#c@bX1G*{mahZL*(}w z%0FH0dqc?_>(8AoU%%HXSGCzALm_HSVS7BjU_aR&laZ0#*w+?4J;!U+9VKV@@71O9 zxld0y7g8fXbeiP8J*~nW`mIncrGmHi{5M-2Gt&&DU*UaCl+4xFbts z)Fzel$Cc6)g&l!t*57+}ytj6me@aWUaLRH@)Z^3QU`Ggb-sYX;B^blwpm>(XZ)TPH zAr~Llg0iHobo5ImNXBOx3NxSVn3*hVRS4cQKX6h29xzM9%pbuaV{e_OmME)t7g^cl z*Ak7}3k5MRH2k)Iu63V&1|AdBTlN311(3hLP=B9!B|=0Gp3|vlsq=XsV80OByncTD zaX9|I9!!}C(*NOx9~-<$Pjj0(dja)Z&34>616A0!5DgTvaP}DF`v*ECSfV2O3n-cP zuo^Q=_GGFUB4)P_k=zV~$BFVsg2TZO$+Plb`3W^*sm&OST>Kjv9?s6q83J0r{O>z9 zdzk(sgjZp=f6geopdW7C+6}T7grS$|Q0_(w&t$2J)hDo^D__paMxyQ!ym^<%HX-6h zAEi&^_uG+hYDn>yuzSZq^%?q#@pd{GfDi{i`xXY6`XUXUcT#a|bP;9}8&TmnTa&QR ztU6lG9z(pY1|74o>b)}A zJ^n>^wY(Ai_}=SQ1>AxiUEW?T<{?t7257`*w5At8=m2vu$aZ?*ltjt{#V?ckhrm|^ zv7`bj&+{C$m!QAqCuXd^_U5p1x9ES8H|oPw1$wHA3vX>=q&@`ntcrYl>W{VfT`|Un z56Os5GTH7hbL5zDXD6Al(a*&D77cyaJ_b4?3p zV9W%k*w&|q%f_cON2JViRczQ%$K|T7X0U2}bChcq-v3Z4rP9y{XMUaIzQ`mOD zvD{$>wR2$y@c>`BNYVYpGqMw7kjSy0oJ%Ratuj=&cK0d{uKPptlY>oIzclfgLvTUK})V;fQw6!6{PeMyM4y1f@8RMkp}8z}e%o|Tt5mPfabnXeI0 z3U)w?H(1K&(a<5^>=KXz6bVIJJsvcnLnNuSU2LeiyxX)?a$CN zj;+gRx?#S{Oe|t*&V5dfI`|9VXf4zAWFbgVhATye>h-?Z8ATB~0&UDc8Dd>aUv|E% zsa0(pjOF9!+V{-e_76c-wFOzO(6P0M_gcyP#Jfr%krHdlZ{NOe?%|N2P`+i}g1+S@ zm*}eIsXosy%pia3_83mAu1QyFZ#@o}DzZ=HV~t!L*hKGR(0}_B8o$Hsp4BAHeirOk zm#nJz=ha8X2;0BN@lCA^^j(PMjlidKM}a?CMmIdLh%N$sv$^HBEP<`%g(xE5EJ^dr z%we!DmEpan-aOj#!d5PKLV?TsO#k&Ko7s`TdW}(=A5X9hXgPlQ4rUwwOi=bOIu+8O zs?Ty6BYkh1_?Y*={m3$dq7XH5Ut=v25NY<$wV>_JAWs}7#l&iaYG?!i;(zu1O7jNG#6nj>XbR6=g z9Q&fHT0yDqLMUdt?4PjiuVAvdvBAMNIQYbM3){Q%Y;9dQQ<7#f_z*DnVEnMmExEY3 zpS0!Ao?~^-bkbB*c=~s&)=dibhUlI|p`p;_oV+}@RYjK%!&aNnyZ`Rs$Ap6L5jtYj zE!N1OlAxwHSHtAH(^ zkzpp9)(r_cf_No5BuaX9w509hHs>`0L&*LC=JIXW>41OQc1sKghd$kOOzk}zLe(aiY-{tKL(r+uBJw#JrG<^b3 zZ$JCS({i(@zsEutYv5qU(~yU3`_kaxAQ)7sYpfUWi130CMIW@X2v!0t4xG26Wb%ol zxUCs!GrrL^{|nmkrfoYr`XkuqsFL{^E4rDj{6=z*Iekzxp5Rb`&u5J=V_j+?W}Xan zTPKcJ0iJnar)Y5G}$2 z+BS&rK_H&cZx>P-%&wLemNrN&py#uz?)2~- z*DrCStjiN*hlhuV-U)gt7!4ppt>&jWt{G{A$_qdLF%l&U(WREgZh7#>H!e_+b{$i@ z_l9Q54J)LXCF}H6zueX?eZ8H26ur#EK1BR3--b2qq4Dyia4T5oRg}G|)b-nvo8#(x z{(*R5tNLuQJg_Ed)mrD5{Y{jC(Q`^MZeu*X^9?EQT_A|8oZ_a(20m33r)4C5yyt6L zk6l%2ON%l%{WpQ~w;~4s`0c=xCl~ZV;w}QGAW{HtLWuQ;sMon_1Ro8qU{1#u2(?y( z+b`Kn%VjJzW~?~NprM*tsP|y#5yJAFlzOyyLQyp z>W@EnDb=e^X@*Hs-&MJziCacRl4U=JO4)mS+`M4@8iVJ*ON+~W zl=XYoUT^(#I`(I%{|MesquC{`tg;1r&jsl4Q6lFj+vQLV2Gs6O{qSp>YILCoIt(3* zC=eMoAVUuw$HvBpIHm4rN3gF9v)C7`hMCq;qiP6-W*lI>zwlS*WVRt;N7>Vb_QPrj z5$|Vc;RPO+UNkYIu=@TY-oJkdaGdR zqf)6U=f-mmW#eB+;|O7Xcrd*6H?*rg<%8KN5U1pe897iaKtTdar=Y_{Lv=+{ z_K4&&Mj%QqreNyZP;4i(rigkNn!^7A|DZ;j#}@qe1I8-e|C|yUAt9;&louyE>EgVm zT!mS+M;5VT-jkh}c+fN;%BaiMkU1o8@&P>qK7W1*o}t0bs^(`N0YU;%cB5R8E6<5q z>ivbZZ)^(EqCv6{d4mC3uc2IB$bu(kcvvsJ#T=GefW;nVK_J(g(eKLL5W1T!Qnt^F zev1yewAX8XdqXlsqh2P=(lnKQL4<-(=vJfkNV_WwLu%njw8f}~7m3xsr@W&r;yc`8 z*;Ois!iT|WwNvN256i%rHvg4eH*5St>=C(Ne^QH2mrGicP`9zxcIiGS37y)@;P`?8 z5u#LM>LbII_mE-4L~jz@Sk@U9N?i8bt6I{@v@VuZ=BHJhyMifm5x)1uxZX9}dWj>w zWX*h@Cg0oTQ-(qV5H!ki-Y@H^=*qY#;AW_q%^zF?P&gT-j8ywQIk_Jyh`gK5XGb}d zUYrgI%mM^Y5a?%+juG_Ih-nQJrbtRHjG-7IoE^+mE-p=%WZ+uG5z6y;C_zgdi{JVO zw)lU4lPUiG@kQ?)GLN3B4{`?~3@)rlU5sz+{ z=st3`A~&Qj8rC#?UD$ zwh~s?8s~=?=aQ6QA&AX!mm%Hej*dT|?+!$WiNwJ)SQtbHjs!}9`c31fRzQw+nb5y` z(^@pogaQJZU8g=ZbK4w0!Z7-oU9*QhW*tB6?QgxIuGAhuYu?I}$tP+qc4JH?5Xk-7 zQG5MD_tQU7%vQJawqATsuq3!Fn&g=3tRsnm6ZP-GuiG3Xyn~OKg&)xOV5eFMb^zwtRabfVEx1Yl)JB^F$SManmEsQeA$WYA#=5sK2jHlF8 z34{Yz7^ROgx3y}tvKsmuwB;y6UwGoH!{v6LAX$0bYe4#B#P$7eVq_kh>%KjJ;($wA&u4G&w4;8 zcn#0pCBuy+xaTiM_#MMm^aG{dq&O}2IuH*A0wP(DQ`+#VwepAvvI4s>rBi(&x2dg5 zqTHe__AzU;*Q+2{fc9;+Phl8Q91gFqn!}LL^{=JZ{o=?2U1ITB-+_{ZiQr*Gqhq{{ z{bv`pkeB<7;RecAn_oBd}N;{AyOTUz0)as+&f zUD2x_1~?ZWm1I(v4AxMd9FBb@lfAuv%bzgCDIoMHx(MMT*{T2DDO_?Le^@CZ#&+OS z@OgORh`yICdfo2i zt=Gl9Yw_V%fX-*xy$8>5AKApG&y}~}=)Fiy$JUZ&9q^JQWQ^pQz`>$C8&u<fj(m9M<$iCrYXW(#TWD)Ei;6H;`)NzzU2(p8#`qojD<{4)h($bjrmr!?b6haZx5 z!aC}Hg}aYwNphrW7icyq!-G5VS9)hU#__X^?K?{p=B$o>igk&a2ov*Ie)m$Zx4x(E zqWo++$xAuF4232M`dU~h-=M^ z$B1ro6;q4R>5PVXDV$!{K!P6wQeR|B0prtPvZsgj5+)0$`^TqW9~k2yU?v%T!C)G* z!T(TiaFhd$)nS;W^e2_M2+zd;CraQDfTR!p8c?}@HP?$qb1^^r_6i9K(|Oa>ZzzEY znVOOP)*51*RM=TMM)9PvkCHDhCHB2^ijN6vo0`}o^aq>BtoVnNX2SG+OY!}l->BZs z{BeF7AdyI-_)>dGO;xOAQ@v*CrPXda2OTl(5M?{PL_oxaAoKNA=Tx_Y@?`9koYVz5 zsMZQeDC;VwIcqrW=>7p_0gLg)sTh4S+CJ&2t44H6Sf(=-?6>P=Sx>BW4VQc~Ks5kMY@U9ms+&l4SM3-fp<&!b1I=tRY z_mQ;%v=sW$zBIT3ZUMYchCRxtKr7+$E9eqB#n-*rbzRLn=;m>+!)$DEUh-+HC#i_u$?K{qWGjsxd7sO{~WsC!mIh##xu^NSX!27DKvjv@m7+NaoEC z@$qoRHNoBlvLX!~37l;4-tVaUrp?&m%i1-PC`=h#*4jt1Y4mA^dkt&LH|j%D?- zrt2!bt3TvmZEfu=5Paz$7j|sIir#!p$$nut$;zz2)t>`*=isLr9Mk{>KANhVFH7v< zmErrrP24DarS^iJ*b2{8jf6V~9fb#UE8X<8+S>bu=ZAy~@wI(R#f&7JLm}}DJ#GSn zRLa?NPS!~C1`ia-Xa+A~J>OFw`WZ<6jW}dQAwY-UzR@+=Nk^cDK#q;Gb8qY@uJkF^ z3ojp*Czfqmx#T%PHU)DTHO5`!ZOYXx(Tui*@3xb|FH&DIgn8)*2Jl{jDwk+jSnOvv zcV<6{&3#ryHiXD3nvultDpb*k`xrLMd!QeHf$`9eem^kMDjvKRZE=0zV}P z#KRz^f-4IVg#D+f@0Ddvn(AJ%>4ig+(14Z@4|YzVNSGC%YKG!1nbBFf-1u%QuJf(Xsb_am`wuf@i}WEY!&24Lm|ZD)qSk!!5w+ z4C*tk^moHzQ5CZj=#?$atELP#X8fWNse6%ep7Ln_uB`a9soWf|^6EUHu+hit95lq= zi|=_Rzq9)2=>voaM|IU_8K-#)I;YCIsy0?p*JY&8r?<+^%qM4C4mz~$ZVvVaCdblL zRl45G`u>eZx$>8lr4se~=~ulf#m>%CKh(27xIMX(iHv-H*y{k2P0*ke(fe6%ovp^!v4Z<-2in9-j3)EDs7cOhaW!<*2e5+ z;@R?$27C(#Ki{bB1~Tysz03Z4JsLs^i_DCzWiLsSlQUkuIF%DdO&XbU2M$HQj^Yia zcND#dY7ruQ$kG7{Pa2iddUL9sH=~uG=q{Iz8TcpXYL ze|pJ`y137AgugS0iW>;76m!R+B8d%8Z+?%9vvKq-Eh`hgCczuxe8QV|YbZoI&EnWb zsuhppT61wdG4HGK(WI4zcxGC&QpMvR3E5L-f+9ybU91dkLe4ejA6W0UZ%$W@pbuTv zG7Hx5q$5|2WykGCHPow$^-BYC-t{1hQHlrpxz(vYE35gd3mi1NXODi_+3PBJg? z(J4lh@dqHgaZ8te9HU<yc8obv;-$?LNqr^<1KD6QonFLD6_idE^m|S7OPRiYTjGkw453UGU!yycFKj~dYHP`I$B&!(lpWkiL41dm8$*?=HFVXxJoAERr z$j$vL4Cr5X`C)I~!YLS?wtjyZslSlxPm$ z&C6hc0G2{wgiYP)1Fcj$t{CUk)|&^F7JW=;3ZUuCKy$g|#L)&VRj3S|$8QG~UEqE? zL}%u3YaKB!s*ZnGF=4Q>tD1MB0Bl8hV@uIz7Mbe!5u&4=V>DG zHpR3mC*#qwt}$|@HGf7w-->K3U$gTwg__bqJ<73a}#*nF(> zRb;D#sJEK8jz7}Bol4g~KQgTK`_o8*XuXl;k)59RgPLmh2e*PLHV&p6H+LVu-$;S4 zj-_loaQg6YY3f??^T#>@9tm5ljsrBtX72%h{d zBQ$0G`L#J zRx}Ys5#boOEY5FVy)b=(Qy7VX<4O3wM&iRpHy(6SoPIYRp-r8?kJ`*P8>N|1BJ=zx z?6CZT0JFh?1eHvujCYq-k{#0KhCfQ~QT1&8^~!q0>L6yVVlRR2iWlb1*u7gU*0wO< z-s^b~o0GBWrG9Yj)xKwSa8%zH8O{m+#72*Et-Fz(bu()@`=K6Y3==QczYt1CEFH$l zn(5d*xewNrpT=1{RB%qVubXgPs=}+<`THJz$od8;p+6ueB2wbSGgfj*B!IB_nesUe z0I9T06+Y$Qt}Bqfq55F3`9Y!^rh-zLhYAYXv(o`Te7!aC%5Ug#n>wwbBI;o)Y3@Gi ziRX_mSUCKDEr7bZso0RHgcw+KwK&?I{qS@W42QKh+*+{4o~K}o*oEt#I}NxypxA7> z+jlwz=TZ40iT|_PS5LQSsQkff(F8o)cW~su!{7Ch*#R6G2WxhI?_p2?Z*uR0_+Y2Q z>FEz!f-d(*q+@eQPTTp+Kl8J4IODuIq`|09MRL7*lo(~of*IOZKiiby7%!B3r2SG; zU0rary|O}6i#gzKSzFa-bP>H!Q|V^*OxB4q(KD}v;ZDV}Yd4PKu&sXvnP#vTD)tR4 z=to_*eos|O@Q&4@I;(NjHX8cyoZNJW)7YP)I!3G{ zQ5Mdl<&QTVMG@{kgu@{m8khpVMjGEgfBrBfe|m(!C{b5ThglFZI@^#>WB%p=cDLrX zHm6nEXb;36IhZI>P4oynfYM z1b$Jzznne2zo+v#ji_exWZPlpa3MuF>Y=I=_rn0xt*dhXcHQlpKC`$V9%E$wc7H58 zG4KD#zaN>NK$jmTu2Y!WWd`&M)5nj?6_PKnm#=c2B)q@>(90}6CESifZ+roO6i=7; zAcXRCaDCIA(`Cn8zQ@nVOZ^^ROcCu_J<^6h52Fi~u|1PX{)c;B(e4+!K-O5c-t9Z5hkwEDlcjQu-tA=D| z)0HSLew4Z_mLl)04QHg_kyhzmRO@qJ-OBf4 z`RnZY^~BVi%F8778aVN5hO;EK=|;j@k1nFfC{vYZ#S*$wg$2g@iDjOG^bOI!6exnL8NxrWhu&7Q-y6DZYMq%pZyr^m4pUWtwNJa_bV4~ zZJ#nmhy=oke_vpF&ehrf&ecmZ3^R|ZLSuW(rPWt4&(DY{9IR!i!ADuoN!XazlcLxm z;*$2wW)FoD{n~Hd?yt9`UNqB(jQ{2_9I>#Dx){&=$TD1<%HPd074e3 zVFFJ_an9E7Wu^E*l8}2ZEP?qS{ecW2Iu*zY=_PWE$*9c8jXkr+Tb#35Rw|ym214B1 zT39<_Y5;a*ii6bkIK1xcb!Qh z!`PJC`$d_MrVV8tUg5J!e(TeRV^0oe=lhj)8*S68%| z8NvqVxor#O1LWu|7A6NA)k&sKdKb&K`<9QXaND}nf~P&xy$5$Rvg|f=rH2dU>sb6? zwnX!JnNWF3v7Vq*bNhBt9K8Gf`IQRJ>|Z+r{d02J0vo>dX&sjD$<|X3{vd5$HD(?7 zF0LJieZd%9V-YNJ%93VV1wWpCF~ZdNKz0Bq!9mahr5c<CGLTjhM*DATY(i00JKpaqix~ zk2vw+mILL0mA~p%Wuxr+)cmVHx89|AVHBP3fng}E@Qusl_j#5M(-h*~f%ThwtjrFL z2s2^FFLQy_Z#(1!W_Z1GUe-7qTiBi)Lw^Ofc|aL-1Hl<10lJ7>AkTM~4NBATSoR%v zyw2kUaA8@H9gq>?Ju~r!P3|=Ag`$aDK5k$K28?6d?2W;@d#kIfSV3fJwFaV2^X>J# zLpsLJu~11nQL%q~g4BdC)Ryw_5QMpl>>*T{%0T!}OJic}%IG63<_mvQ+);X(-IZai zH0Pg78zosfVLWDU3)q(;=UR(Vp5?aouxADdTi@z(qJPwLFJBof&CX4#{IMk~isj6+ zlW=3{DHS^=7qigF`Qtjn8=I+wu6^AAt&;+nltfof-6SX!f1U`8%Fn5#{!YP z8mM%cn5odBSKoeZeh)70`Oo6E*m^{2!pqVr>Z=tF)HwG5tQmHLw|Bt5D2k9*NnIJs zvyWx?;UwN`UIHy5y3&ttq61~JQq7+eELRHR^>?c`sxN4@6`@tpy{-&OhP?#<6MphT zg^8JI``xCwEdY&_m3s_zXK%cH)c%-BhwbT?dw(RRW;U7Todz6cw76gFaLBs;-b`0K z=gIG)?C}{}E5j+n5K9A>=YTPb5t^S*RzM>_QXiQCkqsGhA=I{2SpN9p(6js}2Wx*$ z=Uzq0!^`)dqE?*5AD`ZC;$3E68dftr-@~Mtnc{mjee}Nn_QpVGG9g}jS!Y<7kMCJL z7o~2(n&ZaxM1IT9b9YC)+jF(|nTdMNo^)3KSQ3Y=*z z34Od*AHY9?kUn9;&wZa@m^0*&O9><)olIa(X+byM11n5t&1KObT}!G6G;JL>D!37_ zM-1>!oWjgn8Kx-!2ftk`Nq*0>8cAZ0$j+@Ku(7dmpZzGa(L`-0u-9VH6YJVdI3@`R ziM_C$1-1_v6tUm|uEO$R{CE-BG7aL@mVvfE&52Chz#wxCIzM;7O2FEQI2Js5 zh&c(|r{Gx%iDJ{dB`!`61{jcp4p%ra!wItVrFs(I5vXt=Vro~oU3Vo*-s-26N&!oIa>Rq*lZl8hN9SS!cL9#VFHXF`|eg}*xM zlf<0M9knKT3;hSzA5#2A!WG#faCHE3L!7d$L77Cp!AZ}AB|Z6XjvX%cETljPE(;KrZEOJ@{>T^m%pzeZzcS)9$O z+4%4^_lj{pLz^;*ucqb~!AbIq7uua%kBF%m1~&U0io^JRG@fdQ*$(FT+_LD8qADUN zRFUi!?DZI2xOQ>M3>tuU1>Xa*=U6C={Orm`_y$WNDr;Qy%Xiho#B=WqjzI(tH2pHS zUwhUterz_R75=r=$_9hf_6IFm?0D=rbbhN3{&U8fxt}H1<)K&VC(5axlC!VPq;9%< z-hU(fV*T`^(yjP9q!dBEguW4Kmk$c*4oy|u`CF$_$1``)px*#QC(IO%yb~&F@ZD>U zmT}wxwk;Vsi*Riru}u6gJr)YU0gqNjOTKcGmqTk5cC%$i_*-Q%z;wM8u6+6^Vr$?4 z5-2Y=4350-OpVX3yC_P;{V*zi{iS@u^b~m|$1@B&UE}#mWtqo`#G7kjvVBa7b{FKp zfDV^e5I!)|i0OTHK0a54V9k$YUw4V|_~kp2`(VY5LkBJYf=bmPYfp zV}ihOADzciMj0hFGdcggl9{&}E1}@{FP;jkmW-f99(~m1m{4w#Oi{lVX{Rw~rEUE} zm!!8msFhqJ2llj|j-Wtbg$FE6$RYnW^^K7VBz;8P27c>*T_|KAu^Vp$S;eNzWkm5|= zlZ1tS7fXAP+edJ;q0jbW^BE|6`1l! zNl67&n7`Y_5%n;Eku0s}joK~~uJET*M~oeBNp@mczlr;aA**{>YijCw;A)rI@~-5- zOL)A$js|5UqUnGY^nU`%x9|%fj>14LIH+%B_gme!vk<mp|h6`6y--j36QX3!^nbJR-(+%@mQN*3Ovcc72^zeJyNy3qpT zU>qJb`@68ffMX4*ja*$zmFEFz^6@`Fisdz8^~H=?<$}@_Cs{sDR2}L!mBSx13xNzn zsrm(`D=a4c`6vSv*7eTP`m~1~xkI+U&Jr*MgyF$9YL+|EbU%j9?wXr@$!jf~bZy(G z9C#cQn#d7xGjsDtt3SaLUbW2CtfbuSmojP zBD8MQO6YO5?9Ufl;ft`vtEkCddE=C0+bvHZY#m=iQXDNqF?&P7Q{N&2Z7 z`w-MER8^5kP*IoAm|66;AN+OMocs zJOA#}FTJ`Q5i(Ujc_FI0`=4&Ly zg~!=VcQMLhEn6;nQEru#p{0{a=;?_%QSG#0Wf>YLVbj;N0akg}arf1Tm*$*=_6Qh8 zA(67Ec!D*1)n%!)X?5}OKfC4Yo*$#b#W5vLBas5ku37lLW@ffYwvO@9-A=y{i959 zR0HoTpq@&w7GXFI8A74J(_YpB3`heYehE=p5U)0fL;C?ou-ju7b^wfe@P2JRNMi>1(@QKhFQu%p9f!qKD&l&QG|^X zU%&<6}M$1ZYIuuK+OwRtL!5Ki{Ap8>aL|;1fsrL+XP-uZFqW^5(6QplkW_<;!|l zM`>|=wY)CZ4u7UCPPs{}pNj2G&K12#uf|j`xxWjkH;FAn`l#m#am@MwPTC9k0akM( zS=tbc^O|R+T9MQ#;5b+Vn zjn(yY9aa<2@OrB=WKB!lk-V;l+isKpt;<}yxb}z=W1OqRYK{mpG7`7J^Fv_I%VXmo zU^6%qTiRn0BxKn=5^v)5^Dvfbibw0niD}X9ULTzzbx1yp8SJRH_q?pX5Gh%Sd%Sw# zXU#ZVBk)Gy%A|xs%C}Z(Cjr%@znhZki6|PrMJuwg1ls1Nl5%1RyzQ>|i1yaW5br%z z4jiKwfV2txA5e2U61K7J!!0R}KJz2NtH9=qr!Kr?(8+Tfui0!vs#- z(qkAd;tTB4pw$^g&Qw0jn&o@#+m1uWj1-x@x)%5eqT8X|o0F|Ir0BgPdh1CjS7A^$ zUVC!G9z)_6g5=*O2=DZKsoA*$|HBy%5fa4UMbcn3I905;D}V!Sy1XT&(47Onc(MFi zv)={rI?$uly-ciqVvI{2o!4y8xhhB;Z`!1MP|%^N=9NbD=@Q9##1zJNg zQ!JtSn1W%(@V$ro~Scr zd%Hx6vZ}7#71>gvrLH?&6oFFZO~!bEX=Qj!2YIpIY0I-Q`_eWQnIM~~QRc*A+c=qD zYdU>GdEERPAk3=j>C>y~R^A1%+*v|lm`yUFT7E=jL?`dUhqVPEb^L->wZY7l zzTAXUli4((Y^~B|E!)b3!2JtfU5EmwgrrYCn(^>}S z*g=3e7qqX4N*87zG-V0gZp0`O*XS=ZFwU*_Snz^Mk+8;Ln_s??C5()*_O#;D^9$^>U+Kx32X>{Or--yEcqG@tK5%o=Yu#|-|1tH|QB|#5-6{SH% z5$To=!3|0ah)OCTE!`~&1|b51(jh6`4WgugbZk<(q}epzT<4B=jBkwd&l%@ll)cw_ zo;iP6Y*)^^m!X4lFVR#01II1EC2FQz4zd_$8UbM8oA0pl6QHW%cpw!U7%& zqId@uw5E+jL*09F^6tF){7xPhUS4x^a~U{(5Cy{;rksU=j0KJn@U6xTLU7%D9Z~EZ zyLvLh!;2LIt`+m}YHgJJ9+krt;|6_~o3Ozmw>sFQ^50#&xhM^|4k84F9}9Inxifbw z8|TrfGnJFD5+M!{kXC7`Lhv8bH3|O;JR|(g{-bng&EgPehy-+T?=Pl?{a(8Lud!Y} zjfcfSo7+nLd`qO4I-Xstuc9TEb%irFIf^q{Bq_%-ZnTv*ZibH#9Om z&bwgjw13HwKCeqO$;a_#zU)KLxT{}vrQdEKQOv-S1moBZp3|-OK1B;UA&wYzZDaMQ zn-~g5h8CLQD(+SL4cwGWwnFmn(JkG(NijHJtUXhjnF(nsAw8`QUhWM;!q-b| zh2K8gK1UFeNpS@%8#odul-qJvh8-CAa1C+t>Q6n4)b!J!|t?&p6N*I_NZ z(#~1rEGslxYB-kR6)mOK5-?<^pCi>GoReS{79N`1{)p#9v&C>h4a<-HSQm!ftPGu@ zQK<20E=BJTa_bt#E`;GSO;qZ2(5 z7zd#dKtlBP$*2#coFOa$^3)-#Qw8LwsT&&FjuwiWUKZ@7Zq1iGN`Uu#|HQ|7q=*21 z<>pP*5p@HDPymhTk=&aOp88-QnPUs*$CTw=NG%%lo8JgRHapTE1P_rc{}*{!)F73V z1T{bQ6;?Yf_POOglW&=OfleXAiA!Q-Yv-cm9+b^A)pf7bmMIrbnqg!PJvB7KMdgwT z3jSPPOtVox?Q&t?$eH~XHZ0=bULyG|Yl}=%@Sf&QURq-#l5>#^F>KRz!vbQ19qP%i za(d4DVT>~^QVg0S)58|Amiv@6Nt;QxWy^|k&@A^GMSb$7B0Xr<6gh<+2!6U7a%nei zl<-`XlaN8FOB~lnYl==KKJ7nu3HYL1**m@_bYQbKZ8OHQDX{$46Q&_{Q7Clw1{=aUUb`i7p}??=BE z=tG{KtlmpSU0-Rx?Y$W1_#3OE?;MqtPfbGDd5sIczw{mXCr`c{JbCo!#b6v=&!O~V zn%8KmvzY@1RbA(=9Wfa=PbnDaO{?qQX%z0!88fqr|1>qc9o>nfsr;AH>I3mky{X?^ zf!q!i-xI0X`1^B4rjE#{eEGpjHKQTff|r|<3WM+1W&>$M2*=Bxj%TgY^Rd$ZB}B|8 zK+6JsgZc6cplvobc;R_N1UBjKfh)cKCFsW=dzYE|iE|B&&W1;HQaj1y&wibEFA$|v zi}8V$XvtBv+4?d^CI53#vWM0GnCUlmM_n5-pJg}%Vn20z(7JmCwbP1u)%u~gWKtbXfMZ zRWm~~$?T1+BdL9}Q@>hK(&+bjB!`@e{(Y+Aq!&VeZ_jA)6F@dViaMp% z3p~-+cdzMuq4eZpYp`6G)paf1oost>E;u+iW>IY}3o8ERc{O+vat|xJqt&Vnq3$oQ zX6pgG%q;nCxs&UORGI55D~{jR9eoS_)z{VM=aa)nXY3Xjly9+;FspU%zYw6%Wo$EX^ z9#U}ZZ2sc$>Di_Q`Qv``ojQM*XO36Rq?`KGq}Sfxn4Ao+`+Ab~CEKzE=Osq&fNbc! zO=|IEm8yT?oTHnxd;AuKShDre7yiVWjHDzZ<@;Plt54X=Iw;$4~lAF!i1-AG(~9{vlC2BmrZ&>;o|&|YbsRU#1itOGdO;IAm%2& z^`|fDpgt+-Dzi$#g|QU>6qp9<}bq-@wH5xa4eo>v23b2=Ugg*cr)|$&}3{45BOZ;9A$-!Y$A);ApU* zzddSeQ!k~1$zA)iS&nltpD%sWv^$8dF^)N2E*>vm(FQ~N!xi%&!p3jIy=*IWy`+!u zfQiwV-9#_KQ+L8YQkfOpnG*FgOmi_=eX^K5bnV_3Z^@IAzRl=cH8}FPercCm@@4X% zCS}-&d+7EVtMoOV^FdAN$8hl86=7%=svtyd{4_kpg>)`Wo%t2oOM*4W?>lfr+@`Sg zE$+>C@tST;7hj@VtH_11}I{~sMY5P@V8wq2JuQPKo3(Cabqb zT5ei0V{F9>n(^MR3JVzEFGlNMSQ=StlGT+nRHZedmN0`o zQV~Ayf2GBqB+-ai$d517-ZMUDb>~y~@x)-K;DAu~;?*o3L-d z`LyI56t?#H;2@2U@DF%x`3|Se{H*dS3IB69tsX80NgrQ>j*~~mLa3>%TZur{Q9g>B znp!e*KxR6j(&d@W3i};O3DYOn29hHum)B){m<-%D38wC$>VKCvD(!uaik>DM^PB7V zjJLsUE6lVsVaL$2A;1&#W=6!AjHwvuv%s~o#{BSM!cv{hpMiuP-pc;|{{JE~E3z3y zG+tW?#|rszoTYP_^+C;Lq0`dC8JQGDQJ6-6@sWVwW`qwy@}vQMpf;R{zj(8(u1o5l zMOz-MB+6h{fmaT-7;G}0_>*tGW>{9aOs{C}?WoRiEOx}|{p?&4!I)Wjfuxi2@^(}Z zp1YoZ5K+!p@lcu#b7n~HO1Q_nwJDQot%UWqxKHUalkjHW_R#4?dI{2m4^MnF`;gy( z3O}UlCQXMqopu77^2K-f9v&W$JC9Vr>v5Z1zuUW1;_d^>3h)UeMv;m)czJpKVEzCu z465v4{-K|4X`+gGafvJl-Y+=F0stw1Q3pb@SYkU<3JWP=Lj;L&!_?GO0476{9+Drr zC2?NnKB^z&Exmk>M=m`4YQtk3Gy3ovbfZ$4%KEgIdeTF_TZ@Ws3@+nbZWeCMZummi zHOhUtKYOZxi$OqJMoUB8_&3L^`yn@YuFA1kuiBTBavoKd{YXL6hgh8?44Dgt(PfnN zHWv0o{9ems2#p#Nn|3XewGK-i^4P>pa)T`P(OagGJ&rEoa9P9igOs^~B`6t?bYSxD z%sschZir(v$eFl=J=$zdWNIXm+Q8`+o-GmuGruH4m+n|8ESeKzm3&fi-RNHNeD+9O~NJ$5aFYo_yzE6t~`a~jmpKqAsvD8zr9 z>`8TX%l47~aNX2LO?D1l@VQn$0lx+8w)V%HE$f4NxOVrZtq!jpgr+-jtpAm4&v38p zY^iN^AshAM_r<>V)AE*SJh#P-8*Ol;IN4_Aw)?>(V;Gu2BT7?@8(cCVNcG}*I2TyX zaQ#ux?mo4BfPAsAw~~;OUZW!ZQVXSC!N+FxB{rk17`qqMt5Vrs8VPx6>)^6Y2vuP; z)8)Ckgkwvb#KvpcVWs;rJFf+6H92e;6%KBANWEaC@uOvpwEf!L{Yh|7tk*S5FLffx z8%swYm0_Jo8t5TP?8KlQ_GfR?6-_z1{nD)5j+716UTcFL8Z;XwByhAIc`3f8v@|pgc)o5Z zzX03gKI!S8J7XxGp#1hVAuGqnF2DIvG{y5yb=vEF=PXYQhAs?&n+0R@XJ`Oz_PzLh zJ;sQ4NX^iY8A<;-{^wdR5ahX1xAne3>-mm!V&@63!Byy(pG^h41Y!VQ3t0`u98Qas zUAkvv#-B>GYLV#Q^AI-;(Vs$w#7}6Bd?!aHY7!jB%*2F-G7$I+>+wG*HrONL%Qj$q zG5T+FUt*|c@Jji?e_om8-w*4SvCRc^#@j1&}3`ks9CgVkW%l>sia+}!Z_<2y@C^t@ z2tPoKRe%N~#5D-&p`oEcau69>AY+XWa+M+R z4#~iT2s9M$)Mi5i3W6Z)TdxKESGS8!1&|3YIs{mPM!lRsL-6auZwjrw&GO3ZQ;Il0 zwWi?2gh$lT?|dWq<+sZOa~9vewzrsb(7#SI(!8hgCY3#q{i;Qq?Y~tD4L$+>f@yKKRal8r)eQei5JCB0F;Rc zm47ps7x4XksE*Ucp*M8l!l)m69<(`S;aQVe(~9@lV5^R3T`OD7(Lnn>!pISn1L1-c zf2v9yn80#5Q$2aY4ZRMlPjy2h!p?bidrky^8kG*zM@VwFv2m(9QKAqfrE(b#t-i6a zolyWw*>q0Y9I>B%csk7*2aB5YMq>}#B!H`p1Qi85T91XeLUvKG?0}e(k}L@LK5NTM z&>)NS$tcI2N4f2E`!;`B_mxH&fp0OjlyC^gFQ8s}n`FZCA=5tN{jgQnCd{U&2t&|} z!PtkJAEJYCIuZ|#1R5sEt>0Z>+DAWZ3Mw-4)#Q$qv$f^ZFU>aI&R6>W;U3bvpK0Xg)6QO}N*%Frh(yq^d{@RiC0=sYdTs|ph4!3a!!}tdS zTAeauS!dC@#BFPF^&K&Bx^4q<11q%yBA}|JD1Xgt@=%^m4m^@$KBQoJT1K+qCBoxs=(#HddxB=b=`NUy5h3!* zBfJY&IPDmpwkKW5wIQz{Cm|ejH0$Q5KUVBxp#Q@Jw@u^$=Ux);C=%Y2cYBu zM!3*%K^0z;Xw`%s6qWa6`v~1PIAGDyI&3MFBZGIdN4c5vT;vpN}=M7P;V$m?-51f&E&W!RqYFE}s|LEtNIgAz1b;}n;oJIk~KVSZoK8V5IF34TF zJ9_#qSPm0Y)FELWtIaobq+Q6^tzH~*jgiPEkyOz0c8N=@jqzLG?OKLQ6B$B1{V{!Y zcI%n1Qq~{+kt4muV?4BCkZ-P?r{7|)oL0qdBREPMQdv$+fzqVcK58>RgtQ+9Uax4Ww}<+)kWpPJauyt>>+u%}Ad%iIgmUOzAAs{o$h+s_Qddo^WvUxd{d^u`fbJ>&O#)FseZYT4 zC3H9$Z<*!Udh!%?Tk460&fxMoS!<^ctIBz&w_8izl3n;c-y$6Ia{IhbbLF?Z^zD~t zx!cdMzXmmcGqYZPhVK$%de4s)DwbLeotZL^A68ngP`gz3<2=VsCfuntJeno=l+|?a z{=yH!X{|8zgZA~yA2mK|OezJ{kiJ-?*{&yKT=dX9$VVNTth5nIt?tUwE`z8NJT>pw zn8NV?)9Fkudg(WABTsB$ml(ZL_&iSrb)bWq7$Smy=nBLcq;oDAtKrC>x#fB7ca?A*#{E?p$PIC@*{ zpyczF>paFEL-zs%!}Zd0O`w@*b!7!~CU{UJ2-deh@Mj@6X`co4A_gWO$SHAha-#7J zKME$AT;u6Ay09l}8Zc@oJUJucI2NhHMy_Fyk?6VkbnBMq>A~q{`#rnUpuoV755DOw zY_Um~?h-FE8aTvCYuEqjrCk0quK5+$JHz~a`l9~*rwgBg`NI_}UcY?y?3zPm-0hi$ z6~CH-bwG3HEIxq|Hc^^8Z_7|n$l51K3{0XvsM8yWZQjnI~l4jMF zAW08->j=CKzbyFbA?ooxxSwOTE+J@*`jzyFt{A>1hItuO%&R!`J#cq=>r5v%-yxlI z5(_y!^?_gVDpOdjq9oTPK7Rhc@25;lf^iEikKMm5K5TXOcXKfbV)uWV82tVmudwz< z;tV=3!PSykKk9v}vwx;h@%qf;MX#KqrCssHhkFVO2DQ^=8rjWUIFm-aB1`_v5#jNyk0Eyw zly#Q@mc0C_?Z)ZhQ2k%f{>i{Os4BiD_&fFvIWjXqMm=ivX|?T0?@4)y~>-wqb*nSSl)Si4Hs0Mi3EG!(gti{kY}S>r1LMAvOBsUYkW7 zNP*tplD=&XHMsyeW0`_YpMPYcQbY<<=Op}y>~=I1s!_>02Hpg2mm4~X2(6859@0wy z`;y-O=N|>Bk2jfn1~pB3jfyOL?3w2#*|_HD3;hVoi1nep}StvR$=-@RFv zBoBS|LL_wiOq|IC`85}`=Wfq&B~IVObNc6=%f+)F;q_p$qjKm()vRVuDOEw}`eVjy zvBcxhpzB))U_5UA$jrd-dNMITS*4}eJI}9OQc|_zB_O7AjNMjPKZ z6DH2oUH`G^mmzB7&G9b8`y8Ei=}E1mWn>_QK8s6BI0-mDE-j2A04>@#A59QlU1yl9 zx^NA@p>f=G{7tvlU}MLMqsZK>CW)a=27&LEepzU~SQTlCXlMXwzBS4KXQOX(ZsWLV zp2hp0d2?(Xrpuvl@|#Cp=be38UXRuZH$i^>=k4d0Pb&4KF7857!%tn?+BXoa3W78e z5|SwhQ4~ikiBReaLM12{L7)QU{vXM-!A#CE?uTx=rAEi6R}r+$Gm8a^T`5!fR#m;F zIX4{{VELio`_)}Mv2(OC#w!dr^kaXsveuUcSoQ~&I+J3!NB_S=Cpc8YIP5`6{9W0p z=({0)#I-eG{{^j)oFEyGZA2Z z5Fx=5DuUb8)Rg*w%x?r@i6LeIqLF@#mi~8I!FBmx0&Tt?cMzPSO~=TwsLZMX5|_w9 z7&nmaPMT6U;gD2#Tibjb7h3&hF?obPfB6y(_64Z6gtn$m90#hRWex2HwaYfUk=ebL z3cHKL~5}ZsZO&7e$^Vr^XXV0va7__AE zpp~&)Ty(TS$*=3MJWXs|S&L*3t)-hSyS_|-TSQux5w~6(rEpP6$ow4{BXijstB|#U zO=kwPUOaAA7N)^gVQ`s#b+`>%9C(7RZ&-qZPgmH9?!K#d5 zZblJ#`5*@T9WPD|@lvgG4nP^)6^{J{1udbFiQeJt%N;FnD_{}=nGhSRzV}0Qr=rd0 zCCQSm4U3H~deTqH>Fn@q#1yhc#6ttHi3dJjE4q_Ew&proY9^(of{k+i(SNEvTRq8M zpLKPw$9{FoSjFQ8 zO0&bq^**D2oEgs_B_)~R8snPD0k)y_ewjX3&s@m{8*7|YufXQd=qn?ro4)0kmRi{+ zHFvgDhzjE*BqCB-HUpCY?7Q&I5)u+Bf8|lS7p{QF^78V?0AZaI=`F)}@9>A(7<@NM zY!{)wIvZngcK(l*?m5M*YnB}-?>mX#{BpQ1XqW#v8X@d_RnUkVB_}+UGn3J9QNj?W*&sE^~@crua+d5t_bak*ZP^o>u@zr&;6Mx zts*PQJuDw*C9pr>_73u9oNTi?i2uC#T-TX#yB74{Pz>K<;`EbJVG2a*_#a(yvAerC zcWU#$Q6enux4r`qDq@nlkSAX?9J zt+aKp+6oV^;r6Y>S08xlkhQqc$1`z8q!|rzuF!+y3lMgD1}lhtb6&kPwz8Y{;K1>i z;cV+e5rD}ET-Y%%frSmo|-5$zw?f)I#A<}VOM0Bkmkbo9SV^K|!Ro^Ad_ zQx;;f%^r1ufqX4?6jZM5-nvqswC)UaD;iW0Y@&RqL(u<05_WcfJ)~_jiRK#zBgWTNQhPA81 znt>>4nVL#kiG0Ct$&UZk2Ub;c{0%@w!TZ4{DEN9}!T@h?!!8wsdC3s?3mOFU)aR(E zYY}bC^PfBB)JFd;Ej7X!YKq^uv(%@O3mq0xG;px9@$e{s`UVz1BweMZ3Y?o&e2*U! zCj$->8lk3<54u-)3}FJw`U5K(f~l}a-G%c8q*Dm;3>idlbkU%iLgUnDZ}TG`pE7Sy*JJ>4Sr(WNE(_=h}c!ko8k^Mosa__Yq+Yec8bSEjlKq zX2>5wYRh4NgXqnav^4x628Y&|BgPh4i13GhOijNnJjQWPvMSQjK{I&zQvl-F{Pu;` z+Zhq~utU)_`use1o63rq#gFV>0|g=+70~S-XK~ z)D%0wzWY-GC~g!(;nX<>e*%=l<07~74q=rCe(XyqJ>OzmCx(yFl;=)`d`Pd7Q+#?^ zvx$bk+*I1}ov=j5=u1y$wJ~bgl*>RbLRvmdhF0mtD)-3l zTbt8lbP4J8;k5zxl7oy+->5`PA_sZDS+9MhYDNfm64_k=G;W^zNv=(a00+tlQVPZ z*0Mk^$uLkCeQc2GZ$pGioE8dWmlk0fB@_A{#hepYNY1LQ?w1zizA3dFP?MLL**ca% zIcQzam2dMU=ctL$?AC|bqTTPC4H`#|`t`zYN!>*llkVuXa|K5>;vYqIi06mNSbfYU zbF9=^NZe~be@v2lh0RoLBdL_U)~?Z;#i8RsxN)-XJK6dcf^+sb4_H^^baZqO+cAW@ zUTW8kW&V$Lmzb6pcvr~dHa^BsdIPhpWPue-bQQSl9Iww`;HX8sE(uVzou$jHxAy8Bm{ zB=c}nUr`Voc;jUB8djhm9mC;R~`bth}JRqLVg;@FlIWM49W z->lC61s@ghP;I_zkt!Yiuz;e!kVOZLMk5;{j4D9R$S@8XK7V@U3op6hvwl_JXrSs0 z`A-1K0_Fo8ywPZh1v*)UH3Gm?5$ML^bN#0WA}AwB-P}0XvS|O#K?gBDA!x{vLx3U@ zGBPBs`50K~djQrV%3IhLfCfi?4pL$PJ0onVNT3jiXJCagTIh<0SrWl?LB9Q>ftbhW zW1`jTOdDm?KRisoUxB}rcPRTxgSnF$&~L!TG29|=#aN`p8A@sPsR9AVakEb;DVx$H z;3H^Mjk|=in>8=4zNJ25A`r2`({C9(9V2|aDm>cVUz&?%^Z<2 z2afi|vGgqlN6Axf_GFLl-FxTQD)w2qku<2Oxv_}HB=P!hu|}9OlwfXi+Z!=M_Cy#$ zttVd6fI(PW?frJqs7Op{Ds_@7TJ0 zd*R5v`t|3f(qBrla5%*XSzSReQaFbG)}I~KZvr$(3;@o4Z*<*jQOEh1r{Fjp^V0>J z#xLNFg1}gTO3iv7aWBuj^GTWPP+nR0sWLV^Powq)JjMT24V)eKdH&Rf zX=4B{uBMgadiMqV(xq2wKE20vz#$H~Mtg65uqH*=B^|n}LveYMArfQ|S;D}26?$3U zUa-H0nhKXbIS=Do#q7f=(0TKzmV$g2rq=Z`K3SQ``BVm?Jh{%RQ!&BRZ;ZD!2*$N0 zGJ}iG2+^|21hJP3w%NZV$)uvwJO-%ySE+3T1c-pUgQj5PxXhKow;KpKgO{#U2$VhVyB0MW{KBY^oT1n}3_GsExB z`Xff{+T6{6caMiYKM5YO9^5@@ZEa2aBE2l)HvP*h#JKc!q_wyFS(!6UEVV%S

    @n9Ih(Hq!Q&C^FNh`s4A16X-Phs@DGPVa)-G@h~D-6Cb=HqV!}J;KdfPQ zc4C@F&xvV-1N0~(7B7riE3xQPUV4KxWCJ$ATWX{(!y;d7i4h>6E?du$N#v49eiy^S6X})}g&3WE%BqSN#)BWAz zcf^~4KY#W-qOKN9W=wea*ajrK7}}8Mo=6d(wZflGmM|VlU^WI_FzdxEnNFws${6$F zs84OpXi{HK#>L_tCig+{V?}5DG>FK$^rK8JEH)&E&$`8KgY1iuDh|Xb%QCmJ;{-jqe z-(8Zr6WbYWtkL4vnc6R+In(#qw+6lN<)#cg4oKvE$_a#jzS~cq&Yz0mVi|E2`!=k$ z_rdF}v~#{@xzX#wS01ys$EdwncjHr1QtU~e(8@HzF^tR3c=XjVGH{Lm? z_>JG^4O%iCKYtw6Z8vrNFY-nFUj^Ps8g_Kr>!bC@_76G~G^~rU%B=QFrqMVRRFlW^ zcT~>fj^VBj*D+cddQo!vY&77J)0`qHN)W=j?7yybSUclr#~J#I#SOoO(KGHK&hhYP zgc?eXY2V!VD$m)IfA7-{`+p_Y)3}b=6EUowjH#j{n_BWweiAWXt(e9;6qua_2W#V+ z?j_ROG$HW}C*SpLG8lib=~R0$#*atlu&}T+oNt&3lMDojy4Ti^nq!~U!WN2m@*5Ko z6Bim9zXFi5-7O6v0yhn3_K(%#*4dvVf8*H6Xn&xO5&OrJ>uE7$TfN`r;~?=dW0bP2 zOrj7Qx5ZK&N0ncwB);JqHTl3J#An|0Xk&bDcw|kZR%T6MOL^|RSKSucC;j+mS#_y* zwUTDiIuOBBwH)sP8EM%XBjD-)2I|tlkG=`_2I9-R$j+dxP5b6+gDik3h<~WAPD(Q; z{I@}r12OZf_7UqVu$i=)Y!OwJmX-Zj$I>@MXZZdD1SE|PbSFsb6$k;49xRyU5orPZ zz`lPVLWQvz=rRPH1!2k6bm%CNl#~R;Ex-;xkpC&jtBr7@~Rq%sfJPM z?0IGCv))?G1CO^KPEe(lHsYo$_BCi4slO3TRG3yQ2<~Bes+TD9iLvL~E?#Z0ehV#^ zv5~^QIc6=9*nD|`ZqtNA=z-;84yAI_&}r8rJGc1gi*vh7Jo(k1P8b;TH&M^^#YcTG zizPT5KFue;nw+2s?f#p;{sET;+T(-IIaulnrF;WaaUs!HDpYKl4amBb@^WhMIY8kv zEU#>9FxfW0o%0V9{(Zw=>C3-^veh3NRcCgo4{Tjr0JmS>FKF* zfaq)h>V?mR+HP4SG)qO4sc=5NOX%oh=ZiuB_>qX~7^vEYyV<^()(p(&NmW&&&hhLy z!faF9bH!I#ajAuN!>}Pl4x?7zAr}mxrsq3j%`CIaN=l~MKotcP^z`}vdSIN!+^5Hi z3|BAA5o3OCv7nk!SIX>@PecyVBJ59ghm3(wHlB#5ZJUCjh!in=&sL2KL8a$MSLcz=1sR0?*xYA4Qk;3z@|H{q z(@>I_BfYk_B_47*w{4R&*UA$16S{kN;ns+Ziuxk={BovAAf@bWU4xCv8lA@bc}im6 zVfuu1Stb5Ks4no+0ICF&$y3DKDudnzXv79+CCr|m@8VO@yH-T}GJia_g)fesmM z#{2mT3wuxdy;Do|MT6MI_c`k#4(TWJQP=Wsv$26TDaj(X)}UmZfy0?|@yKT55jIhb zUj!?>Z<+5NRamv)Jf5j)q;SAaUdo6khAvBus@JqlXOe$tr;AZE8cbkbqs~t?HpJW~ z3am|V3i;M&fp@w*+HarqvOK>h3m`sjre9^*UM%)%iz1^Q>`Lu`qRzk?!c!B|)Ruwb z)J8RElUWX~j>JUy;;Kq5ne4x$S2>@Nplm=1^Eq@yy^}}8;xMUz=E~@BX9;;yoSjSC z!f?73 zT|WiY7kASK)?&7gPDD0eU)o%Cj8I@K&b<`1|Mjg~65|r0odfC5X<$7L>J(Un>E)b! z!n!R}L;w}w`McDK7gAO?|d1_oRcQ@$bzVA+}!Xy5udqo$_nU)GPCFprSc)_%DV zVm^N|+u1P8d2zh2%(`dKyn3g4bBDDq`sj&`P+34?j_TYu>dcpxE5-&Ib?kRqS5|*B zV+;m2hhy!1hy3ew%dBOMjakUVR|{&T^c~<2L{1GTHL-6bpk6K1sDwKgCI(}0{vDZo z{7=6!ap|%r;I(jOfg(?x&E&fGtHz{F;nC9bw3J|DBgqs8v;{e@F8WWMCqNMpx^elV#g3u3i zZV2iLmph_wadZ@bY^g%;BNrqk5PGv2Mjye|0SOWy&u~ZU6xeEY+2DL@NHxew!fVka zy+B`~t*%W(`wZx!kJd|N-otl1p}eNeJ2f`wasmW6+1qdrY^os zkA%H1j&$%C5x@D3^Eg_O>ep)zlqm$7ak%GRbUfoSbZXcgZFe!j; zdN5D_1IUr4;$0_XA;ge27B=SBcazVj+QmHmzO4s#ZX`AWKybLn8lVN$2=!#pg$vSi zw6!m*iq27a&2bp=897NXwE#lCxmw&^)js(1dExm+$%%Yo?%UBFNIq+&})@&)$5ii$*UT#fFSE@&b{ zKr#5nKpjqT4xi-e#K?$6N~V90@_`1FePZ##fxryKJma>`ZmrG}6ooeGW;$7e#^Q!V#m(d!fEFT3>r$x%~=PvY# zu6sP4)u?I%X-xjp(sud1i+0}%)lR>8>9nYup2NCaD=2_CNP{;2G69qzKs-F%=PsYUGM%GcUA6b z9z_1rcJ>$^!Lg=Z2<;vyzPZn^=6jW5c;V|AoC?2VB|raWd)7e660BWsDsAl@GqXGG zC>0DIK3_*hlNZfTilkH@+v5gmrn3 z*k#+ml22uv?HY<4Z!~RAL@I58)A5}@{5a5uFbtx@sS zd15R68N%=9KIExI+3E>o51H}PYSKU16`s=>_06|0#O^2bR+H`6zzhS0D1g!y4kg)& z#Ut`P1J5-fuT^7a%*@dp==x?9cbUpe4gDWye#%VwMRY~sAqB5xbl@8Uda|Gp`%=hm z0rs{D!f+0igGunwmsdeT1t$y;_$1`ysRacTkc9|i2kca6TGKWnc72$V*tocU!I7y_ zNx;Oe0}&B0P=F2Tmz$hiG6k9FECr&~g*G-MLJx#?$bir=4*~=TDuE;|pvhC=MTH-W z#8^Nlp$jBZfn)%=qdfws(8S6PdV*gYue=oOwf^V;{0-d6SQll ze>O@LE-OAkZIRJiVUBs{%&iP9oVHwV57->SBDI=N6K(uq@FC_lr>~`2R4a;wS|x5 z&0XXG_w}u}A_49lB(HjCmW2gi_xPu>W|Vy>EhK$cUW^!;_owURzN$drq{RH>O2N$WbORI)x$hvFr&2vNWvb&^cx;6F?-h z=6fA)hvh|6{obiCAbcgYQER1fTKOvpJ>8=fLATGplOzbny4X(ivBPeOBZSoV-M_XI z_+)gm$jH(D61LY9e1#@eItea9W0Kc3WYi8=P>vOsNW}^I94fuW^>B4pgO;z=sI8L| z2B3+S*4FL;Q}90r%^SEgS&B3!+wt2vw>#D5c#dHn>90G{h0Xuv?{o_rHsAIZ4 zsyjgvBT@{W_#Zi6Adqn$=lv1scQwR1%7VSvIeuBzx1Vn{m~MbnartM@t_5D^ zD6_tjS77@~U6)aZ@z1per~*4otq~f0VTDJ|YLTvb!+!}2@)>5lrv`TorY^`rR*_CmzTAJ<3hv^#V!-X#%dscND zQSy~U%i9W*;;@I{KXV%nK}*93jzGw8TENK5${(z(%R+Td87}Z=u==sSuK*vSp8&`j zG?6Q)sDxw<#e(^uxAzrbG)Nr_%5ZR_R5G0|9JhiXiCCZD z{y^(AqF=n+m@~zlzsY}BD{DZmLF?SZfNn2D2aB#Oys_>$*KAm_&HFCXu@ zcfaMXtN_6yb4Aa4yjh>*@lv^8Z6XsV0eLA>{0Gy{yhp-}2&?{+7H9rHjx{|&A zUP|QEU=r?xRUFCd2g4zpnt`BL7t)4X&eQViGofv3`#+4Ece~2dxT_eXaa}Q}a%u$MS8E$Fcfe6rK9pc(g+0f*yy- zM(1@Jos|5*}paZ0VlduY67)NBnZ+_-jocd@=@KyL_K&0$`7PGFf=>0!`KH~T)DJj8ts*lPSYtmBCV7#kz-y$*< zmg6?KM%N2M;#i!ihF3;UVQU;EBVg{&%#i4_5^}tcC0qZ-y+ZKRQ&d_jFul)0^VQq# z?OsMFTL+$z!{mRu-k+Brd*zd=4`=o74R1M)#~w8H=$icj33j2-j`dYa#if;_?_ZP% zdDWnGkl&DAwt&t;f+?%wgp4Jbj`w*~-j6NQj_L1=T;+F*SUyyem+nx-$Ajh{<^_0} z;D);gpJmsNCn!I&vs2faYD1BHZpck6KEdh4BOJYC zRe(1|c9E7xQ8B*69U5SBd<}37@<=Db%FG9aTH`NUmIrbQp`V7qbG2}P0$aCm_|Fi= z*h2H3>ouFr^hjO->|}O8`pmE}ADlx?fu;N>ytv@6fTmEjhIQ=B@pg9$@PpQv$K=*{W}Su zUXaqteKQ;_j>3}~xvN1yzpl}QmWDKi`siEQ{%YQVboX!2D{3`$E^H?Qm5=z{s%mc0 zg;ZVl7*Pmm&@lDyF7da(q-GNb(K#HeHd>Tn2ybdt_H6dJVwR*l5+!}bg0lB9=ufYD zEHg(41L*XKM;8yf=N!y zziGF(I)d_3VD_d0=QLDJuy;Xgiv7_G1@~T5{M*0aEqq;28!QiB1tPJNWbwL>L}9_{ zhG3ZVFDr0B!vqf+oU|`U?F>~TuYj#akN8f<4ft^BSw4j3k6)uxxj~1i#yiaB17fAQ z#1lU93P=k?@*5>~`!($ti1O5^5LQtz4i~o|HNHFX$h~E+J zU{KzH{$GfUcnggNl{|+SAwv*sEKV*iUswGebIy+%vr8Y8FIz@Rdj;Wc?>%K%FLWjs z!(TMf@%x%)r8al7zPM3Izv)Y z`b%sR=6{jJq<}v?J9saB}3;-hzQontJYny&t`RA`hE6v zQQJKq)#6lU`GNp7R5egpWcp4r?C=XUMMt-`&$f5F?Gsx)_daoU5(@b9QqK4OM107wt1s)SR`=^oJ8m_ndKP^CR`F}$@G8RvGtZ?c19L$M8T@v!=BfUix045=?jGo8RH@J?RZ~Gub z&*uJ2*o^P#g73!P4?KTUK5(~FpU0lNmWc48wHYw%0N7>h1OTln6L3E;k%vx*fIoKo%fUwtW zif(@nX__!%HT&hS4CO1p?hlhM@}>Yb_za5YAJ_Xx0uV+4HbAhafPfT_v)IN`ra(oI z7(j2BQGk4-d_m>6JcmE^KD3C`Mf~P_WArtvj45+5E&@qRc3?1_D*h-WP%A(9GPv6J z_6rm;E$408T_b)(aBo=Q@*ulcEy*PU_R_)3llW7UNvd;5UsC4ko4iO`b8wd#hzYr8Q5JU6^TUtEt@bvf(ntrAIUfcQz4M$NM0%E!*X6` z4LO3QPdOcbDl~y4sOi$HI=FJ2|7bw4DIz)jz+J`0yy@7&SaEiGWDkM2GjOTLYaN)L z=*KU#^;$kL@E?*i&5w)$NH& z-Ms^uYCjaq|KsVs!?Aw*|MANfp+WYDA}VBMQ&wfKq|EG`p*~V56RzU}tCdgZUelY$UP<5(#95Xba15B1|xV zq|u*HO>JYG_rKn?Lc2*=a4isN1?Agtd?B0-XopUC5)%^{VCQNRtUaUl?b|on+HX*f z4)cA!lLdbqI|1JVg;Oim=zPZJYt0v%br+bU)*t7*JitE8w<5A@k<#s`%}VuO)=JhU zaXGdqVCgH?&~s=TWcsX^c|adr{*oliT!cNTuh3fmA|bBMh8osIyuVc`{#A5*m3q!h zecNtH3-6kVok*Rk_ZUormTs=wNx!E?(+n{&y5WuYoXV^gAT|=sp#l_q3Ww6 zD25j>Fu!xhuS>nmMMz&f$yTj1Ms;q<40;TJOW^)v_mcz$6BPV!zxeqZ%*2xj-Tm|3 zQPEBZ9C0w&qh2=vDt~UnA(AL6n}`vfRpOM>|<$c0`rB#yN*!VR5TcaR1s!l zm?PV3sUPij%Rl<|j6QM9*>?zjj8N-_>$PlLdsiT_SNO)`$~|9tyV*Uus845a|CPnm zrUb0;5Lxx-WA$V2HT&Tu#-7jIY`m3t<3lZLiO_Ng$#dHl{n`Zg2KGVlL6oA?>eMtDMc~P>fttE zbld|-#CP@iZpBRPTQuIHvEu0DXudz`c*$%XJWTXxfyDOny|10Pl>9dMRS>0H#FQXN z&RBn#!Xqa*^TB8h;Qzl!hGe*-&{Z@dnb8AYBa}(~hLVeccj!MbVU-W;Y`7xtZ*pK^ zbOJf3`9h0f9fjlZ6AY4oc+b34?+^XAiM|@Rctc1rkRg~k)ZsEr|8^FOk7)ZClcRtDty0~O; zG;8oy#<`4*oCjFJfkCppb7qzwa#(x^BCM|ld#g%O*d?ibwu*ZFhJ&nfO#JslzjNLa zr;C@b#RZy4Xi+d1eAki+KUT*J?IE&#TbMVOO*d+&}0d9HjXfSrr+bgu!$?3R}cgMz<2Woppn zMfDU`Bv1s#7w1H|yKhI_o0ye26+*Cc-lIb70X@%~@F^wwoVfpSXt@c;418-Sv&M65 zlL2k)kH1-x7xVp)?j0YOs82ScAAw09{VV8FB{?Hj_|nrQQI0SxqU2%VFhSp>koE}R)T8GT zz!Tp3UkC_{wU7xh0c!4gv>ZSQ01{Ur5E%aJf5;f{jjTneL=yr4q=EG=FE0l=Xz`4z zvvaJ+s3@7Cxj7-o@!(&Sf`J5pqW_bCe*N~1C05}nNH-CflwA<-8kQMz=d+dMK=O%V zcM)M_j3ZX9^vSIsW8&QR2G~rv+^;)R7L-^OSiRRTuVxQ-4j)WgR9r2YF8bVINBUKa z!-%CLvspEhR1GO15Q=pmHS4?pIj_ zpDyGCxwCaptC-<-tYbD*D;B(3ryVMs8*`T@o(5kQCiAajf`vEGC`BZex` zu;x1IjDVVs?rrW^1=y1^dWl!pi)=8veov;F+-b9BS69W>tI7aQSdR$z!hIe>PboHN z4X(9D(sE~o<&Q7CcYH1kM>1aWRCyPMziVxcOwVrN~rmjcXlL7?>rY3oS@SghdU~Ynh=!1fC(-Dgkm7 z{P$L>)ne<$W#q%Wp3*9hSvSotx=J-_lh1=%#?kf@vBf38N5f zWFags@uR2yv2e!Rd@>{4CkQ|$;S&u0E9lmqD)n2`8UbldsQrg~S0KJG944uM4noKz z4i2jnywA%bmx{$sbfJ05U*iTDkLeQ=m#NC%4hm5xsmn8!G2wOicd@gZ^!V z^n+Cmxj{)Kj_i=cIL;~`xn1o>Y`z)7H-$C^u$wRfN@Ua!MxTGJAb5d>jEtxpwnpd(5@5N4{(v=!UY7P~lAcy?Bry%xf+A zD8XZAn1v~~=+)3o(5Av@DPSZgbheC)?lhVEwt^%V_ z(-#%E^xwrBS=bi`1sa;Wg9kWvK?7`n4bp+Jf!1-q6 z=JuZj2F^F0f#}n6g8MXmX0+p_`9`bsC;tv6bmj&*%#HoA7H%xVQ3Ukfq%+4M`IRqN zXGT6vl-%AE$GdIaed3N)E-;s2WLnc>6;h9*W25qW@p!6@prGrpq-KYAOZ!0o(DYjb z7^|!j7W`8F+2VRP-3EKtdjAvK$?VKT2nUme+QoNRamJ9N~v0D*Wa( zHfP*XkzO0N<`9r1xUKmSpuh*L;6lknZ0}*Sj|Fa_II9G{>GIJ}j|&EHYVbj2NF%Gq zaL!Gy^iN&U5gSSuYCQJhlb3eKTPAo>(R;>1>Wc!CPdEPYrD{CP-gd!rbU(*Cm-bx&-xAIr8-KecVIe6K}E^dyEZn!dO-J*KdFJMmnxjdend z7d4dx?cIUb_+;5j1H}rJl6s!U3y#~u1A_NFHCTsyc@9%O-VRHa3w&)Wmt7__snu2M zdcK?3c}mmyEhXj0HN7~Ge#pFm3(bBNnid?Xc^2GpH!h-WeW0ly%wMPSl`X$ApRUFN;M?d0*6A;S?YG}&qOoZK9kGp+0f3U5_e>@>=T z_*b@EpZFCAFMlO_O$(+a@b1zzz?`G--t=W818HVN$5F_DiZ%;Xj_hmfJC=>t2veCd zWi5fkuMjOGddohMW2JSN)9hC*^DqCt_(!HCGc9Ss8b4! zjIhDF&8NpGgsuR)p`O$~yJ-k76eO&gDqr}Oc15{=6#E@Tisgk<)S}Pg+IcVWVs43AgY5fn5qwjJqwx6IAeZJ1~G=A zeIBG%QrBr|Y1aYqiN$GjD!8tkc3JTJt%Jv*#9^1Wf5DIm01|0I)ea3}kKo4+7wQcA zMc8!ub1X*gn{MK~_&b}XqN^>@%Y$LXLN8Sa`OaJ>mj6VKZ8FRg@a!wE-~{!gw}gEj2cBDcIFs1sN6u zdjl**5R(A0*~T7d9{ zR+#L`7V+H3cbEulFPg4ws}}ZV6?ws|)ToXr;WdvcG+b~~-M}W)c$QmS3%`Px)N~B? z%Nz-gvPoQ*h23GJvx0MNdN$r(vcy z>$tx$y|?qNCKQ0IBPe@nIM`l9dl*b|h5*{bCjr0&Xwd55V}q>`KFsx2-i~D8R$Hf? zVpYHEwD&5MPKPz)>?BF_WptLL9Ct24qLJO?xc)0tWDMAItZ3;4`^t@%@9%|YuvKX# z*{l+j1~?`=1lODzPBX6kc;l|)cD^A6BkqHz&wjN3`L8RcHh@ykyofG)syO;q$5%*G zSUWtPNtVJFxFsB0yIHxvi7ETyGcGO)Ow-=cRnE$_rwo+(PK6QhtG5MtJz}nV9`@eG zCtLRu)Ad~eo10IogxN%8PWmQ4oIu2rpilOd5LJ^gPG3i=XrmeuNfgKIzDeI^!cAkZ0t5Mu=6 zc6v#GM-7o$z*z{clufN|v~U>#Z7Xy6V3q$Sta%Xr&IltG3U!w_-R~GIGLb(&CnCkm zC$)O>{G1&er708q`?k>ma9eZ(aB`;{tDG@#9B7eY>6eGB98&o?g6Y1YXagxn2~ zfOs2jtNt5+Cbh=#6C4t4I^1~eym=Kl|y>5`b{n0p(eC^)NhZzrB@}Y z#gOOJ(hJ&QkTBrvxjVJHNb-w>61E><;_^P+xliD$h*xyJQFYqU%Zm>BgJ7@^*Cxhg z7h=#E2R=ho99gp868U1CI_YHQ&bLTeS$D#`H7FQCMNwuw#G~Uj86e|W0*oL6)1dPu za>0FMqE#cAYutj?77hg<5TToK%}o@sIjYCFwek@RDh)fGbN0-#_Uv?WohN^pb*c%EKw<#00R~n|7)>Du=LHz|5#}6)gieIqLLdAq%0h2oy3qd$Dpcf_g6J}+1P9y4(pc39rU`JkVzUlT4x#i- zTan`|WtG4UTRbM4*!I~h22=m*JA?N6gS%PPcf{{Ws`_!i@DNb>yx5_)di1eoBb$?q_iOlo%CXFl3 z{{mbs<$?~){NlRX7q|7NAh!X%E;Dsnotfwp+z*c!g-L6O6@aYK~o`15wBB8T1lQ3Qt;i4@5kwLFVF78*%)=)~W6 zz27k6*}yR>IkCSPgQ=ZG`TdQ{*Tt#cb*Kcr?pf9G|LO@Rr^-$Q&(UPK`yY?RzOuQL zH?5xVl$rkAedMvI@~TqCJ$l1IFV*E-gTns1Hns#Og6TtH#sfXPx6Yi_vnhHVJ8!c# zE$h#3i+hXjCJZ~oGkWKXu?=%VI-1Iy&)GR*49G+2|MUML;uq~RP$vB!Q%_m5C*!CH z7!M>sU4SD6w3<`4r#rUmlVm=FUgIzeKwvXHfE$$0w^A8Dfxm@P-)sGH$y82m{twiv z2VFQw8CbT}Esrc6bX&*rF`U1VfST-djVueu1F-obOc+xOa?Q{n1`k45CTk$_;=e`= zNC*c0)4d|SQQ4Z|$@m@8SeH`lQwlF$C z=O&!qGUp3(s0tNprHR-_<3$3xasb4nE5)YBU`wDlc;6@|Mn-J?4I+ZatP1CHF zdJf*6qKWLq>0lEMzBEGvlztg>03e3Z2n`0P{SiQjh=}tbAVOdrcpBp2M5jL z%LK~gykB5~We*G6{x!88v2$_Jy+t?9o;O&QRKMNW1&N7*Hg5FaNyFC*l{r~i+(-UL zC2(|pQX!OMaK8fSw1rj!oY24Qb4QR)pq=5px+q;(L?FOeD5xFuQV@O5o*Dl_lF1;R zCU5j(lkr-&JQq@2$UqpxT^cOJfk77ZR=43L=Y~PyC-f@oPP5GV8KuisFPL)J z3Vz$EE}SkCZ_o=Wf2eUAW$ozd(!-pt;Dh7mOKp@dB^J_wf59nX#72Wjdc>%O0*_Qs zHb-P(wsL&sV->;X{@*-?(GHKK(x8rsvSFsPNj5QFU7k)yHs^lgkK0f;l^79R!r5NRD;IKPx5lO=OkXzQ$y5N{vnr;~iiolo7T*E$D4 z-8A#jwtjCa9Jh1Sr0v(~Z|APA?{wcYs zd7$ZB6%)r)o>7carXn@ow(s@GjN0U<$|k|d$=J{G8psK8QOq@%KACUXq`zl3x-xPu zy{o=stMdwg07%&4;)2qF0ZD)*HBPnPA|B;_=j1e}5Uxu7#I#MGzA=lmLkQ~6= z{F<6VLWuq{&d4vqtFm=DMX6I+fv?4?EnBm9hm?Nz9%^3xWZ2g6!69$gy=p8)!-9iQ znDGj~OS~@)#V;bs!DN3L8#*a|w+CmeX));=wcP}zg}>Z8vmVpWs;%~yH^fWn8TtP$ z=h9H^+V8aLGyE|-KWu9JMO>>vPwemy+tD9RnOmcE#xPUB(+N9T_`qU7!y?u{OvtQ$ z!XRDfbX43a3u!lo_Cw zD9Q;si_IV4Fa7ymJU79;;-AfI{)pfagyJ33PPBYl`bg z5(6_%C0uYbD&M`tZD*3nZ>8MZy(m9~w8Kz8DlHI+fUu(p0try-|3ET4L_5L{Uba8; z5pjPh?}a3AaUb|4iGEclVKVqTQ3E?M%(T=~aZ~@cJwQ*QxKFRS;9SFNltzBbvK9Xo z92clHPRD)vJ!AvyH7P%TLBQaK(FZr2efNE~Nz|YSOWQ5bV<7zq6)o*Y@+z@Wi**9| z8FEMRfwp4zKpN@N*5W(NC+%j!LUB%vmNk3N*o@lFkl!#l8e08(JT)~nGw}`l+i+*X z!|#o91-7{Tq~2B~}JLS+k~bBzvm0lk6&x`(++y7?p{hO&AE^)(AjP9T*iy`v~X z(?2hCAmW=Mq-v0tpWohV4g+56V*D4zUYR9vd&b2R75cjabRz|35^KD=KYQ!4A_r@O z)uk&g&RG&L3?6plYY*a&$;CZ5E!-{JAby^I=e!5mp#jcruWp~v%I@JUIJI5r=ZVS9 zSk2w>S8T7Y$f*HR{_OkoB_!)=bZx)NVl3bE2{KLoaX@>x0o-31^~crThhIPh)g$|v z*z=El!z4=Ht<>WJL=L5EiA_LXPptbV(fDUK_)T<(O(kDHkSx3l7Y2#zNGPQC$Agv%3VedyO<|Cwcm3ms z>R8s@DjNl2n=K3myzqU2Q>An6RjpqEh!99p_y%RbN|JsFf-Jk7zxH$8F~*b4%stEt z>djF|BwE8`#rYKfI^u_Fsp-E$brc^O#gY`e%P<5^p!CZnFgH-(T! z^9Mw(+!CKFG-?x9YJ?wt=_=p-CDVC^VRE>(>R!$NKMy_*tyX-8v!R zEXUzfVC2oL__N-}*^*`S7Q_ls*C%}1-!x3!YQEGkc4jrUsrFIEQ?e0alMGOg28M$(|!CIg5*p{3KA{#5MsyOf4Lp zZ!o>{%--lLSh%N=?2a*$lOq6p({?KtaHGiJI)zYxm!VP@;t`=+n_Q@iYW_*{;7sk+wp38_>lo3 zMs4H>7z0TUYE%M5QE)yja>At|l(UYo9DFmt#-pF%_U(^F=l%o<7~~RUM`W1|MU=-g zipxtlzQ%qyH58VmN!@PMboxjsqq=$wQw>@{6gtxPr{4$8&9m1O^b}JQCG+!dKWQ&i zEcI#yt-sT&7mXhGazCqYJl5TfyOT1Ng<(nhR4bJ9iPRNu&E~tU$YRN;z^Xxw<^a>$ zQ<0$|f}08H6H1WKAtm)w#Kmsf;d{zYQOI2esmV&!t{yVh33@+rtpE|qCl&K|ZSWBy z_z148rE|JQqCR!Od^ws8aoYGmse+GK;QvB+q5V6?>PKCRm=4U;biyz-xPf#HaZD8R z>^<*YJ8>+X+xJjWD%>wX*QVs>KkGiuo7Dvz3}6E|+l;FgXnTY*`Sqg|QpV z8hnT01h%|WCZNNKT)QeZr?I^@U(}>gz?Af;((P9D_GjBqpFY*$a=-?(xN|vYOQEk##o=)hhf!2i(x7OJad_sinI+CO+u|Da8-C;2Z8;sr z+N{vUqvEMFvaeJ-?n-j-Z1BtEsQBMx3ot5xdcspnl_+WN7aOV3oBw7vAC770s>o>h zdLIDkmI&2qPOVAFKtPF5kezKQQ5s;6S0bBI{D-p$xr<@~>BphP9ZD?F_b@tYLsi95 z;ljr?lDFMxjnyEa;#M*G4Bglo#)`p{>^~H0{&~9TgE9-8fFRBSVGB3BeZY`FLt5-( zLz=of-0cFSsOI?tHIuF$+Rv~CCl>M_o-ypLl@t_?-+9I z%smD1=_v8?oLe=&W3e*7b5G*%%5fWhoz0>5hd^Bws7!metUK;-rUj^_p2a{PRdY(s z)Vd%dpU1~-Q>I{Z3&y_6-RRU*Sa|DVRqd&d`xcjhbYV+E67Es?AI{d_I)4Hx?Ec1G zY;zN4AET2O*^Zt_Y!Bf0LFXt-6UBUJZ2#npt*tG>vO#}ioI>j@&IqyZLO1Yzn_ga%0klHK2m~p|WjdT7ntpnEa*Qr=2y$<#?i_Y;qMD<#JDb5< zWbtcgktwoi0!7M_`Rqxde?stht7mfCqYywV40qs7D{Tjxg|S4Aq9v7A>2Ik5a%@WI z<4Yql0!ud7`O6a|uWV3$8?jjkz0RmM5tc@JLr+f4{in-jqMD})NhPf6phSvPOdj8y zpbOKqvH5IditVQ>eA8_$3lx>W^xi*X<|(KLruD>P}Rb zPa)0@X$An{r_0j-S*B6ASby&cS-@RHYJ<-Lpg_c8YjBug8$a5u%*(UeX$E8{6x5bp z6F7`$rUQ2E76{@}HWwEbTKyb^Wrg#dbh=~P`O|7|Vt(q!W3ZpFb&Wf73N`GAmEM?k z29*e8iu#&0)6QROF(ob;vlxs4wa6=RZ1065U<)I~i)UZkd`PdNhbTALn;(ljepKh)m#tCLxyna0+)t+AYUs|{H?I*rbmZ^Z&q)DX zBQ&TUhWVZ^eZznHUA(@bq3x3moqoPna}b15LoQ4#O(}{IMH)>y$iYF2LZQ#;bKU}{ zhtVlI`RC?y7eoC>B=2MZ^!0o1um-%Y5VTXaTsng0T+nYun%mgO$ji4}ITyF6;VjaB zCh;}ZC+kgRnAJcyfFg~4f)rnK;{}sF+;=A>Ws3P02a(eD#_vgR zymD4;sX;@v;t=CiyuI)JI-CPvN!4Tz7UIC*3i09WG|B}7R(q#Ncmuc=jOwBw_8qM9 zM5b4iT8$L3XwY_Dxk2=|tGrXdUVM4I^PV>REN~VhojN=MvJxiLaRA++-k9B8Wuo56 zLo&9x76HdrYu(J=L}%=oz6|w~ly;sCp6Pf*6)f~)#?D_lkjSb0>9iHw;WcyWeDS}-@AM+`IpC{8-a1x{W`uE( zJv4mGn~K@5qPb}NBcv0<%DfD`H|#qKmIa{h1*8=gU{IXF-3yCENXl7qs_*>`YFPCy zYKQ3B1alqp4eYVeg+Oo(7pqRfZC8Cg%o~sU^g*u!IrV_HK~%OTj62|yPsXf zDC+@dWRn5Vdw?^+^(`||Kysvt$(j7!NK9lBI*7|k`m^)ZSt8+)vYuDUMAqU@$eN2n zg*kYLShIM{h&^bdibC%l>xG`v#8{K@CgrL=K2RS|-yKoqbiqAe@X0VcZBe?;haTs7 zLkIbl-bRB`?`;J9ZPh(CwDFR zLup)NX?=-1BzEZ@7HIpMCACb2kR{w=SM&8Q9e82mJM=n>ZrsT?2a+$f~)8 zg~3|vfvG(l+ZBfg7t!me54&A(>MTlG21t;h*D!Wtm=2asgYH1JnG9(b00uoFMtY{kUvk>Fl{3#ewvyhs!4%%3Y^KQTE}2>(Vxv z?-J_sz4T2k)bt#dB#0+<_>LcV!_5etVA_klA|LMmbNGJtk<#qS++5bACPXZPMhsr6 zTkYn;%vr9W699uV{3(72(Yvin1q3HV^`LM zX~unXhFWg`;yBI@LSA8NNeKlUwFIPewcsmI7y-~4P3-Xb!4MSpd~t7{ng}wM07aY; z*1dR8(auX>w?k7{r^BDWT#`AJ+NGaUyyl&EzU44mD?2__>3(YBBE>b%nzY59`|XaW z+>b-X)hX4)8u95g@~=03It)GTcg=QuEPwUOvXar~sqExD2Ay1{(B*$!V(}fbBy%kt zB_}ltA;J$`TT3*!+POZyX$PUYRIM}cT z{!%*0I(FcfO`4s*>*QO=OPmk6a?3$0_;}k*6c8dXKd)hdC$)AxHjgadW6Wtf@LHsk z_`FjAfc{YC0{2TMT?a_n&?ABzhczdQH7Vezfr}H;^kfe0%Cpq)2eOt7X$McUC8yMk zp2{t4ie_ZL+KB#jmbu~>KJCnS2O^j^C)V9i5DJw@`!q+d&dhgemzzGq;SaE&|14D| zO!s4l{ms(S(!WSPd#iy?eJc+Z9xzt_d49M&_{9(hvacq!oc6eRr|r(~C*QPkR$A`R zARY8$F4a-hQ-7_`UeMbi6zK9cdV~Hw+m&f;OUDgI{8s>e$37l_y%N7uiy&dc;=N3{ zcmiE4fz+wKUp26|@P|NN!6fbO!sfn$69Wl7_Dco-bl)q2agcudw_)yLc!N<22Vm@~ z2kwwE!X0$u)&;>!Z?LXC%%N7z>+;iZpuY7Z$}&`X8DiT(b(-Bb0AgC$_R2<|fn5jK zc1H9NfmPzH8)9$~Ob)3*@R}m|Lug?i08`*7r{&rt=Bo6ClN{(T@H$>RmQQ|2LKUVZ zo^<COSCdZzQjC8>iRbj#KZT@<4$ywK7uCSVF^@isAet$hmQ3I113n7aVhiAuRXfE7zt4U6bSeIp zk@=ui#CZWp`zro+vT=mC!(#!_f@9oP>H}|}*|hr_%U)~g^|e$3IX;@-K+~cT>!KgL zoxuQ(*1BTrSl>>X-`vj#v8JJ>X18>OqK+`}19PvP;v|`C0F=gse?L>~v)3QNK&hoRWf_gvjDC}~oO*9`h#!-csMwo4WO+|?kp zts9d=quuOXcTK#Rjh@W8)bb-wY>53DzW*I)hIQrL%~4|s*LYQr zEOQDE)K!~;R0s4|zzA`{!rEFPq=%aut9VB@BJ7r~+)^fkUAECDRh@V+*6e##6Pjmu zeVb-?FQsSC{pB*hxx7KT&^YOqoiCZ9C*6>8GiFKXdb%V72-n%~*4FOrxV z{P@z@t5_OglzyJDR3)`DT}^80HFgAl4>>uG$`&ab_W-^Ee^DcT|JPsGhdDluW14p! zO1|h&uYELbE4MK$OLq8U?w0sCe!;#DTc_rGB25R4rU}OnocVgD)se4BlCTt{yN0G@ zy9>Kr76jLYH5;82yY_kL-DJ)w%m%D732y4CipK=CBs3hxU`y18V`0FE_7V5QXX%e) z+ba4F+g1TZXZ3Iak`#ssn1f_geVi7~o$Xe;=;U=Y^R32@;jvauEAGUPB!*_n_px8F zsGdKgr7Ab0$l~pw)NAy3nf@w*Rp4#b;uY9$;BJJL-SAe!D(fjwUcnrUPM)QqVuX@` zUhNt-Z-$7DGM3N@BQ5RE+FIYqCm~DV(zpvp9mqBRto*1GMvWwfv)djdoe!#cMi0*j z$6((BHt|1Z63jTcS_SnICsPvGzCtepO>jYA{<@iqF8`kXw7XK01^&wy>XPdRh4eDb z#Y3*Hl<;?^ks8Hlt-#<=lMLZKmuyDzzQ9_ zpu+ys&ska5x-Vm>xPzz(LpIW@lQE3$X*2`F673NrR6N3kFdcy=WAK|TBaB$6!32-^ z(nPPivJCtVz`k_BxY6$b#414P3iuaPFxO!@Ku_XUMmt5F>ibN~L5^#ml|)SGRRb-A z3uu}-V_HHk7nCHN#}(=uoH^*S<}ye*dKul)9fFoS7Pf8O$1}lJip6n*a^VgBAd%@O z!eYbwTyo{o;WPhqYaEHxlkDwp6!*T-ZwR;3;m|wo$kbUZ6fNa$;FjKznDSPV3}2R> zInF80N;F!uY`v2E`Lp)`lvlqasf~IzQTG^-oQYp(tpn{#J#4}2TRqAUrFZ6ZOZk*< z{_JH_Tsu*7IfXv_7ZKJ$vIjdmJAZ+EWd{>e^~U>xi9p(CwSG7RcHrql+D3q{;b1{X z7phQ#*O#XH=RN`V@*P7LkMa@SENyQHucMLMMxr$2W~&eWIa~>&B0uoG1<>1R}MNSRCl7nLk*t zlcuCSdGcgETiKfk^a8hnReHsS@W)Oc9S~bO)`$v?$yZqa8JewYv#H3!&6!1xf>^rd?YC2 z4`HFCU*t1;Ko!YnBr_dJ6e=4h3>H58h~70<><2Ing=pkxtl2LSN?$y8nd<&Ty;9`2 z0I`}WWm@aY=M44DGA-X(W3{;svkM8#<;t6%gm@5Ee5RaKIuYd>+*s{Q3cvW7ZQy^sy7@bExr^kD}nYwN}-$mPx2fqjUSZrYr6k=PKlWJsZ;?Z0SIdtrh zAP^;+5NSW(fK;HWUqkOy1zI^88>bQ4;js2=fJOAirH@}pEq)31X-#hi1qG2LvDBh4 zML6Ah(z>uEwX|aHyPs|s_=JM>7w&=&aW!P3YZwHz`<$LIGd)?X5{}RfiaGA~2C+7( zmIELiM%(|nTBu{Cr_@O9is8Yopc~Vu6mr zI{ia>kD8v@(!9UBUIL;0fI35a8T*AdHtd>mBA_pLrPG`P3?7}fXdAt+J-3|_b<;gF zJ185uaY+iyd&@^+<^~lAS7PXb*VYQmx zk;Wq4R6}j0b7Bieo&IBl8oWH34Z$`nbBit&ZzP|Ga$b3KOI-Y!FNrYQ_lMaH_M%&S zo+~5^61Y{=LSg~}rdx(Ar(>7T+f5I`iVe{hQ(y#?192bfO8^x;fSM_AWxzyKRaFJx zdVOIk1d6~(V!Q)rbFBTNXy#$U@{C7gS#YR>4i(fprX58v|BeE8QW5)2=FO$axzun0 zlgHOa1lt+H%^q~dXydyGo!|HffF&Z0=tyyD)6BA~AJF~?Gaz7n@i3$L?^EO474M`D zvxAPfIduG_bvtc@9pkV%L7{i{is2ToJ2uW6o&39_r{j>&09x&a^#;apGC(0Qz9{_$ z20}zaBf+wPwe?x_%>bAQj#_{4Z8CSdmV2~3CY9gk*!>N{&HuFHkxj`}RrGLi%9K}* zEX#uLD!=S65fV~^wc;+sQ?m0*2lY-ek7^O+Sth;j#WxCyY%#A>1VGm|Nn7zHKLIBuKxpG zjN|L?-sRtQYogex$ip<&vQ^%(!<_YVar-H(L~cIw!RmKX@jvum`BdL^LwJqRJd zSOl2H|BOYp&75m*@iP>QYC^;fA1lGPhyET!;lMz_01Fi00HJzl(ar1EVPL?Z(l95pB$;pJPz9rJ=5;X9P zmt?2Nx}wR+x1dp=T4&`?W$Cq8+~?-3W@>FRxFfjeNlw`RN}fh)!Q6m0VWt6p@oTu{ z+;D9ub`DMO&r(Yto&3LXRl^b=tveH>Yok?n38X@zwIu&#hbm*)3CUJ5JbNw8T%VnG z+%&tnH{y7DX+X!3rmDJ@*Wcux5HRO>v+8@v!O0UXOzUuKx0_V7mP5W`F{d zY{;yG5Sjs)LZ)yO)^-5pgq;Q_qYxKN4j+UBInEKn+DtWRHyD4=UV^XCsM%I;;G?-a z=@l9to(hT<$R-jD-(4LKhqyx=9l(2TJSjbkq-{VEA?^d`aBlnjNf0e1CK zjj(j-)8!UIgLXgcbS2d~y6eKbHb!G7O-s!0KXMc=c}4-f!5))-5FGhurdTt2{<-N^ zUcT;&jHPcctgI{O)8)05ePyvspSN%4TYb&T%bWXhtvz6aKi|-_f9<=@nzvirJZw_EPResg}2u7n@Cqvv-Ixc0rN)DTsk* zGpUKZy|xTw)sSpq^6wuEi2p5sh`fmxazyKcuj&HRvu`7~W-x9EV}xW8d;*(>c{>M$ zB|`T}G}g?ua3C`PQ35solPHpVhcW|KZ9>$3l^2%Z1}5r1{v9dMLGy|9^RVbcOw>~l zMN)wi09fMSrO|J;NoS(${~qgj=CwU}{ir{1Il1kpbN$ag7*qj%XMn~96gu|{T;5IZ zRQvKA^U8lY8C-8!T=!VH9p(t83P2^g#>PltWRe^QcnrXPLzu}1OKoV;_X6(0%DumD z0I`-K*qqtCIQ`(k`QoAYTIuLh#J(ap5p;y`(4|&H+y+w(-0`JZ)@SDpm=nnY%xSMf zQS@iwVDhsMpPS<3HSgMZD%p^Emqse3cc?tiD#vOHV{mcMh_tTGpQ^K>-jmVR1GWcp zz(6kIFQvjDIL}2O#hbi}1i8nW7h)@AnX>Fu1I9tT(6^4qN^T^Q;IDf2#xurHS-28I z+4L!_w{tGms+h!N$9b7S*QW(eKr1|*!E?~=3`{8R13C&jydezvnF`Ph09^4CM07Cm z0v^a+q6BjpRPmDhQ$pE{G!u^y(MEjDJ}o9-@!{vk znj7wU_v>-EsokZxKR9>qYYQiEN>4rG{Npo_;0n<_T=**Yl+)`T1_?VkyG%lP^)LSM zebUnExCV>N#D`y>C8*8ClRt+&@jT|scHigPT+B1)FoFCn&A&uCex3t=o^-$MbiHn1 zG4QjO&*Z|LS+&5MJ^Ur3JK`z^8E{`iFSV!YXd~o4hr7YH5OTTBrHJ9!>CjYIO(>g3 zZZ`0=B;>3LokdPZap={GP=Qr7l`#ujA(?kWUa|>99AxneZ#W1Qzl1RD0>RSioVRWD zEx{x`iv{v5FAmiUsF)Te;JS%1kjcu)vB?bIdi`#G36ucV1E+DL``eeHRh7B5_pWZ0r6)3`gApbq6jlv4@ z;2zUR3o~4}=b|l%yYObb5t!NS5RYjnN^g1H{~=$-b9~+L9f>fzfx{w~?eAI=oUo~SsiSy0 z5vBSUraW16o#vM}oEgO31SR$Rm9-{X+Mi97ly;>VM69@u7(A7*Nlax*xX8u6{Vgn; zgn6hwqpgOYH*k?7=6afbu4?O+o*Gyha=tHb?!R8ybra1Hee;=D<<%j4bG9;^?zQSmw(Q#i-@Fn=Q!s? zq?9vI{7FvCI+9-$T+sWL`kucf$n%xwd+%w_L547Y;T)%UoBjON&R4g^!>8nv!w2j| zZIY!2;&<*3V8-hfvw3r>Kc9DAy^?#!1cRyEa$vX~ra#$eHc0yMv|J}YMM~L5H{zGU z8?|3NQo=EG&|m>@s4>r(WEID_T32qW__P{xAx!(G(^U#&cnWVzlVGa(Rq3F*4wJTdjMZl2wovBstEnYWxT zdigSc3TS@hy6KQO6@|+wfXi!=ScYJLl!Rn*rD7HJ_@e$79sA!DsIeKuGyh4r+O8kg z4_5#<*>@lEqbx6-;tZoW8d!FK&KcQ4+{4yNrn>g zhqGyib8#*?w9iCvmIbWzHNvr8lV!22mhg5iovc;;VYyMzIHw=&-6JzZ+K)d4bU1Tz7b^!q#L;(zKv0O(;sMea&4va(}4YPzXKBySX)Z^{V~ z?2~w!rVc^5{C^&;zVhxZH|1N}`hpimcIxul!(NSu@Ym*J&Aj+pMj|Us@_6P~8Q7uL zaYTQ<+&NW~4dl38+HIIgJY*0urmQyAj(@IqPwh9swTIOj_tk#t9Dc%Qv>Fu<5Ma3A zmhQ~sC)%Gl{o^sF)*0nyU_NB23zK~iR!q%+E?!vLSk>BAcRw!fC;50@uTq&>->2Nz zo3LQyYyQ*IAxa`jJhAfa$reLQ?8M~zE4oRPUNhLJ;#Lswz|vjzG7<%8I-g}C%pMJD zG}y4ED9Fq$_&&2dPGqpewtm0CERrqKb{!*<@qA%iH0^4F5@kJYZO!ROjbYQftAdNx z6Of3=>vejMF8F3aW~Aerf+fxeHOemkDM%%>f3V1VChS(X2FtxBpFZt-YZ0;HaI->; z6g0P_W=l2h=fH)+8VRnS`iTjHu1RGlVJ_Wra`@EYPC*h1&_qBCu7Yt!zLu^WP1~aJ z|Hso;09Cbr;T{@E5e&MNRHQo<2|*f*E@=VjE)kF}0ck-}K$KJ(1nCqcq`SN0t$qLR zy%}b%b4563pS{;_t#5r{W*J*Zcr`cmvw7{AV&v8Sr6MY10>UT)|aG zy>ukdF?#v2UY@wGCLIl<{%v@!zQF0P)v6(u7{|>#Mnzw{gE;H5Rhbptr(d-eB@f>g z*?2Og6mtwW8%U4ZVC|4&HdM`=U0W)fEG8+;Cl*!}PisYdCUerfC;-hv96zCDv&B=281Qf@%N*ghnBZ+8z(wsN8&R-T}t;?;GRjh-Pa0%*T+fnnJX|2hVr)?AqfW-cN z7INd>1AxYWd+4-2YT~1gdZn1na2lzJLM|5uv8WGVV)vn8I%*N9RW-&DJB8N<>Wm1) zm}VMZufG4Y0vJ(k{WXd(fM*dgafupD78n)#EcabdlfT3hUKQ{(fXKa&3dIbjYkl}O zgn#?tzFv5h{o)Lmnl!@4!rUez%<;I8q*l2j4HZzP2mK7P#RVHTDG(vT1`0__1Tg3Z z%#6OkBL}V#yk^J^f`Kry&A2lWPkXErQ%t)#`p!yqscX;%Ns4I~#ngA7nUl){dn>WQ zp(lI)PAa?F&te<9plPd&iR*N#59lV2aJqL zZh>fb{I!5z105hI!TOwLn9sDdl7vEi_Agx+z7XPBgz@9u54&69D_?$6Wg)!(7~FM(0^89=|$rP`#^j*3Iu$rt|StuH%Tq7l$zWyRZ)IlzJQZ7_<8M zj{f`=_9z8K?4Q>;dyko2I%6OEHGSD!2cG-7b1~Lb<2m?D!>4@ow`vg`h0w$SuHC#W z-o&t-)+_o+6tC;X`tf5DQ57xxI3KxDiG%5yY_r?%X+d@q@KB*Ykzv;5*Eajs4m-|G zyDw*Ngc(U9fAwr|mK+({9ST0j`q$ z`__TsLcWAp$&TaeVjX3fl0~E}?Ox_xwjvB4cGHz!96V&yaJ&ocoqNL--afHUJ35E) z-4R71?w6|~e`VZjd294CuO*VSa3yR+mI_RIkOB`(TJ_(o>^2Jud3ui~_J=W!XkJ%N zW2+B40Zt3zdmsfZgoZ&UgCdt%A0v8@lwzaBSpV3*P5x$4JDz0^^EomxcyQ~13@YgR*E@F^wyZv+FP1A@-&59>uB ztDS9VHU~cZWKjNos0FGR6LTveNQ?{zTW4r5fM7Vc8<0B=Yij~X!cEbrZJcKlr|J$) zFwd%%99{%l65Gr3L!-V=kN)%R1r8__I3T#u!CI-XuxpEoTFY91+WhmV6sk<)h8|$D z;%C#unLw~dydb>59@r41QqL=G>A~b`3+zdzAX23Ps^E56v1b>RO3_*PXHO!;?PEg4 z%W#+ePiqRp${(~@-gmbhlS`X6Ob67_V*q7<7$bFwQAM;;f8D4$P5jM4% z(XZ$l2*VcnNkJB%z_5o`Z!$xiBy!NP7z;qF082DjG$PiM7N3F1`R%q9-S&F#ieY5j8 zCGAr9Clsa<16#Lw58>g3{UE@yq}P$L5~eMnCS`J}nkzEJKp}s%cIH)=ciGBiOi3m^ zJjikV4L@C5&~^P!M8@K2_uoHWIOXL|TDIk-7=K-1PU`y@i%iHV8Hbujk=!>qpaV}80#_blV>r*y8OSyPx*Kk?Gw*_i12oVq1+?GAbjf_au zuan{YwQ~?ic;!Q_H|tKy@u#xmI-4I?Dwml!M_tH2)T|y-qSl53>dNl6n8fQ~!#ex2 z-W!F2GZ$-fp-XW4_7vC?@v-KIa%ZZC(0x~T#YYdAt2#Ve6hmoOuFzhRq@B$%msmK` z|B031CYBI>&itN6H2YmJx_Z07i1*H{8eJkOofW0w59O2za}h~vA9*wm&mwEyQR{TY zuf%a`rq^3#Ogv%hW)keeVhEvW5L1^ZL4(_@NCoV4s;_RgS|%oUfRDh*&;Jg<>Lv+S zTN3J?(5vdlndxORFL!wEg=De*;&_&k)$l(<1uoc1!#5%V5kLlk9!f=ofP+9#2Q)N^ zwQUA`9l+{$aCjKe7Gk^D{rm@Y5OKx>8-K(S2b7$oa3B9COG!!!k<`s`9bS4KS7Bkc zD{}CNQRi4-p9$-x=KZfcPPvytzC`>>jr?X=%&i(J2^8{QxM9cIK!jziSus#nyxw%O5IaFS~r#8+dd= zL`3xQ8@sl0!P6pOA1-Vs;^Qe*fhw8NR=RDG1ymnUOpx?XFed_=(LEpT6=lf82#noMQ6Rkx+$Wt5-sJ9x9lk^%7+N4dI$ZZ3q+(i&(dXJ){SA z^0z#zq+dgXE`_9Zf5b8@<5sB>evkL^efie1tmE*7H7`X4FRT0zZ*z8hhlaWSrTj5Z z@S8Ig^Z$<&jRHqRl!h2EaYbr*?s$mV=vEQp!?jj0UYc$-li+sx zAV`Nwmb(qf&S2C5o}!l311~Rp>$P27tAykl!ngiV)UG&|hP`C=HSrI`lr#To>3gC5 zdPb!Rj+}lTo8(F*k>-~Cf&@)XY4fDR=EPP)DTb=TAbTb{7j&#E_tzGgM8q=IK zzQ~BPv$UDAjfu(EUsWA8%)V4wR_+2x(l-tB6GD9*l2--GK--XK;+~2 zvBXfl>A5MAd!aHE)f$~MmL9&rE;8D+5m0WcRkozwO*!k?$7TE1&8}LT zhm^3`sGcR#1_N@Vj-dxbIKJBRuI0L~cGcz$oaXpit@4F8tF$v>gNt-L7r^*H7ZO~m zLDdc}Nu=|I6Wx9@2E(F0>lde+tpH#@Q3)xJ`q8ZcYblL6Q4Pbl)&MVo`WeBU09gj$ zmhzdl9TtdK?Kpr^D}8QD=X^t}}2QoS(k3rx6RtPT}6K~9_P&{&)A z;-^mKPEolQH~^7Q;MaHe3N|$X2yrsEEWFKnfnW@Ww~>`qXV&XClj_rpKT5?8^6NcM z(`v)O3$9PK@Aeixs^D3nj8m?lrq1Q+Ef((?@vM?x{k)i-HVyYsK8SyG0>m(w(>hG| z5HCWX@eo*tJvQ;i=~^s9 z5qlREiu20a)XUSKbeViL~<%u>+$;t-yIJ8@Dpmc?JeM}B!E&1vlwu@bT9 z_pBa<43lD(5Ekau6MG79s(R}+c%M>)+rjn{QZK4?i|r~SO{0^K?zvL(xB1P#7t9?@pFw^j!1Jf3KaV zt$a-q|^k*gjH8aOxDCBBW}kXbZ1J2)gf zJV%(|ydS{d9o12fxm0j!_oE4$IBw9Ovz)C?MYna+wUByk7PEBJL&|qBPtG;edLZvS z)7#Ra@*mCEjoTwMfhj@f8I7Lln@|zfT=Q1yAB}RoVR%OZEs)m z1#X4oJlt3E5})*kqcKCn4Qlw%J3_NGr-1254=(f$odA|rPlo2-$ptGJSknQSjT3g7 zYRoUVrQ&$S%$l*)H06hWRFzA9$0AQl0q-l;V!#wY2Aay{hI@BgnC-;E*zPXsRwipq z8`+}=By;LgrueTY(%sC$@w|Up`KNqq6H;j?kO``NhNfHV-;UKf2z4c+JBZG+t~_yl z+eNe`mp;!fe~QK%ghDLnhkslcNlIQ*BB->M*D>y~+jVruE7-87mXqi} zrA-NCFRs1@g13ulZySCb=NB}z!sicxA;E&qP_;q)!K@OEWpo%X75!Je3Tsu9>sMd; zi$V8f)Qco$AvCmC1aGPs5NRoAC8)}5 z^Q_~z(tg)*!A9d@`%851pZ@U1?TD%BT@B~DNt^z-KZ#(G3#O^2{R6Au$v-}Bl|29P zb9B!l*wX;lLsdryF&=@OG<{fqBdQVT&w*=(QXD+GojdjB2^CxO%XOGVu&q9cL$Zre zz0;o%E0sZ~rN8rN8uve)sh-O=Oaa|;^mqBv2>Jm}ayu1^i*d0;*joR7o@(iM!C;EU z<#$K4e>iw%qmre<7`*BA*x@M$PxH8j7sr(L)JAliD9Tqpto>YkfUNMwAQ3 z?xPnTCo!r?o7eN2ZnDJ2{@y1WUO7kbrC~kd_BGAtz{dcVKEgP8;RdxGzW&G6$G-I{ zk4|R)aydi7;0HJ9_1yZ!$%_h)k)2PjYPv;dL#a3a+^-5e65u3>g+Y`6wJd$tHM3{X zdFK$wgpfo*h$sM%%FK}4+S-bEg#kqZ?68qI(1*Z$07ROwx83x~^<@Rg;h_=0-Aatx zq8aq-z+()_X#)cM)Zu9fv@w8_APF!na3A=AdGPGF4h|roHsAN!#utTTn^&946-2Ib zg)wV$h~5B%JdMbA!cqgQ)h2%vwc}9kX`a4&VH_Bez-2H-fp;-_t}>=LoID!z<3nug zU!v#YV?!O97b4p{Nj+?vrH)k0>BHr;j@IVO?99w$oEblRi9o&c@temJ){khOrik5C zaWuGdS-xK!5Cr42R+w24fe=9N=^#skl^jYAyyaXbPbW-$reNjDfR+p=n3&$ZZOKi_ z0LBI}3h6KV3XyNqAMhvfk<{|KA#l%h!Sc3-leJO2Od6pQTYWZq3;%mf$-L;6!6#S_ z@)V9u?rRMDqu5%kbIN?pM^rcR7k&Bg@XWNxJs&c5$`S}ffr7e%;}=2i1JRY|tJ-R=Z`2-Gp>G`JIG(E|ezLMT;a6$QxC??PWA|m|;bR;|x5;l(@ z?mYlppzdl{UX9oD5`xweq5hqLND@p&@;H?rQG|V3eR=)iKlSpAUz^tjkLuPuT|JUD zt1g|(!P!Ca;IsV4^4@@QwI3zdBR}`*ru%%N!+q`ZiG{;Q0*mAKn*jDt=xmxF@Sd8m zYn!N(++*p**O4D{cru!8ePI1fDf)$%w_+Xh!>aoDw`Kx5?_V190<=SOvE3AOF23;mA?$}b z|M*@@$^F5xb|w$KPdzchVME1EE#{rRY<7Itrp$u)mh8GuYB3c(p-!1mqITsK5&n@k9dQC3!?> zC_zl|H@LGwHSbXRS#!BL8AmmsPR8gK!4wv!B9&!g0#^+_iFU+pq-~74pFd8G+1s!2Fg1ju) ztb(-pmF_f#XDtwa&CT=dB*&VyPcXe+#9(-1UYwk)LV8=%op@b56gZHk*nI)2Ysz%i z>}k^E$&H~R1yI*0ISM}A%kt~;m-Y1Svp(KX@G8UfucOi(43*xZxTR~Wo^~^$6{I%- zT}c86Z9RNnTD$@XqR5UM6cTjF)>Z#DRMnsS0zCI>Ru9BuH-Qt`O|YT=$g72f$ATOh zp&d_5gu`Wrae%VcLL@@tHE8}+8Pm+!N75Nv<4+3!07uM0Coc{JJQjG;8W6wdp|{Yp z>;yWZ3swMiGpp}7J;+1dQPKV0md?=&w&V7Tk;(0U>OzfbBh}>>2D^&$nWwXH2OkFy zVmB?kOO>6xt!vFzuLr6P&*3heDk~z!q9ve_2S{-of>UT$zF&Y}1Eu#-6Rpb2m+u4c zZyN5*wc$8=0}m7OFOdO$w?~2&HmE0P|0>{-hINr4WJulOdDWTWaQ<}}Vzq$+E^>oI z+vRzmiR_a12Z+H7CCO@SfRIw8yQl{1Or{E585wMZA)%(`2LS~!lktkl#|^o3pj(I$ zQ6%I>h5zpC>{OgvT+9R)KDhN{IJbgKARPi>tiV+RKPte-A#8y#gkN1>B@B}i^=YP% zL@>|io<7TPG9JB`%*5LPCMpJ@x(hepJ9Z zmEU^wEf~t;k&}}nmdUdteSK*09VU49vHYb%X(edj|3fOCgY+J9_gp`aHeAB}w37%) z#$-2dB6jV_LLH3d=pNtwa96OA(Z%96i^R9EuW6TSipqMJoeXs3)%(v=Yq8^hn-Flpf@qI%01VT63h!YQdUH3Gd%*n1Q;~f9z48;iP z#xxO>TTc(!7lYE#eZN8>Y8A92xOJx!cNzc_#4{g!86jVag@c3t+w*y1G>f=VK z=|WUo+duFsSk7~!qNFg-!qj}kDQ1PN`afTMup3yI5J2{3U)G6Uh@&4Bkj$d&O>Iz*#D zyH}kcf77jI!c+ezer@TXeg%B8tdF-bQ|s4We5ZDQE+vTN{HHD5iS+Qh4ArXJj!X2f zbr}rLpFe(3eba~en3CTLyo$pxSpHb*fp=^5{*V@!{3FgT0AfwJE>gplglY&bbEDI} zBeY8$qypt@rI{upNcbfZ91FR!G4xd4sFsaCT&L-)cg@nQ$CTxd(WXSHbBC8Cv?{(1 zo=Ef}c#x-OW;Su2LuEoti4r&s{N!zwF@jsj zv4Wn?58=vEi17O5R)ei_Y;0_Twufl`Z=)8C)LYX@ad9RDA<~Aq54a|SH#6~m$c&Bp z^@O7jab=*?jpU@{bqi$t31dfOhyuRLT#VKim$!LweM8u&orGykxPmZmoKS}R3hn!pwIZ+yoY_V>8aHfwn#xHJmYV57Ls{=MXF>L`Vo6Yc%|WksT7L& zrM;15gbHCBPp~#t7x5;(5@P)*lfbLZWst#o88Y14o4wQa=>{elQ5>&Y2Y-HM9}AKw z`R}K5k|q3k!hKT=iH-wY9O&tY-3)@`!tg}{WOGpTJCIe(lq^TFP=qms{LnXxFflgP z2U9O3xC>mR-XbeBL@uALnE2np0Vba=Kp;RQ2|n02X4qI+r65}lcn{H4hL5)Y=}Fg< z*14hg>4{|0@8=X*`YpPcKXR>xp4Q3PCV!n(CWkFnn_v1MpkQ2G<$o!X2S%i zPysR&>}j8T+Z`L0jAYDrb2ry3Jtu!&;F+77AMIV|_;R#~NpsYOA^+9&y6vfT1td`$ z>q+>4o4F9`!4s1V3F{oJMGfym7qOs6kYzYaSn!mY(|yQ_r*?Hh5643eYaf??GJI@1 zC+3p(OGKt7ZUrk%L=uZDAFsO5@!%HvJ6Y6N{oPHBca$>KdT7ET(I5J%<~nZsMPgEv z{U-HQ+My8pq3o6J(TH8Nb`fK$Uh67K6Z6sc{BtK=kFnkoFQcs@xoj^JGc(Tl`8n_k z{Q&bi-XG}iCy?t}GIw*+BKXrzsG+B%_RCl;$$myw~GKJ#a(?x{`8DcTE4Y*J% z>!|9!S%ZwTDA?`+M=9~sYq$cx+uEcI4Cq0Mhd7188H!+8QNA=8NQ*@!vQLT4%luSn}f;Nc|k zxVJ>Ys~NInZbNstld^*xq0|6}2W)r3o?Hie>a3EB^ANoYbihH6dM=xtYghdU%g2bu z_$)~iT*o_O`Q`FGvn9~7N^N47jA_kN`bcuE(dET|I}aaJwKPq0!X=`vhs@nbo8@Kf z6)r{+`|o2!F8>(WY~U|1z~~#K%57weYry=3eAO_Bul&EBk?*{t4?TOMYWZ>V%dsxA z|K-=$0E73)LMzWDdm_i^^GTifKskQteGAh516AGb?Pu=8<(`AxeU4d^B|Q|{5C8d= zZ#MLk^d6=qTrg+qA*?YlmV|OM8;MvRBQX`AGVCI*G?iV#{meum3Lk4rBp{tlKO9#f zaa@0A3y#RS`FY6F?3|m^kSU0A;-A7MV3iZ4dF&t7nRbZuqN6?pJ0VgdcD0`*4J>Xa(GE&>@RxqF`oGm zKQ(!DO}~71Zdt@Ut5_y`w50&=P=iE};)&w4m24aLCxuLL z%{Jp$w8fV2_VP?RHF7MA=Dd=E_iqo{o?2Z`FKI9cPx0dyF84^ap0fBUoc)7F@SR&} zV%pea?zGu`H|n_2)6>(i2X47peJ_NuDgHdVXz==<_0b605g$MQ%yLfJJ9uQKID`A# z8A%8+HLtlUeuq&8#LHxMR06N5pdSqaVh3U{j-&wFBRndEmItupBWT8Hyp9a2FE37+ zB$z{7LS?=L71k4?MLf64HS}b=qkf!Dc!u_Hbsh$TUyj2%feIW|n7Ru4r6Hrxkf;oQvSEoA4w7O?S5OicXU(eV)aA|dmpJsc|1aN6CeXdF(quJES| z-}iEa@5VW^6f@f77{z;p9JBBZv+l>hE(4$!K!NS=`!-867%=ohKTfF9T=G3+49uNB znr{DFbC7aySynxQjUdc5nZTX_-~&{r0@ZSvLsqTdHr!W)sz0O?wZ2g2+TYu|Rqp_; z1l&>CwpLzV;!KJOKG4&VrYP0JKO=<66=bHUso&PQN-p|x8!MtDW{WQ7vCqJ88mw8! zowIW?baTS7Hy-IeOi^zAgKbnsdvNl!S8_PMFlOX%Ec~^5@wW3k@j)`{{f}RYj;j*mo4Gp(Y;jXeL-LCNK@$m5j_nmon+-hWqQV#m)$?Ybp7U^f* z$+7ncL7Wlr0HzXYCntUwX;d^c-bP1XoAvoidq+xf>cI1|D^aYKs|Bjv;pLLolq{{T z+Z8p2)cPj^|K3(ixZ!W3nKsWgWG7CwB}KL9I?57yHQbMxR8A4TUNP>$vr%;uNwa=} zmr!8Ghnk9u*OLKm$m`lW!QNYgcaEv3oy#-3KTzUPpm#f1tO|Tlc3Pl)IBTTNN!Hv| zNq)c6(;y-A8;0!K;XV12V}QnH&!z)`Ml17j8tXYw7XU=LpuYrjvO^m>R9M@$j;hPC~#kTRiAfTjJ%>iRE`t-oJIMa9Q%wuRc37ETbv)msz- z8JG;=hjz?S1J(Gy^#ZcP1S>9ROAv{p-F)0L2Kc3uCqoqwPk$eriivwfcL{*wVLKgg zb4Ee$n%+7AoKZD zT1pnL<3uhF>v%>U9#Z&?;39p+YrjAb$%`aqQml8b-K9=;9D0HB8Bh`-1R@Fmr}Y3g zqQehg1tKN{JpM75j}?7DD_*EuLjiT0$rDrvGQhM0x6QEad8eOG=3oY~RJ?5px_2(j z-JKnz_Ukvky&{9Ff>NCx22+uZu-2Hi3vikF@$)Af`#$jSy%FYz2MjO*AT9um40mT! zK~V@QbNVr-ELNCjsVbHl+w6ll^YVgv8bZb{o7M}K-;xhy!&nbA30b|08eax@0%05c zVBh&Fi@wrSQ!|XE^|KRw*L-1dg09K52E+^O#BkEdhjHlW;cQ>a>Q1~uiHxQ5!%6Xh zgPPkq`cz--QF|U&9(EPAd4c8aIJFFHt$Z_IjrL&lkptnf({7>Z?}I!=vxSz5!yKm% zBHv-pOfT%+=}q4>s{85HJ!w>8%#|S@!$dD8_75cs54ud^{0WQ@nKWGk4=AWGu*~@0 z1H%acSg@s$SoQy9qD7>>3i1e~dcIbcRU>OJknOZvH z`I2l~Er(LMeFN6b|0s$covldp0)`;ZO~H9`_5sUq7r#zzS&{C0vWBw+;O>=j^C%-h2G9UC>nIBn4e!WMl;9 zTN%)_1Klt9wMp#*-GRP7UudT=@cyQk6|F{jRS>GLXR5&kLkw<3M4qJKYRhD*8vVX` z{W?9|$5mBTs415A4~dE9Cq1qN*#1n7AL)#pohx1ti|SGX8wf^5FkjCoEBjOO?uY=3 z?}bJ=;@qF|C{s1|!v_Wdf#EM=DU5v8Bemc=OaGW zKv{1(Bp*pmNeKfg`r4Wm#C<37N_f<^OFN#u(P67>;*+Ni{DCnnpj@Bzo`5;1YyU}W z?Y$;PYE~d@5>S%$ilcYq>Ub%ihZ^_z5(bU-lpR-Yn7W6p3g_IdpuTcY(~fh6lVoqW zHh9+REYI;JF@0C08d$w7Ygnao z!i0HJtP>%!Sxs8?TWrlVuP}qTjK%$a_3r?DG}NI!_^7|Cy>i0O%R9B8^%~8V=fm9> ze$ouC559tdTNYEgQD{^P)RJs*e0y^H%h5a*K!?6UD!Pl&@tb73g+$vb(x68sVXos- z<6pGnLIssRd;jHrkV2bpls$T?ZPX)vcy~+NVoC_eT|!o4&ccCiVyz(_{=>FZrPM|1 z#N0F5zyalRO!mnL(prxYrWAT7YG7EGx#Oin5Q{jTOu-oV3n+1_5L{dAxo!#S)ykRo>_~>j z@<7h)rx1?DqwQH_;6sewkdvUI?%WzYMyJ7SLKbF^3AfdIx366h1)EEk)Ab7CrDIGF zNa%fsNMQi;YKG!$2im(tOSoT^B+eZWD?+Gfh)9j2?(7Xb?67$2ZbGuq)s=*>5O=&g z@!Edy%PAkBM3>jMySQyC*iPuZztwgL-Am!42 z@DdhJO-OF$Gd<7i0M)sGo^-3r#)}kkfLWA)fc+mQ5X^;~HYdWgY-+AU&m?n2;=yIb za(vy{XEZ|7&II4RJqKV-2@^2WUC}_Sr(9iKky*L0@R5nhXEYZivjx7THA-1#RxN1f zH&I+Hke{ooMG-#_7`>?Kfouglez2>OgdiJ8KL9&6f~kT=`na!OeX;Rwh&}BV&#f4H ziph(9%XT4reiEc!`R2FtxL#9kSj<^YmeKM)fZ+rvWz)GVJtbf+293QV3k{X~jd^w3 z$X0vvNL9{JBXf+rlbXV*rBkz{lZ~@H`GYG;W2)@DJ}ysgU*np!VJA3v-p{EyJH)@B zk*Id{5u?$Xv)pGNi{_u<0c`X>-|Mdx_wkeEmJA0KnXr9Yqs$yTB5&0!sGw!rHY+L$ zgopqDMVbxU&P+r5zen&!0GbK%x{ZCf<(H>5(+>wClwsrm;7!h9`n9-!Vaq{%SQBtFIBzju!i z7Wqw&Zt5T^e59oZ@i<-8`(c!3nC_DUaN9svg0~yu9 zIiBD4IiF^DEr!H**V-c4c=lxt!9l+SSok15g5XyX^fx?%)S6$y6y+l(oA1AyBTTH@ z9D?#eWL{~f;T_DXxcB!0iTN{RPa-z~SG7|o}E5O?KGl_E+1`R84fK03#5Q)o=7rZ)E?6mg~+ z74FvttvIgQw$z@cx~;Hg<>bspgMMVHvEzQtTi5_kofQB4x^a$K>(X@-p$n`LhY4qE z&ngoVl*~tL1e||%-*FKWbf5HAbTq*5EkDmqv)ddIedJ1FNkBjps;#}LA9O&ZJTlVl zI**pO_V~|DmKeU@fmyEGaXl+8W|X(bgiLo8Co*>v^L2D>#x!ov`{vt(lC9NSmU8Bf zGT}UwjV$n%dVKpDVs2o&2#yMsv*G^3tG}SOZX>y!kOaWoEq-dHm?}yR5pWL~qV{fl zhBuKFqx1kO5=tLfJg{v$S~HcfOjw2z2P^zHlAcJLixaz^GDUjxEn-y;_IE97Qo)@{}o(9|m;0X{Bg+pTu+hCVi`hTahCWsHPPQyR$9 zLTA7~!O4hfh2#;sC>-jrpp=H>MxcTt1ZT-4q}{wlARMcY$CMqG{`E7-BdjVol5Y(t z8hmx#eT6{3Fu?&B{76?f6)pXW%ovGkaI?xwoa+;!Kl17srb5Lv=TosK!Ay`#(p4-B zTRdJ>1x3|fi5|<#f+i^W9FLXnt<^(spnUw#*GUAJ_tbQ09dVu0FQLVLKbn_*TQ0-( z#j!4=YJmMy8lHHxM#8AyWNkS5v+HQ#q`Q3C=zq}!t5?qCGnD2zuP+tU7f|#Izq6?B zum3t6UW>o@(Z0n}W5nQX3>zIqVw1PWJF&@?yzCF+*5;hqK~~u6TFAc zZc9+zVoS|3%0LBMKVRBC+D%|>)!)6r#V~UvYkF(Pz%uL0`2e=cx{wBj>FtN_--rkZ z+=MeX{F5HsAMl>#6cn0Z3Ic0%!%$}mU#pNe5uz_cnAo-o?6WVSPE&Adn7vOMlcB&5 zwV3!P&9L0t*53X=Nr~t|MkG0Vm0d38*Tx$8n%KM1SFNy9%JE(wd^Lh(^4KsKr+X= z-4iT2TbjX=p8fioPnM0?bn4rL2dzV-rG)c3vC8?UcGaai|8@^fR}#Rx{;U7th)?WF zErmnV;`b-r1Ji#k;I1XAGVssvxVat^PJe3XO^o_(+ST&0?8>-H3_fUU^!19y?d^(; zCO}~lqV>88D`M6TaqNHSTfMr;BZ#4)WKcT9IwK=uz)O)U}|!M_Vd0^qIv2|YfwS2PD;<>UgZEr!{uI;N;hW=c2Er?i5lrm)VQze;me~&k3$vU?&T! zv(YqL##Yqo9gE`%pZ1F)k(qW2!}3l_I{Kc)tl}qXazu*t(YS0*ldZgiICPBoRXwj z$o#+=7jD@t;6PpYq$1&9ljj@G&wn_u0;}LEE+&#m&Z?e`EMgLb?3u(NMtQdObfXFJ zX$A~0*<+^-Y2R%xju(*-JIkRj4Uo1W`ehy3XX<`;+KfvPhrK>oB;powYLI+yIQ$j`-Bksp9mYFhMEUGCWiLId z5cPpt$53|0?(FpBgsQdXTJW4*8_a8S3kyUY5jhWZ2&uwJ?YFkiU3AzQil>~|OytmP z{jTswN=TZLBrww1D zhN`+LMynK~i*@g_20F^yv!(~zWiFx{s0TzJfQ%1t0rl)Mkc+*}T#ze=(22pv6Cunb zziDSh+_|p;zy{)RGI*c7u1;|?+m&dIf=s9E{H?fJI;61HUr0Eww42>3wDH7;pkeUr zL9Qv-XQN)r%U@9vUcL>2w;1l=cL5tbG(yzDzjIu~Q1)w-K0-vx08~SOok4pnD-s)! z{}+tz&QJEC$%DDZer|A1SiiZ~4EyGBUJ(ZRPM(h@$lSo0Y!+Yd2puYEnD4I#3P{$_ z^5=LJSh`8ponJRI7>p4QL~``-0wOaIa$0_>`7-^OmH76pIaale| z8v!u!klIlY1wOIs0R#XvUBHY<8vov&WNj4MQjyx-=QYwo5nNZ$AS+8UTnEVgu5x=@ z8`lofz;mDRF*0J5Jntl9pHF??8e^Wmv$F#$UYz)j0N5Ni3AjEE%1dWq=lzVPj;R_C zqbLgtizL_%wgq=TNQgbB8UU0p2K!T17D9W1i{JE##o9Et-9(G2z^Zh!!WUOKjTvy} znHfWPVX`DLI z$Fp{IS{QP^V+F)c445fR0>l!@43;_xb;(gAS{?~F_Ln$WE!YEH}5 zO7hm}^L9)c4_p)trcbPS3(=kS`=P6;B_lE39KxjZW&T#&Uuy86{gcUg&oypiq)y|lP8{To;irZRJyD!Figr{53 zq5UQ7(ixL@%~t;hGt0qojqDQiZ`_mt@3i2^BdCDku-Ey|sE^u_45h!^{~6gg`^?#K zL!JQJ9L-(uEJXM-KtP_uEnl|OJEcH)7I$^4|4O6&0n9+eluu$R`NrM`f;6CrHGMPb zfF~sY>1&}^1z(zzm4c&IiD>e_@J=|rFFcTZURcxqEwj9dtORF+nNuZUh=uMs6z~$y&OCtNgmEzHb1%{%nbXD;pju=~_BwZilMUdI|Il!=QZ$ihwyN^_ zbd|x(_YhOD$;E(}#Yx9(&!z8lonk7D36P z`t|+Ww{HY;Hk+65g2--0Q%F;2TIER4jm&;IT%wrX=_p7OSh$!v%%5BeUr}i`9{pUW0;Vtr0!5i-GPl zepqk+>cYkbCN_is|Hja%|pBZyPN0Vxt(FC9R%uirUv zaB#MFI_}Q`@+5G)x0X4TtVh#98w_H_cVV(JGVg*7U+Ic_ZEm|D1UEP(vqVRMh~*3H z4t)Tw7I3QnsM|GJ`3|&tTo+Z&E}_x-xlrkR_NSpMx6LB!#g(2P zsJ>wJjs`L{Sm6aLYR-0oeF`jhSBHybK`aC6r|Iq6yN6G~)wr~DQ1Je(stzZJ zU_ndp5TE31>H`(1O5%A&<_qN`TPvXEA=n+%P3Zh#Jp=TJX2A?c4j^EvJWFZH*XnIB z6jA3h{BYh^BXw0YN-oRcV9O1J!s1!|XjT|6k8u`NcSTpv)HY7fy=3!oDE}IzX-rND zMqMtuK4iqiT6h4alg201XueHBQA+Sb^P5jiL zzbNIWE$H#+%I$Jr;hypWPXsJegpLj>>clKYzxdzz6C!kpf7ulfaN1G>X%q>%Ufay# z23`^n7fH4L`5UvE&@;^ip|zM+-yY8mdlwjL>T?iEo=iMDaK~E#6ZOyEl@{q)_{BIv zk%xLwzs#akro3OPaqu|buD?!mVoC7ZTy%9p@Xf#9wztgH<%^Fy<_HA{PWi#gdA9S&A-apHoB+(^Y5vIh{_ zCxJRNoNS1p2v~?*K}^#@6IBB7rigYN;eC3YLeuc>zp(4mjh|0m{{f{j!k|J(9zI!p zBCb2eMnTo^S4cYTR!M|sXQ}<5s_ZmkI+H5q&gpsLfG8qecDn@Z0FHnaHv^zp&>f?E zAbn~YLgb_X4(OJ+^nj*e_Mh|QFUSH5fL$vBPyp-W?>7^C=*bYU3~@|`%f*GTi~Ri1 z!LSaoAU92QWqQ?}dv{rDOhO6aKw$gB><74(1E(JM zx(dr&ZVM7+YtV=pN-01DM}a*{GNvae(%NPfvI*)@^$6jXY`SC%BnPldZAaAt*1J&o zNoM&QAs!FgXnAzu@qB-OKNTuB8+&S!Ey0C0058)Ax-c%-S3x<4b_1kmAcY}<-%dnt znj@s|ZASO`eQh6=LVcv)?!khqTiDxlw%cJkB_v(QbgyQsaIN- zMqL!P`+9!)vw=@dT8`GSx-Lh;=k~XVjdzWfvpW5H-Ef+Ro|ZZJlkIPDr5bc4x~A;T z{AL!iG&$(*n!dtR{v05L`u^SidFc#1A-=#6GC0{=MndRK@$T74aPK3`WMtL=4gv-0 z6+{e&f1*Hz`te`m`Y3lOEOso(y;D|IH6ne5yWM{Zol*H%2^uw&!4KL5Vu#y6*rk`2R zzVSW2gzVP;a!J7r6bUm47h1U06jEV5_71kpO=MTc^i&%#K1(ya2#R%YU1&PfDOUc2 z-5@!(HRvb;^Ciqcq-d!zG5&B1#t;RyO0VY{=nI-0OCGw0GtLKus2zbQ{v7)Q)G`E$M>lr zRn|_Q=fTIQOOJTOp`^4BLKA>4%filXpZxZddV_dC^ZsX4j^7HTc%ju=Hj@p1+pt0R zWs_BZbahO!_};8Wb{>`H*B4UK?Q?+oz^M{5qhP}BFDA%TzFUt?Sz5=Bo9^zr*;tmt z3}HjPqIW8j9823YZh?AO##p=vbsl5Jj8fB z9SFBbP#Bc*3C}|vxF#bFW3md4n5c-e9TI78J~G~nRfPeXuQqsD%gHM=Gn4t=o;%SB z2j?H^bHw-aGKj{b&ocVTD*ibo$#XS4aD-(JklwgF-mhD7hU`pg%)R-EVhwj151oC7 z6?W8Ho+Py(lPZqe}A%}7IJ>Sns+Bsl9Z>Nys#j%w;YtdjLA^x-@Hu}(FmJpU`- zh@DpbqVseRTkV`LuGY}Mfh}Hb#K2-8pGs})1%BYDd+WNB$X?9D#7V~VO$jbf@VRLL za(x7RH1Nb+nLO@xw(a5@MxkE+SY|o{qj#;>w*9W@|Yn_t4D0Z zKqydwLgpIicaz4;AukT0;?lS+(IaV0GH8i_hNA7?6BDC``$1xVm%UO}_Q=eL zvXYg(zVGvXp6B@ej-%ta|LCr8eLm;;e!pg`yd*wrrQam*0-neFlR__j00$_t=)I_G z*GL3MZ3X0O*h8Mr3^;EaGw!}cu|()kg8><4BbX;oWNyr2Ka!!T6r1FG+|_5s|QY zYqG9ArVoUPV|RBKfH>Y3(G${5I7U>l1vT9W7>7gsSI>ob-&l)~4 zF^~@)<-JjCQX2adj<+vD_IN{Y*>Y1)9m-$EQZO(` zdE^0?C6K24+t5XsaAg3lBV*{Rf+3jwSr(9=;82RFM1pGzVkU8nG@`co`vk?Nxfg` z%d#fcuw#fqpdc~$RfsEq#{K*ygjx-j3`llDpH#3mzSsbF>jwYl$L{Ih&)QYKiJFF^ z9>p0n*uv+^mMLRq#*R>V&`A)y%ax(_Wt*#MH;o8wr%P~M@_bvqMjvsDYvl8!2r(JW zI>#}mf|Zzv7R%JiM+sQxia^^7eBpV?uZQmdDR8*?;hN$vU8PKd9LkIuIktk$TFtrX zZNZ$b$_qR^eS5Rs<(r&?O@D674~U68AZ!rP4!bwxYMP+CLiRD|hS8FzRTJ@=^T&Z( zSmVsz;JmjZRWZrWg=x|^?rd@|dcl+Pu-fH1+TZ&6@WI6LidX$c<&QQ^&Xl8n*`0S2 zKvo}gLn59aT3J)Cn~eM^p+wvFIV1RoD3C9osCxP9U6D}RCK5I1PnnM~C1GB2C~nU#M=i0Qf2^ZJ!^iGLIRKH)uQ zZ5W+y#=@^=TjXq8V0(7qJ0`4 zO06PH6;P|JH~7neDOwWJ6vN1I%lh7h;?YaGcm`!ln#9ADLOA(Pw{&auQ}VYyOqdgN z*2wP$bY6{?dP~w5@=Q$OPkKg8B%bo@*dAjwal7CDhRwZagf)oIHC?8lYmBGa*tl@QyED1Fg2MA1c*_^hig|GZMdJjaR1v zPQ@p_$PH^JVRma^O!x!FJ#X*2rg;#JH^Ki(4IzM1porqTckiA$^Wnj^&#^0#N~;1tZ9g;VMOwVs&zxwf zGpCt^rA5)6Pi~jGCZr{3J-xWzrrhIUfl31Cs)A_Ghst5Ia*W`1+WPw=6gm^5Z%61s z?J!cG!99iK;owUIO?wh2ar%<0k5>NEsb^egneoh-i+k0@(YOb!`|k;uBhc;wS~o|U zZ{IpQnW#RhTuS`9S#cDbegQI5Ku9aS?gUQ}vxB1})LZ_(;y(f?|MFP5F-+;dYn_Xlr-3P|g0%Ok@ivT|$9R0Pr8Q|5IocgB$=bBKtubg3$rQ zhtS!v()RXbf5d;2i;q5SIDJ8f@bPgOnV&QUE<#Wlu-D4KgZJ#&voISC1A~<-VU_iy za|D?Xw3*1JTZl7mcX>V1OtX7!JG?+7i~5NlLqR?0?~uR^Wo60B2enCAFqq(aZF?k%GKkiugs(te;EKUW#6yKzBWpI$bNMn!B54&8pEz zQe7WEq+73@B&}jNQbjRTAj;ax@JKh_+Ohko59ycOKbmu4TWV~Tl?Bc|jvuXA1HM>T zbOqonm+ZNY1@5WLg|FO_7}mc!VEw1I%@X)+UOv845VB|E&JdQDo7dF`FZ-6mK5F_JY}e-7o*Bju?0d}w=GysL9#-lVv~*d(}Q?u zZ|*(41cxd-^(+F%%Al!-J6LX+;G_{_nhz!X;o%bV$Qe4qZ34&5K2pLrVKA%=edK%Y z^r-E9J3Z}vT1tqBi#m6MkrIW1B?wyIhQSE_3Pew*cl^nrBs#z2#ZNEbrPd@o==E%V zK8i|5b&RMBhNaU0k+`nt_a}4h0j*8Il?ifj#_-Tf2Lqqtd+IYNa6G>B>TdrL1P&KZZQJ42KsB<73wL zC5F`vz^T0fITc^RzYnjrOHxBc*! z#Tipv|6jrfq}w4AFJk|Au*1*)c$#W?_JZNG#L2Pvv*N35BY zu9D#GJ@Xy|((g*wlMM|9PYrAcG3BJWp<#otF~9Z^B*}_6H+{Ay`@(rV6+c%4y+Sae zz^yHcF%XE2PT^!>H!$1Fh;pl@@V~BKLw7@aU6x9P90fhWWX|qI!c+`#s&d!P@^$?N zUF~^kx6#t4JM;2VuRu0u{O667T4YZZ6P&bwC^bK7DoX_W7C0yn^Z~&-D8muRLXj8F zj5M+XIk(qI+DY5bw;MBf&P-^?XHgvG))cp>ZQ?@<*gx(9TB5k&WKp~wcdp%W_=bT( z29Gv{(JbvMPHSAHzhj20KLjHUrGy(D04&gTcp}UR>OJVaffI-KC53A741q$x!Mw*#eH>c)VcT2m zQRj2&iI1JXcOFNc#!1J*lNH`u9`Cbiq+K11R;KjND{G1yNOD9h>Jk9t7)nP+RciLjlfM9InU;oa4>H9R0yksXk z{a>v=1AN2`$B zixF0t&GF7!3h?238M^K?c-g9@Zk;?~+fw@UK6nw&boX{cy-#CC=~T}5c(s;~$%%$| z3ZfMPgEaftl@_08OP^MPe*O{0-(yab$pU}Dx=-~<@PdUapqyR+usW%^=6&pw>71_sya~o?u<$_o>XW8G3K;K@@)pejuxf!StC_~-g4$D# z+}rmt)O7enw9+MhH|dEq3oQ6^92AXZ8%cFSaE&INV&vo}?nZFj4JWPDZ>*BNI2}AY z<5i9hgBoZ5ZI4hcd z5lePzviBGLtMq=-r^|);FNOn)B!|3Jh#K7sw|f7+&o5o7x=-}iGQ}x;UVMH-EB8~Q zzChlBfK=i?O7Zl9rQ6|jatp4`&d7|0$T+wlZ`zCtQ?Jp7el3EO7`RK*LA0LMu&%fK z7GH2AN*trus0O=AbR%>tq4@}{_V;EG`iB;a5%UxjZ^0Js*Cp1N+S}~!ZXm+kPCzF> zgaKQJ+ia9PD$Ux$xW~)!UOE$E^74@8O4+n&jmI>@qt$8|$PT&)Yy;x#KOpNG%@i z{P>~rtw#mtBKY>7MHaR{$9?ehxn$RuEF|HcVX21K2KzEn^}-LvIng^^Bd?}re89($ zCh2#??~+HeE|(g7jkA_I-hG|5%yZ4a_pfYrDzvMaC)C>gkS&g`RSbrxfrieKy%iI4_AM=Mg3{D`Xxfh z0-k4>dhOR>px!-)+cL~mlxA;LbK*$GtD6B(Ow#co8 zQe?s26e}3}#OM+T7qYEe=LX#|8InJ{>K1k~`nHEbM%x7D`eL)?x?28=!J_}%jg4n` zyrL{`pLB7&9wlG(!v=0;o1$FYps9;WAd8TR*0qV9KSvF{LxqmkAKhjLLyRtV9wpCK5G`4@-ccDrNBCuUC z#HdCWKsK}3Oi&^FEBM`ouM2QZIDO!8pp*6|BM5)s&knOvU~fG<_=wX1AMgKqnt2-B z>M6|fjIvW%rwCO>C}UdP#N$>Xdu0|cXm#_1-@r8a%4+?!Hhtw)94?^s+wDO2ma6{! zC$lkUEuYl?QNTM?rZ{n#==~t6T3SIbZC-5Fa|0&JB!=Y_F2cP6z~ObdJaC^rTQC!0 zX-a>U2()D4?)JH8oWGZsF{btmcgFUri0IJXp~58R)JNki)}q5MdVzF9fw6(f%{a}0 zQ!)Hfg+EKI9EF#i4A*CQIe?Yj3sBCnENWc`<@!QCnBsSSvb z;D-a~CukIZw#s*kJemEFKL8I4wHp7M3ll>_bHSemaf51nfO&z|z6K0&kjD~+XNHQ5 zfqH`W78n6235whHk+_myQys4xXq(xn&hBm~AlXxcLD(2d`%rKu)JnrWKu$Ubx+9bg zii~(pI^Jvb;491G`jGJ$(Vsy z170q9(X;-e{LI#mZZpRL%?C=;^}aDo*}7hg>0a$o{=QD5lHLal0x|({)2PU=tDB&* zZ?ou!`wdEoFGAWnFp5ZD>x2B22vdCU;9Uq!I`xa@5`U)XIr<93!lR99f`COK#ro^-s`k0qgN}tM-qVU(78Hc0_#g>eBaomlbCD zteBLx!z5f_1cOXi_OB;Wo<>To^m-8rhjuLN+bP)Oz%anwru`j zHlPVw7#+zWqZ1xhl-3r+oUupW_<%`BhkG`5e63at5F;Vh;AxJxXVwT&fkyS;s;iYg zBuSjE!e(GJwg05COyXsG`PW9q{TsCd2S>KYTedRi42V6K_m-HpCm~gW((b(rC7$7L z?%$j&unJ30BjmG2LtAXKR0DKP>$TgfU{sxAm~=9NZg$VbK9vjLh~7Py47z*Qqsil@ zb9F`MTNEXlh3`A3gl`q(ZUq{L5jqk3A}N%Brh1vI4eNW$osqCT^g@+j7mzfrn?byMefJb7lasN zUA2m0Oz?vqDBcF!wmh(WAcil3z$I9@v7k@`egUA0dkguRjkiyS;!A5>!gOI>$YSwi z8?=A z``+P1Him)p3uaO+-Ubs*-j+VmIX!tj%BG}?0%W4YsUNvUGc;fMSqEq0`))Eb$uOO) zoydx6Fieuy(*Gx^*W_a0d~L9y-?iU0v)5i2^8hd#f`6tg!;^4IX(+t1L;@LmL@A(S1F$Zjv%nfpz%yP6 z21$|hCRAH})wv8zaiOYuG5Oi8ML{BYb4}ao4?mo)-iI1cP>)FNGP^mn5S5}`v6dX1f)Z)5S%CS zd8fv5KJ9+&oS|{+wU8B%+uYU2QoIFF1Z35AP(37q)j1ZA3JN7*!c^1MwQ_jLmvkRw zq~MF~pnG1c4|nWLD{jLtJ3AW-HfX?#%sNo=6eQcF!H0qvEl6FtLgRpm;mX$JF7kU5 zg}J+K{a4Ewp*SwJ0|A2x61 zG~t|BrbEM9r^w-|R0(EXDZ(Cs@E~HsRad=i+}lL2Fga{cOnab*g1e%<{Y_>55;`v{b z;5N_o_rJvI=~)d+(ka%y82sqo;=>utT{91BrhhgnVOM`@yFT(3LyUAIKF z#hUcL@kJ#0wQqhBlD}djFKW|luTYv1A^gDO-mmC&=EDi$gs%0eLZACnYc2I*FhP!r zhi-IheG@WujFM#+EjJk|+8JO}Y`l ze!K&%xhF7aY3^Xm&dfCG%eV_M%v)Pq5p;&B9{TQ)NBP?$yrg!-b(bie;%uKq2^+O$ThT2c2I;KR zg9=Z`F5p1V#OO{uvzE5lhbtx}|Mg2tMlW&>BeVO%qGxnjHSS_-{#O&Ll|sp&D5H2` zgIgzR<=f6S=hcj?m=nZ5ucydab6rlsWg7w7m|tU`#)1?V%y+R-F`))4moyJlAZ+R4_D(KoG?9w^nz zG#`oIEG2a%Yw|-B@Vdw7D_a$n$TkML(60yxgj76GA|ZwzO?p5BA$L_Gc>2Mnhgukw z?h$Mh?2~`(UH?IC(I+so<_4kA+S9FA~HQ=HC=(q)cp!90fajI75Mzx6NGcXxF$ zQ~fi2PUO6bT(qGE2N&T=_XdjIczR{8XrJjp84yvpG4WH?(;t^Ui)^ z!$`d``tb75H!b}Zh}S6LeGo<_O&IKAc}-uPFM;z4PD03BgOErB$-r+kCHk^xmaTz# z(U`ETv{YF7*)MtA!L)fpPn2EObnw?VMEd;CV)q*(oMxCyHE7m2{2Bp!0PK=PwZXlp z?YCBLm{P4=xX1dPaGKE~BZ4Qzbnu))o{{COAl|j#ZP|Frr^_MB8ML_#(VQBulanJX z_#efFQ?iTNRtQ;%{C43`;kdbp0_`D}uy-%+#s6sm0>F%iPIzF?*-6R|^BHa@5>0!$q_k`a&msMC#!)wtY&MBOC*jHJSl;w#_UQGL&K{W@XKIm;^AU*Jr zE#Z$7J6x=df}8FGU!9m19**owZ=Sr~oNf4aODj}3Pd9_oyd1Kd82$vc3oHi}I1^3& z*|a7&Nhr(j+n_HmN=bH24VO!;Xv((9OXR<-U@)jAlKqE!?xnT85+m7&8g4uRk|Sv0 zTQ3G89vO>ajQs+(V^f%qQ7tRd&nbP$Ix`vWm8r{|PkNS#Rx~UA1{aKNh%5)CY1Lgw zK>+#>B2jdCey{IwbBy?=h+ZwdUaRl?6IzQReg4dVp-_y+xS2d7 z{YP1~J!nXbHWvqjx5P}(VuAuL)2cvFb#k7R&)PQwOg&){cZ>ardvCnPNyL4QPTufj z#;l%(Ub??-EQddE%R7qK$2)3UExQ`d3m<~~eDP{wtoJ0?z9WjUN?xf0larC4egP$i zNVBx{)xqNdLA3-_aZ-D0ZWPxzP*4o7ut=x5iJ4h?MaA&E>Z}Zs0s$EWZW~aEDspk{ z^M|ZIO!k~UDz|>t@bv1M<5&DY0?Kvo6)q{}`vqjOEil31CVKn$O)2;RHF&@+coERb z|4GY2D~~khWs2M&My92PRPIgN#s;Xr&7 z?2S;2e`+o>KNn9-T0R-?*g*I4!E-Lz%_~_ygc?pTQqyS21b1r?__vGPdJGhY_}-0c z6Ec~4FRw(tRiDpQx0R=|G_{n|T9uTGU9=43foT1M@#o} zj_Y9AJX|)vhy)j}#SdZ@nfuL(20qP!(r%Mdu{bJDh52Dbc;L-M|m^pErA5 z%-Ty8@@^@WS7g?fsn?YSy^I z{%;)GH^%y^#g`uabxd}IC}{A+0Zk(hs0j?uJRV(E80MOt&nJZe+Ap^8qBp-L)ag8x%VVYbvAyoZsJGLBe!M5L3EY1_C~a9AzLF zAWnr87P;$JN0n6c2YIfHOQV0a7a_MRbSCegP_Qy4B|JV^hB7-D(}^A98%FN*8$srKZe}qyM-r|`_!c6 z!zNdd+MHb_nHgNgdU`#q+8hfM<*}p`ArTd1)ytb0ik}>5&2umd_%f${-;z z6_Oz_b!4k&9%@V&eZ%*bYlv`&+xPVL{5`Vj#B0Wo;6YIJjM-uw)SIF(aUFF6~#A0S-ILH9j=ykp6lK_x||g>ROOyA)5k-OvE z`PH~tob8{(;wU0-)*zrOVgL*1dxBj4~X+SxWULOO*+r1Dsq2y31%e53Dk=qw-O&iwT{NZ5!pNgovTU8P{7pA37DI{o>g3L?XS)kV*U zsll5f@9bQrX4u+uBJYib!s-YiKkaD^f)}rD5Rruw(Z1djr^jD#8l@X=Xl2{+ zxQQ`)GZgXgrLD_sKB15G1vQl#>_%4}z z+^Js)dH+DosIC2;^HuXqj5zM=<`b6wK6^F8sYvbvDmSCqHR&@N3ON@cs}{Me0W=MA z_*T{rzIf$D9@-<$qOKL~&-+OhjYEBw@LQlhLT3O}_@7~=x0kVUN86*aeo zG2db`fhiFUvr)N(-5VPli00mFoi}76X;;LT<4@((f#^XnN)|zTp4AwR0!T;7h9Nxn{XT)Xmh^-OV{Uu6sm*}Uybos5%a;Q`40{L6Ey0S|sgsnyjUvUMI_bw^6O8J;R* z-NAOh@|`f|Z^cGQ^qW>nRRrw{qU!1Oy6rV<{Zq!WaaQtyM+H=ki(x~qi=0=O*mT}4 zdI?IWKYyR^V{uGdQ#AIBpxS2d)mZ$uEDno=@zKH*&f$ZnCo8G!E=P`5I&z@edPc8* zy|H}elyw_PE2#AZ=H2GDIl=Fq%o>-9@@=My-gH)DIOb29{F?yiN#0(l52`ekMwJ$i z!=eX8j7QV0WarYmQvB-xIu!neaytRk9$(Few9AhM^~@+t3k*!cPNfDI#rP~M%3dc? ziS#YZl#@S3SwbB2m++v9+f@EKE1!?oo(Di<4YcB+wL82&%9xiv_IDOvF$Jj9edD4B z#nq%=8w|zd-*>1jVH#l^0MK^ltIq*Gii=a%`|A??X6#6Vp>bjx^y3BxpU>ID?QIO5 z+K*a(s)C@DVb=ik<)A?F&xj@N{4Hh`)XrRXDq3YseC#iF)K*tU&_WD46TyQ=KtdUd zAzn;{#fa?{;aJzLBbz1KQWb&r37c%<%WJL_azCg)kax*)ehUQY>x>aJZufVZ3HfOFx3Rz?1Ru%#6CJIzSh$5i@NvG ztK$dpZ@RDdu&;?(F$DUjrL(3#43=mWtqG_7uGe@OEJrwYEAujpuD9;6CDGcPVC}IB z{rUvuXTdJ_b8UyzSDnI%OY52Jhnuo}^@C#{sAOQXqq>uANQIRkW#w59XeZ$LnSbTQ`LGn`=*=aDIWr3=|64lk4G~KeE&iIpxk9~?4dB9?W{@1km%9)VZC&teRi&^6n z)S?yH;bh~(zhqMU20lGlY%jp0iGqX9)$iPaRXB`i+!b=2f>^xiAV`Lns$93YU}ARQHXNvJOh75F81_L5Bh4>4TQOV-8M76lR5T)nLvgW62fo z$9^BTl_uUXpN#dnnWPN53i==f2S8Fjg0EmE#zOc2l=&d!VE2TGlweVTG}~MpQLLt1 zPUACqgOO%;$TV9DH+~2E&)PS5QB<#(^r`hUXq}cH`zFw|cERUDy}F+NOx`DL6-Cb1 zcO`E5sVGf1NEWZu7;F}5a+$iZtz;i%dEACTb(>EMAvKXh&u+>vTw~Fbp1PNsjEd5SwV?mL7j{CK7vYupLK1x}ZYAjNz?0>i4Z9bAo{ioIHq8 z0)|9*d))CRIBp#eA#dgGuM&`&|L22%y`KkY*nxoo&_#|2PY<(aC4Q5GhXL;lo}KLH zzi{OOI+i7!u=U=wXP>lzQsyU??><+9vVoI0Ag_PSG-w} zW$VmZn5a3-5;W2M9v|}ZP{=1>!+@yDA58=9h!h1tMhhswJd0up14%X{zgxA+!6inS z?K{ChPW&Hwh)i>+9RiGK#QR&zO$hgfL`S+HP54{@015)tQ~Y?Rpz1?i-9#;O2*Su( z&Bt%ayE^7^cbROkSj%-t;CWH-TqM-If0@7hvAC(5F7q#OhUFM0RzvnrdFRy~u|^jO z)4Zy{#nEe|?ftsfDzt$N1NA8x+xjD1{+HUUscWXxL$5@qTWvLRquDCHd=DSCnaE!M zCfVqe!%w^y(MuQJYjAmRU_dziVNCA2D?LN5CK;GlL4E1FK^HgC?dcAsZU`xc^fm~4 z0J6;tbC$lGhAeMBk5{=VbcJ9_HC=1rQozuhda;^O7Hbr~e%^fl6^$9c6+FXeRS+AlT@Ir><~CoI%u6b#lS6oO%9gvBh6C4Sh1j;UPMu`k_!8c>Ig@=7{d z&Ke$@%zg63!b6l%E|iXlSB>}i$Al&0-p_a3Yy++YJxaHOn!k`#5s*fA%xO}(Yer4k zLZTIX8h|d{IPUv}5#M?5b7aowbFlW%C6I*KmR>JO@BC_B1?lU&)}`;+#U^WKf^IJf zl8DMZ8y@owkH~J}(v%0OG!<3lyAM?&ji(E>l5a4S#MvkdVs2(Er>ZZ6<$R{ z2!;n&$`=R&k;mvMVxdbC5#j({waC)oDF;PSD2_llIv0cQ&ys(xM5mmO0Uk62c^v#y z6f)Hzks3NlKLezX*2tzv(s;g$9V^?=dod)e&{|EidYNtz>~? z4giaT0_FR3hj*10NPmf9Yc5Hp{ZaFcnrW(AdbmdKoHM#ITjKUP4GxPnWoO9^TL#0~ z4J+2i{pt&QJ(9z_2Dw5OU5~cD5v%aO(f(Drcp>kb-SNWS6usI}!STog$rN4{cd3?l z5vL|Bv(NP{-Nj+G@VxX0MxmqNLT*8xhr*nK)C?bO&)jgX&9qDXk8`!}CYKJ}YbOGJ zf0Lk#60-m6d>sxZt2f7#kopIR5@c%td@)>P6tKXzvArZJ`S2B&+@8aAM}s|2Nx&_h z4CZM)tbJbg$cJzq6sV|SSl6ld4kY^ta417oBs@?*F?L>(lebRVuU!%2VSHK#`FWn( z)suIC&jvUx0!33oM?6fn?ZNwy6OPiZ&vVe>@%#H=I^4pDd7u(=^DLO#f5(~sMEzO7 z!2hj3_J&r3@5AQ?&Mns>DBF5W5M{*!zm7)+)RJSKN$E{BoglB&Yl)IxRSO#sNq~G@ z=lRU0ASIH2?=!RtA?q+Y0bwt6%E+JcW?YsX1N|iSG=!jmuoNhcC)1x_HU}<1ki%0_ zz*!J<2yg(M4rtYwARZ+m`XZJ#>F|>5eihU$WQe3ov}rtuKNFSVDeb4cPyfR}a8jFL z^!oF6%C3b&miYI92UDV#|Grtg>`+FrONlYFRXaO>_f~DB^<2$|qp0h#0reVxJ$3g6 zQdd}xR)bXbgKyGf;g^amjIs^jxLes{!fIjYQdKCRcodSy!t9=vuh(sZAVYFM=ANfB~6?;vW@y7G?_X; zK&lX|SPU;+K|#8vi2EuSJ1j+JsKlMtTXT?HUvkW^Y*Df9%C$i6hYcj!&-7w1y8jh2 ztlC{Z6hXjsMk$$HokndXBf<4W<8JB}xm%>xwBcK#1` ztA(PYOsc=kGJtSvZxA;UHI=9N!Jd!4cqbTN)w6rVJn6sWN+50-HqYC9$@vN&0jRa8 zj1%u=`f{5dNdkGa`h{A>@O)pzQPonEt2y!Ne*I28##bJqhG6orIixIdTYEyS)^to5 zFrbzhg}>!FulxFYeL1t+sfOASJe%vOvYKdImCv_=0|(5(+O@eQuHnNk-j z5rF0Z(o&4$B?4n1__B}@3?{x{5ZB7z*n^bm>0#qY0jheGy0Ey&Yx#os-I#|IWu`hO zK@OK)YE9I^V~V$6mxWOcf^5*h0qX$W8mMPlPp>V$YllGr(bi}}Q_gWuzGZ_8k1mfI7~n0ttYff)vl2m&P6fH@JF(jfo=U{hCL|34*XQd)4&eE7*U-6?g!Oq9 ztS4ocXqL0tYO}tp318`-ds>yR$@S|BZ~KbC5C27W(Nk65MUF%x5?zJd)2s5ln4GUO z@iCBpU!i3@zwAZQZ~RB1b?sMfsmeX_KT~@q3H=LU1mVg9pc_Y~5g1h=!;1io$!5Y|ZhhyeS*A zxwaRuTPVdF*fRnQ$?+4e_dssQANMWrqn4B7oycRJY}cG}yL#}f<~gR_V@C%E#VLyY+ZS!0s67y(r=x=q7{`uK z(N}Yw2|*yxJp&&WhPUf*F4=<;W?9s|Y5HC-5Fy1NK>$|_s$fR84`2`+pIzYQUeQRQ zya+wPGt!1t)ZbqiE^=p8T%7MJR+q$9W#=12aldBal>WG#E2*@f?2+uAtdUFeU!q)< znv{{jmA6(2Azh-$Tfai2%P#-uqvNvGV9sBes@Bd6~$ICR9GA=M6eZw)D=#58N;B;$er}HesfNS3LmwJ(RH4pIa2zch6w%{)!(`kq^P$4SuPpYES zS}4DzGGQKY<~jGAJ}u#dYf)LD9G#T0q_P)#jG1*|mke&(PAS4AsV>M`)%V*2lL5Mc z*1~{afkcK8$z#M<_l;R@i8GpDiXyqLa*I$s^jEx5x;^31{m(CTg;raCw>PQ$Cx_JT z37GxhDg_S#gr+IZLLDrUuij~n<&_SNI(-`ZB;j5rBPYA>pQjL@)>}`saW2-&u<)E# z)?mnO-+Q-C{U|*6v9g`;InE{;cBeYYiR^>>w=OlDx2FTU72L)sa|4DNgbv)TO!Ei| z+_G4p{XAVnU^pEgA$t)NCVVXq!3KdG3~)yE|AlQ0VRFQ7W#M@ElOxgwUG@Ii2v0_U zKj469$b<)pcp#%#A3E193o40WTF=#FKeG*K%hw^=!g`0V|FH?fu?#Y0k=yQDq)F;9 z>3I6^#zANtackpe(zYA{vVay~MV;;7Z_|tCfx>D_T$(IfG*gqK^ zgHEK2R=;bmuuSi$r`Qub+|`vk?Ku8NlY(q-F){C>xsH=TUdPPdW$9Gj$8!ovzvACD z|BkdOr{CB0!BMNM3?5>;^yM<`ZD=bVFf09dZQQkW#qje{kH}|NyM>a{z1p*DULTZzxbMkF19S1c&>MiuE> z4i&*}aAGttxsLlmaZtEjDNNaK!W#lo#vr{6sYixT zAWjYod_;~dt7D&W>Acl-!j{csg-fe*QpY1!RhT*7u?bFFRFSKT? z>-&{k^)_B=f4DE(bFjN%->)Q;2Dv34YXSBfcNw#Wb%OmND-9WnX1NWh69ihaaeS~| zDpJj3Sc{I6dv_MjWw`ICB)&y^5(9DD_=11V-n%$iLbd)=aDy^=mR^K;OIDj9nO?Mi>E zjsOjf?6ux{{QuJelu-}}oOKenP7NAbcVyzI9TF7PEFKWS{!D8xv`!qIF$t((6!LoC zRVGJRdBQ8nm8k7sJ%vJ!Q66y#g>bds%`GSaFBwW?%AEOrmg(f7;!1J&iWS*CK_VSm z!z1yB5sxwKQreI#GyDFsg=dktOUk>xTz=#PI9RGbx(d47*Nlu?1Kherrx_+(vtmgv z8lSG9H8JubrF{DQ{MlWA1W=K8u!W@w#Y2p(Va7c=BbtqgF<{PS&BY8Gv4fW^`swM^=SrS-6 zRp^l?bOgU`ic>RSq+X-~wkhK0z0n&5@^a)i9g-Y`!Kw#y1&jAi8s}?GsAz)+n{S9K zMTDF1WLttW_Xfv)e${LLRLDp!nE4`*LutjNZ8$74mBnzS$ZEyaI)TaEQtZP{e?*2x zk=hXVzOmS-v))@2?hK_*r>g2m)vrpa28k7xN5+l$<}9k!Xzw?zIea@=U~Mk8=~X4^ zL^&>PFvtlS61Mqj+l3LFa3ujO?=tB&%xH>2|{sU6d0xU2?S_xSzqk|LRH4}of;!Vglt|)+59yIDflxrwZhYw54C?NZZ zxoPQb+a*}eslbl|j}r=sf-#J5sVqOg6NpgXqv==wOg-8n2XH1|oRM2MXJQhXwOC2!r<0$U`@W&hvE*`vGy9~O{MH0JPR%= zMiQ=B!Wrw-R>9^I?Hjg4DZbOBhO`A_7V8rHytEzVc=Sw`U4BVIk6Ic8qn8D;$*L*d zjTmPI-gsFn_i=RNGj4HsH1O(5zd-w%;jy(b*Vr1HS0IJw5@h4+GTrbL+&5?FB{a7> z?Qb~<_Q)rp*j}*zph%8CW98kl9b15A$0^1ijLE-&S1|Jl^W^sngN695ng`z%o`mycq~&5F z^D!T8w+j^8_cwQZn3R4i*4#rUe z7{8GmPz?Tynjye{z`&Xyem&+M;!^^l@J!!W(My-0ky%D=%1&jBii<3LLASR8d-KEg zn7D?Yn54F&IX8qMK#mr`4E)Lp&Npsq;k%cE8o|b(|aVtGhyG)u^>tg zl>Yp83{hyUB73LWcWG9`^ojXce8U}T(<;ctoD$vzm4*EOhF_uP6EHf>ZY4q5HAw3_ zpZ7>)cqUnwVU?`|-X4QwqqB@qa5IDa7lXTaVXqSn*IUis8ZJcmcqO2@JX^|U(7SCv zX{YbhIjT0lNZwQbWA=4{jGU`lT^^)Uq@y?W6hn>_}{A|Lg1w!js0 z9VpA5*gmK4);O;N2rdG&PxzT_U;gKvfUpz%>uhUlggG9SF|f6W=wDh->2(<5?TcFO5jbh`%1S*s@b(2X z(81qmpU5@k-8U&<$}Gjr#YI1OzME}JSBz|Gp?Dv*C2FOQUY6F@U%~K+n0)Ne@X~Kp zX@j#jwf0eY3QBc@DoLa#)ODMF3H=xBpeopr%t&2R*{_&fp?g9xZD&$`d7-i(L?;)K)fFv{)?dlj!Qt zAR;2l;xXc(L#fMfSOSZrWUnD9<6gU%LFnOry(P>t*-s(9@0Ru5MH(OxFb9H##k;Y8 zIg*JrUOya@)^FL5=^n!sTJzv7W^)Dp* zm**$_^1D)S-V<44Ev)^3oqE8_m10^09rrnNkOD=}P~)PMu>t*$MTtngC4t{M+0lBbC?t(ZL=ZBsCq3|EoU-j zoNhgpcqVr0`7FJ7G@CihjxC)+lUC{aFuI4hod6iNpn!SvNaa4^n$^q5!~batl=!pa z{O35bPf^z=fJB-;ROKPLl`HdP-R?Ub#_dS}Z6ks~4QS+0sK&`cN5>P$j-}icI_abq z$4pO;FNmjoa7c^HylbxKbTN@a;dK*|1eb{X@pyjj9G>cXSZdcxx*BV2L2zzM^3!%k zK_|tEEoOpb&t}Cg;ed zEtB2{4H-=JH(MAHwhRdpq7LL&yJt4sO`=;Kj&R3BiDr)qmAjXkV&&L{1O)Ifprt1S z+%Zw0<4)JViztc-44;sX?X&chP3QYI2xuXK0$@y7{767@2+2H{21X-hA)7=z&$44d zI`cx>m^9H-ipSVv>+FI>aZyQ3huTjoV;hD_E=#8$x#MZdF|c`7olU`hdbLvOOpNRN zzFV=C!%$RDX7OQsNI-G5yr}3jFy+l7+3q7Fa?2&1lmBS^aYM_GxAc;>s?0T|N?Jbu zE!agmK1z+X{m&^d=;@p`0VwKEa1fhS&`e$KO-X zxr=z%mjK`EdTkD(?_b|zSpZDz9rgTAEldsWyBn3WXVCwIMwq5kQejYuY#gaB zSfR!h!#SI~8+V@S+dis^1W_y6#KF@QG4G?!dK#ifC}7B7BO-l0eFsD?DS52vXH?Sg z{&LP;`7m4v$~_I$aA~ms+Z-MBvsbvM-Fm!#o8#)51zOG3PF+}t@9DoMO0p*@CwK1L zIb-0CVT7jiipV&`4RK3pOr$^mSQk2DA$6>3LH>^k!P52j)B|+cc5lG4C43&?aSE#&(7Y`(WC7r#re$~Wrsi}rN- zc{0gSH5pH0AN44;TX{qM^O^w>+w07boSUvff4ANI*)$F9>(NtNUzLZ_0^daxOK3my z9Bq#L;mYuO$T^de#H&z3|Cz!<4d?0-v9P`JuDH(OQ63ynl ztluRvQe{PxTxj(Ay&Y;cMKB#V4|*fy`(A@HhUcZ^QT7#}xQyGj20X;$a+27hw1=~x z6q9hH@8R=4^)DVX5w(s7=`+Pg66WzC7c1l|=Dmp$qx2FT{eg~bpQTF{wdTT{DyaB* z8F-1aKHI$;%x+V7Kmbh#7EWRs084ca7f;%J;60I5@7 z4xbQK%jb>!yOgkL*7l%RNw0IX};NZe16L3>U%>^3(%} zG(49YVL_IF{6ohYEu5N^sWQ7fcw)|)PctIdITZr>}sjGL68^i&bMO6U&6>5GJ0EKc+s-};>cG*9s?47`aiF)XJM{LV3hyX$O)8Wd zrm_;0I+X}D33bTwR1VFj8~Is&tpY`c(} zUZj3Nur+NRo47b5;IbTzN5e&+?wUi?X^{DZU7|`^*+0Jc>E8~H>gE08=S~)I{sA{b zr2+#5_?!r6XXydhEli?Ffq|ynu8X@Ji3R^tn3>oM|BxI#pr-`W#lgS|h~3)9o<5T6t@8^a)lv z$7&kNe?21)ssBIiGM+(_0>6q*wwWtFkMP|C?FNm8A+;CLhg;ftYIjjTdlAC3E0Z-! zG3E`0geS{%I$V`G>$k7BE-vqrkZcL_&6MlibIN(e{Y6t!s;-D6I?vxEAkHdE)8&?m@Nd}b<4?P-Zdl>rc{V+#y8!ymscf`K@XOiizG@>{ zH5_%Ngx-0t`aqJ{FqV`be5uBZraR;R5*OX}?R^6iKnP@r!R?wAp7^HdVbs0_th2*B zvxF+GE}&f?U9iaK)Dm$ShUX4pV}q=+Yg2+@ZRoC1U4itc(TlisI|q*S+Lu;kRDnOe zZ+j{hI7LT2AEA)F`A)9M7vh`gdBD$bSFrN(Iwi$|R0zM=wj)Dg!XdsKC8ysaI-$Y| z&j$7JL&!;gxDV-!$H6Z}?^#sWbwR4|_I?;s&n}XZ3Y={_Qcf}%(uKGCJ#W@*+M+-b zAr7`QMSv7FT4%-yEX?JwLcE!lbqGxN@i;p?Ff^t?{6p{rG#axl)k1wBCE6d=oYnnV zqE9eB4kxKQdD~6-{UguqbRWmXF8UHQ%IvaSq1i*j7ijm>u%oUZT9oI->#_o&9|L+) z2nhFfc0%4u5zfrixX`MR=kdspF>IOWx8J-=het`6Y4y^38tx}>1xza~9k}LW%P=?Y^|9nm-ktMf+bH1KZdVZ?uas@3;mi1^xORqGuU&rhFa@R3n0a zs_pa!UvsdsauaMoIeLEU^8%a3$6tibtVDd)xJAQrBg=o(YYbO#_?y#Ha_`S-VOaEr zekUnpcW-J@ioO!R`T-yDlmv@HWceqd*4=F`&AUZE^z_=3SLbSqYE1Fl(n-n~g`}Wf zwbKBv0aY0r&nGR0dYrZAR$S<_2{PW1O(#5m=N`2-3*lY2BhRTgve7CuK}zm4R@5^& z(%WpE_~C3_jo3wvpX?wJh7h<%kPsj^dp6L?iL)^yTs8GCSeJEGn5B5}gH#`J|5OOz zdLyiOeU!Z2%B$at`vv~(=}hBcV3{M7u%^>BTLifUTWEo2@B@4Yq*|1i!5xzjFf@2D zNElb$hSlwm62YbeqW#uwdm#;&mN00HR@tW5ztB)uZ-L~bn~w5cS4asFY4+jvf1Fzo z#Cy=0s1&hjIXXc_nYcUQJF8>cmS0oxZ(+Xu`y} zeuc;%bM{x?b=Qb4=cLfJ`G?U@nu=kshiVk^>K0t6J0A^#VM8zEx|N>>=J zm{E_yS)$U#F*MJzgCt#gSkR2y%{;}aP`NWRGXoXxL_Kq~D1|K<%+pyPKM`W^as8C( zuQJAc>CefnNGpA}#v-n&15-K`!U+Nel#x*yt5oNEqc8#-9kTB?3~50NjKK)sl<-CK zFg@LWuul;@W3S-kt(HX?APLO4&yT$BFMK_bHHl<5R&T0wuC=OHvMvvoGfrJUzfya; zhq)XoWe%RqtGAhI8{z5jxnsT>&ayt@t^$&&eF4{W1L;!|hn!9$oJ& zyze*7eJ0z!C5dPq{$#G+%3}i&Ii15h0y(QjqrcaDL;9bNGsLiU#KriqP7j>six`mc ziFLYUSo{%h;g#Z|fOP~&XOIDUE(Ys#XLcW0?-H;9c_uyp#}<|>S3f*UNVC?^H zbGcRKe`F&edTdfe{Z~+U`QLpk@f9&e)k9?dfe@Z}0sAlZGbMH^U`+;jx%QFE<4QBn z{WPtsJ}1udMQhr)={8Ks%W~A+!9%C*C9Nyd_Y!(I>#Dg}dOKBWW71a!ytBfpX#4Dn zd&{5mZ>$l%T=tk~M7x#jM-@2MU}gB1eoN)?Y-WSmt%zayKN?%5$ZShTsdb7@*_xzY zoJjg5{5)+4;1T%$z?6i45uQ0%t^2PqU_qJ&1Uv6w(W>t(og1aL%5LR`K@V?xK_uGnF_T2V*>+5c(CbK0>kWRCse+q z2W=;UVg(U3FMPI@0-tFHw?CIf&QG>sWd4S3+~Wgx-@%_)U_XGWv}MT?Nsb8v_i04( z4IYrmA3iP|Q9md8@Z)6|t_6eQ9mY+>fCqAzhR|pP_y;*x)^y@klmJo?k%Ymv_#U;b zOIaE}D+8t3gfL)`nJE`Hi}+4}qSJ2c7YpLsf6WhQazCH}2nBZ{>AGt&nO#D<1mUbK zxsS)PCDmBeF`q2!VNVD36v!42S%2JRiCHHnBTL|Yfvi8C+%y##-i(vY48ilOR|pPs z=#7bvj^9^WG!)NC;rjOQ(m$|LqxKyexiP_oTX%kF#;?~-P6PG7f+TaSaWOwur8PBuN=2* z&erx-mKKL%E^B#(la07GB+R`)bSh9&SX{F@$k77m`Y`e7_Pa{3+X81sxSYa(?#g zm*h4xBl(LuQ}(lYgENBMz@dMpTwtEGA2W&j4M{)aH)z2oPlkw1z@Z~Id-fVif@XW6 zC%~+M=jfPr`eZ@6DbpUZx&^LTOzxlLM!3nl8A?03i!jXm?o#Ch=UtJbrS$4+akGr) zn~cAA-8XekC{Y`rdKV&XL7V|lbeBUW!buW0la8X+PQOt#!9?oQw8*gPeeR|E;j5Bz zLK}URS@PPhJGbS?eaI;4`V%+e)!oo4#v@+IzK&wq$UYt=G(AYzVwq2KFTic%|0lnc z?5BV{(6NHx|?ox2D_SUD@xmMM(FxkA-3f7C6U~Ai^sJ>TR)PYg2+@cA) za470lxrQ1Zq_yaaT;y&*tq;nWBxz2yaw})&T6=CyE~C`@v@q-ZXwN%`wG5e=q;j{e zK)1pOt7}Mfgwzmu{D){CAD{F0B}!cHGwK!ERoXS@lb7}H30D*+PHJvB>Q%Y_D|6V` z5IZDjvO+gb9uq{Txfif+c}y{(;ic}(G5`5Qgto7@L7KXNsWr{N$vx?`!P~6r>95f2 zrQ~@5f&j@VW?|aRSO2s}_A+l=APp#Sl7g}-Jn#g2aIGjDG(Sa*jcg6#|J!w?N4Y^q>Gww#B_P)VSx#D6cCBGGo3)O|xS z`&}4;^D0oxKroEB?jxRj;2Vy_kT~jrY8eVDLa~Go1?vU0MmoY{itp0E7j&*R-!+3iu!hFg3i5Z`7oxkho|O#!YBP$*n` zAY??C2v7$X93SenjW7Eg$vvQMv3+T#dpe=A)hDb14@xJyN$U=?hwrQ++}kRX!@!rQAY67Q0}rOf3-xRVra z+45y1+-zR#{G+P!QIjCAQb*D#6s&f`Bud4Cja$80@8$(^&d7H+bI&;PzUbEXut>Gc z!xz($#KT-)6e*s35ifB8Z|te}&|MRc!=xUdrq_y(YVbXp_>vD$-iIuuN1Neq{*Mb_ z`1ClfjSH-y6%IM9vm3&PMl&7Es3_pM$y&NX@zh^Nk)NdY&`VyAtWxmi{x+C2FNPlj1A z`upt8OUEXR_ZuF%omwX$>n%Z_ZJkzB>oee-}_9AL&ux7b5`*VP(j>WuA7>na?shh~}nX(x$mPjZbwT@cmF-*{;?;9ouhJq*ot2XHIo{=)H|s zSmj0E{?64XvAtTOV}W&&$d&6KS0_4-bj73(g9>pT+WD^x7UrhzFR`-FcG=JA*&KHe zdaS(}TXVw8Wkr)yVmo(8#}&kmFT{D{AOZ6Bq+!3@o5F&(P)vAF5F&h2jW?*omGza$ zn*$b;y(oc+56z~0URr@p%x?70-7R5h@`x$nRl=M&mfwD4-Bsl<5+r5&QIOP&2E5kgK7L@ zpmNNuY#(-w(vuHFDJH%laI-#cAtzUERM5|;^%vq($(4U)2boOpG36D!o>OG;e_D1C zd8!H|G+@xCfs8vN8Wrf~0=E$vWWZr?69T*0m^f)EaitYS}zDl zmpCYdaE0)PU6*sSxu69$4i}{aGyWf-CPI=_8NlHN;mAe)x&>(%@8HU?^*P2M!9*8p z!Vv`+LXSsu9RNxR0Jje@f}HT&?uG>`D1JpX^0kl*xn?j^3E}B!=0ocmZ(V{`nF{gk z0Ly?-DDj8}1pLgA2o<~CVNI~j_}h#K9)O*Ak+Wgv3X~6fNPL-r@J@g8)~kvlen{sH zRT?3WzJUN+WV4UF0ED0wyR5xPbX!P3o&$Z)&8LVQ4*53V>kcPzW5wW{1__IW>l8T3 z{|N{jyZMmqjrcCj^>jrA(Ba+n4|&bJluc4WHlFv}oNb-|(ra4DW-gw}Pyq~+x@23g zH9@j$1#L+IfARN9#7!aE!Qa;^yx{%UEi2j&LK>c7NnOcJ+oN{y6a)T-Ji@?|1&21o zE(1O_l58Q}K2$tcw?yF*JlkKwGTK}+^7M$aIrncOSC zJgk{tU{W1>d9PWVl!S&<-xxy`im6JzP-k!|zgBS(c@-rz674U}a3Ye4z9L{h35J5fAO@GR-mMDU*r78}(# zRh5z%B7rHY$t&grf1Mes{;sU>uyVjz4^@p^pPjDER~q}-c-KJP@SRr`nXWz&sqn(x zRy7+X!fHR$Xyd$ayR&kyJk6Y*FDJ>(H`-;7GcBLcTl32l%s5sK@;G^xg?pw{zMCs> zCOhyP_PUla$G69N`K*e$U^2vp{-N`|CA#r2Dd%QYsU`QB-H@|4gZqH z+|w$RF*bN<{I1P!RvPw3mk*ZA2`8`G^j5WxkI<_tglF}Ri$LsCZ$uQGuy3U)jY9DekVR%Pp*i+%SNFz8U7oU_?{- z382mRJLJtf2KZI}=bh^$ z6bdp%=yQ-2B{1KBbNmC8rSdm8lOBhg9lZDCr=g?c?Jw44{PpTen$kbE4ZE>eMn`&a zFx9#9ui&MBX8ton0v-(#WH0Qp+Ke1T;A0}L7zu5aV4FzC%UCW{jC0*9+*nOZ>pdvG z;ki%C&$q&N{j89UJW!#u4?peD)=uO3`F^15;pfDsUUSQ|LUzsO<}C=->hySjF2Ahj z+oIUMVAP`9|I)!>RSI(k_%Z)}|J@{ooCw;1(4W7$DrLNy!~39h-fRFCxA@NV5tI9YprMeF|V(FcG8YCCJX%F98(@ zqJT%TqrfrK{s)ETe{cY}4wQh~GLjPol>Z3jW|Sc?+g&$Wh?KzwNBk74h!ktYRvw9l zsa~tZaG7*m6WRL7JPLw!eOMwP&_jnj>^fhW)o7X8^LrG`q)m9b0F!rf;-s;GU`K4vg?c=ksa6uL7}y2hUZ`d zF2_00{SqK=hgh^C`E<}q%;d%!vnbQGen?*5mbwbS<) z!8#zqJ{(wcB(R$k0I=e}w*bZ!86wbw+Z7?zg7QAh?F962Nc6}%lbbPdHw0%eunMc+H?%{P2&dRN<=_~B>&*ZK7Rkh1tu4u z+*_)6(|ojeg|hQ3d=%-+PG;=AX!<>m%fyLf(Xao$r&*=U^;2Tf#jwhD#ZU@bu3<|n zLkOtrDd^!mAK}aKs+80SZ7hkgDWt-<&K+zB5j?Rb`arogc$zA$Xw3vgI)Z}ard{u5 z(zxQoA2P>Z+Z_&dBmdqmWThd~o#Ry+HT7@(RHuqDFA|lybd{6?0-AxZ!TKrf2P51@ zmq-cePh`$9)?#WeDQx$WPK}f6Aips`@W=04l$kdSzZ@qX%7!~3qUSy^x8*V%Ub@fD zF8b0Mu3Fcv4=g1we~@GdsgO&Mqijz13jVWtd@;nZ_oiv1oyrc-lbaQ`@hSGxK!U21 zI)i=XRWIzW`*Q`k4nAjz8k|IuEbQW~hti+A%f`s{_C2dQ9?r9^224FpR*=5sc=yW5 z@L8YHW1?Kj%6|TwfI-3zCsLWp`{|xqkm5fsbj&Xenlld%7h>nLNDh2B@4HMbRN1kp9U`+!=B&C?j`t(6R~~IbhKR8`5VL55zaqR8>~-Omf=$+qR6ow&ETL!FcWC>&BoA(saXk^Niq>@`14hX|P1E79{+T;kDQbtTh)FCZo0NKao6SCe@h?SiJ!F^&dkD(t73~P`DlGN~b*5e?yNb0UUt;Ny!5Nk*SCT zuNEjjS*}C_mho-+qs+%a!w6i zF7IHs6nR_jzZm-_*qqz-2rkBxWW&VKjBpO=-b~mN;^P=zQ(9nP10gV|3XV$JUxtv2 zUzWeonxXlEOpec0Elne^usK@FHRopMy4r8e-g2qYtvBjl4(`+DtIg}T;Hu~Fi8Fja ztFVr&56Aa6JsYPaxUj3ouk_2z?tB-ts6eEKUlYPWhvyg!Nd+y^Ntk>u|Jy)gM-tfo z9xd_%|E~4p=b`ddE?fHQHdb(e7btH15g47utk1p}ny44bs@%+28}7ZkF=onl%lb#$ zex7pY8LRD(*eGFAp>?R;faUPzFFs|VHY*A(E?!}{m)u1$En;6c&G2sSiLj2%6|VPh zg48!+GcR#$<*Cp5`g#yhNW)mf9*5&?3sB>{q`4TvL{1oR$KgX8%y@-3?{iP=3$Hn8 z%uajuMm)4gQiD`yB>HeJiPs6LHMGv)lI#3L(tyU21Z98f+MtgJ;);tmuHvi&J-RPt zvVF7ioq{j(roNQ+O7d@^`<$GN5pvNhYTFZ8gV@W5^t*1iJWf{EaTY(|>JVZA!^p0W zOT-D8?0gT}GJ~#*R1|e5<|%}a%zfi01;6|3>~;aOp=vcI<>Qaf_wHTP(DUCPo%`bM z&mKO?V*Pc?W$P(z{jh!JY6+PeLA-OLngZ*^J59sfnrDT%JXTZr3Kn&o?z4~AmG$2C zC){gt?p_|xYUy?vBdlDuzvnT5di6Xz)ggK=pZp4e!jNRg@oLI);?P}ZdQ}WIbw$Zp z;VhZVcTvdEal_K5hGAzCZfLQ9-b(aE%oq1h1y^4UW?Ok12K=ybr%S&j4QVq%NV@W9 zgGUw49pWnx0L9qvo8)v4DGsxh7@NlyJ{?BPfC&=mR0^q*MZnI7dD_alU{Eq%{?7Aj zX7IIrHQ_(mo{(~N=d{@rwK3D^vHk;X+m#W2U6ypwea}_&dXF%vRgt3cNSAh)TUnCh znA1IitJcZwyO{((Cf)HMg~GN3Qk?OZ1ntw3ekC{Nl{MpUGC`vj++5 z)y{zS(^Ur~V>|E$L1rLirkmXqKqN%OSML~tF2{AXq+OojH;5I3{`R;K1+*v+>cI-9 zJ(qStQ4AVTBvJrIc*FUQ7{n|9_>9Q-KLAHH1y@o4cR#x}2t5@^mQSS|^oGSD^b5$K zR#7pWPpz}R0P?gzQ0H{z@@M&~epbR1)sI*Hau&}mkW?CD*PBWkxW05uB@68+(%!7R z!8*|ZwBOENHR11b5ah#^lC6^axR8W_JZKY|=aLKa$-tSFovzuL5F7J?5GHs!=NTJpt8bJ$KtKgHZsFQBU}x60`@RnBRNGNdu|0J z06A@5-y*2fTO|Qa=Z|UNyV9pYa!`evywoL%3&%^hi+)dxKT@Yqp}jVH@H*LqVx;ztRo{#DzAy{r z))=3!xT!O>G#!a6ettMasm*Vca7toWJ=VVBza@s7)EV^jmCUJj4Ij zL`M3Fw9Ijl|c;k2`b)+d%k+zEq@q8c$Z$tG^>8%w zPKcY7^v>y@XK+74+Z$Gan9zZOoSDYDYc98T-_Pjds!V1T%wPb+^D8fRJdPhsIF?J| zBN?&RySLQ2GDAlAv_VBnREnjWkct(?Sp+i(Jd^KwMD&5uL^PLRJ6zN4G z%$F58=bJHRdq+3LmB(_7VIdP4XIQXMn6)|*B}d|d6&t+v=;Rb8muD*V@gI3B9LE~i4NlvTmhINVq(zvZC1ietE8MnC5Ynyy z9t7eT^Hvc9@k?&5;q=k=-ji;#jfQovi!ed-w7cI??1lj-{O-S5Oq%y%aL<~4d&nS$ zeXu}4UXIqDS>N+F0oWeS)`lzWf{S1O@8a7&{fAX(1%Bbq1@`cKPkb$6^m}7emcXY1 z+U=wx^3O|ldf*;mUp+{vJQFdetfuzoUuINmjZ+L2gc>3*h3GKAR1e1zQum(Udk?Zt z*o7i8Z9ouVqtX^zx=+q^|8v>p^crW*=Mc;aC#f@JkvV*(>1?H`D?Sv+S+Iu(L(~?a z6G6f+Rs1zG_@1s{Cjm-Nn^)=z3goa>BA06j0?7Jil(n`khUgZi<<$!Ft%s)*F1Nmh z462$&<8)w#_067eer#y~6)uddQa{BjbPmLpCvEzxD-(zK4A;qSiv_p{pu@9{h1I}C z@cdCOxR@i=2RbAv&&5qwh@A+v1r>Pp(wE@Uh50hkJAlVR)bV$)u0y;vkv0YiQ|1D( zIQm#lP7anr%P8+P7bWeRWZ<;{K}Z6d->+UAZ-F2+f?=OaAgprE~G&xEG|jVr7t z<5#ZVo|n=udbpxY44wj;bM14;Dja-8`7CY^S}`=k_D0uZt)d#TH-O86h}sdD5}AVA zC8p2Yd0}ZybnxUIgD*FiOx|^@JvWVvjZ`*Go`n)vxClu+Bd~}mVM~>fc&D~FuXi%v9 z_vymLSFgB2wJ6h>?{>{H1Bx1E3GfK3sWex>xwV<^-?ILn5bFCP=~yNTz4F7K-~tK- zPZXhR)}}jfEConh=xkO|4{ zy@zV2(xF-&1xiieo=h&Gn^FMs{H*L-(1g@X+td}-NifY^SCsm`<>7p9Ll5EwFL#?2 z;pnt0o%Y4vKG8|a;~&klj6VtqV`+by^u4}~BQ?9n{>tKnb+|)s&YbjM?}{t)l$*Qki~ktB)ia@sl3v}!x!qYJSt_N{QF;WD(hr)PW!#y)0Ak%a`OsN zD<2!1zmm)`;v6;DZ3!B*-a3xhy$$SPk&*CksfqVxJz}&)ja&cL9Hj*@JOcImrDTB zBS;qO>^^Dz<2u@QN1~7w5p{<0(j_ zVVim>yq%s!NPy_iE(oy~G9cOB+{2kvO=^6P%`IU01&uE>cZK16EWk}OxT^;+*TLC- zQ+N!UCPM9oAcA%Cv0^Bz^!WjY#~cKO9LU zL4ZPdujUUd$?qW~@!R6I5xj^ia9O~r5(RWC_+&33cp?b@hy#EvB=Hg1OeDIDn}@Wh1b}kG{pPQ3zJ3D@XXC+5#G)8hjlbb_B>)QOfn0;u2R)klZnqKHCMYH@fZ9E< zeXa!w2SuFgk$uNS_jAOB81`2`f~nGBVnwV8fUUj(xmOIad!hX-EcZ^Di_>OY-u4k< zP}wMDltTF0nE!?Araw<~(=FANu$RRMY$(9q;Gw!jJf339ZS^d*e#C-$-%zfowCB8T zU#!aO@1$3)aK_-(EB}xrU3hehipcKjbxy%dHHni??|V+IYu8073`{KK z=c#(6ylGm0(d#}^mfZP9)Uv@T*<56)`ZKxdp}=(qudXl7!e^nJS-*V!n3!=?x4*wT zdDZ;A#Ewvo(4Dxj-_B8|qP^!-KK;4$M;xwoz9iC&?sZ*a)1<&nI{8A zvO(W?1>a|>YCG_bG78Cd37C%DZxJ&;&U{a>*Ex~w;=N)S$v+R}#uJ=ZJ)Whn$j$f#Kg^2Qs;sHeHhH7E{xNR# zYLYb3a8_toZkfMV`CCcD^TXG-@!Gu0%6etC%kZf_cbk$K{yx~hkk@14*5jC*-pNsC zC0$(J*r;!9CZcI#WhIY@c6W!e#ngeV+fmB>@y(x~5iGZxJD@L5y}((o1Sm#mY;3H> z_HzAp&mhq8ziv9D>FVr_pwSi8)mnoTHO;N4d)5?qxw`K=(nB-04lzUGx&j$t3nFYd z7FGc|Eo4g96AcaJz1qEF{RQGOGjD@rW7uDQaNa#XTtHm*XvC*sYVR`H$hvv^Asvp= z^y7`NW}Oecf`qxj2O+z%m5Rb0dsl||Q$zxzGs^|>VM$H={l&$ry1z%qs5Z{crN?|a zk}~p8X+(@PgA(4VL*xtV3_PSSnqa-BY!yEWfbO0uiA$ z7;SHHhw0UQ!z8SWW6(`&5wFdP3cg97^HZ=m7yyi~h*>&p2@*{Tdt~^-lUz$+Apt9y zVajgon?b6c%3l}v5?rF2OOIFMsKrJ~FC2LX#HJi3r1a}dA8F7FIy@n|$S{P29_WEe zba=hUV{)auwDgP5ZqZpxR(3WR$Ym^wEDE}}3r{IeI{vyHw`9WUkuY^UwZELS?wJjL zWf#I;wFfjVmDkqhAsXniDTql{=Zvq}Y@=nHKRZG<={Id$Xi9}WOwFf+1ZWLE>4SP~ z1yW$LGT0Y?!%*4ScwE<{15q-$rlzJ&8#9up9YrS{#>;b1^Bq9Kk6p9%sq_B3=&kVe z>(|6Dprgsuy~C z!$e{mIFsJTYqhZZwg_7;Ivp>h}9zZahi62I2|s*7lyp zq)UTF(m!VS{hpY*aHSfie$rN45Du?0oayxqZYf^58UIQ0a*O`<82Y-1gGgyNaFOpV z%^chw?eq=uqd$J6U-F!aurb4rJTzRwt`1*zYvN@XBYnz17(Su%D(#Bm;(JN%q?=7c zcO*@P?)EVKxz5Ej|0odilIh7t3~xWTyo3n7`8Hp>@0{`BE+2>ffm^S$(A&lo2^)@2 zJ32e5Jf98m{0z);ltu)nh)tE+daezb7DsIROY-7OL_}QHgUt>NBV!Sc%8>9v)wI8e zprCfr*kYNb*Zrqohx5X8;o#=sUa5SREr|WQ-!Q$NFu7ZCueG(c7L2@|ht)OJg<`fp zpr)d<+uGW8O5+;jIoT1vj=lsoOawB z^2ox=E?^eERN(af}yUikRI`K&+e`+HDhUv3rEMn zK{Yv}m~O+*QQusgWycy6wiHgG&-waU1HYKcew~PS(aDtNviNECd4`$jiniBE>Zv$p zU}ZN$r>c=r%(J@oY)<@a&Y}tf>x2Q}U4>@@$LGgB=oRlj(zpIQ9~v4Od2!=zK>?Bq zoPS(o4XY54$xE64>$XB~s7SbkS#x2dUX0+Y zxf?Mtet5B$?a7^Dx^!xnNBg8=Vw=)D*6WHo9+=bsZ^UUX^kK4dYu$WF%AZWOjQwX%4869fO(TPmR43)(v18MA37iHnDfzuF4NVr)LGfsEW^Ms&=Nqz zs5#ONB~u|;MEm(kk+j{Rk8ur9o4&5v#R5b2v2-{?0kt2#;cLV~OI3 zFmj%cjwdI=Nm@kjx=5JU>0QTa?2_=c*?ksblGq3noMP`D|Is1bq<&Ak$}Jk5tMOGG z;}WZ&y<(m8`55_~3pI`Ox`}NG8{9)%RNTuR zC4ayZlw`k}|5AMMxIydXM!R3b$_`(6sJQ6E!vw#lxckwJ+d=3f9KXdcJCJNdwXHwh8{)n!TN$zU z?&L1E*E8&$@%r@9Scz16TGL5qQ}nIVV4qD+uoR^-cW@{r%u@~fr!n(lM7=E6rx|08 z2c-(j>)wuub27=?T#9bL8sqP9oE`C`q=`O1T|2YulK;Ghi=)M0<_Ole&*kM`gB)nw zzp=LVMQ3g1^NiDbW5k4`p;GCwnJe$eG1{G}bDaBpYj|$Txc*&^`n~c+QpU77x9>_E zsoD(c+c%aJ&{=N%>(E-lh80H})5dN^T|kRWeQ-#2cr-m|?SaF6%CyaGa3)P_i80of zhqrTZPyyD*plb3~^z!vvRV_a{SX62!3lVVva#;fGBjmP~v9JJ*(vJCa1%+kxBKKix zgFm~kqT#7t1}(w}Y{#@sjASvvSER$}`s=24IYf7J6-Be1teSXjEaj7r6APFx>lDO_ zZT?bxpU|kHxSd^9{4eya_tISfH~YpI8y5%NZ%#!;1<612j77%{xJ|o$(~(1cWVWsW z2xCp}SPyMsZlC+f@^R~9;U(8Siry)shg)^x>_u*&+k@vmf45UGHko#9o0Lr%mW7Q{ z(1dyIUdR4Uj3|FRT~dy*)^nSWIVxd1=GKF#>hKGFX4<;CLr7e!7szVRkev9nx?3pr zh}rn!z|ZS(DJovsN#}}8aV{*o)a!B$<bec1srvBp4YQrgm7_@_!bxoAH&BlFD<8 z^y>N`-W~8qbUq+ez}S)MsGw)(bnv2&RzQHx=5+H+Dq+*I8OR%R__$L2ijJo05*nvx zOziB6V}F0n9J5+xRdnm1UYXGmFXN>N>yML)LdU$389~MolB~Vkx4kkZdAXSXH6&?K5722$ zG3KyNxzTMu+aY2SUj9I7p^Ws)UBy-LmTr|11Aj6Ryf{aHFB$1LNnt9DQL!Z2bMCpJ zutxJPIGB7bS33X2lk4&7d1g9k?`>iljWNoK^)d5`=D}sAV?0-oj^Fy@?J9Ph_^`tz zOc?v~SY_nu2CH6nKG$)Ig1~VdOmD)D9C*opG%KIG?XM>i{UI*%O}eqF$T$YhE6K~5 zx><2%6vu8Umj$`FlyJJv^v1W+5<{1dPQ{(+t0r$Z{At*IP{#i=rJU$Yf&Qc8(02Sg zKXpQya%tV2lCwRx5Txvey_peEF^v+_H=aqT^=G0?>3-UMCG~G(cA=Te&ErqJcTfrL zL;J<2q}R2Zf~}Q_Pxi{n=SFb;(iUYG+**>SxAllLWM8!5kg&gxH8{wj?PNW)nbe7- z9%l_BcFx3fWK}2cybZiEP4Sui6CoB&j zd-Ip^C8LV|B&6`^l~d5^ocEO2rA@lfCltt?cken%Mmzpn+s3Q(_Y}MNrO?6SuNiJ- zeM|YbDY1^Cr;4 zuk{5phzCq8);ehj(U|W$4R05YyBoBO1YYC&{9MlkYjPx>;@7ae$D78(=oK-i;4^ZL z39|Q37c1UfmDAt4a=K@GURgL?@!urEE^r>=Efu-bGJR&9B;+hB?lL&S@rrR}MqY#A z@}KXQddp5SCb_NOoUYeBu@meSm?Hd{*>rsFUVBp7X<7GF?n2~{nYw6bl3`h=-uW>H z)<^D0-Q3tqSm$7qGGMjFReeiOV1F=-XDan?mYCzTN>E?2ibAQ9zHa_SYP7b&_79tZ zy%TVX9EJ%Ud`l=sGP=sJ|~qfX*bp)Lu1=mEHN&o z85a0X`zP^D9@H)IRjtwAd)aD4ww|#MLUVlPT%J|6G`F8-q?@{Xb$dSW=?agCh#=v; zZ5XE@iF?^5YC5Un@kjrYmtKN_#Iec>CsJC3mJ3nz0z!}f;?Xl~eMpt|zZn~Y-++~Q z#VF?+;A18M0hksEJ)|dhg`Gsk$lF<3ZV~=V9di7s#bBzlWI?yw(?rxp`0!E9%ok#l zx4qH0^N~|buX_ab9XjOZFg8`e&DYM?_Y?L@k_NmM$ky%8f0~6|mQ)csvz zzwSZ&eXcB8o2U?;=e#wgS$|Z@zV7CB^w?@0W}RqYQw(jZm+~N*Q>D|bS5RwKJxrPS zZDyhh+L7q3gmGa->#f4-B; }_ENvCG#y(@XSwO{hOaMT!y))V|WpT#yyu z?BMy!XOFKcFKPji z(}d9z@58A-54{LFo*hyCWnN_VBI4k%lfT2lvb&Qlt_PvK&?}EmObo&0;0!z{q!oOj zrInLhrudXGXxH)ngaPMlG_K25bFj?L^XdaRrq5f?ikWufPBRkIcZOvGP9@ALJ`wi# zoN34A9N#4pAq+A8_3n3hTD0Z9aJZ|3!EN>Sl#NrWtgrZ$s&N^%i_=)eKHK>(oPLyz zS|Kh|hQ(NLmoM@pH>g@S7Tg@$N3Ll&YvnNZ!&vaz$*FvNcJ1Ax#_}G|*hYTCA~_gI z4xjF@(uM}MwYT>kJSbuL>QtwPz#l667c0H2#%JU7&s9!`6i=fIo6e5f)eOeN+Ev^q zlWDq>^^YHuHE2ZcFn9s4Dfd-->bj-RQc&a3_i${ij!o`DHdXAcVSU}WMOxu9SLm78 z*w|iZYv)!TLc?w4R}g8_Fi+XACVnRUY@l8I%$|&tbZLCORzu~n&uK|G_G-$(+o>%L z>{cgd(e00yl(MGG=&!s+~#pI+H3-xmf)0oY6t*c}gBOS6tLYp48*kb?-ZVxP%L5DSk4< z2RBZ;BD;M113SyPRKFAQY6^|rY57QMNI#T7>3@Uz_0{~nZLD2ib(DA2Q;9&S5ku-w zUO!%1xuydCm8#9mvPViiURkQqJD)W(U4BssU8C-*ne3Xdb~r90J0Vaa8q}TPqEv~Sn&wcj{M{3u}*w`ve%j3x4NUBcSs*Gt*RDPoen(gEW=ja zm(9a6quXy0@7?y|+)h~6`}KowJ9O`JFw3(tbM7R0-Ph3i0kU`tyVReq?y*-izUD&k zMMw@(fGyqKYu&l?s5l!n+Hn~~T$PGkf3Sg8SQ%-fhjLW`Ekti^mC}R;!p5M!h?pII z+kjIFU$L&X+o%wjb2Wyvya1g!x3SE)+^W(wO!R}WAoVFhudGK&e|kTyZ^sr5_;0&T zpY2tBg}$+O$1E~K{Cry+z3(->{|pY`?nsC2x|5K4zNx;cX~|;bsa56VnoDN5ZN->P z)o!fM{`yYvdH7Bz%q)>=zcyiURJbU*?&kF-%xtss#B<>RhHdQCxP2S#PSHTnGp{)_ z!IXrzc6UT$E@(Zw=)!4~W9hc51jrb4uhO3g}O0_eDP{v$6XzZ#i##ieeR)oeM=VCxsm#oRg(^kdw zXkISITYj3fv_hj(B+`Zf@ZSzg#?1&OzBWXPofDzyJ-=>Dgd^kFBU;_Mp?y)ZDG<^-{Pfx}#)0oYs9wfjs$xPc1-k&VTwZOjctu_ zvbb7fMFZ;$bI8jI!M^CLdkFCIzRom)!iaLRoiEE`Vl(58rw&N$&^ zk^NlEm3(_IQo^kRih*Upm9-?ogc`5UzVEOPe?FO%P93ge_G~JuAe#_zc_4@9X3J&#sdP=y%$uB?{4Yx3>ieyD z?%?qgE^ERUdYp?5ZufKdwzPWOIw%ajNlmu@py<8)H~LHHhVG4xuER&#Hw{D>5;=A8 zQzw+Oqfy#D&;Pn^*e0@Nj7?+B#%#3@TGXUxzj{F_Leq&w<41oEcsL$m;)U@q=aY7!wee)M60jo zb(4j#i$TEb!$Y^wurM)G!}Sl>nm&fkEo@pQ|-4Gd3apc%K4TY;w59`_*2ER_ZFiW zby1nW9Sn}QwR55en$Kna+>+yB=_ZbX>Hc!R=!2wN8R!?=%!0wl=!oMlS?9AN_%9LJ zZ>XL1)7nEVWTNDk{OvQIH?Y;OhS+}B=GO@cWz9~iETJUn3I74z58&IBfVS7rRCAHn zF0>lp617!TqOR&NwCLGL`2=;R{JCFkgZ^3dsrNBuz3woPC6$Zb>*XR*W(Nu%xF@zX z7yU6d_2|YtX`RvTR%a`M1uccVNDjy9Tj2#v&CJ{Y)c8~>CmS^Ua4k~SqdHYP$Y|y5 zlCOP5@2F|mojK`^YU}wA2^Le|9#ib)HiCaNEFa=*#YBI|D?HFGh--`{CED}QFo)vP z8b}z6DBnth(PW~iLhxb$x8pXfRwVryF@u;Bd76f`j~(?Z8*oVws*)E-im=vMLDvhy zWHK+VrJw7La}|~C4D7yGbA8mdyAJ&uxu3@t0b!&Fpd-oDtYq2iRDFcO(17!Ip`8Tv z6qVL(ukxRxBDmGx+)*Gl1tmXu#N#*b-&4BwF%U8u;1j>M;5F3OAevWDe8isWJoGKr z-)z}=Os1#MBj@0x!BvJ#-)nZSzS=+YQt!UW!_=A@5p_9zwzjD?p)o4Y8e z!E&|XX|pzfgYJp;&&=4TNo#pE`7T>q zP|6RZ9&^G13I74Kmvr85KrWkhOiWCyY-7aN9&Momi54JN8Ja#^n||uxTBuZ788UUR zk;J1Z^la~ezwma-Lw2<$YcOgq%XlTk*nQ{;4lnsyUHu-goyVdC*V0!yU!Ly>+*S?B z3xC0Oklk!*g~=Qm#w`vgaj%-#!8{`UiJP0=(jD$fIrIt#;!3{Q!mpW`nm!E;4L!cu z6X4>&YK`<5)tq_^j?yGi`eBgFS=jPY^O#TSvhFt_n+*0g53!|_0}OJnzx~-7wdG7+ zwa>P6PA3LKp^9}H8C~%bHQ~l^C`n1MJY&0P08^08Xaa3whr()JbmWeoR#sB_lyQ-c z2LhsN$g(-|6M^9R?UA&!jLb5K%%Fk_b{shBez{|OwH>7_`KhTpz6g5= zZnggY+tRn)lydGR5}v5-{Zrc+*jMQDL@KH#iY+}6{_`>A$gi&VdXF;m186h5f)N8W zFTa=ge(vU3{?)8u4Wl^UdQcaEV$uw7yuMvv5ajz(SqV&Nza;a+M;v$f$9FbZw@)(I zBeVM!<5$ZdWDOY^_DqvXTB=UobpMsI?vUasQM<5wQDz~GBs6RAYVQkuxmfWPLf|`M zuD_W6pS1uo5J}yORp6A#n{+<7s-e-$Ea+fm5It@hb{8iL(K8I|RAW7xjl^LJoxX-G zZ(65z9a9^&`tU}h*8QsuMzWh{jcehL;)9Mdyb)DG_cYX;|AG8?=05i2G3*^C_w<2e zjcU8~E0nw$&d4n884TrzCqRjNiS5ozp|xvWBGBsXpSU4aqqiO>1s6f&)}t>cYRMI+ zr?D^ZA33Yv&~zWY@NWJYHGY-HBM!M+=S+1Ubbub4Y;~Re5L464YI!$7Z139i&zB1L zmvBd;;%y1vBjd{tWT#0^U`2Y6tp$iRpVUzvJmU96L$xDf zi-*S_u~>mAIey~(`duEW3;&l3P}KT9{Jj~r5qE3r?8?^uziX!g&-N>o2o-Ao4$fw~ zb(r5O?Yj8nw8LqXNPF0~cf^T>C)F#(B0Y76;oA<9c1I6Upr!O2mBtr1ipr3+n}!UV z9pj4D*lo^6-*TW$$f-MH&aRW|us{8q_Aw+)gcBAzVERc{f46J+;J#Y@y8<`pGXSdk z8pAegnAb9@|L_fnHrNs++d0lY5YRgN*p*iPG5R>yva8v%M`U8GXT4QVkt6i#xMB4A z%w!}7qX83So$J1XB+t}YjA$HQEr)B}A?iKvwCjeH-MYDi3|d$W@~T3UNdPyid~ ztjN<()=UleWT1+k2{h$qx5lO)$Na-Xr;r(wp`9iC(U5)ytwYGMbr?ks(fl^P_SAX;E;Ex8mQo_o3fFSO^kGPQ0fC6r)m zkdbZH&}R8)yM8~_@5G9{U1rkSmIEzSv)(`?jx;ov-l|r!Hrh&?!#8|CX8_=iM&NPz z>1O<&KX(A~2^Kwf0YXG4InW^);IFne*>pc8B_%sIcW`OR_G)5_CCgA*&$-_d{Hgw=4WAnvDjRP2L1DY z1Mg5n#_G2tMwJ$#0oC*4%A0nSy^ zg4Ndt4@;SCx@Yw924k!z5NTMf!ML8&0+r0^A0JOh~}Zw9AHxJ?q?Y4Do{ z^zCmpSchbXVRxm^%IQ{0HNvNZUd{rYv|KfSy%z|%OPQx|Wf z9ZibS(sXz@)uVcp+j@BK zUYlB$`fnFIY~5;9>;Hx)udZv)OHRubM|-_QTB+Qnq%$cx3px*R=cz)~1DaQ@NBB*D z&VI3l)MfH_Nm(2hhbSntrPeWrR=(4j9U3GV<|o=2$k3AiLo@&?(gA>O z$pEt~|0WwD%@7MvcG8%C^@@|kVS5@{hsak+k$HrIXfs<1e|;Bea$+M@7V2ajX=Kl9s*kZ}N}Abf$jP#dSd~n?5>h69pPxxPd6L9(1X8s@}-Ek@GWdi~Yez z1WR_RLafnTdZbaj_J(vHkF7GcdFh%>pZvd4vOh6%N7B{s0O^k_;dwyvV%_)c{fO6; znHMMXqeoGvW{8?~O&UiDVcrL}L0vv|twnZECLO2bpH2JyfiC{YSwJFW65bLK#gpe2 zACE18*XUhb+@K$#u=?9`w~(w;o&w8ScRD^+PRPJsNxKcLKn6lu@6(3oC6kX}-bTyU9S{*OT)3d-x74p%+)jmqTVZZ)?yCB< zi=v{Y=9jXvGDJ5_cG+m0jX8e>Ou*DncGZV=pj`cfM2Ku$an{Lwv;bpZN1c)6C+ROq3${h3wc*mkmAm(c|n*JR80C~ z+BmR&Cf@!0{?>ozRI4DvnWI1Bjz#4vDQR879K65d(DnyZ>ol5k&BLDf;(@2p#v#34 z&J?*I`7l7TqJy?tz&>GE!8=$n(jtQJhzZKNBo|b4$LV>GPRgxZQC3}<9(HDip>cQ5 zmd&;>-^o_zm>&+hG5MI>yvxunR(HoC6=p-Goh-)QwZEKkd_jq_0Yl06-7|Ds#^*!3 z{?&17z)*c=-LKI_igoF%(VV$W=}pPedJUZoh7`lZUcW~%a#oUgx8uciHQ{nea7bg< z{ap{he}Ilf(YjQHf>vts!tGjr4CcKm)H1m}ZJiGG+v>hg^1%c%t$ z6eJBB6lcWDvzvZ|m`zc8xBsEyNx{tqgGTs;1 za|->+gIln>(PN{*B@J83Ssyn0-8bVHKS!SCteB*6WO2n2%An+pfjWIWHa`2KoR)R+0=i}H`t{kxs0^kmHT!dg+nsG$9g(6^%t?@!Cf6lnf9Ps+@G_eVTr&9E(B#@{ zd?nggEniU%qTTGI5FM_D+{eHeSf>oeKi5EGVf`>WgQkr_1h5*t$graG9HWJP!N`S% zMe-S_+X{BLOEEFIE)k?Qf6I-^jMoZ|=_-jVjTDhg80c%LA-mz<_DBtXQ8RRAWH753 zfE8~01_cG7(}PLx+S8a7)h|LSMwOV)w7TZ%3XMNzaI_sLQ}n(j(SLB!UPmvXKnY*D zF{ku|q||<%7j9k}C)YXmpwU#@sKG#Q1fiAJ!hYtV!fPqjq2etp^`HR&6#!iy>$%sf z9G``S^sbW26BMx1#KxXci2q`+YjvB4Jne0Jcz6ByxA2R3!U==Q;pqp&4e^|RhiQBN zo;7%j{;f|<(azGt;Bx1x+oa#Wc=-@!Nmq8!=07e2KzZh-Od7gWPfxd+^W^5D2xuteYL{qJ{Daq z_!0l97Lk_tyhMokaOCWrc_FeO2uD!+0;hLes39|H5(hZIyCI?lCY{Z6_+5Gt3u zRP<-=gjk*l>1|l=lk3^C=N_YAGfvLWY1gl>dn6W3hn@Fc-{D^>uIXMYTa~T3)^&g9 z=gT(PNXX8c_Qc40@oY4VeY>tXQ8O<_P(+=-WH_=YIC;P8%SwPB-)5s6i`-rpj3euu z$?Yyoh?)l^2a)6i{JqdSj%pU`%!KN>R8a`Nn6@nalvOaun!kV~%X^+L&S(8W_?|j5 zn!T>!Td!~C*OWG9a`MKm(iC^+FW-{3_}%#yKR;5wt(V(lz#!BG(N$$%ZOZ`1AaZnO zrT`SF-&}Qnxh^^6NHXs`+MCW?j2;J+`b!EvCMd$oeTqX2Z-G*2p6a_@;GzZ_sy^gJU!3Dk~=iRK>XX$hEnkzs-k!G@h zkYUxhQ@I&J?AAI(>n_MvNUQY?<-qW#Jhf)pH{NnV1s=WLi%JRW})b^>np4`8PSC_qy z(nC7f7zZDFI)JZ4_xQMK`=0taybqshVzUyCn78KfLS!Mrp+~hsNJdeYe1I0n!{azY?&GzR=y`Rn<_)T3x za@KM)6vDDbud^HOaSLF0r&C5Txv*3YCXye7Bem2aTh|Jsoe|z{V-VqFvq%9#S zo%u4~B_sfLwsB8SkNRTsiUyBOuqJb%Ujd9kv;}fXWhyzK6GG|wvMR&={8A08R<jcj!wZ!tsiF|o0s;0Fmf$73`(Z*#~&Z> z6m32IqSS*-nwKSCVl)`;Ygm4E=}M|ZRE6vDKE(3<_{fzKsYX+;3)83w6mVrM0H}+< znh;PdSp&Nnq$yI%rsls|#!->+57z8`zx}o64j0+NNlVb4$o5+_8R3X{gTm?q;uYuA z(pFfQb?Ddi5?eWG$bA*)y2wI~gMrZOO38581?*DBrZV-CY6K`H9`zU?Psj(}29`7O zybnPXlRx-XD*)E{PZn3dc<1suvp*E;XKG^@yc+~l&mcuBI8Nh+o87uzHbx=F(CUBI z9itc%n5#npO~^v;!gudhZ+BvSc^re)QR!7`vAqqkr5%{}mUTUPG55AxP*E$|H)_BCNonSXo!+zpX`|M%%Vq!#q2 zLpN3IZ@x)e4mCNT+;MtIqNwucbZ5k}FzFB8m=x?x+6l3;KLjaO@ha z(PLqObc}jBSzKtNcf{eOgol8t$iEHgZuW4Tx8YbdQx^YMaL&$x!Kf8R)A=O8P~UFM zc=n3GgUShbNzC|aK-1qIZI}5G_}K@?1&fXIam&tXrBLa$f@EIK0PX@Ot3}p4SEz6i zl2ao3zvEJhsqF4Bl_&kzs}k_0S;w2v)03r;+)GBR43uZkX$W(JCJqx?-*oVmU;P!k zXy$)&YW)2?E($`uwZ4gSU*hK99gUcga&-f`kJq37LrJ%Af}ZjtAtvtjhMziZm}Rf? z1J5G&K+8~6OjjNg3wf!^%VJp-!QZy0EW?s$3W6>3xo1)t?7FQa9~jw-<9Rk#?mzIV zAOHK~M-*L4vgVX-5|0OasA6rBwLUKGC8Hr!N>V~{Be+ike`bpPUzsdo{~?#IxD10B zl1213)J9?CpWxg#NH5FV??SknVXNUdOcH88FSKU8#2tUonjx#!wRNFyPG%w7#QfGPgZfmF3y~ z`iDpuftNDiuD8}GX27d@zxI(d02x*@V=Gx(ncRse>X3#01mo2kg-+(t+XC}-$%n;%t}vQ515?@lWM(bTjL&}mbW~47Se4L z8#JG!4ZG7(>l2UoBNl8JBIOXC9$P9dr_N|kZFjF6Ub%;^y|btp-oR&K)1$h00S5j? zPw{Xovs^&lWn*LeHu6_txw^aPKVk|t$o9|rz~O*xKR&Sz@G!Y(MpnOlI=8xhUs@?? zzC|^vhR(_DWO#^QoP99d*tVPNYPx;p|H0M$EJovzDHhtq_Tkkf@TXk@lG@J<_XO@b zzZ=^uL0l*sOP+mFI(|!|Cg1m2E60UA@qwp5+sbd(-De8wV}mLNoOUlaia-0#UG2r8 zW^lF@HY;s$1yaN6Tx8yJICkfJf$7YTFbS95G~XzBzcWjnTMLgM%6zwzZnb{wi%)YB zuW=f+gDydTH!q}OWLzC?F-4y`OlLfSf_?uG>aCI0(1pm*tYeK&oR-<2CdGuwNAP!k zoemxHxO!F{+uk!xfWR(1C%wY_hwj~1wDA*FM)cf0v1AQa2tYD%RZGj3@I18#?5grW#KnJxx~9wj9d@`;Lba)T z<#~?z-&T{`8QR5$jPQ8{mtDJkFg2r^sJo_@>IG%B%?cFInTXGJ45s`}BGx0*kei6e zSP!4-D34Qng?+QYF(*xr%yFk96}*a;Abd<{Oe~(6fNAV zwbqiOR8r;~3~&MHCX>T-acfzb`xga?-C6K%On}S!7op#ih6=1q|^YOXUw`f`Sc+9CjWd=bU^vk)(oZIlg zgL?n|eK)@xRPRX1lv&k)@8fZN9S{rqfh&tn*&`w^$%1SDDnojg$Y9epzcd}>CZj_rGK1!agM>@Z#9#umwsWG4Y2{d>N*ir2FXIzA-Fm2V*0Au z92D8|3^?JQ4Z0=Nga4Wuz7cqoMZH1$=fLWVKhL`=S*aRmq@-kbV+a5klT2k;8s%WH z7;R%w5em29 zc||emES+dUhl>qWT4TaTmc&4VCZzQ55n+5Ptb64Dztp*%RC*U{oSs|*U+_e0z&MQF zDl?i^bikjx#{4L*T@Ysu)LIE2@s=}sjuCsu4ZD-^g!g-y&^}Lb3IgA3jI?IyX|KaVJocS+h%xf&9HeN*HHOOJ?Bl=wJC+%uH zB}X-g>1tPb>#Z|rKN=+mBn671fgf*gL#q8N@>6Go)w+ghc@2cAMl1hjuaBWX1|uB$ zUG-wg&n)+Kk+rw&HZ;BUj6je6_*5oOz=2%~P9qwt8Uz>R`A!>i1!|m}*kP)TaQpTM zY{&lKwU2@|fm12~Y7>EVhaa#$U!jY!=;YITheB&yYu>CyMF|c9i(6;;`1--l@mPT2 zr!K8X+nsMBazADw5QrM3Gwa%cRVN3ln!npHrvX9rH+I{E_q4ReWM4h)_{PCz`&*Be zyS8(H&V6m^Qr&MjOSZ4_4|*r$fR6wBJkYuSkL-t4ZhcHE(3#&u{F*a)l-#jBOED1m zbyItce;O_2fo&j@$=QPPwA652>eApFPuibV_io3sh(px8#AXOpP%su~Dupy@9B~%^ zmkSV5+Z`m!IC|i+s&~cJ)GE1An_yz|FGES8Ntrj2Wy#3@Xq>9)@oBtts^s8&+o~F& z&`Qf%%ArBUF)VpUb3XLb??o z4*CpXwf8rFQt3MJWjc;m(Mnx@6fg`@W(t5mWexp_0OMSoM9ONVD_urLXCW;EK5)q7 zifw5?QpZE#T`<0iv5e=bA@%E?$ya(?Gn-l622_)iF$Ak~nMWiE?0AKU6>@ zb0)YVd=C8VlPj&?V;G|2tBZt=U@oR1q0(3>MdX@JldbxO-_-Z+wbsn(Da!@wh^%_< zfg`TA|4%_Q*8Y|0Q#Bvz7U`rY-Fuov7li;BI23>q`TRI;jjW?n{eprv(L>f0x; z=EfQb;GMd!Lz8P$=FJR-T#Wei@9q@k)upxSjI9eQ!^N{>2F2Ia7k-54(^3_@@&zDO z!o^x}^-0hA5}Lwij0fIFchErNXLapJA}O-@Vt)qFBiQ$u?Tr%mpztg^$(mJVr=dBz zO#;|EYJx3ha$Ue>up(T3eXc$wWb!2`9q*<9OJ(4gelsI~A#cAAAdT6+J(NykM7(a) zEUWN9$^3a`*mCeIX|&}hq|oKE9ZptE(!@fCkCLoO%DB9@V`DR^i{u9O0M4adY%AQv zl<>DSo{HMJX&w^@jr*e4QCteci5Jt#o+BBZR1-IwYS}RB0fvWiajI7=2 z4a#QHg((hrUIQ>Ap_C7@iceRG(Tc0*NffK0n@tWae+hn<+xki9HlR-MekR_q?FAD2wNmJl_(&?scD2h9({iS^5f~rTsxYR+%(Ew`pgVk8(wqy}C{_DJMSA?1Nk1p=~ zh`6h+<7Ft<>%B3xIfus2=FEB|*G~I8$0uzNBtCEBc^;JZ7TKZU6UtN;f>kv#PUx%L zjsYzX@nY9k@IafEKC?ZVZqvV;Q%-LQBgpq7igUbLDL#>{;2v%S*y2^t7SIv)Z_{)a z4M3JRzi;jHTlwlz6TL;a-6)JsVN42Mg@<}UT}qI6pFfvyuVD{1k60l= z%>=QA%2a`R54O?=ieXca$#GEM5=_NJv2%w7|Dz5#pC-{ss;T%V<+n`6VY`ejZ!_oxSGRO!K8nfzlcx_&fDPeakZn1Q3m(;7-y{cW^Kv-oe3TN+j) zGcB|v#2;2BRttmihf|9;h0~mE!OZlCi6t04&nyfd@?xCaV1IAo@~zHR$pwY+Q)kP5 zbIkVk2PytuiH{qFw?K~eRbW-49w27q8lJu{c)0$|H-0mms%`6jZkoOsCbp|#=h544 z86mAV+{&=~o_SeqXM=6tPI4C%YxVrThD%mc96vwJ8sC^2I=reJ79WRN(jLJ|e7E|L zHRDdmuU!*Y&v!7l&kW?9c+j;hzV=1jok;h;m)}<98zv$)$40GNotLYf>gYF zh7!8GjW!R^o%Z_b3%oT5AW$J>0&54dJsN>6eEyBMty|r|)p@(}h>SW6NvXDK#Vm}s zu8nWMlns6F99K3&2qGnTJ#@Y$mdAHF)U&3mEy;8gFkcqFE3CBbo|+(eWrcN3vz$z| zJ^LhjHq9DtCf5{wEAC3A-&c=BLhAQ$<_N88=W2`%b-totBY{?mt*tTb4$x#j?xoNH zmT^Y2>zHd7dIGFv(W-ejNxh7Bm_!7x?7oT5U=ynDy{w?pzw+0vd&Uf!%Kl+>DdUXH z#2HXIXK5qCl+JP|XSOUTd`DrXld`yF2mDz88Mm)Yj6p|kxcwxrMQ&R9^VXs&0* z=6bJ~gU-DZx%}?%^g@b$;)H{1zK5r$WvI`&*D0e36$1_{BsN4S=JZTzhb$_?@bH%2 zsKPBUJ#ewRx2QIQ!67)fVUZnfZ+XHJGg!(!SscRmA_!yfiNKt2g}H)VgQY`E+czn? zF7jZ$hJP@tbfR5Ht0|uQV>bnN%A34Q`J%KRFl_$R*j%6m7IoFcjU}L$Yq9e^qPu$J~d1YbC_R zeH|Qs5bV!8Bg=YKeWN^_nmaRFmL|rRnxm|J(BfjvTUg z0%m_y9Pr`@K1v&B-`z?p|8-LeBfhLa`tefD1&kRXk?#{M3Ra7-CbWmR7|OF{gP|4N zS^(WBLrBfftaR5kll4~H6^96kK(gsnZfZx$i3=JF;+F!nC-*c!8kD50D3sB!w`=t}Wq z2m$7!vRvf)Q4-^J^0bq)aWD8=G1G=g58V1-3*$ zy119{4RHU$Rvkn>AMDVTRcb+-1;U}5x(8jz{Wrj0nJjy>fEwgbo+tnj!3N2P=%YOm zD%tMHpRNkSM;zkGzz3(?63w;W#zkM;0BQ!c0ZCKU#H(WeeFV9Hl2QMQ1A*a)nb{IQz5OZ5LbqS_q+_{IoGj6w!-riw%kXGMkp^*5X- z5pkE-Ht0S0_o4268~-!_ACTX3h3U(N5sb)mUzmg}Gvx{IXkdRN)3WL$I{;i9D#pC% z`m#!3v3?Cn9W333N9@1>t9VFYdhgc34A)_S7~y}8PWub8fEjKgLhX+kbXW2RmP-V> zaRYc{*;v=_XDCSCc3!${v%e8s=rFaLh_tgvv!de0&3 zqi=))>2m!OS9TtDrL{#Qq4@gTlR_irHPQajZdOyCRONm}Ev*Vbq6ZpuK%Bo; zYMS>cSJk;lt>4=_JzlSCmZ+Jfn>>C)HJ`n|>nFF%Vq5C(xx{vN=p{}F%NdE+zYeQS zdakS0^@awv^vWnFusl%^bwEkN18xa@=i?(AIbRxAwbL*o%>PL;@y_AAL~+$pK#YVr z<@hbL#5GBi5*fa^&h^Mx$JB@Tjw`R6-^lvX(c9wZsT$8ORz1zHvACO?K(PYi9Y9&T ziq5ieYS^g(YBAuqG`zpRA20o-H3s=m-zyzie2PO!Up$77OwieIhba&%IV$Am_nDxtASN>&E|aE8iXM z@VhNzSHb0CUXe8R`l3quJdXOdQ4=lA`D_dzYQ}>30|V zu=zY*N=~q2&ce<^B*js#OYv0hLMX@uRc>&RS5f&0j1lOBcdhX=QN63myk7~hQ+xRH zOq5wF>np1%dZ}tn_UvH^Q|qqdUE&%1_eVt7D*o!+o939-i)6utq>#uEDLfi1N5OmQ zwzgB#lDpzM{&n8Ecg3BKC6P#^Zy79O_q9P1mUPKEn{}_K*YFRY=cni4D6LIFC+d|t zp=K1Mja-+vZk4C4r#6e@OKeO>71lJqzS}MFkP!L4nX6%@ zX(*CI>JlF>K1vBSp4xmEAG>j7ls3`c5&U~gUK(uXeSbT0+6Lyhnva^v{37M!1hsPL zPHsGDAR_6e7dX}1dDE0U^>Fp@{qI`Dq=coLvLQ)YAa4aY)){CMFKB;ot7y0dtR_j~ z29@FD&*UiHW*zN=0qrjUxEAu?@9^4xrL{lHwF0Er!&hv#-kyL2l`kkqkd(<*D6$ne z!dgYZGkpnk6F3n1`KSe0U}n_%rw_5&ZZfs3d3X)X&lklDYkm@;z8Ar1)8I$OvJsRX ze~=I38X9U{8QkaQxALWaxv6!fY5SFOvo84N2!v%Qwb+g-egMkP`@?4 ziVe4%rfcBp!Bl>@m;T9(fgefwH#jw&O5K(C9OQZ?Qq@AVMY3%AD_O! zySJ`|JZ{;BoF^#;%vtfr+wasSvzgQDJ_#WFaqi zF0q%!>a1`fX3k>liQe(Puk$lwIvP$d*0S$6udluGd!d0;5e7EX_c~6w;)Bau6RdPq z15|}M1rgztY;8h;FE0Zc%_gvZT`iAbk)0t3?=gnj3d-W`xj-gd+*c zqz|C;0d7VABqK$jyUFw|x6oEU!7spZve?x4Z0NgTSm$MO7MWswy-drN-yLySCDRRu zeq~Sm=w*&iquvxfhj)$llDYPWGwD^YV;99h)o(Ud29yIMHj!r2v96faK-XRcn5t8% zMhV6t!jPow6dBHta7oUqOZ{*$U?ie033-Tlsk@@7jg_**3Ncx+zd~dr`0Fiyg1l&1 zn9?W+Hxqe5%vb92cw~7X*iN#}luKw4_^Fs>Nj0$M+YXEtTFr>OMPtx7JjctSlF)Gd zjYD#H8qFgShQH?-OBX_irpD@sYi4JKLPYv<{x8R~2gH4^xd@I6I}1s);lNZJJoo4L zHn787Y>4!C9>ZZC#P|J#pj5Q1#dfY@-VYiT2NU8RjXhx=+I}{n9OVEm=&PFg2kkGZ zgR$E@+yy1^MP_Y>-?<>Kg3GheqPp^~&-7CKuf<2YK1OwFdziGGo0--nHJu}xlf)_z<~q_>8hot+N{cBc==BL<#Lk%WPW zC^)&uNVdhoE1Z;bB~sgW{xz`d`rsMp_8ARk5I+z^wSqv>a&19kpiy!@xg1UaN58J5 zq-0xYdP^u|9fAA|Qcr%uZ=ylh>A}VgR%iWyHMGsFy~&(hL|0<|?=vXsXB5uOmUNcB z$pT)RUo4Hl^HATLX-p7OF9~d(6KeeT_R3`mm-1{oho*3z?!6U zm;NWO2&Oy9fC|4H&_r+8=+2N}X2>%dBlsz5YghjMeG_<@FGsP-^aF-^pLhQ(RuuOz zznA4a16um2l7$}>cjp6R_l1+q_rCmnx)#Lzb*1LQAl7w>mnDNi*o#&AODMG|noZyi zuJ<|kfGgnG(hYs;!^Z1fpFaJ>^oXOJYPULGjzER9Nw257ypH#X-_Bt4=sH!Da&y#gJe}wGo06ZACxU0SOo1*D zeD7D~fX%%2ei!#hGW2R_T~00eyeac`FDE(lafx)ELR63S>rI64eNT7*GBfQ~u-In1 z{Gvt)vvDxKS~NWc5+1C`jy0+ktU7{dtL%uED(Ce|9SAOlx3e#J0l5oMr~Ia7MtU69 zk9z>I^i%K#>+5x&&$F3MVY@kcbT_Z0X?$|(Yu9Q8yZr+ehL8!q#467Lv9(@(@ugI? z4iEf(5oguvR$$K?S{v|rf zw5YmB*)M4pByE5ttcmAUB-D+!#`6x7ZYJjjPGQWD-CM6}>Q$k2Tv_~v&!3~Ad)e($ zSd{hP;>5R!{^4HAQbR5^r!|T9T(8Ko>~3UTA5otnmaPjiv4%1amsW@3RS(yd$?15P z^&y4IFgqe{&4*L%l`Wujx4Frz`ol~>&1mT${chWKM{9~CF0>iOKZOvdPu zNJdV)Wz;j5f$4QIok@EHvQVvhmo)D$AP))1?OwQ64K)HB0_`mx?K`vs?fsae0<&-; zT`Xk*I$jWG_xXQ*teOK)ztOw&>gsBtTgz|K=}T`!-_^fI;GBb5N6qKouZMq0t8i^A z5Lpmmo#I&^x@M?$iT|T{*R%1Y%H0sF@hUhR?!Uk119Y-agM%Lerqs9p!s?u=hOJos z58djaM+`>i4QCAp(|vnZ%LV_aAc(!q1Xo>`2U4jvAko8{Zw3Gl%xZ`7K?Pei?M8Y% zNY2Eyy#WGQ^T0NAk^S-ttJ*hUjzt%1(4B$){bB{9oTX`Tw4%CO?+*j~55@lX&YS=2 zQ<~)xG_?Fa@{LGj=8voJm-CIlOEO#$NWP`44MJuq^CO&H>IE50< zeb4^jpSvAV({&C;dB*CpHjLVL+|-%5!VEnuZkc(I9`&NxY|PfrII*9Bg*jw81EEeh z|2-QJ8_&an^$}%x*1vk}<#gL~B?O}(hLS0eZw&`ohW!Rhw#A|3IUncqe@ck_V^(8PkjO7huCdlQucW%b!%e{( z!cC8Zzj@8BG*8=021+z=I7{b<uIiyfXP*bosq?JIdwZc4O!|5lKS`zke4``i84wuwYdCj?R3Vd z^N{I2FPVS7@e4l$c#)Hy&fWs<{s-WgeJhe2$kh=}F#i{7kf;AVdw*v=u6vekFDRjYW zTjXv)az+;{{urgNaRBv!{UTrQq?F*W#3MRZ`2LAKVe8Bl*0cXW6y=?v)dEoh<+ou@p<=<&sj*4fm zzil)wYw2^eG^4;A`4XDhp{)zwb#-#OX}AB6m+liwceSRY6W~yi0e=9*JsAMq$F~fd zlST5(mv}y_?KC;c2L* zk-px9{-J=a-UsSW@fvMG;7;<0UCID~TiH0M5ML{9{5TFPOwo;G zTVwP;NB&ROu)AQTYv!$*#zIu1WaN`&gQ<-6WLl0cg!jdWEc9jSyTSHi2HQ`_D|s{S z&>{AqudR1QQ?cnCowahJ5|?@olZG2y?*EfzR?@P{#)?NoA^H39{<~MAw~Go-&)l_~ zfUc!E4etDGKDUP3X=t2cO=39iq~>t~{hT_u-C$aWo*AdhQ9eCr8}`k3#p|hhre#X0 z^M|~B%e#&p&O~d+(!Q&GknvvL;hQ!yt))WsYh)N`Q}3|tPqw+Q%N26jpLHQMIAyo# zV?0_nQ~eO`gcKiPd4Zv3ppUw^n6VIxS2D*)A8#I3%0VcTQLc0AS1@cDkU`emCa>B% z*6i!0_~w;(YD!bo|Hso?heg?a-@}3^@Sq@}fTS=mlpv^dh|;NmgrtlJB0bU!4U#i3 zw8S7CN~e?{Fak<FO4E^N&P=79>&6Xls76ZOJ*1QdSbnO6{p;3oN+E@4Ph~{LzAQbj%&>Su|AUKV38JSvz=4SKLt^wSfX zCLcbZ8FFStU9JhF*pA76cTs(PCEWzQ=@r3zI=ypl0)RQw{?F0}52UuhPP$t94#mYR z#sBP9?ZFTa6lq3R2I=RA6V4!>YXh9aVPG8$)MA!8!3V%#YH;Ubd*^>%t+m_Z25}%N z(depqE(i*`0h+gUSML?qgM3Xy!A)RXXn&^l-}Z^&&9{FzqpGfR5h|QzI(Detm$8pp zZVjdWG3!rO@Qvi=kjtn6hUxXlFEcj$bH!g8WfhO{Xe_CNA*-I@c@ygC+jKNJ`EAK^ zoetOQc0`N_fpQ^H=Kk*T4kOG)DM2N?3N+sUgXpaNO|;q&_;rx38X0tbs_` zO-9xp$&1OQ)||e>WtkewakI~6qW-;b>$QV3!yj%1 zi(yP?-YLoqHH##=;XY3y#uYI>bVt>CR zUxnA$Za^k@_kyZInyueYp1Kph{$svmM}PXXv0Y4=HQ+E*XkBx^RY<8Ru*X1nb>LIo z)H>bWac$&nl>NW`TdN3RzKthS-owIv7hC|gFD+faQCm?*g!63JY7<2zxpxG;TBoBW zWLtg#Tn3r0zc~Mp+Pv#egvzEm5_L3J(`Y`Tu$UAH|7 zI9e$`_-x=aT@9KTMP_%oEBitG& z|4sUT1M~FhaP|6;_s-E135h~g{#v>JL2V+9yOF4q69ClB^m)$UP0r6}E*rLM7Rb-1 zX3kSDHhj*DhjvylK8*ln6aSx)jjI>d^{Vaj0OsTQAi8;5aLDH>y1>p(Bf-?W_G%^g z3bYmg3-4F>x-xot4;Us68`{6FuB$}MgB#+D$v=PEL1dPjQ0EofaAizA*x!$CT=8sF zl)-7sWGB=wa)1w2Slsxg*lURwmqFX0L`_Y7rK7g3p5j#gpL(U~IJ~JBxVB6G^P^Y= zp62*n?M$UfnLqqU71<-Xr`i+55vrw%L!DXV&s+?YB|b<{;Y3LbWrrnSH z&JJVtKAtO>;TE{{=fvpd$2FpIWGt*(cEI-Jft#$D8EZetrdVKPWc405-ev9UD?-ud$vi&VShRD>F z9wGfjBk1aHUqRY!E(!X)EPl=&ef!XhiifpyiL&>WWCA3RZ$A{384vv38LMVoxwTDI z;xutk?tb4%F97nu@R5yFBuMFn2;l=C_bS?a|pP&g1T^QgZaOlB_S9e`@6? zbox<}mrpGIJb{iXA)0@V3;Q|ulRHdujbytgDHFxM=wJ94e;fZUp7^M_=`mi!@A`hE z1O>H2RdJjzJC1=iWv%*EJ2yN(9Id>j%<6s@~-9jyFzk6S-)gn-tq7nx*02(AZh_sVdH6Q}i+hxv97wcJMS0-T_5w z^N;>8uF~{WGG4aq*HgxKxDDa7W>$={8*-4Djq_*9$rC6|Z)wEy!=!rEH1thQLCB?w zZO&~amV~nf*KyuGe<8LHpUJ;YW}UsmxU;O~NNUZXyNyPb@2{!$>pjpc*F;r5Y4qxm zIRskfiqhKrzs2v>uk4Tzuony)8>Z(zFOH^NF#t^0+svB<8NX0k?9CHMk= zV6fBeoeMj}3aHlxLpUo7Fw&-KC<3(E-6-Z`bqd}IST3%kE>=-4Mom{q27n3NbO?0Y z=8OCQ#OEoIwY6eXKrM4Mtb)>2$stD2!zcU_c#S-M{CK?S^3rn0D1h&K!G4p*Ot;un zuD}2s_Wl_gSG+&nrj@dQ;HJ_l#AI5E^U?2k(V*ZR*nowpqOQfi4_k~ zR{N)$ZAEzhY2I5Mh2`O2e-6}+#Bz&Q&SWZjCYp}crXCrcQA9Nq{P=-SIhslUtlx$~ z&-9M>2zGQ-zck}JtrH(V|GgDrvNNHdk9w&|_84`DWz~L@s3<|un~BNEyv#>hwGg&? zAM!giS#sO?8fb$bCMY_U5w`R(V*fkPi^OLoCjRFB4~7=Rae>dIHD(_73b_xA3OeSd zoiR#Q4N)sF8K*bJMNnqtx{!6;Bnc+r8}zA4J!Q>T{@L6{P!s`jBJ*?$gKSrsXB=Bx zoF)-AC+tjxDK2#l^MZoYyq?i%$_1x_>^zUWbc&J^6Qi$l-9dttOSZ30v)iG@JaY#d zMi_dtG643=DerNlL=5e?cNm0YPDw)7J%9Aq&TAHI><_kA*`89n${g?1GFFpoO1`X9 zPb_+;EG)Y48AreCbG4(`t2BZ*nzo9m$rKBhcvEewo#yejkENxh9gp~&kA#G{EilZ` zrFQSJF<|O<;S&Z`UP+x8kQ@5GoE`u$eQTf0_m}?)0wGLn_Ho}9|5j|wpHsc%p_(ca@u?p_7u_W~ z|9%!cJ~}d@cSjqvSB}8!UexQ@f%}51N@7^Y)9p#1P41Y@y#>zH(<1X!T(>luCgoB+ ztw^-J^yL^EK3n@dUgMbR6|z=X;7&|m+91Vt#OB%>ciNpyavkP#fv!P*!)om`dsT*c z>g#VvVwmuP1Rk$2MRO^O?@1!FPvtP_cq@t4KV=N3B60F{G4`_x|IIU{{>K3L{rk} zEBj5oY%OlIPkhI2e*=-&DaI`PNL*P$L`3htDY~98NgVr%?AG*Wnozd4=4;|Z&XaK( zWvU)?{FOAmgQM<*a(D;dZJ5B^E3P8LwRa8_D3d&9yVk&w7p7 zS93lpmu`#*kWQ=6MDY$Lb!ssk*n1bF8YWn2J?VglWRqaZL#-Ob2!sbd01ImidJ zD}3$WrtB2U$0C61M`CI!Fk8L{O>uZ`Gg|VMjG4H8us@kn^BT4c|VNMAbecID-0k_A^?r(A!VtgRp@BV6*T_N`d>9jr=&!`CWU#!IR5|B$WfeUh5UJ^Xl! zn3xy_*pr&03-c8O=}H02jMjT*?NeCf6Qh41(JBlCD%VRaHFhqnAT6virDyc0Q4b+R zp-TqDf&?Owz3+AG!df}EmnT2XbQw8RN_*5VxtcUC+!$-L2|iyOb>jDwV!V#%j^wmK z3EZbH?%jE;@hGSGeYHk`DkHVn^1-1Xzxb;^g78V!zGHj_a)I--FjjiBT}LYa5~U!t zmb{d=RMy2WF|6(;SMi`L^F>MubzTO$r54*t;Xc&xyRO_fBJxk2x1RkdnzEy9Ms_e! zH`Da7My(6fDShV?qVF$a^otD<$}hyr`R8`eL@G7iHj>~;jKCM<5_@twoFyx>QqzT9 z<8`$YY~C+lNvUV$GMjyGo^c^KH@7Xy$)Xd3`f4&@>E#O#9APEogi zW*@vgJ*5PrzQse_=VRCyDm+yYubdX;L|wf)FFZXHkZyEzbX*Nl$}RXY;nRC8*TbM` zeD;oxrT<_=xFUAK6CHyJMMUn2W`DwAX4M{}Gga93#8|veO7v}q>U*^8iLJHFOGj21 z$|ZRwPR+?urE^g~h5on>skZaaK8jP?iq?A8j>^tCB(Bx8n)L`re`%C=yz{HeB5H4} z;3v~9%VKcPHat2UX}WOU1bI&tC2gJn+A{}6vVxBvYrn|@wzyZdZQi1^LWWA4@%px0 z*70RN)QPQ=EM_ngPlMKljbTPlFLpUsadahY<=dUO&r5q3Dee!EpOS3(53>c2KV)eSDyGRhqQ8vvTOf1CH3uIp^#3*|%GGt8@yU3n;$MYF5$2{-l zddcO`$yA!Q32gA&K-b9#!qD7ygMTA0E-pY-=Vz{k^*-n*#IwayL;Q6sdt!LD_oy8e zA9YQ25s`_h*%6mf@Ce(x41W?z?%mRGtoCFvvYd*8v?X@3f#wCM+8N8l!UO zi7*eU71aoJ=ua#puZ#>Q;ls4jlZsc3kkWW-um!^X;YlvvYya-Lv_zVjtjv5^X@trh zC4}Us4PCg-uaN{2R)}}E_ zVHD9d1v*_?(*iQBIMw%$5Fi0*uu(e*M%^sAe&q@)oe7QiwLfGb1+YtMEdM3@H@ zM;)^uja46iwyr=#<3O!Ph9$MARpEGnVI(~c?!HtqD>HI z0TilSpTlRkokYRQUJxZ$8HY|d-^FIIWUNl&7y*XZRY>oS|h+Lp10O33KYc_`NF6b{XD z!(4vf(=M&Ac0CE9h|F&{CF5&VE}Wz3d3cayn%p7-)V#sljy9}PS;CzT{2s^`^?yp| z&!B=`r8>!4iV?es6y2{)AElel8Lb%QXz2cuXcbu}-ltkt@4ro|iKN&{zKC)zv9Tv} z{(bz+M|F2n<1~GGDxL{n%2bba44g=9_e~5u&FFr5ugqtJX=Tc~=Hg=U?E^%$-PEZA zO$>)>JRe2!Ba#yXM~D-n+>mu89SaKzJWhQO4FC1(S77)R>e0XqbQK`7y(lp;k&Dq8 zbd{wlQqt1Q8^hmukvHC^Tcn$zJFdx_hjl<)4Wi!ZWV~?r{)32(c%xN>!wh7fY>U%lZmb*&1MZ zFO2pFklBPBE(Xk3ZH4Bc#wI6?z+7=x;_%5uzC4t8M`PBJ_A$QmLOeRQ?0bm*oCI%N zXBbfrehC)C){^4j;xjAVwUvsP2aWrZago|hcL8i_=-rKfS-l&u2{DmDnfCvxDNKLv z*2-PxH1Wo%IC^Jx_ZU80gI%6^qH;GsD@o#Nr|c5Cx7Z(SiaS4l;r+5SSaE3;S~(E0 zWf}3_3ubDecWS6#0G?m>>$~)d&wG`#L%6ydI6CI4)DY2X27mSB_yj^e@<;pjCPsaN z)fSi@ZI6{hfyjpnq|%3il<)SzK^;*31c0UoNXv>v4Wk9WUj4XV(At8k8YxG zuu3DYK_d_j*k@O*dgLIOCj1qTSYchcjT1<9FwyQgFtxVq6v!t>Bdx>D{n}p%PfScO zBn#VyQEN(;mL%J`l4kZ7TZvT6mpt+TZ7a+9s-olUPrr=fR+@vI`vTp~I*hTsJ`SJR zR%mEzr)K&U5PgyRv5Uokz?&N|KG18eU3b;&>BlRCAaui%Q_7EMKT9g)&eIgr)6s;V!D1x6Ff}l>%{uDCnS!D!+Fbl9LBLiR}2jf z;j;gy+~zbEFOb-8>XxD>X0++(sgoRHfHNqNI@6dB=j3h>om&@PhAr$r!<8@<=?zC) zH!TP%|K}=xZ&z^GNCSu6XEA4qS7cOTSqv2Lk$LIu ze|e3B!d;Isd2pg4Kx-Y7c91py=P4y}+%fa93vhS2`a_VWZVvpnKIxjs#XkEUNG_Ri z#;G~fJo`GIZztBwe;w@Zx4)R(zQ!$IQx<7Nzih|M30bFgO%WmiIf{v()(mNusmPT< zUAUh&PyD&|=Ww4<>89G4FWQXan|1kVdV+UUYe)!{Xs%t{B2}!TNTQ39BV!^Y^Z;_F zm;e6wHCHX4%6QVPif_}fnI9-HEy@63KB4d@kQHbG9NV9U~LUtwrzFYz2C)QUzn@}7Tv?1 zyt})?X=^y6uBl18f(erw#8n7T>JH|+JnrI`|6RbhCVOGzVRmcDKWg3=bCkbF4@-fp z?d%9N{8qn6-uEq4z&F&Nd%OGuNwBmzyUvUUm znrNRR6cF8lAV9ChxCLW+c{-wc@xo1Y>uP8O&}_?x#*pVeEr0I<vigS5ZSX_pfKcTTpcZ)FI67TlJW^KD#90Bx4@W~S$qaLpe zFgjv~9Ex(rlM8r4eo^7l-c)b|XYqfc*!sN^Jg&5tDvc%eMAA;I zicaIzQVSx_{x%+Sa#R*hY{l;_4?g$X;CxDqY@asX+a)(Bd*`ke##rlX+FG`tmI~7; z9tocX5`FL?zmE#`gR2RU$2XcKL`C&Ct9H{{%)ZV@YQElrMJ-JDvB#%MgsOAG*Qo>2 z{ZoJ6p32=Lx|XOPKH2L$`G7C=PC8ZIx_H&=x(%(ZdFNY=gbR(-ilO0D;#GRKs{q8} zFd*E7Y@YAB`=^9(5x7#u6ojMFcSZ2edw<0_5o>byKATeD+X^<ZrTh6CnY8MCvxh?o@b$D9#WNTO>OVdHxd~^)SqysNDL;Nwn18& zYXcyf&k?lc(hIP15Lth)>^7`v9u!&~Lg42!9vXNp&Q{0$)b9OzAZ+HmnrP%Dv=%Dv zvmX37|1o$;sY-hI!+Aqx-ya_9(uU6_V`2E)MdR4xVVpNH)Y^q+0^fOCG`r$eEH|2E zTUb4AD=TyStJpRfrQOFA76|#V0gwA3UCRx*aZhW$HRvQ~9*Z>Yt9R+&{%B~u-2xv5 zat9H*IT{1CuZGGtM*VbGFqNI^>^>{kDdWL^8`+R4gxp!L0okz*_UV@(!)z+#=S?C)}~t36P{>enPG?W=anO#wjyl#23J zegAXOj$1SI{8J7{#}upZ^@MS3Ew*%S5^Z9HwF__YUw`Zvb&vzI*CEDNerd`;&CdG< z9;&i5FHo~(d?GJ#(No}ql>q5Y8_N426J(kPH5nTjdF;Lg;8fbGR&q_Di;IgekR;wB zCvOK2Qe`yKB@g&Jna^a=o~oRPViz{cFF472Q8p159azm#!>uK981wgeMY*W@g-V_T zY3?9~GyB7y(%061&OOI^fVTGS$5!_*aPSzcE8pyz%V1dYe`whrR*9J$IGuSi5oh0E zoD;#~m?^{*5h8{7u0dDIrQ?lo?uw^W7#?;u-BFU2C-^_3YoZ~CU){S#m77!yb8Y2f zO*K+}1iQzhOnGSgT=Q?dNBMj)-F&>o|Fqa3eta!CZPkZqrB|d9OrwEwSfb(oX#xIs+){F&)P#|QiU0l4*cMXy{oo_*BU1KI2^-EOB9mKLlNNKW z)H@@VUVLx1jBH&$2d?}SbL?CUsFQUgXAk`#Jzuz^g`&@A-WGb8R36_(I`4CJoMyXW5pTqN&GymE&<+BT>CM8Yu@Z8L1tVcr~-OQcFX9C|(xN zL9Zh9=)JC3714GLeZdZnyjQ9BKeDiBk}K`qiJ~5)WL@(dza4XboW$1u9Il0` z>qM+PAid9lV6^0%(-2Y?CC_Kl%D(^z?Ei`aI6zl0Y!rQ=pYnRorAtOkqcY|Qhie0; z$Qai@1y)rpe4$4Chpe4kNi`E;@N^XIcQMvX|)7^a7BvVYqY zD_$V?Ll%C?b-21Z{L!w;5PW%NCe(4Vv5?Tuf?q#6Wg`iKb7d2AYJH1AWqM{TwF+*f zLB6g-LpKly$8#4V7W*_|d>}{t>OlSd^7K{VkhznSkju_A(|6sE@|UYK zlg!7}0udc1HLLB8u0E}e2Zx9E$hyIy|^gXEhnuzyCyNXL;#DaIr2Jr1H4y?Iaw z;U3aEkstHLBSS&}k#fB4+EmxVO!rIM@^g5_0NLzq*C?rPpBKLFOkvh0 zO~&iI6F*u>B4m9f8tBP%61?~(GD_K&Kl#YZtO`yb{7g6C9mR7Ee3(N{DN5RihzPmN zKCZWn0-lwkJFST`3yyJgeG?j5m}F_M=upk3K8z4_7EvLKB!w}^4A2P?XZEmt?Q|Ly ziCc4#XL1xA#zuH7W&F2KhH|gR*rrQc!Bgy|$-k-2i_xFc3MLC6wIyfXMWj18MqWf; z_=#sqP3k2f{YGyhXAp0DhrW2duzEvtn`VCZ7b|{KHk5#XbtBGODWfDZ?HW%hRqbylQvSGs(ol0rke^HJs|I8+Jcg*^)lmMS!zLFa z8Cr{*4H-&?p9@dj<{i^KOr6Pg=@raz98tHX^dk~jxQQsjzko`v?r?0mNL&>{Yik~1 zyGc4Q(uM=uFFFQ>aDZQcUg+W4*iJ%-D3wCG6gmq`IRLKHXB=V^(nF1GsCiCz<+|p% zb`z|Hhl(PoSF#UU_AL?H4wgJIE~nyE59GbXm(3)sF!@Y+kmq^u(=G5I(8i8Mjt>ms z2`&Y6SsNBC5i${XTM0Ik+ZDo13sC#&*cywaQGXuN&hlF?6QRO#;sbh@G}OO!5@xO>i-ap_EO+$$t}5Qusb8CHGzS7vdR@ zA`4J;9+lkB+$MT{Tbx1K-%Egt0hI3|)+r^ceAAR%K1CSROXW}3q`$3GO2*&28Va?4 zbI)KZTDvC~fv0?6^kwA0hQk<{{bM?a;5M*x4>7e``!59PKZwlddolQ(~FEI0~mF z?jVfI7k=zF*oFAS$;y)O=3z&)-P4$ zWl=exv!eJJNvIZI<`O;YzaDxsE>}3uyKy#hk+S1G6ixc(gMiwumI;40t!UAB|4EcsPb>665YbAA)9Nr`Jb z%LZz`CwX1v#9oF1wWXD+2KY5d+OuNe9Ge8_et}G!S3l;T`0$Q!oQib* z=MamgM=~-j003%3{sZIm)p!89o4ZFPw{~Qld*I`18#LvLii(+IHVXFk_JaUG0wh#7 z_f(UQ52!-bB|!j^ooAc@@-u)e2^77qTiqXnqG_42QgiP%+23+AzQ~B^I7a-1jWwX| zE(p4^;{CO(O+wSn_&9aHvdj}gc73;FeBd?-E%&WI>gp%mF2RsD$+90Q^W3bP zF^?EX;TU%IiD`i|moIKuy|8BAh|-*MJz)P6lSezAzoG{5Vsc%DAN6g1#@cjKj5}D* zSwGE~=<2JV)fa*et^Bc{@@~+y!AwL}$4Iw2io${??svJeJY!L7C@4-F=#4)~T4*5V zrARuM0?Sn|9<}nk zO5OLDK`UGeqC9GV5>7=TOzgc%Y{8KAt{BUSOYc@Fou4@MQ-8WD?ehZ|f6eioQnls0 zo^=7&YoQL=-L>q>h*@{fIF;-Y3k3F%yRWx$^1+f>B*dV4;-QJkbJm9?U9G^AVjQh8z)%5|r8=wh! zu1Hi8N1g`@mS>oKLFb3Eg#r3Zem}D!qyrm+55Lv6@1oCvq=l(8{oQus;)Sm*4`o(^ zsN>JeTBVjYhRExF9_tpb${vg)buJ>G`gkSV&Zb1_Ym8fI^GqN@p#DILNJZl zG-8cPSlD_Xricy_x6J5bIYC?^VT=1Iq&zWfC)}t2X=yuN$U+td)SmfGn^UQwCFMHk zKWUeOfI3Rzn>VkN8l@iwa=&Wz%F{RsI55~0fN?azG3)Q{?wWR1J2h%0*m&la zALzVmFcEkt=aHgWY5A0Ku?4Sfk^5WnFvw%UE#DN`6oOmIrO%bb^w*RzAuUA}SJ~IX zYdjMi(-zA*2Pk$?SS4f3_>%>A941%E{3umg*NDdP+bTSCOUqLmrf&1KRz4!8vr_3^ z9iouppre8pCu8ABHO{!gxFUoNb)0Md{i|%?D2%trO*E_n4PbL($cU-WdBKbzH{`*p zWv1W*_LKXs$XotfC1N{6Hir|u2#rEB5SL3Ts$CW~ur(4*#@6I(strR3iGG;a&WEoJ z9)|28RSA7=82eKUNzKLGr&Fg?MM@LOde6Np&hdslPO*tTFf}pO z( z`y*09md^Q?CvGnb=m^l;N^+057hmy^dy_VvOi(8S0Uzj)csB!PH5SzW<%{Lqhz6aF zd2TVY0JLv8l+m_xf>W6TK{RzA#&2RZy}x=N_d+@#@S3T{3sZ3s5!x*m&$f*Cb@fWH zX1#Tv>P!Ab;S9J;z>K1D*xLB$Ek}|ZL%OktalWJD?2eq@86SQYQs5m!@{cIib_6%r zVI6+WZUusvoE9@hYaHU%z6YzRxYMa&M==oJMS5qf>kRKiU=1iM~zH5l3 z&05AK?2seXA+0x9E1ZN8I{%bkhg!rz@`*0kA^AyaU2dLBqCeD8le?iUfE|2VK^lF? zXwSKLpM7|%CM57{N!s?V`?@}QG;}v@VY^hph1HO?oBc!cLegaQ$Oi8D=XGjj^EC|& zezaes_Sp-=d&{_!R=U5Q0N)Hh5_4GL-B~byxD|s!$4owO>|`px|9DP_N^`K>y9-&1 zN0V(Fh^0`s{bO>+ze#b^{Mn)FEF_?ITwf!49@CxuNe@M#}aJkE&5ntZa#URxdqiTNb2sIQCzcN=7rZl zSdn(EmzJM*{KbnUr_HJEdd-LxX^n$8W@7!3>(O5IFRsc|d5bUgE0^DD6Q1nII4tS;p_?8=&_^mb^$YToAjpM2M=1mt zrFsm$^ot-EAr%-Zp2~)_vGvzw)m(S-_Lc^4$XdPbA(qq;3fG}99j*Xp#H~Ljjb>w{ zSb)m5s@kL&OP%&F5P)-`EN8RCV2&sAe8mJfunJ!EY*;8^hdl8El>({Jn2@(x?LF+B z5+q{VBX|7xl>ye z@I?9~-d0;fgd}fo@al$P66#U5gEOfbP;w@58i10@&tp$|QsDrpb6bmW;Q;Hy{au8( zDi8iLw-z~Nj`y1}P`Ue-Xp;Jbr9C+3WZE;zyqNmKsuNMqiR}&eP95s=#SSR6fZm{5 zQ@#9KPV<@qt9WX5GMT-qY|`49;88l2MyCp5nAOH|i*Q8IjV*{f8&JP?_upbmq@)w< zOuapa2Yi_G4oHY{#AY+*&RZFS9HL(gyT-b(LD$YHtokdzJ0OoLwEWj z3Di+xoAvqM1vN)i{axT#`L;d+Q zjHf3GLOQP>9u7N;7&!pHm7#Dal$1@k@!QK8yoL}0%jD)!z)_jmKZDh9BhLG_@gb`$Hos<<+8 zIyvk065%oKPnXo#*~92^sh*FTwzx-P&ypAZLnwj z^JHY9`kBJOh6j!0m9XuqIp|4~;@y-EB3>mv+mC&;++RFU{lU(owqgj#ssP{yrqU0Y zzSsjAh1nV8>+RxONBjAi>5MB5lZ)4lwB#`D302sSqR2*q&#)zFF-8dxRJA(Ea{_gyz!BbOSej|IWi z{`dXks~5Woc#JIcetprlur}HJ)p5ja6(3^ph@&oyi^WIwncOv53A2oTKp09$O%_QB zvJ+e(?^kpLn6AqTRkF1_xZeVBZ<>5(v7+5*W=(SGYAFAITr_wugCc=>wW!mg64;$E z4Kc2BiL+^wjkHld2cSc5+s;$s4?U3T55()qF|8HaoL|YQn4Wl|qkmLQ*hEvjPlBV8FlkqNdKr!J(w&WXOj5h87b=#gXmw46tlOKqNJ+4cB`QdDZW zXtwnMzwbvuOUGWjrHjXaUIP`EgXQlj9c_)-;?};fdrP~p=&N6J>55I~j>_A*nSVVI z*5!EP^|Xs;7d@`OO8NOU+-8*iJmimOp~&5qYW`%-maS);&|lsTGG3nu+m6$G9R3z+ zSAF#;uK0F;x__RCK24&K@wF^o*t<^he1Ub0M1knxWXJc$Jfrxn&~F!-4F}-@O&J;| zgSUg^a;eYC=*R1Af)P}u%L0j76JFDMUk1aQX?T@x{+5=1|AFB3mM+GfhLHBgkn|V_ z?bk)iCDXfgqs(iDmg!C=cX}Q*Y9|=w%^gP><>~MUN=O*8)z$LGXiktMpf{r$8JqH^ zDtP%**5Pki=U=QD9FdaMMQ%t)TV#y>^vGtJ>Vd|tGSFSF!nELRwCp<4g4t)>com~1 zQA}XDfcN9H(+uX)C+F5Y(*^uKWkHS87{YnU=mtmG7b74wAQpL_`n_(^S18XY5HF_@ z&S6P(yo=k0|mRb6gwZbjV}eLok? z)I4(IV#fz#>w>1vLd)=1pAm3OXK6-prn;zIpQRlwQdyg*G^V_WdY*jTJdA7E>y>fi zF`CWafMRRGPlXdv{;p#$kw(m&6Z)U>_mplcYlRq<7K*lrH?GkJF>ROaR*PV!9|Y6XGh=85LIYg9ec77j3>W~Pk6I;y%5 z3#~7wuY{mKi&AwU8;IP`&t#}yKy$M`1BJ#h*j;5-L^6hIYlv~YfB$~|-`xKM*Yie0 zpc%{1h$OyV2emzo@b%AnOs$BE4y~q6W+Sq2<@QvKX0a|tS6o?eIG(QM(gwz~7XlU7 zxR|i8OVj?QmAvJ|_H;vC329{ML8ADj&P-t>k+B`t>r8uOf7-h83uG?k)>~sWHzS~h zg3^H)M<6#c2ejv>+p-d_vB!3jlr$bM&Or|%Cs*<2yVm^L;k@m>OCRbtaG?E^UFSi}!X0=yq4Hos`h6#04>;@Y6u zH48(bcju^w+inmXMg~@nD-(ve1$ZYOYh?vbpn5E2hC^ZPo??eapNez~Ic&Pvb@YR& znfrNB(db4uub|WRnzkFZ+rqi$WcE>6%jVHda*5##Ul#7G#%a!^d$=!>2qvCBuYf2vzJG~WST53t=6T|?}8B6Bo>hd*e30EAQICKN&hJui_~9a?A{ zfyI7mZS2*ssAg`eam)Up?B9RsCYgRAW-nE(Z7^-WTyh{W_|P`W&B#`zjhoc*`)2&U zNH+Xp2Ohkj`t^L5(GD4DswpL?TPDC=|4Z6QHt{Hn#M=DD;nx3uYVK0J`_xUz8%oLf zYh3DqWfv1QPjX=tGphl=AH6bB{KGpvsdTpz+3+b4HOdeoF-bB#=M%%SyD#JN+@JHM zy6+X>D+*h{7?Zc13X~3~oG&$*gaqH4(rkKqdWJKRUx?;z&%spsC2;J7kU=QDfblj8j>+n0aV^PH zCwI{hoeNxbsVfC0R{GU;#x_8~c_sV@x3pAe5)Nc0Yxn2uvdPZZQ6w5E%6&D3J~(Jn zBJgihu~>_iCA9SC^H$gkf-R@V&KjRO6Xp-B(Fhpn7`ok~o6um3Ma_2#glw{a0tYUC zkf!=%B=u~`wSoXj7@Gp0UX@^)YN_hwpE}AnVtM>G27oF!4@8?-c>X($rW292nED~# zlG6t*?vr^FVnAPUMIqgYZnB?gG{128qhEcI z<2{w8q@}#WcpW`;hTPKowgsWnB6H-;FpI{IF7nfm}k(_TdL z0c7T>?4kryN8m`Y;kR{lQ%kwg@3bM`0cDyJRl-19T3eVHD1=B@AINw#p>eDE@AXYZ z0Pbu>73%P0voj3RwpsDNJf&6{6hsgr0`b;3O#!9MCM^jj2Jzs#54xa>HC%s~#&{I# zRD-%gK3H59sQz$5o4CmGks$` z>DE3xW+JP4il4G~uWh`#51= zKZPxHh#av)mpoGV(8vo~^v}EYa=9fI28ruQcmUUk_8qcsC%_6d=H)cH)ANPHI=py? zSXg}ci>%dB|HL&m2vk%LzQ2o;g?j_1o)AiDl#Z))TAvF`-n)Jgfcv2g)&OT`OxWo3 zdt=oKmmK(}6&>?B9kA-J^7&Zc>G+kE6}_k=2;8kP8R|~h_yZNn5|BX{49zFo`4fHSox37`B&>->gyC2Dl`!8mf)q;#*iiBzWM~qk5n%e`22RJ zr>C!aH$FbT)+>wltMLo?Og*_eO-aEf^pYAr0%hLWm=?*1e2KXuq13SBjF?D)aeYc8}wC ziq^Y~{ zdbHjh4qS5pavp(|+IH-lnPCANJ)o+pl*)?3JU_tCwmMRwpKNGJWycGt^@@n2MIcD$ zVjoUpaeBGU=0#KSPkTQ@pF}&^)$K*D6E8H4r+(q(2`58C%4*2sy!}d(TJvDM<*9Hr=Y=X2R*$_mh`vszm*l#xD^Qz1S>+FGRS>+?2o;8zGKx1MRn{T}Jt7K`V` zCuj^2R~qiSu1gyIpB8|-@-cvzCuGs85PsJ$ANi!DK^Nce2@M&tIBIoeCU!wyYWWHTkm)px_~c1Yb#Eq|X1KR3r0RcOVdWX2^{d|+BtCCg-#?yB(ox8vP^Z>CH0+z_ekx=V9p>{`j^~Pm+@a? zn|ubyS_f<-v5Dp^X(NsvI2S-UJ5K+mue>8@W~7!zcX6}%c6^a=o#DvxNR4`HrhR8l z<1u2VZtv6W3FT|edqmcVr}{s~NeSb!nYhzJs2$ck(2HIlB?!tosr*mxIoMStyG97`DKh4@tQYH>Z8<`mO$^lZsv78BQA0MBq z9k~#w^lqpi*m#7);iVQ`@pz05#j7;nEZYv28OZQv8F>(2IXu``HGV_WTjS2ckwzq1 z`}onLI{;;o`_COMzvucZ_;%Y^EBW>fYvAUj@+@r@B=-q`?JGxx3L7DFdSAS%y4K2P z_(jyuk#38~IwdD4IgswEMmL_B2uNkhXk)Cj8+i>cv|DPwdV+seF|pO+s${QrNAhGY zG3VMN8F*9vt~g+x<>Ub2AKU%Nm2yqCC0w|rY0Lx~lcH~?CF`W&?9pF5!(H|Z*L*r= zIh?9uqnrqq?xFYfi#pBzXpi+X;L`U-?GF{Jn%{jn`v2H_&#6~vSxP_vLe$1AdsB>x zeRPqX!IYy)BE(u~lD6GnEv;lkn1ek_ICL`A2}9p`N-(A zutM&~*?k?S?H*)ErL|ez?aryH@6{82I>c9*T7j7hq8%a1=CV|YkpA%Ptmua&Z-2*R zKw|Fla74YMPQ-vy4#o-imeiJj9R@8-3<&xw+(Vyze&~5ss>7RW!NiMdhAjn02|HEO zFNNgSoZ7qOKmT#=L*$)%yllO(_7VwCGk)!6NQ@3}@nvpk47&MREhPH>^T>oY_V;~< zG5`1X=j!Z1SN8KJ_Qx60k5z`T(64(|=9*ablBrm{`Az3Di5TT)yW_V{2-77n_N*@) zom7nSzC3u-2;$|R{G71OJ6r{r;=i%VwK9(Hni+yM=Eb-p(SC2r5U*jk&l^@G4tq=x z%w60k8S~z2#%*aHM041aCx-^Jzh8d+GGOS+?zvN39=9l3^+%Szurx`GL_2h6v9z37 zxO-rPZOSP%$^UKN!fxGh&l0Zt!7Q4plmrWR-Y52VcZ5iMVLbf{?wqo-g_8Qn&2GWg zwzb~~GQS-l0||NNqxI?ee^eDf%59c<-$+{4!|5He&eHFhMI8=Uqs;sLeE%!ft$i)# z>792Z7ysHshv~V|a~0Lju-3NdVOms!+4c(ams}Nor`@uO&x`%+DH`nru4s`Gd!==I zWVb(vwf#}S?ziXm$$O>A*RB+fC;y>;y7S~vo%8CR-{n^SVmEBOv~KT>1-LE6{X*`W zYBa6Z6~44sj%Le0{{FD+c;qG}f8O(&DjYN;MoFQmvqnJ@XZ4bTkD3Lx%j$@Xs;z#e zFTI*AS@p(_58Y!Ex~W9I4Eov8**-B6@q+VZwud;2>~y>~fXFxD>dzUu9O<8#F zqg_0#@&zcpQAsF7WLeD^^lnt^W9&6qnwB2wRlZ1b`?B>O+ykD0Qpv2tf#dAHLw_k4 z+x5t9Vl)xXct^{jlgt=AASNfk_|l@SB9z68yIQ_;*T}*vS()=Q?6p_b<(VwNOuHFze?T2po175|&l>=Vi2)sZ2HKmtqg; z@rkPa`B3@YX`6z{&l57L0SyZbtKD^EZ6oq!jaf?f*2Q()-#b~A=-nIE&wpgx?!20o zZ`ZrBIx4$=ooD_DMN#^XIWV4D1)d%tr%<|nrsYL^yb*Meo{JRL5{#^qpDkOW@31+s z`nGX&PhN3qW@hH(jSNtAqMJ(>PTHMW3jX6)k$sx}kryrs=)g2+mf3P9EA614S-Os& zPu#vQQs4Nk-|7u5t9$v(xDUVF)YL+x1)VybYj)?b=a}TyG*-cEO`h@ys<7WJdcMR> zmPK01jB>NT&gJfxOPlsA(^t-D#qz3AIajnYi7vFM&1a}1v7rlsGXvZP8UXA5YIawB zwc14#smZyAFCMh69hd??cG&5(ii)R5ol74$ccP(ot#p+(+C9e7zy%XI#LAqh$|{m5*MXfQ)ua8g)~3>%*ATE2nNyo{!m|cqW?Q4Z7=M zuTQae4uhEBdCdNIHS!)0mV;kfSkkT*k(f7#<#cu%b=gRNcWphL2A+S2fB7O~YxAn^(Ed@0eDhxOjwFs; z=^^YsxFSRL=TUz?VD4<~b{srxb=zv+T+)03kMcV$)8BtczgF0xse9k9GgNk))pfxt z!K<4_^<~UA4)|zsl*&rHaxc)xk1A!QHZ+>q76pl?yF#}N5S2`-l(1@$Ist2G*9Prk z;yHZgH?h0QR7zY z*R$yQbf}UG-|d?!8MvU=uzEMIpQnXq+4AhE!*wTFUyYgMc5iIH$)DY3^6Bo)-K;!4 zuCcpvkeYvPWsc#bK0(S7S;C%Dw%WXTFk=W`^eoHHGYR{xMHoqMi1hGL+&A zF#53=N97dUpC#W?>#XyGF+<%|Tuv!pC-(LHN2A?Z84TKknNh;yeyoEVdxHlJa@5r6 zTBO_Tx%N-)eN@+(w4mM1T6VI_a5i>t3g@%p#=YX*rmL=6PFAV#){e;jB{luf)&eqQ zVr0O48|UbC?KwDP`ylnk*#2(L-M!xhRc6XI=Peodml*e7pU`ahCiE(0vC_F}JWPO< zG2=0X5_WS|%)~rBdfioY+4 zeqqz#>{){4_D`dasN0iZ(VC8XzB9KxG=mi8C2n-1*_l6SI!=D5W42gGuEXQkY1Vsw zOhUzo|2hvF&dDL6S+db^_LIxhD?|O<`@Q)0Dfdo>XdhAth?d1s??*pvlsCzpE#mP< z()uOTCH~I2`=XX7<4Xn%X0o@5-Ovo0o11(8^ET7PmJBQ2&%P33Ux3u z>RmaRiNYfdQ$h~(ks@nGqc^zVpUYsOm1%x8AMhL^TbF`Z@AR2Nx|OtC9nzs@vacYN#6v%`lns)zCz*w>?141y_iFC_VorkxoSKx7-i{s^ zQyqFT>>x^BB|3aHDps}$?UIhZ%5Jo1^N>SMR6V4SAxg=#Z&NN_2n0y`-+bXk%eTWU zHFd-Lm#%Qz-B}+b7C5ms=84h#_fGGD8_ne2OeVkXkt;_4Ip^(+POPh=C^Zy zh&5RMd|WNW;c2$%rAznrX=$-s&*A(_!eC~wh&Im!k8vA#MwwXGZhli^@g=4mSG3&eLg|0#4r-Q+T5y`>tg@!vStN(UU(ZUG~jW zgS5{VyHO?!*1Xy!RWE?9HdAtX#J+|STsA(gomoPwU&44j@QbgOf1bi(R!r1%sd4zk zZK+FT>)Y-mY(?`2OF!SCD;aLf@r?|1 zw^Q(-_;yLr{263x8M~%gphPkIXX^|7(wT&z!W~M-f)+J891AROWSg|O?4EkUCd*c) z{4HS^rfoIPoc6@vot|UPY-QW~-u~L?!EkNzb5RHmV`Gl94W#tXhx|V?+Z^pUCwa_s z(6B5e(a>$xp&$56y;uOP8m9J4N3?LzrXRc=D7do zyAzj94=Q}-ed<5!kr++i7g`rreCqvQD77fcZEzgtY>n-tbdKFwj&u~={%3C?({pm&tUR7W063E z9)oGLhtrBtvGH1fH@UrA%&CynB+gF8OYVkZK?05AOVI9#X~c`VU^LX6K6ahXeUB%) zv6U2H{!0lkz#`_~nC5mLu^~h@#?$a4h;;ZC)XsDCoF=Rm@J*GR+t1iGIB~P$YVquV!Bae8_c4M#kj_+&SMcoNm2!>S)!pNCIV#7S%p8 znKM0Em!n~^_4?bOZP~>wGJiggWFuM)=4yuDIJLtZ-f;OZtqH~!ZOpVWY;~wnBng7X zysOS9zmyraM-MiqA0EaKY&#hVF(f zZky`!Rn0XVlHJe6?ke-#KKU){>u@U#kNk68`K7X(GSxkl1Ml(r`94Ad9#ceZ3vWpD zGOI64Nv6bjYPN_JF6c)yOBZn||4^~N=_I{y-ot&@Z4albd$UqJ=eUphA7pTx@*R8p z{-#ml9ETz24WB7rh3TvWPm#S`SNGYTY^xsr74C3^8p?fHH(}p}msh817&kUr7Ylo> zIwac-V{zk0SEGDDnX9{mnKT=Pv!tCOZu_va7&Zv;=ys_Qq;Bqo{@HKF$jy=Z^^HU-CVip`Sc3|q~#61eE^rt4T0-Jp{-E3yl0PouZ_{OQvv6nY*- zubbS}n(^bbhKrM}-d+phPrtH=*src0AD7r0zR6$hpMYdtIW}{l`rI8Y7Y3n^Xfuai>_RZVT(u=p$TQTk~&))h+2I z8v0Y+={rii?e9Cf+<&p$SCADGX&Yja%00KuCeudig09E+FGEjwKbP>`l4dJQ4K-5A zv#oS-A8%Av=yHlrRZ5o~dhRdVvk)c{BHtAGW*YXKa2RgLin)7t+p@T|u-rGUo}uS* zYqb+ds57@ki}FHJvDB9BXj>`LTj)id@nVdHpxegQ$5Zan)9INRMjKAAJ>%a4JdZ6e zk5Ka)>901M#TOA|^+`qajwJ20QhYkM?xv6nJn zNOij(5Fjm8xYIO(9uu$B7e7lbp4LN;=m+4d^qd=kl!jd?pXpSr zPk)NWt2o<>Xui5QE6jcO_Zv#-n$(H!daQ;VRpw%}p35OGSrbEPANR{#*Wq^mc3U-H zVd@GqrZN9;K00t$sehM0kJYWApB=S~9yiJ^M6x5kqE+MkAWkd)P($I|uLcLdpd zT%1>I*toQ@z~1XeH-BZy3)L-2ld6YGoa5zOxKl^AJE<5RL?fIb>LvE4z2g*3 z1D*o1>H0IV7v+C1PfSU3Y>PSbJ9o&aCpWinldPUhi+t01tA|d7XGBUaAM)mn+@Tzu zU^V&7K+-7CC{JxUS7*6&_E16D^1K%P8sTEw8fD2P#N{(t6MG~yO$X&x%D$Z|6Rv{`XbUNyAfq0q)h$I zU#G{GP#h_aj`aS(AyQI>3mw#Dmxi47Z3L!(WG_sJkJ`oK@^NEl%5s0oMI16x+(@7c zrP(6oNZBvM1)`$6=;d<~dV6|0@ijkU7i?Q?ON#8HCL&yl4ja%{!3wcBNT!K9oabXd z5iZy6(S7b|#1C&V;jq^SF3=nMwmLjNn%zCu>W!OW@$1pYdbW!oPRPbSMbUg)s#waMp$W*1zr$z5GV^ z=DqBz17fcwcQ?5!{H~ty!Nq*aRRGD}G4v`Fhm5C+gnV)Vofgb#9~2oS$vDIrHvJ(h((ga7an(bwi7vgZ zip4ST=FNCc>bo`lpYO^jKS+@73)uKj>Bh?=yLg({IqSGZT8485_M0kKjaSNM9=y17 zSffWTc*yprs;?89{|@;^!+AdL_Q0*Of6>k7LOz^}l4Z4}pPh+-4(pmi=F8qTPUS^E z{5qzgZEdP|e}7NEQ)s~PZ!RyQjK@>AC~Y}QiUKW)jWv)bq%!Bz`G#BXq ztmds6>h27cAVOi0PrLTDeWo6qOnH^AYxI!qwu9om%XN-y_ET(n?F{rqs`5{a5b1__ z9a5ea5E0RCrXL!KzG8UbXRB>=%(RT;a^dbJ)}<$9_7}@NlHL8iMhbH&t1Hb$0;nS% zrqTOCdTtnec`5udBUQX-d*Rjmy`Opchi=-38x5^xqj2ylo6{?M4G2+Kd;c)Blo?yB z8);&eveRpH8D zZ*$Y6i1V za-I>2c$DuPpUmBJJ_k}> z@W~{&-*|%U6LBzJw25w&@NoT}oe4jr&z-q4SQ^DSP2at5({FarW zpMCVl`#+beuA;vouKy}h%1!JF*m-ovK*m@v)%*I>bMt#>p0k>4NwlpyuJGVDakUI@ zvEUKfxGe{w!sYgy+4J1CK8R^8t>~K2(yU1yvHGRWQT`hF;G0ScmRbsmy1KgVt<@h= zOLOr06tm_x<73h?>s4%a@o?9w;#oQ4l$HWeylN%;zm8P2XdG7J1HabFEoUf}qQ(=N+%wg4p(`Wpdil z@&1Pvpfj+4nzA)a?`4~HIrF}Nzak3Qe{S8V&PaJWaJ{2+gHJAoY>&;BNJ`A3!!C5h zaT$jn2F`x+4Pu@ABRfhu@{7b_^X~7hjY*zy zP2hF7Q50mkte?Qe@GSB4tT(0b{Zrwyr*uGVY6W!q_|Of%G)Xf=dhV?rq z;MA8{X4e@dI(BPATe*>%_;!)IFZp(!&O5$XL3MV2nB7tG7LgFjwerG3?IVoJ6t{1g z=iK7%$&)f8ag|wlO1)cbnsfPrJ4JjZtgL+h@?(d36csFWD`hw6uLvuJLntcqwz{TO}^Nrq{-ZOpvg8dc}j6dnRFIyna7#3 zOa25-cxg@k)=ox9%?3%%1TD@~LT3>tfQO$Q zy(7s?gcA{t_1Z*y9v@*Rw~E_3XDH)+-;40hbwCH7>+g_e90Xek&$QYT%7%=gx0OcuoQ&NJR*Re5jO^WlP2pLQ@ELKT^F2xx!dPuQ+Fh zO~;D**2jlXDc0G2FIH+x2!}HX$q5nHk|f1Op4_7t9bi+45KJ77`aZ%?1V8+p7zl80 z#JyLHPM7tqxbVZ6Zr#)@qZ>4#9rh)$zioPGf+As;bCKBwKkl%<-QdOXbgf;~A2}Q_Gv4y^=4$8D zK@YmM4m3?}Gvw&svRdp0@2XvO6DPKBMBBJs#GZCWQ|F>77-oEl6#2U3s=L(=Z`mNg z9bsY4quDzp#3;w?)6Y-;y!Bbv+F*yhA2b1zr}3$!QlF^K7hc;Dz6w2)33ngzf4zu!C?&i=>7!cW>&=oQjbYMUIQ(i^-2d{&MzF)i-)qYP)XNP28Y|u(q zTX>le1HC@cZkzsZthc&F(#76(6oviWsoj@+P9jykMj<=J@6NY8g)6<_2cH?1uLe zh2_~!j6E@m<7=er+%^1TlDBq7Z?tQ%x4gR6(|^@aNAGWxjEi}aZYgPVliQ=&I?FFb z9_yT)o}7G?tS-4tQ|*qE);R56+NIP114>WMJ@pLBa}5d6MEXo}C=-aFT`KLP7)TxW zTwcMEKBt_bOS?Eb>!?2anX(A|hW&WxxPG_9^^DhJY-6A7AMMj%k&nq{U(9L2bYSkq za;=ywq6{E21KEyvc;DO+$@8ElcYpDZAo(<3pK&FdJcrCW^KCQV=|nVs+Eh6++qn71 z@Xbx`VGIs?`+&>n^+W1@4Q(rCRj-tKMr!yc&$0~2bRwn3 zPJUHqPGk)juY^`kMG$-u>r)vihBjf@Uqpmw#I3I`sA%1vi<-H0N}<=~Ewl|x?W4C{ zW^y_rbDafBV@LLBkpUcqWWa0jNAC@kyUOktbElGQ{6HBjz8s;p_DV34xaWwJ&&0DbRx zr-8vS>DFrpVLSJ+t#F?h^7}%jM@eF?ix?_-X%%s`$MDcj_26E}2+iC+MVotwxXxy_ z_&MiKM6P7F2(WB?Z)?38y2~`c%lBJ$L9>{Sj3&4_q>Kz5gXCvt4I#DK)@j za7PBadb%I+nfht&)-A2suasL86B})3@F?KFQx04}|0mm`ZJOfDLsfS7jiC>9(f*1> z8gsq3gVdd?Djye!0&5gH+yP#e8Ps@b$!%yC?lHQ@YFrqWSFs{(pe1L$C4ESKu6?mb zsDza|###bpp%F5p_$yS89x1xJ1Tg_*2IjOvj|gKYL`rWR930N<1S3w~BWx>pW=(fV zIG_!inSH=vLna(29iO&1Z47k{DZ@7_>TSuiA-Tly9q$g168$vel`7)D|IwYvX_(g? z@@vGf#kfGeXZQTnzu(ySBQDMm4a|*oM!3o_U&=r^N!T964nCqIroRnYl2Dd zb{)vuwo+$c5tf}3)DGdEM&9~CWHsX&dj<^>eK%?ZL7~X>+lEv zZOz7gg8r_p{oh~N%9D!UCf&LI;Tx!5+7SrZ+CQxo8WhQ(WBGskpp|6}*!y=&=6|^6 z%7+E;&5e;X=ZO0p0B(_)BU=o72|E@S%ltd50 zd`=(D`0t08EKLAA97v2za{he(?09GaGYkMQpL@(?8^*moBLp?PJxFQG}~TT=_)1Lb_w4>A^Op8kP7%%%tnSG+-EjVIQbhP0k%J zdq0>~{`~vpLMF&8gvSaQD7dVdI3~E<5bK#BIjuwOH7F#JvT_pDQZKdepc6g-1b&Ps{0%VeOXE8P@E5XC~76q zvy+XuI-E6zoge_Wtoeup6~#v~TerkVd%Eelj}?8#Pz?_cX&W|>nVb~W=y|nP_ld8B zzJ{Phtdp4ZT)fTuK0ZXo0e?-=A92%!1ui7+?EPf5JjFKPs-B+1_cN(jL?Rx+aIOQ% zSv^mL7Y5%_sHrpY=M93Lvu8c(MqeHJ{lI}stIn+3YJ7#}<7FmAc8-jfNn}Wqia7TdT^6dKKUOg3$A0PeeRJ#{-X%U^(ERy;H z<+)3@Y3e-$@IlUaxbzmIK^Pjq$0sHpf&!rG+Nw2nNDHycvbc6VY;~ddJqClaTt%Ie zOh`&nG%+z55N*Bk`H!rH;hYHs1sofIj()De-sdvN6-FQ`GW)}O zqU>l~ASwEKo6^;s`^%AR9{^^ zSS8^R8s2ncFi_cW&PY^QSy^put>vibDlEi@l2WCP)jLJ(j74$hZf$Y$p;N=Zmfq)1 z)$8sQceyg)h(Gy&ok?|A-^HrO;;wf6{rxKE&p+JBf2qp?A%>0-mZus^`_86AqPx4> z%*?FmX)lj%2G>l7msb=PqyFlVBS)}qJH?zV17mY@#l;5SoX&?dpc^bW^hOimkL2R~ zJR6QrH|}f8aaPvWZaN#Vj=ZLTpve4n)mT2d)}oxfSYK5QjS%#IX7{31K++}>GjMIb z%}RL88yDZ-$=c{yywlV;+GDyDASwuFM^ssSOo~9*`p6IAi5VG!8+JRKgO(vmAyQO8 zHD2i}lTGf!gQ_pOp!c%&h!?T%=|bF5M#~xT0Ga-bDGzEQ3ce5`3s_p4o0k!Vokle3 z$t`QYGvfAW-o*XpVOAF-9q{hmyRPm~!%8rDd?sa&7Lnq+3ayZ&)wfxrfa8Khc@T0$ zH-z2n^5rjN-rcUSWP?0W$hhPa6B7g3k*`!E)$8@k;faO?o=vdw_Rw#q4`1=bTzh_O zv0ONP*}z*H8GFXdd8&w_g6PD|8j|&iBsWE%3e~m~Q2m?sRmb54ltwzYKL(F^^=<8M znwWW`)>bTppH)w`qv0+1|l6yvD)FsY7}b?v;%X@`%_ z%)p#&F{9%9rO;V~!#DElXFHVsyu%vBYgBCcZ4osgI@^!vJVKH+9yjiaWQzTd>l=Ci zBIE;!P0Q*El&{7}UYw42Xq!cTTw7Bw8hBB4a->6&GtxnY#0Q(01iA9ursQyL{b3Nu zx0EI3jQvIXUvgm=A+}LO(S5CkAu*T~zgjp_z?+k145kh%qd$ zPyxqY;280nRxa*%)jT~p)FOmfr{ZmuL`!{~<%Fp7a0IMnZ(OK>9NH7;hQ3vNm7H7& z-jd&{`Q4HEq}b=XcrQw!Bqp@!t!bv?!CRxObP{1I34E|`30%P{iLVu4NANxl9XhP4 zeSR!7BZK= z?^3@ulE2UGIb}%xzP6fvp12H}tv=sY4n6tgE?|kOCe!Fh*h|mYF}T#P&|OB9uw3Or z@>Tnl)%0MK>#t{b#;fIdto&6Z10i%eNGCpe0pc z@dvBf;=OH$$3Jc4F~%j#%*}OPSuHQlx#DK|@Y=qf@0TWjFCxcQabw-a=GQAr)~Ir* zC7Y(X{nz)H3Fs=ly2ii^+FJvteAS{SpEG)%)oUU&B{Jq-Mlz zdhl^(ho>01H)5e;{6!Cub4gqe`y8-OFxk1<@2~uoztA?)^WgMmZ3}-Re-RG(P;N#1 zA&zGdwn1cRvWDNh_T?XmHg$>WE2f0>embm~tbnE^_CP--@M5xom<=k5U;PTOMs7DA zHknwZd_d6H7cV%FI4RGYX%7!Rtl0yK6KN2|&610w1c>!Dq;y=;I!PX>G5a?>(lWxm z{Y0FbhI5rtBZy-sKK^ANz^FtJbmsfYLt!X^YKbVVYiHSp z`p1-BNvbQ0`{>6_tPzMAX)+0zNeqwFRvgB`5g3*AiXgFHM{Ae}?XxpTN0^z0Qa3Qp4< zKL%z*2~W44jwOPiW2~9Yzyg}sscC4u0Ib5t!$TiDe7NQ5E^>DlboWhmpY~%G;oB|h za5-(xU=E?rLS5pQ+8n^#o3L%}x)|C9Q>(~JsV3LpnEBh`(^pv55 z8qTid6~>X<2Y7hk*0pihf$RVSkB?tEL4J!Lx60Evf#tIBbfHuHI&(*1n?wz zr4>r3NJxp(4K#6!7&D3AlMU?Y=|R+Rm~|?6p;N9i(L~q*l)O)kJ74eAt_B|C9QOCvbORkgOrR}j( zt(QYrfJxG|Z!-);NmmZH9S*;I2@0V(GU3o~mluAnhjsZUs~z~c?!mWJmD;9}=^9rt ze3u_y2q$r46ACLQfPDC2V}YY8IwEqg`-$XxJD1jjHm8;&1gSuASa2V2fOuJp0$`n9 z`{)I|&ElgU?(Y&fL{bEy`}~EUr+bY4_(-0RjOx6EGTtoUeSW*HFMe*yWRV&*)G{1b zy-OndS<}#C%B_V6$Q_5l#9Ai}5PSl=HF!tDsKaCCE5_GE;`F_E{+w+H9FbKH9C&@7 z;h|tYpjl>|1X%s6)>+*l$BrE{hI#61%b5`^QFI^kHLM^ql-GJ$d<4U(tJjIzdt&@( z>3370q=j@Hj!pQ@{C5ddSHTf!-YY*oObsuuyb$F>&v;ti5iDt?zhbT} z)dl5$4a8`X-=WdH^S2)f2b8q-*ID^mqg1z*{>r~-!UO)(w6A>SUryzL;_`!*SlJ*! z>D@F;R*SP^kA-b7>V^^*^hUj@>zj})QMG^N{o}*gosypJx}oIP-_+UWt{m|b*MIX^ z@mBxNse~#L$S97$08vc+hG}i=LxR#;0Th838-JM|6A~i6yo`h}sLQgF%Oan0&gGP$ zVCnsx{Np8(%e-jCxbQ)OSb~9+f+)OZ0SwJzTDl(+62hhRW)A|5M(N-E$j$r+icL$} z_;l87sy}!m_xm6F0ubeVxxRrVjGP93jTLWNWE?-jsfD~a@g&5+H{ou8FBZDU5HgDe z!dxI*)KOZ>86APX@jWCa#r$di`hDApPgtyxTv9C#V2wt2%8eXVIUXn+BWsP4dfhR0 zzKm=$GFxS!_Da`7>7Ec>>(aZNQDM~C0O}XB_{fl$0ErdbYY|NpG$i^VDnHN2F+7>$ z*#MSEguY2r1+eom=~YCD%WPl4yYtxPbJGYZ^z6S1JVvbpM+z%hC`-S=$)&Y9uo@G; zVgh=e-C>afs+}livgvvm<1Z&KFHfLmMYN}CJ0+cmTUS=H1Eagihk+!hvKvUsy!7kaGuc3VG&=)_ z!k5$%mT;obe#~ohb|9HzUnyd0&vTGG-a8R756NdbIy!c!xa!8hZbdv@5c`_-o4y2i zEmHJ6=em=YHcQO@7=+Wp9e=^;53Es^JWeOMi0;4$aA5x7mJ*Vam0;;020?^a@1{Xc z@X1j_$Nt)bM23)tH%YvU$moYPD@Rpg)8D=;uYC-JmIAmhgq%TlSUrUa<^n*9KIy%F zzbuJbt59Jg^6RO0HKN%~a1&%Wf&qf&fP5G71aG#zt(jpkuZ$1@PW%dec4qw&{l2sA zm-mR`gfD_FX|;4*6gZmv`n3Y0WfjDL29{uzjaTfD zEu4TXD5L>Lcsr~ziDtTZuJ@DBQQxV_B*tRi%lS8(myCw)yzumwxDoOUBJ?7Wayzo> zggI2g8?m2mGVQ&|pme$IJAtA!XL?-jD8Ga!CkD7;nHwx7TE}Jr{wV4CI!6oXoWwGBBTnTxQMcy?4^m` zswxnY!R&Y(1rmyj&vgaCsK{W`uhgj!PeLn(o1(;TeJDg%kweBBdlm%Efzjtg!e5T_q~L$TRDLsnv#0^mg`8Q z>JCb*oWx~39)0p8vJ_0Lw51f2>pvE;zjS-^?kC_vlG2ByCFjq>K|UmT=q8VuHh#SQ z2&ZNL+jg{9z- zE%x6{JO+oXzerCQu`o#<;0LnxoZB1+c2l9I+C$b$;>t2G8hOu^h)+X-tawn2AdkRE za{T-jvbJy18Ri2K=>yn}oNl4^isTQd>g(sVpK!4_Z(uO2uo7rU(BI5=e@a*`H1SDz zJ;_g==$h57V*zxNQz>3~N%G`UG=kNaXg$zpD@)|Xifg&RU}g7fK~nO=irqfZa>!<2 z#sASXy8r(dA(5D*Q4LN7WWX?4wBU7z z?md0m_`|hTx@nf=L1(oZ`^p7va0sgiZG{;8kWKzvkJ|#doazgOQgQ;p1*JCwy`%!C zU6p_IJNZRcF)@#(o*{4$2`MR6yPaFdu6uw{3zFx~GT!*Nd$als*6S)v@~ z5X_}=phCFd5pr_R-rw<%96kgd6^cS_kBGmo)nUde?i4Ur^PI1VPOizg@bL!WH_1Jv z;pjjIqEw2WHSf+(5ZLjd{?sqs3xqm$YW(XCLCdaFb(#}Mt(p)7d%Vi2yDYc~P<{M| zH{GSOM+fJCM1x3;A=p%DVxx(taD`xgVtybcvvQ7zE6ABiF~}PS{bULlL{^rF@_UIl zh3O~RSmWk*W=v`n0Qe|E&}V@~o++wd}GzQ8$M`qyJ!J=?ywmIoWAyow=EwKV^@izV3R-#|aKW^r)tA|DI zE)UII9|@#ChoZ=bu#4=a$X@U}4K||FgefvfeYFXyn?-*;t$#Ctr>;Z*O;8s>R!cJ- zRfI2uG2c%ZIowhfdnqvk4#TY?@DY^+!OqXmi_iax!Sj(w3+oxLnPNa9EwC!~=vo&K zD~$%E-*JdA#0f(?z^|*LLtHm#RLgUI zHhEJT2ohV}^!4>4Z9E2aEz+qIl2m&R<*114>})kPHNv&dK|+w>y4~!!sMBB=w|=&9 ze{BM53qQI09~8F9BX1yR;+8}d9K=riurE)382%FmIZ}$GN6pApp_jnHM+a5MVT3QiI)5S2EPKMMSLNhQAaoMKiCvTtnC`3LMDV0_ zcy=k8lyETHec78eR?JibGMc@Vh!X1e9g^4#5~3o_q`Vp<1OtY4l3N_LwaqO9-A+DZ z8H*F*aDtCQLwf;ezam@-Vh`d}t|UhQ9v7=g_BG*N>gnDJ96Q#9a@le)u1z`=0>a=C z*h?V|2qsKzjAYmJUnB*R3kOPKR7BVlaJ}7q@zIqebM$q31vfOR3{D<-i7@z4aBw%y zsXT&uBo%Xr0fBs}lAud=k%w|B6DUkhHWkx=1>*_cAn2btqrM zc{PQrV{L2)-=p}X;Pq=Ru-7^^EkxK?nFj>!Fw*XkbTv+;@3ivyrS9P_j|$j z&w1<5q%yP@9<8dg$hRh5IhvRYlBXl4gE#_^h3Xs%VGqEG$3vtk0;o)OX&e$oS-+n9 zk`x!&Xx{7pASpI5%#W6)TX;yKII!!vFLxP`07>n2p-IhG952E$U&1?<4IJ?pxk@r0 z;|ayL0sAZD5O&S?}Ww>-msP)QewAK%X z6C&DD!V{|M>MjU%P>GMwc&+u25FfLpBJ zAbBG=XBI;R1nozP3Bg3k1wydz^@Y0JK@}r6Ok5W%k9Y~Qy@CZ52aKQ8;^kA9MofWz zh{ph7(9i`6r17c1FKmrVl@X5-%e|Ot??_nvgTYmh zW!!`*IqT2-SpAhox`YupN$eyK6(aspHy^O?vIhzcL*j+4>; zl(H9&lOOC15|Y%@2tztNEs~6|e)Y}te~@>l%OK{Fc^>`E%2D#3)t-UVNl4MT@owS; z^CYovfNh{zFi%tw<3JhhPu&8I;TJ*MlN`}FunJ*q0jsLk`y~P7 zk(3Y=o?e#=lp;l~Mt2dvaYC12-a1A}q#KP~D@C-k9n1#uK#*`iiQxhcb^`h+2|_>- zBZWMNF(QR5;1QDAK?=mgJBk+zk_+JsK`4ppuU5P|JgO7ni=0WJ{$Dqt|Ad~_CC z{ERP+cu9gDLmJAE=pjtVt&E52XTUmE01~|gJTd{gCQ;hJEOzT)0k$_Wr*IpDH|v92 zu}1vLzCxL9JFL<5?KGVtLMozGyU%i*kc?gHQ%(cUk+rxeLd#z_{zjz*GBotq8N zuPgA-1pKr|ME9CEet#0d!iViDhKA9^>H*8T4y88`I+T#_IH-^&nx>&;c!7vCtSR}$ zZqQxkc@2LvDPH%3*StBhB769-J?-;mF{0VR_GIOU#6?Y0GambuXp{(uCef;wy+7hn zqADWbD?zOcGAI(3{n5OC(+5uPmE4-d4eV9xD;*&H029ceM9SfR5wUN9qvQYf+JyZN zMY^QdrcxdJ11O2u{Co*w=nxK*k0%xcW;lFYPFD~1G0;y}zMh~8*+7I;naPJ)6`@=i z4;5&uUw)B+9ESRGW#-Y9Eo&KzAPj0#Zl=}(Tod1dR!W|L-vTcx$?u~?z7lEoXdnPf zSa+slrud-#fdPU6;Mik9_>h>N_-d&6TvQESeYLF68UG1}IzEH@*->PD+UoajJ&R-k zeyb(>zVg=p^}$HODF9!1FW@J{KvKcWDe2J+KoEm6MHJXRbLuPFs0wS{ky9_g!Ad>sR z1>fSSGPq5{g+K%m)|GfS-O%y7D~g$G0T*DJnOdFUkAYW|a6kC`hgc(6PkzKaiX<|I z&JTiO%Wn}-0enH+q)Tmb#ZMAwJ2~8THO9Po7YsH>)BAMerDeC+&wvEP;}_RiwjfLh zTI{wdx3QnNY-#x}L|4mIcSS%Gy%woS0w4)@1mdn2ep?1^k9<5kEZEQWUx|q95&(il z9(S-DUQ_w{fDKP)2Z_?>+7V-jYY2qG+El}Y66F_(4h zy1F<_3p~hUxWL+%j|4u!yl4G(1p{Zt;cyUX$fc^Ny#0pjt|f)7Z1{|)kP{jsrv-c_ zJAR$D%?%_-{Z%h4y6a$Si3(&K$h-9#uYR+6WtY6WPWSs&AvGf-icX0H%?HD|2Ta6j z{$Hh#|D{X%A3OVhO632K&!PDr|4Z|4RD=JYSVYF;Z}Zjig!mCKuka%XiV>tO>^R&k zIQ8rMKDbt<^pMwvp#O=^&Jt=U66&l7FhLgrJg1r0B@&^wqex3GX!BT@rS9(OC~Mgj zvEl4*Pr}265^ab8+Ha2iGR(5Pysu-^CL}bftE&T{5gN$4`?|Yls-eKvBFp4&}91+s{J1f>w~fkZn9Dt0st}4WhsNu2?7Lyvwd|QtORn7 zyx0p#4Uoe>mhf;R+#MnSvL6WRhqp=cEdWHM#)2`J|)k`W}_BPcc$%r?{9wijhXj-pYxpaKj%HqbN+|EQ5up*^wr0~;tNHJ&W-e&h8Ut3 zN>lH*CkYi56cpem{krK1$u$Tr>0baxZ4QqfaKp>6wSk^jpsz#G7k25(QjjyDi;=z? z6)r~p!UHSpqx2w*zE=T8^@j&6;KG)k^1VWoY|z*6_KXVb4)|(HB3II3&9X3f@fAqw zpOyDR^dt#AD+CerZ+}2m<|8Zx)AJR7UmH?`Ab_6NfDHY4Nafha)xu=Z^BMFdQhIqF zJwk@{#cMOw*Tv|vfycU3`gUs&J~;BOy^4lys*en%3ZZlTZUACm_jA^BDnv0c>aOhi zt21-ebMNN;7RU^DSPVsY4G*VUmN>4nJ+f?>9>Z&@G^zTeNtf6g4HCKrUm|=p#Gp%7 zvb}`3_|(>xD1^4EKIF>EXdz{%!?#UcZrnIfe31j{qk*hI_>H`-CQ!qf9*K2Px#g>o zG%?`_+-@mT;r{*uk4AcXc@o>D;psZr{=B)lG%x$%>^}GKa4{SXcgrLXC>!J3-9(0q zxuND?5ekxdliDkZ#F*XPNFW<<3k(#{N0)K@&gj$_kpRh;OJ%mk(tPle2|T5#84Y#G zD=R0csP*W+h4(IVXN|ueE9hIs(w{aX;`EZwTnz~kZg=CWudjdhZdp@H%TO=-q#;rN zFaqj=$z=5-{QE9Gw(-tjC3FJioodYl3P{u3F_?qIOI&t#c2J2_c}WpCY$QI7>*`1` z8|LsrXdUCBmM}kmeMS$?0r?hpB$69GJ{urnZT4r6Cs2VJ*w{RY+LJtV3fuPLg`kp> zQopYTRG1PW6l*4hg#hCnP~e-&-htD9+TOJkU`a4$1fH5A+XCx-8HFNbenS^mR|XKU zn3$NRuI}jur!x&s(2S2uoTu}l#gf5hgx>uJ52S$!^rC`Px>=5cQtQl;K6}jOW~hgn zh%XBD8ko8=3UkJNMYCQ&bsbcWjg5`zE8T5fT~!ywv*r%SHC>2$7;fZz+UlX)b0bMk zzOTnX6qo!j4oagB_s>|#3vieg4awc@Mxa_WV4yx^4uoH=L#p-bogHx=9MiO)uwW7k z^vL-X*5Id=1!4jLt7P_stbRBMV)~;ipKn!3?a;Ix6F;QT!=YKAVw zSA#FXIN48AlF;f#Y@Q8(>CLk)KFrHL1<4mf;C6laQdCip^P-JJ|7BgBJ6+7x6mDE= z3=A9eR9r&B)x(3CL?ZcVikp<}U{673PJb*m1^#zQQBX6>eAq`lFB5~sN`iimQK>-c z7!fqd1RW<#ib6HTJBEh^;(6r+li-$t6dFcjQdTme@Or66RqXQ6iL~ykn&Lb_E^Wjf z17;4-%3gNeQT)e%_k(_{-~%0DSXkSnlaX|h+`A{j%*fC-<1e!^f{}odNfM#onie*6p^hdV8+=RT2zS<=(kV zmoFQr-DCE<@ECx2`pp~Wx^kFz(Z#clqtiB4aqJA20?l}3r}IZgwES$ z1(uITQoCnWR8?bO$+XQ)b*?UDdfIhk7wh2cJhQPOoS3W6?m9d;8{iriCJKe4;o;#R zG`M14`G5D0%s6|{Xw7}a?b$%p2*=zNGS-$NdPP6jJ_ao(&@w$Ol|mrkSr$L6YB9zj zV7jb}1>hZ5;-zHs?tt24C=r4(gXy_Bb~rJdRaivi>Fn$;`Dsjg^*D^be~eiHW5p=v z-ENl59#&8U;C?bI7_@pEqQfJ_3~*|xke*!LMISQ=6ZYq)T1)dMOo0h!6moB^NS@0Z z&?jE{xbehH9vHabs(zuN`|fnb&(2;2?FP@TKZ=1Fyq}#t^Z7HsAv=Iuj#GvE_3NBq zE7+z(WP5ICt`_aJUMX<;DahZ}&JG_n2V(lTu;AwJ&j&`8nCpT<@!(CEC=?246u^ZE zTV>%jpnJjfc(#7|q6g@%Be}on!ruAyt97p%*&=&r-?YiN?=~+ZkYu#G`S;^KKLY4@ z61vO^b`Nm56e14l1m=WDo;p8@IdbQ>KhMdA=tz$FYP<>f)xpt`K3-te1*rkPVw)!C zgs~{7Qd9OtB3*-ng<$T%EdazqmklsYKq#O%Q1h7$s^?>8_Ve?L_8}(%%meElcnMQ^ zygzGZW@elona!rm_I8gaP@sDzvlGXC*>SC!zy4}aW;_2Vz3>{?9CTo5dHYrt=JT&{ z#V1b6{0YXLr;h$L{*lC~aGflwBWclzlq9f$JXXUbY8`t2RF1@8VDg|Ld7^_7uDkoJ zyJs-*Qrr9Y@*jh=fj+^i_~J&^*1<-NCUwl@SmeDJVTVTh5DO5Hza5qg7($fzons+2gGxwvTVMyFr7K&gaiLz|%M=3Bf2{jE*uOqIQxNO*x!~$`LUc^Q;ylwE{Rooy(0=Ar-6ciNXWoNc5vz_+S zgg;Dq0qe=4-bz^HHD9hbvjUMI-qtcptiE9i2yLjkUbrBbK#$= z$=PtPEd`gc?^r%eNaF_`0`gkAY5^vK!W!DxxJT$0Uu*#bLp*d)k`YYGu`h#Oox;{; zbZbDP^Bk0z5Ip<$8wFcgs0=_bgM>cStt*tsM z=*hfX$DL*yPy) zx^1kyKLDUmYI{scS(!*8#W^UgmzrFK4F`lnz*o&wG_S2ij1Pl>+haiwi-o8%GP%UrvP|F$c-WkH}K2jIu z2IF%l5`$L5CLW~&3mVd?r?>6}er-e0=4XAD599tyz1r);PeEnA<#D*H3y$p~=Qa zD;e+EN&WmtE}K+*G;c0?ih{jNJ=vS1{yAnw;@dpZf3j9MqbSOw>KMI^a^0GAQO;tc zzlQF9`~Mscw2qxM4qo7Y0SGrEBzrt>^y6Sig!|IW@zPpa*!oUggzoW3SLVjxr;9xg zzMr{~0FVtZ19iW45KSPOp#}%2#Mth1otVm#kbQh7A_ccEBB*p0&OG}5f**i8$#Gw10InAO9D^z<8 zqok3Esd7Izn(&y^|>{uhibBDHX)0 z@n;lHp!ltQkfZ85^HF=~{&x_ojKEffYJ)?J^f}RWh4oPFl93N~ryA8Y;2{~@yeDZN zgvTWc(V5w=t58wq_A*B?SxqWm`0N*Dwy>qMgx0=I!s@BLU1v+1k+FEooRVDH7IGuA zCtuspS!O4l-+G=4tA5_Fo;z-}Ds|)Sul&|co7#2dMrc~S20}Od-?=QxKNwQI7+$qT z9uZ)$Y1oInB2_+EM?JVuQo@l_Vu@Z9LWWBjXWwh=pt3PI&ha8$k=o-yl^KNwRsyE- zhto4F?Gk(Yg^&j5^-1@Q?+6DPXkl>d4YCPEeQ`9dL9F3%;LYkXmFoX|q6yDGy!FK( zVBHX9$Uawx-6kE_=O`3Ccj%cYQ!Ku@dSvz(YTd`{u5y@mf$+BKYf!DNqWxkO%MFe}y{LS-MFJ%6UsS8UO5(Hpnc zbpEHwtelvbEe;;tHg~L{y`r7`kP{vl$Lq5gi<-!4bPiM1XS7^QDV<-kR!B`$G12FSTiJNm#bH`O+lMfN#3yAK=LjiN2q(P%I9HY-AQst{jO-(7u&Ilra{yZw8s zR(=}qmg5HHzy?5}mpD0Eb=V za_(LJ2|l?+3#1#71KKloPaTU;d+H-?UKQ0HT7Q@Coe~O5kDK6p@O9Dkx6|gv<%TY? F{{vP{R$Kr8 literal 0 HcmV?d00001 diff --git a/doc/img/euroc_imu_calib.png b/doc/img/euroc_imu_calib.png new file mode 100644 index 0000000000000000000000000000000000000000..75067310f4bcb4718904dc15fa287f9b6674b9c4 GIT binary patch literal 615342 zcmZs?1z1$wyEhD?fTSqWA&SzC#83)Sf^^5w&4AR%&cgzgZh}6&n3^9}- z-QDnR-|sxn`G4;@Ui%sbug%_TuXV5czJIYlX{afZ644Ri;NXxdE4|Xf!MQVzgM$}D zh!6bFg!1dBz>nJ=vdTJyz&}4i>u?;LM>xu_Ug~(KZ8pK`Z0ro#&W)W0eKY+#Q?x%N z+!mCz%m@~3v2)V_CJ0s{(k&9XZq%{Y%Y85MF=}e#<F0NQHv`hSKDTp*3-Lz~w`(D?w|j;OTDjX^Slb>gA9op{IF7zT6m8GN+e zjSQnflKn)nR6)|qJ{M)pqnTtV=L!>u%nl4PN#dEuSp|2Y_j&xYSN>}o1}7`k3ivb>>Hn(Hw^+VFP| z;56u&j*@uN8z5VdG7>M3gx{9+LkVIa)HPSw6Y&3B%dQ`bo5x0TcRz$3Yez47OBgUc z4POu=t`b+!U;mpVyt`N6)9u)#0T>i5GiLja7L5=Ol|US-jHx z^5X|g@*2&x`+>TVFv0!Ki^nVPZk=W0_#V#Vv5gGPu3xG?i{q{g*nb~)TCsEPPeQ;* z8F7b_C{!`K_kUUW%d43D7qP1ROzIkC&-a2WV2os&GC^Xq11@}&M23kC+Z`D;Z8C57 ztx=^%Lv|8%&FNLwnKy%Tt=`k}*&40h!aahsjQ{hxr);5w;kh)S3s60uB7=7I=Dih7 z4*h#w!{zh!0YQZF<|n<1TTC0uDf9W!el$%1^m&%JSJ%74+lc>VJ;<3kV$476S%1(f z3J13YN6&aZ0Q=2&y}1A6b3QVBn8t^)hxko9pTG=RDO=p#=3_WkllvD9seknU5~z|; ze!3`4?uTzz(vgdyd_EK!I617hVjg{d%-RFZN`DE(VZYVgV=_lpT2O$ueHB0*uEkp9 zinsWmTlD`9F{+EIGw!a4sAvpp0p7Z1yiMiKfJrn|aQwNIRD;s7DRcD4@Woqx|H~Lo zSHjxfhPYHjx0#3ZcuT}J7<|#-)gLO<*WgXMR!&M%(_)R=@)k2QO6k<361BsZz}u2f zg*W^EUfVLSrcQZ=rQL84ta1OJ@ga%e2e#eBgschsZ?p<;TU#)JM#(rXPLm5Yn_60H zy4ejrx{Qp9I+dMrK{2mUAv-9^%$=!RyfQ@UhzQ3VF43B#R=U_8_)bP-PzOu|Jl7gY z<&)3%o>Ju4zhjVMFiF}n_hddEMTWTjv-_B&Sf7;2)P2Hy5AX1gNR~mqV)|!Xi)jK3 zk(JG}KOgFweB!ETWN@gDiy_5{RA5X3``qPixfGnfUaD9qF}vVQOj_3De0YP~i~U)` z*Md{gyeX-J7C`sV(7eOJAt)BeIIVlwxE|~8JvhGI6?iixz|F_=Cy^SZrJh6RM%PbP z?or|8|6^@Hpw(*QpIGdge6r@e&SDelDa?|qz5#_N?BOrr&D^yIZIt|6V7ZEO z3;WX?l6LIyruuy(kuuIym9MXoxvK)DvJb`8U@O+*uT;bhX*@43hY{pbZYUyBeJPRiHreEFI5# zPbDMVr`Er`wl?I<`olH`hr01J()&P&+-gUbG*pwAt@#?}Hy#OG!8<$`)qS7z5z zvgG_88hcH5bJhG%awG6+Zg;wiu@!a6K$k$7P7u9-A#WnzY4#%Rx9!2({I5lg3JV1X z1|1B_Fy{{6Ufern*ok_3eHP|+d3~YDO=X*Sf=&WcbN^PqIaB~j!?z_mXyG>0 z{{8Ld4VOn{{oJlrR#M2c9&5>(#*!3W)q2RIZ`LP`3#i^buFMO`fa{zCjW16wFI=a? zL<76xVn~osBBtoKx-}s(;?gJ-*5ML*%jZ6u(ug{nevKOZnKB(7@cH zeH8GZ(y$w9y4E_Dnrz`nQ(e+Crv$m*>lr6O`Q3q;}5Rishn9GTxQo~(^X_x z^?`HW^S3(BVT0{OmvQBC7IDw*>gaAXOY$>&}wnQ&i`+9*%9lc)ZK%vUnAUt~^~ z?}K-VTRx6US}+{^J6ryl zG`x`2_LUWy{QaLPm*q{&_vfP<0x`!!+lOx0u4|$bse`<_OL27qG?}#Tf!&_@io}r0 zd-mdNO_dnw?T6m&Ditqk4oIgDGg?|1n}~NmF#F*0^5KOKFg#Od8BnHt0)lk;F8?!G zizXCZ6!kMq%ggJNBD{mJff~En8aNzwK1(yBM()O7_w9G~eo#%X$spHG+cnKa?}Hbp z3rE**vldrI*Rz407aUQ$C7DfkWPI)K>OW^SeyUalN>)u!mbRZH&kvVQM5 zBlpo^C!=orpO{E{il)5lm|TLV6h=d$_3PyNsmu8k@oqg^{8#BiL%+ic-*6Q?5-l7z z(nup*VuIsr3f#p8>EIjK!Ad19ayNuojL{@;0s;#;|MOp$JhcnestSk0pN~3@ad$T% z5Kz4nDx%gRxEEzaM;{Yu0s+pVTfp1&m3`C&R*zZTKn<5;CwN1u@l1JqVSk%5Cg1xY zuDm1DZ>z-HQWtDOCx5EN^|H!<>}k23+ulTDE@i>uYJ=eTJG)BtmibYk|0pM~QgD{& z9773P?*(gySi&O*r@bGPEA#!r*vUk>QmKS1$dTaU=#Dzw#cbCTZ1i*(zhKurG7+O#+9@+L0*Vw=@61JTYQcj#x+1F+v;#8nX9wIxm-2!*(;T7jJ9k zeLi~~Qudp$-Hk}6q)^vto<8u)%^`u!5?=v@ilax(u$}a}7Up!{m}!Xj zf3;g(?XOs(DCAqKtWFk(vV(QIuPfTH;XuW{6o{?(Ey2 za-+SObNs+;a4W_c>FT}1sBNQaw2@qk$$Kx~=n4-4XNQP$@X49KqYl8{`M6r1JEz*U zDDW)qc3cn5;vP-zFyZ3f?c6=W#bH9=d&?gE4U-!~=0n_nw{76D(#HuCX7i9+bP-;o zMDLx@0!ABBBxu61Gx5FztuGgNp66Cy*f_LsG#PR=fHJQCQheb^z>%0#m}ohWg60G? zvHC0=rOPdWfPZe{!6r+m-EqG7SUFpS- zL*DH@QIV3YneDx`d3J|tch7~irA3oC5ov1sL9}VDpFQChQkl2q7MtD;6=RHfAd`|H>fs=|87Mim0Zibw) zgmklLpm^lp<(2rQ8RFCQd9f=xcYMQYFk{I%m8$dW(aqn$g2PFL>7M`6tnFn2#;IST zzjxz;b3*byaB?&2^9U}q6QQ0ou86yXE&ZLl1)_^|tZdx6I7H4ow!L^-aA`&|%`_c2 zbMkKl|I>yuLYr(J13f=PK0K9*zyqA&gXbs7bjs z)q81d2!?~(-(20gE;jBIDwdM0n(lgSA<-S+sMQJy=9GS3m`$HFY#(oznAA66H}jar zgdj$K9v)OPQ#?xvT3>s<5j|mvDnX< z98s5LoUW1_3s$*;(t`HeoD~KfIX+ZNlO7^!Ff7y*L8JSmZAzD8| zvLjG|6zw`fpoKm`AVmW`tCkzk$k4pF7PtDX@$tRpn@jzyy?}+uySJh|a zEt>zd*Z+N$w~`9{LUrYuXUu;6EuCKDrYAhEF+jI)>F>4}DZ0QGu)qdwniT(>^Q|OO zlQMlTFeN`chh0LSn@W?NQiGk6pMmUaK1VET&o&1oQTU=*L%s&PxiFmtaJc)l#g13@ zv3~|mtM(xZy#<`r3~bJi?JUpY?mmm_DVN@th_b?Y!O*1?%i54QG}jn?HFEGejQw*A zYmd%khb4t_to6yh$tw6b=_Z$5w#wjDk&bK=xGO`-_wDKsOZ@An!gQoMCA!n^=KN`* zyV#R@lU1LwQ$?(vT&y1X0G|eCW?dKz6;9T$y|vY_3vzf1DnJ(*!>X*OUuDpDF8WQi z8d^!ZYTpBc_| zE$&ecP6~|NK)-mEK1@`cpq|b3co7{(5KoR4?ywi0(oJg09FOHi^dB3;Gza&RF$G)9 zWMMRs3I+xStw6v3MTPgr?Im|whm;&0PK&u_|K!X}#Uh=bZ^eEAqh<1*f6tKt+)2#+ z4TvGF)YMOV;h$G0bI}jj)Xc>g9xKOkh-WPhEJDkFxk(k^dY!PFd z93S%aG=M5G8D(gke_f%3U4CEsc=~Du2d2_Bv~L&=4wc1)8@dG~>% zb8&Cf@9uDfU~*#)NC~#C3YtbKCNzDI&OkP%pSToDNwm!;bKwofDz! zyFJ8t6$5wnKaD+PFC=kXTT!h~dV^hzw; z+}uzBw2=xxxY@&vfVi7Xv-XcS<768JFEp0vaMmrSIPGf79BJ2`ua~&>@*wADb^=7V z8xPcKjmkI-%`X(`ssj=g8zTKm+~cn-VSk*sdgIj-28xsJCJtU}2fS;T=@Y5hAB$pq zX?m|ZUCzf0k}@>mXoygURaXN~KC%XoLZgn)4=?<=d3b&omz4kf-5v&n`P<$3m(I@4 z^KAsougdg#&;9oQDA!^kX~6tV)Yy@Wh=^#E>1h_}0G~DIYU!X*zJR?5v4Bf&5pvxY zV^C3=9kXtrE@uLVX&&KZDocnp7k`<4d_>CrS zl7Ng%G*@}uEt%^@nJDVU`8&Y+Am;)k0=yy`^D>mWPCp)wqtquSq}S8bN=pIIC_(43q2pr9zp(W z&q{?~-jW$alEYaYJ(v{7oLMJ3a9@jC^V$yWN*+SBE zkvN;TUwr!gHe9Pn_+ikqrcZm`U(^cX?o`ORgSV*gapR*f&#D@&*CdHYe*-0gIB^Jp zJ|J<|$Z(t+gIYB>o0~3iI;dXs<40|}(o>E;DqT{cXCIQk3+EZd49OFbZW=T%!5~kT zzQa3!{I|TaQj-P3iZYNDcC@V9*8PQBouxBih41YT}&=42C=DMAMCM?oy>Dg<=8Q9M${+a$`kh* z!_FsBNJ()kue{kf0QUE`nFp~d16*y*i@BdaWjkHrMm)ss1A~LP;0h~YIva#X$yf?q z`_a*nvw$B^gX(sF5?3J*iEFe@xuJ)7`xRgnEVuPef3=}32)v`85^C*bPvUHt?d!SS zkA73*Dc8MRRsHbAGFLHa(SERB>2VU;XoX-YGovOTex3PPU{nu6Og*lPzcHZdDKp`_xFiAx6Ff~wGq znz*awY$c?AZ=Z?qA%gdFnbJ7eT zPeK(H6$3-Vmkc}BSq=)cLEKJXUTSR2$0{_A(-CXd*0ARc&_@e3^l-X9r-Q&=Yx|lw zl&lDkmJ&&w>Q8#G?JSLcJmEltczbMzRevvkzHo zuTqvuhXscF=v2rV&6aepTqD)?IifiRKmO_Ae&U_zHx%F~emrZamV~b&tkL#}Al*@- z*$CXdMsg=W_9HT};Qg6~3|udkhpiApbvKIj9@iQMb7s`)^gy$=t_b6~32@IN-OFE^C(c?L_?N1)9F zoHT_z`MeCf_wsARXh`y@FogXR<1a{ht)7_ygNN^0E|JQpQa%ctg6^LWX;X^KyFiGa zJs!GVhc*~un%CWU6Fn^2q&2@E(;o5f=w3t+pS7yR_$NvgiQKucSTVI9FkF3{YHKaj zJ-P+05vjgnaBUcpDv9KFg~4bE$eDgEEIdXn?d#wprWi++Q#y+MEmEEJ@)Deyz~m>> z9_ko9TYJaWh{{8tsh!Lb!wXNzs}QN%k3^X+87_(AGi>>xLrG8-0P?Vzn<^k2#7{&T zie?{@^q_}aohm{%Bk#>URgRrh03avOYXLaa*w|Pp_BH_-L+kpw<1r-%3}_52Y;5j~ zIX*YGFVrjfHZujZF80Dh_QD#R36+620e!$m1vvbH;Gt&WpbH`GQ2*b4HXiI?@pp=JG6h$#-)8EM$rsOx+yYyE3Rn&j|c350ehf{v2(L8?awD4)_0@mmP(ZY^5{;>D*un!1X zhANGRE`LEdP`QRo*{!5P3Zha`zGyEo21|Y#RjIWA-racsvwEw3ATl83px?a(B|g{a zOnw}-$c?4L0i~-gdux2t@)mOX{4=E!scY+*TsV5PXJeX&q_uO7_Hu_ia~f|o=!&t} z&}&&^J|Rx94+H4qv-Vo0Md(Nw#NOg4MlrOZP_K^-_-g(X?yhE?_((asxY&NYpH6RE zI%1%2rS0%N>N`61V>HO_4|5(8pa0bCOdhXxv%#gKbw0@pKfaSY^-}Pg>d+RnfXOP& zCToRODf@fBw}ZQ-Li2AKecFfzuU z`}^)9W@|6rZtIrlIzu4YI-D#~i<=a0=uR5h-XMdwfaF)E=Y$%*8~GK4mK?PDem6aF z2&0ME95UE|?ML(Dpa%Z&0^qk!kRe`1T0m0ic44@I^!8)ToXl(fj<>_k+YUr}V+8y6 zg9muf!?uMJ=1qANJ2f7%XJaVod zr3rD$9AkSw!o)oF%?UTez*kTy(e-$hh9QMJ4ur~xDSBexIsJ8TOrykzY!y$0xqq6F zvmN`r`wO^C;DlmOY=H(muJOE)y_Jz*ql_W?#tMJQ%6Po3C)9t|?K>holTan2a#Eaz zmS*1++X&>+_KLtU$8P^Q<+^gNl=v0w7?IFx)7RhsyY)R@-Je($V6zCOKtbt!WZ7vJ zyE@2dqB|3lE^tH7(lQ1de)!w0p$?ZVa%zLudFavHtKzu{vNvhnBX3Zd#q>RRjbX&P z>1u4m#bM4*mW&x)5i?VF^r$EIi1uPIHZ}!QEiCkrSMc)|9Zs7oP9Uus8_N}pyet_* zQB|e%Khx9Kuc@ZdC}>h?{tN3&OnyyIGc1THl#Iy&IBvGd7pSBk16o>C$ikdK5`%|y zrVOJ82yXgE;~T=KPHU9KbL)XB7ek2H&y59O*)3EJwQPM7R0R8CcIiX-`k$eN2Nh#b z_L))M>gKO#vClcq!*hrc)SD$&Ff$z&ScOrWn`(H?bN8qskn!EL8^OnRi^RkGQ)t4+Y%({jm@ol~4`q`)M255@!$~>&M^(%Tjj>Fempp~tiD?7{i#Hp2Qw5NT2)hLmVJVtafIb09^bcPpfCOM^$*+W5xw3@J*E;C<|##(1vvX z(KZ&I1ac)i(DJk$7UbKg=+K!J%Y=-$1H-TIG9Mittyj{vojGtIq`y~-OT$DgzUoM5 zyvRCukC;{xc4BDtdG1(1+q~=Uioaus@pX?!`91@$lpQv9TpB+J(8a6j>pwU7o~ZFy z<~gM7-KF*d3jF$!4`NPg#j6QCIMrNT{XzK6|4omYtnq8fqJar6@yve&B*UvcX)oCxBV&qxbrm&TpR|3wpLEp6s z^iIeBRLcyaT359X07F4a%Ivwb{w&1$?55)YUqG7f*-zMR&ozM!IbgYqLy!8``KE~Go2*k=a#2mwItI^N&r0-59 zW$$lEj{V4sPy#_gY==JmS}U@_=@C%w1M3Jz-?1M?cHlF;^3ZkCv6oEM5rxIX;(YkQ zxO9>DQ(Ge2%@^CwFC!4Jf{|}1%N5a}&7#jnOIPtdhjdCMycf>FvGb@grX~=(j%i~OC&Ly z?a8KW{<$cpD~>fZ>D*W^qlN))Rt70JNOhMR#8&-Dv&k&1P_mku1nrbIFEQ9YPRjGJ z&;IBk8(ox%6In;^4#UumjfndnaV&bKZ-Qfpd=mE^*P~$&P%l z-q5l*yx6;RxbwoEfnVYy8Gc30doLpEeou635Xj4MSL5Y~_^@KJ90Yzf3N0CNjC|9y zt-9p!1A|-jn%DaB{&%x7y>_6^C-!S`QwiavMoE#L0@%l;JW({` zS6Pf&G$_)k4k|hhu57Dm{K72dvSx`#qbKh4LaQsZljXwh#Bao>mh3rN?$T-HJ>y6W z9)+MnE$O*gZ`D9i9%Gjtmdbs*^t}?DJtIpq5>R&~2hx|GT;t~pbx&kA z@|bPbO&~Z-4Uo1OPLtU%TNoOx!6<{}J^mE+=;$jxYU|SC+v}A^XIA4RH2+S03`0+x zXk(xxlU+0{Y}IiCQwBPeh)!~z$wvHv>tZc!F20@HTu{V%*}1=v+q%2=Wl63dqzxW_ z6wQ-4?%oD^Gosq%c^%%S7xU%?jImyAC1-mqRTML2TS9({#ZNU1$kymy&9c(27_R~(`v~58 zLZIb9mFKF?FBHM$JIXx1ZCRSDWOn`zbkd)Mn5Rq>z zhk|P12esU(&RI5VKU)$Xrl^=~S~JUDS*Pky$Lg;p2`NYUo71)qXbY4oVr?!I3r%d( zi<1(zVFxB%GXwg()|%jT17k3YnCK?_d~TiY3St8bFOb`+^jhk9bp_c$URo^~gIjpW zi=ERudT(#x&%E9?*$cNWHw)aIf1>#X4+ngXR&2OK)+IxGIlFTO-WGRiHLyZ)evR49 z7qrzQjdUimOV!N%_=&XC$vkY}&R`X!{?=frL8z_ZokW#VhyOGBL2I!@^y624ypM;I$a{{(H(YB(e;Y1Uhp2RGXv~i7>DaZ?!C4mB zC|^`>>CaaBnV-E}vk`jFQzq9L;}x|9Lu+=ikBVZ+n?$0JH8nsF15`DEzbN+Nc&qoA zh!=3uB_)%xUtN;Skvo-;C&D-h$U5^K z;vTV$EF%In2b4o08?6dqy zNxfykiGpv67|mfAgOP#e)PBm)2L>eTI>4cdq&6(4f)Mc?B5?yQ@3Xf0doQbM$?g!y zl96|PxEg*@l0LUix#3;B=)5s30Dmdu3t44qz{wpC`S3A2DC~F~!80fh_jvL>`siJ^ za(-Ve?j7G2ugx=GVE+=oKMx>>TzvcU(UyEloUwRhKt7Lo<&h27O5A`hoJWl5ct$vd zXRtasq5q~;#LPWY*T2e3sk11p8rO%5t!(@EQO)V_e%!28Mb&#|USWGn{NCi$)b>zn zaQG9&D04SAiq?VN*SOYgo^M>t-^QyGy=D10zCL2eLa*Ua!569Dpapxi#cj@}jhT9g z$rzIQG!`)AuIsX4u$ne}C(#9&I++a}{x#qwVV7W6%KaOOGDzox4vXr9B_yEiSYQ-r zaqceEGxR6u&|fYfL-LbW5g;!DlHi@v(o%DOe?~x6QySSSvvh>h6^}VW1A&EH?yweo z2{-Cr{MeGe!Eo>?aqLuDm_7?3Yey_i+~$|ekdLhexffuAu=So>b`tBl{Yf?3{8 zO_}%-C&gB+X==FqSMKSJx|RV#G=pPyiP@8y>!S|Fr;vvXkp#MkM!m=<*shqbc9Ej! zNAVQy&z6c?#@^;U&c&ma$I`9=pxp2oK9+s6Bq|=rP;v%so^Ss8MvnyY@hXb3!5~P8~w#Y{TL31J2#56 z)lIZF55r6h4ch=>wKEeSBIxPq?U7i+`Ol5!q>jh(Cn<=FAtO4&Tu&<5sMOh#sMNeN zOowl2TFrs-;2svgtQ5~Y{dGdZItlvBj$T|E^Huxofn!PDn+&1v1B_TJJSk35J09mf z(F$Uo?LA|>h$%e~Jh%<#Z&4NRU$qoJ-&aU4nF^HPou*Uh0{!t^GvG*^?PZt&S+=L1tgXl`6O(BQ+9Rc)zK6n6<8B(p$ z)R*OKFTFhZfMse)y#5$W&wwereQH4^Sy@A)cGXL5EZ95S>=$>m*85ubq@;0CxxGaX`JdCi_LultFf@lG0A7^_M)BXia3u;okMth1>5?>Kt%I?#No!q_gcoDuQax zsofvx<$RV(>=WE({yH(X93>+;z~g(W#u6of?cO*l!Uq=|bWg<_v90A2LoZ!zGNYQJ z7-2zI+O#f9wo2m$On2L+rdTFjc91Wp46Bcvt#f!(&f*q3#1ry4)Y8P>1MtAscYfUQ zIY1;>0?MX^#a{^xApCuA6oCY}+TLO7lF(Jarl+ST=*#Y!5we;utS`|s5Ervex@In+ zU%HiRm33}Tb+!M8O$N&HNH`IrHt(Ov%wsxwqB4@sBVXqgje3|DH$&BNJiLA~^q8gV z)k^yDr=u7>=iuh<5f_0RVePAeD-GX>_x4AFVuPz5YY6?u0p6^&2MQRbN43slHgwZS z>Du%_=x|W&n7qxpo6}d^(M>zmsX}2O4eHJg@FrxqfcLrBifmdCz(XWK8xIX6;CCNSqlw-~W=N2gMeF#7g zsdH7zK!>CJ+BT(B4jQYfJD)nZ1~;KRpjAK7Gg12XYKCF#)@d6C*lO9%W`wcBPv5my zMRK+^p*k6w$E!KtpI7RdRr*8Ks-`vOj?x(Uj@2)+c33ON?eQghUyr1}d%2qeD5_Ex zc?aNNQP@BwBXwS8lUgs?UMw1g&$DR)XpWN$g#h1NUR~XfpBLYmI9JL5A9wJzi%eY_ zk0C+B95;{$T3Cwut|=}SajFl;p@clVhM*ACm|K+>)(yUxZB-%oO#S18h(o3E7Mt{1 zXVo7)T$0j~^n3Edr1Ej5 z2R#iw(ciw{Z@UN3lYl6p{oZ}MX3&ZD&^i$W5q62T%q-PO9hhoS)v~~VDr@vT>{&*p z(m6dmuN~iJyyPCs=9XLej)IaFj?C8XG*s;muj?{aNM3M$zlkThcQrRFJ7W$LR*;33s?pEdb+wBc{xN81G9;!#wHC08$sYlY9+U8lPC!=;jHCwLOJ@q+2RdaMPAx~u*^}6=6-hSP^bUc%r%{_R zrQ~bUD##%(#0<-1c{R(99Mg!~6TYEml{@6(^#774_k7bdIBTgM;}!%jr%t_BS0HEHWul!7dgLTs(UtsqK%Cl%x4mFKZZh5Nn3~SY1~mT+7Cd7 zlJSz#;B$wyTObI2*b2D$2@}6bf9S-zUw7PvPg{oj-G<%&hzWEl;`=H=g3*-Gbw)^p zlAnwgN0ai6c$Dy~Z(jMdCe9_cVSmI!FcirhY>1nhn3c=70h5US;z4|x(yulfB;s0_ ziN!OmqIjFl8Q+~I12DMr4z)?l9$zFkIt@$V_O(o_$a)EQZ^OAQ#8+8p!Vs{90GJIR zO#p2ISVRDk|E+KhG%9AZ)bg4L!Usm(=<5*gsVKJW0gG+}-Hd9FdDWvr2Erc8-gi`V zo|T=*GGiNpL2Q<21-Z?^Tj!p*KE3J#ZJTOFwhiG`zx0RUOMaD&D&iK@*UtXy+=AW~ z!Rzr}f7txLWK@H@R4$6gLl14kZ{iDNU!EHJHaRwwEe>4Bk>#TG2E)?)dLxV~jum^! zZ1g7gFi_5P*#osfEOg@H0M(mIiWOH;ON%tM9>faD9fjFjVcULK93>YEz;_NF6 zqqSDbZFy?IWzqXz&XaMMhYVJcON_k_Sn3Vw_UQ)XkJ~V1A_h#RTY+f#Om~i?Ua_0Y z13(vdJ6zQy36q=l7?hfrp8l0B7nV=8oMVqYUKn`~kdVH`QJ~nHgIkOwN)EEOf-jvj z6SjOR(6YgY@f1+7(af)^g6SORJk_!DB5WLMPpqh?%u0-uUGzpEBQbDuBZ}-GBwBW7 z*hiN--60@s8|hcH^=wP{6tG?G4at%J9?F*cW~yB>7Q=cM(AxlrQGn3NozY@`Wo5zsxbY#huX@$Gc_~wiU>W-_2RUSR0SgVSaYM&=i3}fRM;}j2GN=; z5BAxckm^p3kxe}pN(AO)G5j@z((aqV_vNnCOw9r!LZ$`+eY!n+g!T~XkdDAbVK|ngu^J=`z z=yjeJmGg>dWb}|#H)WqluL1MByx37^F5TP5q6q;EUD~dC*hR=}r>V193AY}{`8ZYC6nxZ@&dK= zzv4GoW6EAQCf|W7{99(`p#30snNitCfU;rC1b!8q?p+cD>@|sri8$t{@a4y`jPzbQ zr$6T;b9IG2Z$9@-d|vWtT-#+$%;*~4?E%_)E^^ULw~Ltsx)8fEq1Fp83pE=gND-ly z@Zg-L7SmQQM;wXZW1%g?cC0pUB|`l&36^3(AJ<8+KdfuA(8B#0I9lS?E1bbk>yxc) zJ_OXxv4o*Prl479S}jSF0-oSHWtjC>{7LT2WpOLe4v&mu%a+u!DFtE&0Y*stVXZbP zlX2ypIIbauEfrsq9R)9~$*RoW3SqR8kU3bs`u68Ngt~WB9Q6wilDlNaTd2+Ce$D0Y zxq-9pfXNkMJ|WTorGR#)^gR+$ZH-ipaJ*q zE6tFjBd@!BjB?7&^Z2HZ6!H5yCrO6u>ur|}^ zc|x?Tp98jg^9U&Q5WJB!PeGZ&xgEPk^v2P>E&%|P0X_gS2C*Quf?xo)0rns6y`Y!g zXg>frvZ-gJ`K-SZP#Kt^tEAzs)_bC&T*Ini!&0e`LSj>Hm6UNFjID--?dOrz_w|H@^4BwaObEy>Zl&9qv- zoW}Nm7_*HdA6ubfW(A|+ajgb%VZK~;)Ulm@rW)+c+3Uf*7JTQd#+N`{=S4ENW)1^8WH&lvGwlw! z%8rqHypR<|$m0tZ^u|&kIr@U6#EgGOXB~z~>zE zX3&8@>PGHdFk1R`U{u6R@iSJZqqHSbQb*ChKFl#wzSJ*^G``21FMpW)mBM0K0RUUK zQQoi%RH1Begp7R`6`0%OOmL5uhI3cMRj}SkxTl9NwLPGZ5 z=Nxt{MxkbOOXNO47-<9`aG4TwCF9sy%1VdCWkDMOgLbjXfASh(olXE}2tkYwZ|7%@ z?3}nQ{JQ&>pXBS`f;MRH*Mlq6k5aLO0vdx5o4-&__zj@4SJu@fH`(=|S*+(A=EMfp zpBU0I(-AjlK$a32RZ1kdTS6|muE{42e5Ai~ZAw-yO;)inmXZxihd49yDB5K0e~e=yJZ)K%s#{(a zEm9R#i)hU4f>j`NyVNU??!TstP;oGjkwb>)+`ebjIv$#{B3;kLK|&T{*Km}afD2+S zoylKvO68F~pPb_Ndp&QmM^0sOvrF9^6smwXZsJL?Ucj6iAUw=WwztO@NE^8SW6;9E zg{gN|@M41$&SyPeBv1kw|KgKw#v(oDGic2o8pW|yCdAN%{iX+yEx~P% zh}rqAo&w^j1uO8OZX`WrQlxWFo&re33*IY5v1Mgt&gxptt;u``mZ^ZvF!6^;#du9t zlZ&P~qXj-S_m!7w{4(q#q}yQ3SNKKQcp+X}wJfeJsm{g~%XOuHRg^X1lq*8FrehKx zMe5ts?_I5y40a`T#%|x6bBamvqwukmqgK_yOw21XmAWi^(6G1o>YpPC2Psjcq(Vze zGpf|Wj|ZDIwAXr__S2NXxkrxo#9xt1ASCUUGLOyhNT>9qm}}`YQU7=W7W8?ze%-JT z45Rvo9>+F`va-Ry++(bro9c{dw@=63iw^UQL-0lOW-nqy%!jn`a#FIpV86(t9kM#` zi9DHBMIJ$2k0lx9v7H0&4I>`ZWGwlbCFG$Rx{Ixy{O?Fzhn>(&6G> zb(pL_rumt2>{Eib8;_bNJONpF62Wg$H#;>2Boe^bZ`GK1pSISL3#0Be=P&nw!!{QbIm>~(KQh3DzOc# zwG{W0?Kp?KF{n#T7D9Ar%PQO6HTaWQ*c5ElptPI_95Oe(M^^MC^p{fhD-&}OT0rX0 z0K==p5X@MHln9K=@M651BbTv^4$Q>g*EoYmf^U_6;pkpVnzFv}EYW1=l!$Q#BSF(F zN>O%W=z8MLBZyt$Tq3pX;)B@0L+0+_V~$;qHW`DrS3>Wm-yi7dz3n(#ky&p$x_%pO z7BJ}h_VADLe;w@NTS+~)tE2HnzMFl%y_vbI8N;_%g7h->>u=JjFG#oST(yWj5uPu}f))^EHu4))y=zcc}$uP+CQQVo9fT7{QtXksMjF{#wH6@*$mUL;$UO+}@NHy)mg@7W!LaZOYq(8gP- zF90EHt3JjexP)yn4o{?H-z)c14FxRSsghkR?G~!t6eoSPF76awvgdq(nxCDt#V`Dt zchE8L6pPWw92Lg`j#R*^1xUUCt@GE}4WNI(cqdF3$vsjwzVZJNaXgFq`+3rjrD#Zi z7Yzgp+#wKBAZr0uIKVS*s38r!Uf62`6z#t3(lN(x(;Cfa=_wxd&16nf;qH6xKV=)U zkJcKI`w=#OY>1Y`(@|Y8g&)T%7X^)Z2cIwVCbgimfIZt{B`)Djjd^fo;~c_xAURLn&Y`8Y<(v?zME&t}bUj_; zQ5&ct5voUpb$UO;_XXkC5wNbUnJs`g@4iL|+fKfAHCD?Y&5mf~j4R`=^(R_$SaJ&` z%?h!0CoD#)c&W%?u%fxZIk;gT{Fz@D& z=-{JE@N6cwGyVE(-!SxUp*Z=#0Tvh2Q*>H2pDecSSrV^)B>8&q1LpeJQ|0z12^NQJ zWP3s}%T)JSG0%|1@BDw@4@9xZMoIhaWf&vXdnSR{8jv1j*u;c{O0r~dHLrM7x*de< zyVXbJ<~{~WAGK!P(LH`)S#Q%_x^xNxB6jgy^0Lm=MUtyG8$y+_Wq2KcsZhiJ-QB;_Vp@xZzR6^Ec z!YFFDF}}8t=IB)BLh%utv%4Aigsnhzi2bD@U#k*ZqvmV$Z$9;cUR*`_wsAKN?{9}7 zgq2FI`LL+rclxh-2_xRB$N48Pw83u6RxGx2Z#b&9t#{bS)7n05+a$mUtLMeik4mLH zGjgUBN>cszAAjJjpri2C<#&j%d6V~E%>*D`4R5^sm*sR>aZ`GFTiScL*!)9$JgwCE zVIMlxYwEL!OEY41Tq9srN8ERZgRg$!Hkb)FQV6w|nXfWXlH|q3kq_x9U6Q5Q$5=kD z3K;%ujo%ItXtF??GQsgr5I6L$6}uMqCPCmlp{?HwOQ};9S&Ivh+p3UJS3S1ik%C#< zNWbKFcigs0o@RH}pwN7xqa?Kthgc99$UD#4EjDTbP>7YfQCI5wxgG)s)8u=8ekF3q$9-&qV%z{6041exO$bAUfj}awvdrfwWe$Y~+^wEl}AjOXMY~ zeItI}OciT*@Y6jZkd@64&9UMCTa)_!Z+%Y~!;m*F<5pj6wA{Nl-9qo<@jT(~U*Urf z8n-^385m`_n=h%Q#ajBPE)}KPDVroe&TAdMMrj+%saE2ow-f=#mY6SIGrMsmZ<;r& zoI0A^ftW%=Hq@2QHMlE%NuPYH)tSnMemzcqjRH^0rGkGG`c^;9KKbD87ic%Cui-(7 ziON4?XeFyzF=E_h@jf>@F-S81g}b893sR9xxb@DF)P4Ua^(?F5TVV+*W5#@mz$fL~ zY>rb;&CYpzn8Y88^Ofin?e7*H48+0@oGjoBye^~9MoN4v(Oi8%?;>!NeA*wq7kgw2 z3<$^j8|Vw;5D@>CL@4Ke-A&Z6DV!K2u2!o#M1P>GyrkN^{n6&-{d|qTG5aqB1;2Qr zN~=ts7cvf2>VDLuHkAJPEICS~mUs54WRyPc{bh;q^_UiHeHJ=ScIzw8j_;z#;x#Ja zkKRLDk@9I$T1JIZjH@mHb+EsOetJPPwujN!@r&8wD#w-nsBd^SiX&F5^=1yambhsFtuv6}ab?2u8~ z0Z!z_Dt(PjIkawf`}`)f4|HqyN)ljQ%1yc76gxcMX&ED9OglOSFcRuf5 zAp{z@^PJj-KfBCnOD3>)ppp@}sY1p6Ofhux5k}<5(+;Sm4?A0jk+=GaJOr@J+O`?91%j zym+k#KX_{`g}={qMF&Ya*R4aPR$Qa~az3`rdJnly2kg&|1QJL7t!M;6%0x`~-~eEG z%PSdp9<$lQ``NrYu*vxw-(f|*gNF$LD z_^GHsUeqVVJtO9gDsr9QE9Iv;?JC_Po`j|fTO*30Gn)JLtVbWc`?rvg3UJy0uXo{A z09?q0$VMUiKO*n=ipK@AT~iZ(zZTX|6(+?b31=Z?@_1OY4xl>WWVLEzUH~%z_J517 z3Ko|DYdD=#UO)Y2C*`*Gf>MPwTW=9^$o5haQS?IanblHDR9I9aymc!>nq`g_A-o$v zTGHp7pVOuV>525=JvHgzZADIF()!pfxPgFBU?7dG3U%;8J7VC}RIx^H|cPbTM2)|)Cu(k_m>+Ut^ zp&O!CcQ9J8nRI&?H~M3BOr&p4`1$$gfkGFw z7e6N^CgNl++?XC90^rFQrKC^FI~8o)eS+ug!@GC$)xrN_bX_42(w zZYEB5-OlkXk-CC#bBEZKM(3eUt^3S#mmJXxV+j4cF_Qnxr25@xS)u*xTFH3qgP}A{ zi@OOpV})1wuIgJKzD+vQqobJG!EiuFPyh7Z4Uz|gKvGH%06*Yn0yL9+h2gJvq!a?* zRm*|$6EGBSsy>raP-hG~0GakIzzBg*e}B@81)ADBl<);*!HSo&6>GJVrm|g1N!?er z=_VB|{5hUiw6W!+I~*ihk4_uegB=s;-Wlr`1T9GOT}|v>EDW^Azrb6qP%8RpEMKEv z)XIH~ei>TBYBI=YcsnV$^JvZb^2P|tK>{LWx97XK69v&1jiGjkuIgFyo06*XWv$kP zAD1=R9LgU~jW;APW4MoWGjfY_>oJOf1n-40W@WEo3ZF`)jah_4_lI$Ngy$;@uE-bL z#9(SG0gM##=Hadur_UWkXRtNu_gogja zspCAc%)yQMn$}ai_iAq9+d%EWJPT>j>)bw`aNPACBeZ`ANTfdU)d5YT4X& z>#hlj=eNHaQ(JUR^L=MGSdLDXT+cxzYZhy|6t=(i{Cp>TmpuDcY0JMC{^vsJpWFTR zW)_a1fqP6FKPa5*$y~gh8b z4Y)DfE-n#yR;v8IH%hP5I1xgJ6VORAy8nhrmZ+2VE+Kz(45t~>gR{bC_derzbw}Hi z)kifnSm6@vN5*HYIq6^Ar)ugHGl6TIuql@^og@2toMrXSBiVoQY91%s5vr%@V&>O# zGex#`D;z|6UufKV--(4d`%q_}szHt9=(CvwY_luE0TKU-gMyHUC zyWscN{6WRP^?fFty|}iutB9j^@bFyMPkWh9Ee}0=3nH$^XKx>3!t3H&ZYZxbJ&@Jsq6Kg#&mn7$MZBke zt6`eHPnLTanrNN2)nfLqpZCz?X(#z*BvspS4IlSXb#$ggiA{R`bez}=|16L4lkCdT zquV}PqK^z-l*6f4d{LkAjr|EmfcLp@2em*jjxwhsz_`R~L(K$@iwB;;ikg}az;u0~ z)dPG`+xR#H%xioN%MUMJ#?Q>bl{IB!t7F|KMlBC|JO;#tMU^!ib(X!CD`Fxuk8tDM z7$Mx=jjpRy55nlYUNl(YvMPu|gqeV&oKH+a7@Nj_Oj)-!s1BbmP$iGvRBjviz*x*J z*OGb^>^W6_3ZfXWY~aF+U-FjfP0PVPeR3X4E;=T^=xg4JoGkW?Ff&BWJM6YbO#@RJ zonoBEVZ~PbzR4KvoSrnZLueacCrmQljwk^fwPiQYjSmw?T7Fr`;U#^e|AV@So_*}w@&&O>Fw=NA=zj!)?lXH z;^1;5^=rN{d8A6sE_%jRvhtG&;W3mEdRKa z1N-9H8f{!3k#7+wAqq_`xqxLlVp-0;PdebWnT8xQoQdXN@Ei3M#U>^Pf4gGEeYYM3 zE?S&&mk1}51QXIuUQ1Qif2Nu8Ee5Iu!4#ybfd+bj#1A6sI9~Ai4%@UyPg}x=V@{=C+aieks*M z=nqPgW+Vfy735#BDv=tCR1lF#XEFD=7vyodkq~KCTjx{hNsHJ=6!^}$mNkdHEv(ExZbU3WO)jn#_6n~k5&tAJ(9m}jH7fe?fQ$r8`QYZQB3gZY^fQ!3 z<`Ym2h;f4?vNz8~d+nUK-XI^$&H~S0zgzn*V>Qk#s>?!K{K=bqvs+*~u5_$SsK_vHGR0fw|F z5h?Q|wLp%8jYI67|C$H%eq?=Jd42tN+u~@njR%wo7|U!mEGkkl(+xGZh||isg1a8U zy;PItm~n9*O06b^W7Tm-CX9|}w``Qev3h`0=xR}MFw^~RH@KuBDk_sI#K`2)-KOhg zy>}D%Snp>xjIO?Ga$BoitkDceNS71*5NN#z;_;08C>AlKH0mHhK=rT1aOg)Nz?o00sbZo%#Y&Mw)SOxeQa zd)d4e-P&Wfu_IE>r!ZbTO2alTDs%X`a%+t94QbaTG5V60$I?7y@5i$O`elkI?>U4v zTO2#A*sOGke&yFa|6gS~I^SiJ4N3P~l5`!W60`jJsBZQ5t^Z9^4CY(6@2cOKRRY7& zUv)|=62r9Qc7^=V9%p*c7%5kMPP)<*y@n5)wSV8EPH{1*`R0bS))V-6#FE9EDnt00 zq`w4EQi`A7ni4y`s332UC`W9Hp#?hVY=&ZUp!LiVX#~DJo_Q-}eDFQ}@V?ZBPhb1)hy@MF z0mh&uWco05`X_JgM2N*vt_7y_c-5fw%Sh|lZr#}tVH2C!B8-Rpy%^cf{<@rz14)+m ze&ci`-no$qL?3_<5^p?y%2OSF?S5I3-W|6z4pR~CKFC03#EV8qS+sx&#W2LOqz^Ju zbX7MKU&7#*vQH4%6FU!!i$a<(J*J8<>~Me~g$>Zps)oN;I1?&`aWlbCLEk^l6fw02 zKevz-B}=djAw&E9@tV#gsvN>MBVQ9X1*`5WH-&TJ&k`(3bm$?|{VtNud**~!G^{dHBwaWuIV)Yef9eN5MPi{WArxi{t8g9fdD0tra}R72AAx{c5}6_ z0SWE}^^dYBS3E<4>EoH)zUe}EBe3*=?>X__(#eU56u~(5SS31L7tv&$?}DD^N+Or# zqRER{9TrWeyp2MW&JmZ;TN1&Ao`yCSR92~F#?erD-^loB9u-^GXi`bPgQ`|8oBKSK z3IU(^UuhuGQ0L4;S~sUrFTMvxVV|T*DeoxbrNUHJ3M+%7iNFKyEOvIInr+lZxX_`j%*H9%6eiWAu~8p6Q(2zLP@WiAuUEWCtaqiebbgi zuXb?$q-Mivpu-@bO$~9~mY*O#xaYLMKaBL8m3Ddlvv*o50KLaO8J{;!=eSgGqIth> zGpBcAd_2k69+;QGLT#*P?K&V(-7)s%P#hbyg|FVReXMp&#c3b@|mNMvXQ+KR!eOCgFpb%AeT*UpKN zE>}oWOfArGuj$AOVn_gB$U^)<5+oT$#kTJ}<*W4Nu4fEx*hqcP@b)Fqs4)huOo0K{ zXlvakP;6WPZf9reN=D7YI~y&#FCn$`S;POAg>r*t8O4WXm$OZlY@^~?ji62XDyPHg z#+4@%L90Whj&eQ^c9qHcnvWb#u=_!>rBJtpTkxv(&1f=DhD82=6&3GJp|p2PQcDtJ z6_V?9q_RiZvR_7;*AWL7HW~ljVv7!t&bkSz3q)+k16P2L}k_rAUo^ORXz^M^W}-z(RTclpXCgYOIKzABE{>i2!29*O-0O@i>0 z_g>kkC1=hw`p+qSJsM(MaMd=~q{A71$8FhL>h3q3UrB7?Smb-Y1cAYp|2Z9P-`#hd zsHE~_jB|EaGf@g9b&s;$tcM&rjHVZ=t7JFv z#A^EO)CRIEeI*``If*_M6HDB*${*~iEV);gsZ&{A9YX>60n$GmOS7w_qU;9{#SlcFXTp zq=K-o(t6_)ncWtK^sLS1(I@8fk-jz&R7n#rI~cT{Dqo4beTnShgAgp!6{!^G+F=9a z-_r_$$x^ZF-|>vimZl|_zG;{9B2Q$^-z4`xPtgaR-)y43_g%PY3vK?}28OmAR;EHv z|HDMv8*c{MMZ$P{%n-|dray*z$(ZaCPq4>kooR@1L$*GJ&zvsBJaf_~&KuoxvMROc zhCXbcZQZCmdn$u}Cj_RiP(kG(_*DaWW5FGAi69s^rU2>keBQUphtgtNP4H53iFD(M z4lyd3pI8sk951|;GoJ~w<}f%=s*mkk0ueu#9w7cug~2gU85|D!8s)q$73xLf%$+IF4`3ax-iy+c$yQM9tQgK7Z&xm8oIRDr!V2 z;h>m}mwRsV1E=>SxmLjhK<-OiT_aJzh0a_xHpK_dg$EcbHGrp|2(Ubf--iehsVBN7paB4_p#o z;cEnnyflsWirMuqfW!i23V2c-YQFrhp-qQ&87(so35WYnZA$@8QdM2u+Rg1YFjav{ zy7KV94(I|I>btuBh;@kypCRK9jT-h>HpeMjk&foYQHYhhl4%QPO6vbl3vgsskxqGM zWuJ$~dfIO3#&J&NNBPBgDyU^Z66Qn4I2T`I#IEtNJbk07p+2H9%H``L5KXo6u(;QU zJ}+Wkoa&qP&5s?>YJ)oWP`5u@(M&Y(#$MZzd*ePZ*Ft#Xs?0Gpo|=h`?=3+Z*Xv~! z!P7Xn*B)pfZMoz?m)`hACcgp8w^uiAe>`_IEfNS_3i@x0+r2dCUs3VDld9e}tzPNQ~9&lvH0->zTIdRU+`=Xmh?gu)e6JdSbaj-fnsn(B z4X|L%Zf_r~)wX=-=C8jJJIu9yc-Xg@D!K8?hduSZ4YkBVknOe@M&U3h*O2{yLgwEk zptUO$CzMo?kbt-k8lZ|1H1!3;WS5G0$mh@3E@YQ9G6xSxX5QaX|8b2yB}OLbm{{As zEp^h#U)R{K5M0htPEP$&6Xubs*Ll6NhM8A5@7?YtM%woq$Aw?@bLX`A_L_ZL749_L zo%2<0$EiHd4XBvWrIN!l(;I3ZJr(1i5;4gq%PK7(*&E@zUCtc&s`i=Ar6ewEJiEC; zt}zJZDjNYOXK*4mT59Vmkac34%C9?B_uxo08^$(kKGwpkBHgruJC1qp_5UUtku-y& zfPSc zOX`cS?p@jj`DZJhOV$;iltLBl1^&88fJCuJN`iE1%g2r|8~K&O&dt?1hGhLZ-U7y`}^0!xv*Dy)#26n0H%&vmd*(0!# z@$WA^M%iTTU(o4c*MjYjJ4@_K`51Wv^EWDN(k7uzw&_~NtLHe@8SJ~0YISKreH@unH$p6(3`kOyT^aMW*8CNgGWkx5vX#9a8mZ=us-p*1ZF571#h|h~ zOkClJ&D4!d9?Km;+bHDp77Bd)&OIH-eOOMuwNf_=hVo?caWpSVhiS3xss0of%jQ2r zg9`uU${-v8?Hf?O9s2We$_T*rMr$1D-@JJP(%S|%OGXHseRS79R8)QTZDt10(CRLf zBfIkqAb%uC6ZOMb(>E3S-Ub=U@1MdNI1wbVx?e%TS5JXYjuw(UoZ)7-4Y!l~l^a(PvkC4_xu z8BOFVDLAdFd__+LoZz^kfmZVy*e`4PAq0<*RU&AK3uDV(Q{MmE*6`0*`SN-Rk{_S(wKjnc*8|CI8ZZp9o7YTtPd98v+Agd6o)R`K%y%9(t%gvNfb?@B z{9sd##_FDY-Im{Ud*alQeu~Ga6|DM{yH}Rwd{@PyjlK0y?GeevZ|?v89ZfWqb=ZE> zwD-O5mtSeqZT9n@ESB2~kKCRI8>9uvM2%N2y6#(LJH?&L#%%;__<4gCDblRbb5>FI z=vLZJ4*RU5#W6(YWR~V)i0){d+U08k&m$!PVSP;p9sJCGXBUtAO>Hxq2J8-#1cN07 zx5cKs=lO@}C^d)Pl29}Lc|&`HHoP>0fPjR0HZ~%n%Bd0S1vaOf)e@BVO!_l^pr`UN zQz3l7HHbi3Fg7AkaEDL2l~B{*kk7ttR4XtA8N{eAx=FE!wq-dZ8Y+;^JkLEGDRQ z`5_slvY($B+PKW|ZbP^t56kO!f!(ou?SK*SQ4UWvaLR{bB-Ga$!}*Ll73l;JHE68) z#;jevX(#ZGLsO~!gWv=~CgQ3o0}5wr?x3 z#RMNq=5{!_l@QQMC%N&Cbie>tK7U?n{{T^kKUAj3h!;5-vU9qUfQ@h35S*&~TN*B7 zbZTd^JY*?j3KbDfN)gm$Di_sGtG4k&B%>yMk#5m&ZACAnzFhXevl?Tj?&%V0!AY5t ztqAzM7nD*Wu`V|`jJ%3UKg#|KTYRmmjxj`;7S~T16$W);;6ax3=?a`rOTj`5q&} z@C1dU!fzpNgCE>Wnv7g-ta;l{BYUgAMeNuH=_Z;;WO#>dEH=%SvO|a7)zl9Xc0sz) z;9UV8&!q?Fapn!dnS%28LU$7JQKepMdjC<+4hf~NIop%#);8(h4~hxFCLLZ-x)a@& z`Fn+fztd`7o_Sc=5)&O;xMX3;B~7)X2_FI~1fLVC4`QZ~C4i+HfrAOE^tY6hi_{#?^@+~_NdherXp}&^1j0ixj^wl;e6>RO zweODw0EzpGs)4(QX@dkisbHl33}eAWBbleaXXNvBQDAt#?x275r6j%K-4P>nK3#Zw zd@Fp~319j4E4kE))a*%B(wO-&1w1&K~oMNK=Nt`>sK}pi&JK=c}us z=4FXnxiw$;KI&J6fIq&;=d%&)_M=C&OPs8H`zLbwT zWSVkhh+^muy}Qp(>-(5?Oh9V{irKu6UD_dK?c-veNYsp)F4u30pEk0V%AnEPIkw+F z{#H1Grl&|dp0F^Iyy$%p{4D1OXrV=H^7P3Y_5sN9!NW!xN#|cL!I79AWwgX*(tRH{)>Xw`7`i2Kd+3|3&=i}wg z)GoC2^@SpGXu{;~hRb_2ngNo2!A-(xyqc5jA80Cok2h7FLegvf*ZO4REwrm|`3NXN zbaZq;YS`~2I%xW90d5&-@IA0|3vzt#3PrxIwd(-d+@$ZOEkj(;Zxdg&a1jn1H%i7p zvP4UPG^Wt2L>2Y1T*ig)$VH&%dU};V{HGK?3%(m5ySVvC;_X2t_8m;^fYD30AeN_l zX2$O3m6f0M!wv|Z=o;wY@Hd_OWDHn|pdC1}Uo13`ki)N9%+IiwyVL6LT!!WLq zk|vaYZhC^t?kQwU!$`6D@LxL(>9YosZ2z)teSA^xHSB-;j*o=1>6OH!Uuy4CF46jE zrxu@-!n_PAe8%(M4IKUyt)j-tqkDQ~i<3BD##aUL29U)Dxjte{ihB+wH>9ucx_!umKZwv$j=skR>0uB^!ie^xKkC+PS( zf&=I{RR+fxi|gJ;@8b^()A^d;?3N&=Mh}tHaGaeNhhcNx5gPi>bbCxM?jtB7;A10t z9zR$T*`C~v+2b`qS#~Gz+6zNgQk;Y#zn8X0Yh76Ur!}%izU$`=J6Ks;KO7#s;RLcJ zR@7y;1Q)9@EYtgg8CRIci{(@O{KF_I$Lf)l;*{HlW0~_gZrV%b!(&F_kDA^vg&KKx zeXuhd(KU|^WTdw?Q=7E)Q8|Va&2v+?3h0vC`nOUrPG@~))I&XV+czmRJ2l0C;Rt}^ zKP_h%B_+*sel9G$ZYYrR!L*Up2ezhLKWr>0sJ1#LW@Q!^Fqbz-s!VC|(T8_beDag& zYtdRKMDa7+w6`tTio)pN&AA=pT}G(`wbP1Q3??!p6>6yH7&!aJDyKGZbXqO*hE--? zKC}y{>d*$w6D$;ET2c4nyO;i>PlYVF{f<1^;#Q$-*XE6XyVJ^gU6TIFH%H;XLc8dR zrZJ=GHGBL(S&{0n!+GA4be~*}?h8E~>J zkl0cSXAhi!lbH7WEhi=f`D{^7@Y5w!q$0@cEW6P|$VG5Pyqp#?5 zYh~;R`j9d^-LZ;+X?TE92jrK-m2sa9!DqZ`#Ab*HoZe-K)p031S7f8t5CH%Eo0w6fcZbg4w`a@R(44hDdVIvx8{k=i#aTwU8`G&&%;j zS%>$9Ck9Io7b#LXMQN|4uBtAAFv~$t!1z|kI969j(V#i5QZv?J_P$Pe2pAc`ecEa) z+cc!>dik7}g`j&!laIT{)_Kk)*WRPf~{K+pc&C;UQf{oS+_?s&R-@9m0z1~q#w5}|BV-ytLT&}cCl%O38KB?ZDhBux)AFt7Fqi2iY#$iu!ZX9e!)@Tacdr*#MHJo! z?+i%9{Sro!fhXn(KI>zD=ptbI2Sn6>#Q`8|2=s-J$j)yq{U0Rx>HrQ5dIv12xaA1U zLSlOOIic;2k)gqc!IVL2ezleae0tF#6yqIUB==NZZi8>`g zKef{fFAr0(ld+@mc+6zF)x9NJ5l8SjE#2{2QD0-{O(cB@-|;up2FBqU(&B9!BNzg8e=l3AHwP1Rjbv%I5L4W+W$4a zWnkR@suG_=o8$049%qvZzitSG-lFjF_i#LF_K#5CFA%l`Zq0cQ)heg4%Euy)cw%&> z-o8sgyS*%>=;Wz;+bp-i+RS6Pvs#iRb^(X3S$S+#BH7x(UOp$`{ z2P3F3ng_D_Le>D}g|(+J0}i9VJ;_>J@gOd`90=&Z!{SjO>YK*0CuRZ+u37fHcFTEc z$rnznydn^yqmsJzW8Cu%v!DT(XGzuW6MH4Ps_ED0ZLj&H4Opho>!*!XbX`WB=!8{t zUt0Uh?P+>op4-~%2+xL!4IOyB^Eu`lNf|uyKYzx>6_Ac7=honW56zaGlz3o8>kkI` zvS4xX0kwM;i`B%&R6>G!QJFABRdFk%tCak!0z-Y;uxAW)gl>9TngUW^%Ry7HQfsBNp`h=+T9-uj=?nrod^lywmzejTmhsZ|p$GjtgMa@4| z6b{x+#NNs&WQk*mqcHP*PM^S`Bc5Lqq))ywvDj2At^w<)rb>HOP(?Vqyz5wSfuUtE3F6U26VOgOF&KCYI&;_3*5vmM7%;(InWu5vS=_0i0&c_Kx@}#tet&Y$8Y{MEB5~0#H=ED-W!?IR(CBe?^ zhJQtrnGG4ph6yMhaZ7cjU}s>%mpT%wyRk@p4{2~*$eDYn=iUaF{8z6W(41!sLnYX@U~)fUD((13eK&a37Oe>TGtEV!4BF78F! z?DB%Qxo>lBYtO%=eNWp-S6yI*KCdYV#w|Y(S<~foFfl_I&p5|toh2aB^&GB{HPq-{ zN#kLW^p>ez`jGdI)d9T)>)3rsk{dBH7K) z8owl#QbGqcWSNX?ZEYV%{*gL6n0H+*%%5u@lrrF7l+0(?^vRfnCDXy#!WU^ons_+$ z8n}Mz2R=bc$d=5$o-W(RcaY~cx3upiBM2LNsS$50f0%9<9ND*)JT08>^K_6c`A<$R zMC#SNKzbkeh#!kUl-##^!Q}_QeII6!8+H92D7zrb2FtNy$``h{XiGwo_3e9l00;pC zwBObCn?gcDVCe(6Vqaz7mUfY%czBFS$xT2bR1aHwg(N>Fm|xF0Y=wH*``0bxomRU~ zp)@us;2^0taCI9+wI>u*}@bF~1V!=9)E^|^X5~kwbEuDs(pR5qK}Bo zdOd*R#Fa~d1#9TYZRHjCVp{4QzIJo;C^VgTigKoRfgQi{!aNtrF^ZN^nVK8rHj|)v zC59{RC8d|a2699b8sWkj*umY&RSFfqfH17$;pnPid=He_sMn^Mznk;9u^UD3>e_>= z*bdfS21HW<4{lk#7>{hyH!b$oK7Nf>BxSstynM>&o@S9%7{^2B8X2x41H+HXbhLX? ze1X>AWiM}DwXcP$fS|jwZJnjCvvoI1m^5m`_a>?cVGOTN7}Zf)B2o^ zqAb<6UN!wOiukDYBj_9e`D@w#g%IV%URh=8gOMx^hq#a4i4g>H5| zOtP`FD{v_tbxB;DzbU-0ny>L~@%HnlR|yYKeg2Z|QhQ}kxoay;NcJvun(HIBGzs=}#zgkOhiCToe_*on> z1g-ap)-!f^y(~hA!FpYyaB;*DTZ|Ja*H-h3ofAs*+>V`zvSkDB+C*(RsmLJ8+>{T8 zT;*&FznDb|z@xc5dZr6^4WD(}As^O6`QgE;3iZdv;6?+vi?G2bPSY(+`RResUYTPj zFimzT(OVKNb1ybopjm>XJl96w0XTz_zv<=$2?~r`&*!aE*`YFgp?^?=A+L+qXf5l4 znPD?WJ&PVy3LnWf>HJMdM*?e!!>IB}Pu8#%D^vL3hEWt}Vnq(Ts+BOYbiVKtx!v zQ{?K-eb;Wkp=+2uH_77SKEnMEIgQRgQ76AN;@S3?N;kXa*hah!&pdms9m6iwLFvQ; zuYapay}lMtQDRl3Ua)(^%;0_Gsf~$vsfV|bS+)dLkG#&_cI9{5zTwy^m%sTo#%>^e z`VeTK!Oaik@)tZtp)S@BDVOr!KVeMCye5^
    yC2^-e?mib9jQ&S4xGgqyMTlT9l z{9Q)s5Zio;?}c|hddzwk%$Dp_|7Tw$%R5;TD~Cp7v=W_aC^e1dbNXJJ)pqn+;XUy* z7P+6Y zlQ?7EQoGYslSKUSojZ3{ey%ko);AZPFMB*Hy%zGotOTsKDO7!odV(t&A%M+Sz-9}o ztX$a$L-=(HfhUQyzz+0u3E325e;4HSr%m~kt`+-pV8-fdo;<*_6R@_EEhLOckkt>!@`mwsv(NZQ+1NJrc? z)llLTugDm*wdWRp&2)w2%HZ`MJpHvKoscEZ5?v(#8R)fLA2KDk`dT923k=DB{`{FK z$c}2$Nk7s}@!#r#{aW_TN3A$m>Z>d8lgNSM(m>cGA5@CjX4Lk?*w~%& zY3d0O6Z!40cUTGlE3y)e3UsZ!9r#bRNi4YHZvtd($3R~nU`RKwTmpJX&y6W65*u=6 zcTx97X`ganH83yB5A#t|Rn6Jv`huhO!M5C)dBe*yCNH0OtLxa~ovP2XpHI;Jy+Muw zZz97}N!JV#B6Q@iTOlop8*?aih+0w}2IEbv+G=$CshmErUz}F16@$~vF|FDH>r>qK znmq%@HkA4E1`YWkia{f;y>m42lmFMr4cH(=QI!R>R(SkBUmUYQS5~-Qgt1M4M^cpq zaC~!fbA!-^!YYNxS7vLAQaW-e)UQOA#iw_Fs511tf!Ux9(F1&%#ZsOtR*3`o)kA)j zX(NY!=k6S*6q}*cQ}2`>W(wCT6q1W_L>t-2$nB|uhK>yU0iGFR5yP6 z_JV5e$9<>ructnXUJFMrD}QVs@gd1l35GeomQDxOdPt4cXFIFro64^=J}w{*2&**| zvSjSLtDyTXKNciWIjZZQ1IEZ&~2i1Y=p(il`68 zudNtIr1!-3K6^h(?9Mbs=1E44MuDX-!^3(~Tff;xt6_J*>@C%I0o;R$^4G5`0Q|%5 z(E+bS<79=aiMhGDmoeZKc6_D1(-Qe2I$a|G$e0#B>%)v$bi)iv?da=hty~s5?)l`a zA~dDZqA7!`cc{3$l(guBOV17BO*J!|M9o%s%LmnlfAuY+q~B`fJ1Pd8scmv+drj4= z&2JbRRJ--dMJ>sZp|oMBE~?TjAy9v*evOn!L67|`S7I~u_)h#s-yUX^+L`v@EX3f{ zjD9t7Gz|Lxv;c<;Uf1-Cho46LI^)9WjS<>BzAP!(VX@={ftgHGzI@6>(|e0Q+i&=4 zHgGZL^e(Y%47=+JbG&m8o;Dkm58oTu`rIMGCzTV(mUt4_WXs0;=YL4hNTomk>7@ip zC(Zf-9fk8?(u}spDK!A(k;Cd$uDWuXay?3Ho5|-QZ+uuX5MmUCz&}a6oENIh^n#Bp zhonp42sG#ww1@zU1e+AZ?a`IXAF)b=8j{2Z4-&fpBzHMk6yBB@#{6YaU6P94^z9`; z@ubejiFg8huXe(Xa_Zklu^Bm*qnqkdn=ez`Fr421ep1i?$au;3*)woEg&-ov=ZY+- z$d1)V+^-+peLpT^_#h_;`2#JCO}wLNM=uTwXSlGcrqTOT!j0tC?xiZxVUdGRKv)WyqK(w%WF5Nn=OIf zOlnT>-mawW&BYA9tjn(!ze6-}!8X!LZa+9}vlWo@5!=s}c=5>U8hkixqTU`UJhVZ$ zZ+`^yY11pAF1Jz54p-mp>QVw5*Fs-cLR5j72>>}}sz3)TV*K6sL)gBcb}BV3DzuQI z?sR%TKsdQac!@94Vc1XVSA`)@-bW$yci&I$3Xu|!5h)V=-PjH)D6Xh|s4#mzt6>1c zIg%B<2pjpn{?SniI)u=4Nek4?dR>+9GzE@hLl(yZ_Y17c7>nQCp8&C62 zAfd@BIS$Qhrngi-Rdx^aSZw!xc&H)!iv1wO?Rh&hqa(i9{Uz-8v1zZ+q7s~jP+2`c z@!HQQdX6+w*Y3+D$vk5oxS0)dpQ|T6vGR3;HJ#awK>(!W@R)0-^*i!Oe-{Zu_Ufc* zr|q8B+~wiQ_wM=N=kbn}lHcfi+#?FC_@*TSn)kWqw_p40Ol$)4&jj?>aDS3Hs*HVVF!j+p0 z*fPyV+g6_wVir&G25H4_-tRliIn^{RfR2#sjMdMznW5^&U6vRQL#5gtFrW;UkY{Kvn^1aKP3 zA7GhlqsA@SO(dN<9WcM$xB5(M+*NVuB~F7HjoXh@f|eh~?6FY_Aq_-R2>-*8EV{Fz zX!Ks=Tz|+$zRuLXQW>cikf8iBKA}6fGPu*0$8qw2*lap zw=sJQ#62exGN{at5HJe66+BcAH&{n>Ozs)s^E^-=Q4l|6*(j@5P(dM)3P*Ub1jCgGT(f|?mMp56Vh6AOI7d>*l1 z_A+FPCKV@Yt#Uk<#Z7SS;dOldZ=BUNqT7VGsX||lo`U)Y19ceS09Gxq&P#&65;cHq~uM z8uCQ(^2L@8871j|w8;zmTDj3+*y9IFaVv%8;7=}osqt_TEc%GCrd30$8 zbmFX-BpL4zW@hshkg?~7`SUQCgKc~~RZ$-goqLVi@f^0c^n*`sv)Rjv(f5eD&VDR@ zw-xc;o}px0ZKF2)*)MI6Ps^91Q3HW)>RjvC7Dpglt;9YuJZY=IqTb2~G<>7>4DUuv ztYtMcYaB`utCpVi4$TtD`1u0O8e_=puh6{VnB1XK&_Lf}|5_wW9|31ObX5~7b zZ6@_nGHKw|i@ABJ7fy@lmGZ$&ec>?>xHr@P=%-|2;$|n{><*q?=iizGk=Cm>%5=F3 zLsM2BE!$JXSTm(5f{b4&yU@l%u>Y^fJwGoGOS;rJ$!Cnz|56VE1^~X1G;IdIXKl^! z-qJObmoBt!r)AEt`ORYRqL5^tslWYhm7|QI(NdexQ8LulN0vVElV71uyr(Ef@HB6! z%GcMb=C`6@e!SC;7Q3<4x@(rH2aI+-X6j9uc3CC)a)5Or4gsQPwYtQwM%FjA=?4kx zq&&=35b?-oXt50BJ%IFs3#O`9U#%m%!LTCVng!Qm#ts&8QpxmZND#TFU7oUr4g(&o zL2@K7dw|UHtXGt4O3#0#%?L-Q2P8+~7{!qn-=p*r)RfHfB{hhQfl{{Z^(_}|_F)ar zmA7}d_`@HjKyUvgokk;{2NOa_%os~v6-4mFNbo7WHT*h*P75>Zd{#m6qyEP05wHKl z)SE{`!M<_hW69oF5@L+CkiEoUjARShWy>y=?E4b3Bs1`Tfp${^&WA>TuupbzPt9vxv$!m;V7>*%e9@Hq4MUp zmSSw9<&pH(Y^r3tvYCthDM|K7NjeXI7me(U>=>U|B4k#(Nt^DHDu@UAVyvP z)o;P>?aLIz=cTV+sN4JqH@$OjtnPID6|V+NeT&yfFMeg=GyZV0 zHQ@FQ0fABFtg*>P>>tvehBv4c{x0>*jGeXTSA)qu(kIxTJ}Hh!eXTshMNR|+gM8dx zv;x6+OavX-PLG)6{{C4VU6R31ob~09VWw#^qhoE+vm?nF{K?Ni9}bz0QigH9_Ls=) z(fRUYR_+P$o!U>w`A=B3OrMtfkf1WtUeQ9|^BIDNAH%{~1s+XdVroM9@TlTp94cU>X4ZCa6q?A+~?dwckk>Q3h|#wy=UoC_vTfoIet>9m5gPstlN8XzislUTlfIFtsA*b*8 z4(igu6y>G!z$%b6I}xbCHQ>t`A)<^JG@WqTELM2`Yg}O3B=g+8pW(&qP}f18e%ptq zhCkUx)8wC*xS#7&7(#zXRE#Z*M7l48dWq5Xcu&0EzR1vB3+u?P%F{OimOho)sR#|I z%KaMauVq@Js(Mu$rlV_ji@y$0CQuj_&)O%%%-Q4e2K#L`9){F=p$}XqTK3sDn)vDP zABRo%73dpDo5ZMoN+$B9Z$C#w*+v&eDLcpU&a9mHPwp5R=cng2xJ;oidv6HHoGYr| zRTQ7K|+~5v(2y%j4tI@viDvi{#z&Kq<_cq8uN%U^3V`h*e5PFMT&*m za0>5|jS4%+j?13=CXZf!G{J#3fME*<2Z`SGv0>D`leb`>OxMCJpe7T~!33ea$=P}0 zi)w~Rniu;BKB?Ew{RYuXuy3uL?zUwPv!Xi%)ebPu64x@xbsWT?V^KR0GOO`L+ zG?R{|6%KAO>Q*Q#1J%YoEVlp?N?)Bb5}eqU z?e-V(ZeSuYcq&@B@Y~ul)WIfvQ+unsqWlg$(K!S1BQd{#p_ zZ!G$;7NNY8WWuxz=`LISQ0(b%YhMdd9bbG}pFRubjjju)SZjIQ*7~bo4bPXG)7_?I zTv#PZ^J_>HHhx@dF&#J_({MRa7HC+yJ+1|YU;Q&x%c?kF zDJ2+NRel_j#NtO{_l zX&(huB5MC>(9bHZKIfZ$zn5Q194iIBnAZ1jsk`xWWm(qf$vYjQ+s*ssZ8&_!<^K!7 zuT0dIg#8JC=Uqil;sTmb`RI7u;#M1cj%uNALg9i_{m9NbXaP#R)F5Usf&{f2fn+7&`#lUBHB3 z;u(GMcHV^V3gE0m;g_2l9PARmb%Gl%7JvvE5Y{_MGv`IK$JuP0ndrf|9?d{cI>@8=Pllxxa zYJsXC&9-pP9jZubE+Q78kA5)UzfJD^2$%w>vDvMjOgetJV?jZK3;p$@;Se&DKDgK& z!iA=bYBCF*k8-*bV01XaU6#%H~8kpeS+%?~${`cOmoExdBscWvZ?3SM&jVo2E70brfdP#F?`jiT`D@$zhU z+}iAtTs-0h)EN&+{3p5QJqo4t;l{<4xq}TaBe^>rZKI#Vup8HusGdKYj^u1Z1Ah4! z!6T4)@i8QyfaYsTUG5ZP6MoUaPi=JzW_L@&edT_J(|*DBN!Bj170@D+J>oa^0%qJu zFF_XC+TeMNs!crvd@8@vW1?p6dOULjTkJolM-Q!>_NAw*j!k^3;&j&87K3W#vIx)l zpLEP~dEKq4_&Tk>_8dKT=iE1b4`TIuYpLNLiM4p<;$kRLk(Uk+*!W1za^}~>pL1>g zC;$D&ZhULoMlt=#X)Zx1>9Yl9#PRqgO2hs5d%v4wah5g?03Yk-eJvU(HclxE{|RRFPVD0anY@9AAq8JHD_V5^tl%UWeM3tqFLa*JS8)Axe?FSIW!0}5Rxa3Tt(QF1X48>fAphMUP@ z(f<_}0v1|AZp#OxM$3Hq+=IBO%3pXF^eaSk@;Z{=%Asu}o|dGy@FrghzeY{@)V5s1 zddp8Emj@et?@1}xz}=|>tgYy%F0~x5y6I;TI|23m{+xGXtM2QzVWz4y3q}5OuBnY9 zJp44(oaP{W`r-fU@%Z}>fL(^&5if| z%ymHx#>U@vKm7gF{({hhr-T5u-R67;7w{i^83htX=>fJP@4MM~I}c9>(oKuEtw2<5 zvxN=`*$MFbf(Neh0B)Xz_pmAvpY$>w5Tp}?w#w5zx5(ncH+VxcedYWYzxP+YU#kCc zquso8!An8H5#xk0~EkNQ}}M;5&kpU2ZO z5x;<76mV59Qm`#8L6!t)ivT6G2&s1hd!C_m+ra1+3 zZ{(Oz;e-X01n}8ffr*{M>@F&F- zt?=;wbmjOXxbO2l{rytRIhi8cDt=AasQ9@3rJkZ?>pFYk!8fyjZ$(_2+m(`D;~Rkl zd)aHIf2l|-6olw7TK9AFC|Me{#a7D95Qk#taFJvyKhI)WQ(k-BwI@X57LKlU?)~!puv^^^T0Rh)0A4fTf9O9q z#q-&F)kiKjVv}w})iBiq)wJ9sRy*lYFE?c8%{tf6_X~rc;I#Ec)#_xHl+z5x8Pk4-a~=~g`t`cW zZxj}jk>d4Ao6Ss>l31iz<{+3*!GD68gZ6U9TU-Msav#$xzkUZhy%E{Fc}v!8ufcHO zxc&)<+`z26#H--_6?AsqJ7@K|JlRiTFw^@=u-n>}EUNmkRcyT<)fHrz3@G z|4>wwg*3=t-ePn3F^#^-F?5hn3r5!}2M;0rt7(j(W#JI6jROPRu~#=k6$jKqCBqo1_vwJeYYX7pyQn33*Yu?MYP>B(9qT$=q_)YHMcIRWjoJf>2>~Axki)(SpBm zi{Nn|X5UA^n-npfOH%!07b@B7X6TS-TWCUji^bWF@407^2zMfg29c+V-3*s7J@bD& zC;xJOFTP*&mJkfPqU!I_828WX35A=56`V{q4`-{DvOq94!AE&{5ixObrFd3**t5@J zozf(o_*|%%l|`@6mh^F6R7=@Iq^Zc#-lN8D0@8WI7atA~v_I=N-|#nmG3ff2^R5T; zre8gM(ij(%vTzs#&(F*1q<0A8V?`tU z5WOp4Pj!r%`~7Soib?it#+Re&ueSsj+H@Bg6l6y_k*3L(=)YTfhOz<%7SugF#=%@N zKx8OIwG;FFYG(bkzfVhoCk&g?W%FZUaAoJM=QY2iym`1PG1rP7!%oKlX}X?|7Kl|n zefD^H;saF`JDs~nM-nnrp*`v9JUW6e@TO^pBGtlm>W1sozKIPYWuw4AtcV-`=bf95 z(sqN(G|**%#Wx5;r38Hs$o2+Dy7+N{9uSB0ZEiYe6W#=901pyiH4nG}rtn@so|7Zu zK(2giYrIbJ?F^>7xj`Rg_tealRXP8%H!H!tWj_o0ZSqF3%dNN8-koO`56asbCYUm8 zk~TEtnpd@>*;7AWp&xvFvIWzBzvX!kLdhE>mHoRxevo9~MO_mtG3nuE@Wyy^Ub%-X z{JZkkXqD{Yejw&E5Qud3crv>zIcWGiYu7ImUv{ct^)yd!gWRMrE_mg3C(+k_w+#MY zapHOT*3{R&DLGP6m-Igy*PJSG7TDtb!LRcy6NsnRk}IWaz>FfOv9n?U1s8bdaJXSN z?gLfF^x8tTU^h*uE(;CO6P5I78@p>oFU|?o*I}}Ny_N1W_H{B$A3l=m2rBO|H@qXC51u;&kVT5ukSH0g*?lc=vNA*(r zy6gl(7O3@KWk&Lx8y18PswckDd)9ijlY@fH!dzr2mrq?;WH%$|!P~+BM+Hnze*}qD zO>Ow-Nie`O{4z8_*v&$0sn9aOAm}KX{2i%v*Sr@dMeI+^rw6vljK@LwStlz%VI&uHId&{cs zDLr)S;3o}fP>3fJs9029vaOB|moUHs*=vwR17cC>^SpSnsIS2ll z__#jyI$vR(UWR3(pLj?L220t;o5%*m*M)E;9ivb{e&EI$Hwk-9+yZ7Mhk-)I$3_*e zr};nM$>;Z9w+U^ms{F8aLc|6J(+MkdO!pOS`NpQ7e>T>t0n%!OpG4=j)H}otx|;P9 zqEbPqWqVQw=-bR%5(bZhjZ(W(!ibBO*y#`MY@ZUr{R1gDwr2xap35@s`W2VfLY8e@~W- zu$^vjanuW!Be}yaLpK3U!-c!mn``g6vC>=u3SaSY?V})6pTU-|{Or+Vm&;=NpZ9ze z-uBx`CJa!Idx%IU#O#VFjt4k%F0tt95lVU_oov4iG4?r|=lAIc4auE`MU1*YutH?@ zP?tJR@Lu?RlMt0eE`Ld%~UpN4D zYEX@Au(l%o`c80buq}zn1Dz$@5t2z#Z_8M`#Zo@eJ_q!seOg*XFo@H`0|hlb;wLtL zM;K1K1i?EQLCu|N;}C9!SpnY!z-DCik!$h}xHhk_M3t6*`gk*7cEi2fuRWrBtC3HL zB{>Kuf42Y<4=tm8d3bxX{rLGzwF7N?y*;Ili-Th$b>#)BCY4#vRn{9{os7N8}C>hh+=K^e7)8@6Dt4ZT!6K+6Mc8cla&|kC%bEot<|&NWY16+^U~}=AdP1Oz)F8Tx4n_* zf&Zipetbt;(sOlRWBn#Ji2cttmFLlZz%1783B|U#m6|H7So~QdemWOAH}Y)ZJP0m8 zPeJ^-d+RHtQZy5vW<_7M>b=wa{OY`LdbLpO&QQ^HDYa8#>GP|8mq>;-z1@`=7G4Lz zcY-Cf4s7|*fh3)K>psg!dhu-n{*x=~c7;*(Gyy+7D>ei!c$1a7Fx3u+ZFFOuIc1pO z$e&-H*E*617a29=RjP-SYj51RQSG;Fb#W!YwV7^o(=8mKR%uR`jr}kt$PcLifGP+k z1M8sY-oTr0dGBa!7>;(Ll<|D@v~aldzyIifk?Uwr>)0gskE^e4f1Q#OsSx?;^!#p# z?J{Wt%>zrqWMI8$;A}%Aay6UdIOI{|oSWj+)zp8@U%DJt*X75E*l-%OIUjXJ*V_7* zK{K2u)Jgu!s;eJ)6CJ73`{~1`$FJC<#g0?9L&?5LSD7i#i|I|e%ucCKycj#`5)>8t zHKl4P7F0to6{}(2@J`1^?dNnW;VYzwqHust9=;Jg_0+by>`^G9A3c8QH^lfW2g6`SsQnKb7bx(SfOU6ew5 z2@~GdDGOPP44F_0Q}XIUy}Ot0*No(Y7Ip2!-vJmo@pq{fF$K0K&1*89+IA%A@>9R| zh%aWP5i$;x86AmVCxD-jHq)sq3@h3U`wQ9W{z;RTxpGf;K`_3z3Va3h+?E zK_JncVFBQ#{QCk)x7Ed7@?lQelTxFUEk<0il?K$?xw)#c8apS0gNVY3o~OZFx@@+k z*XPmOumFD0pnu88!~?rdyx*5EO@(@$8%Zd3aZA(A-#>2r&CcrFNR*{G<5wba^728^ zdEmQA&jUtpv>v{?A~ElZwFliUhm1>iy9HDiO!u^h+vs8(&clmgVFyrr=UZ57wy{&c z&4M<-Zn5dHO5?MvsH6&qxV_8nrk!@V zxVk37S6lr&Z{-?3Dx?zM_LjJU_FwytjtL^Z>TOWIKbo8>vX2aEH0>QMF2?7LKQwZf zYX^B;ZjIB#!az;}ZqI+oJDo~Og=bz=Ca|KmFODEQESt>4U>$OyI`qmGw-gdUhX$&? z+qI$+t(1CipNnZaJZnT(0Br^P=Mh8oX>K4M$b@ zf`7H^udd_%3A($$AKvfZTCgpf9RP1GG^DKgY}3zp5W!=$O* z2=31Gyi7G5=t_A)C-;7uI7l7`joXAKWehe6fSuJzlPJ~BL?mgRJZx$32q{LVe5%E; zaLj#IM&svR@C?8LZ_uc9<;^l(f>;l%=p6=ks<`2|n}6J3@stf}G43fxYDFG}8`CC( zD-uJ^|3vFk0`o&O%e04DStMApod;Nh~buGnqR9RD5+R;IlL z5DMUtzX$wXItd>C&InlG*NY0mD5Es=;&_dg*tF--xrMNlc3f8vBDyY7BV-{8{e{$x!7N z3b3oMiJi;*8R`UUlbaU=hfP;j#cM_K8Y$$Ap;jr}T}=_Y54WVxo$W~Jmw!Q_Efsp5 z#n11wHcj^_0oXRDHVXm%Qkgyf%8lG7sV1W|!k;Z?ttI`ToMeTlNAdhg zC4XrwX73~QZGt&2E8ZS?o6f@rmGtyA&zyOwP1hcSKm6}CRUqWe!UdQLW_mnECAH!b zRLhu*eC0SnPKp%e!LT}4!iDckRDfur@AI8=fRY2tO(4Pq;~LrM+rP(ZM0WO$SgV-}O^*mRO`p{8!MH3zX7wG7|!x@wm0!X5_1TAT)Ho^k5tXUJb zvK+4QHROuP7Hk)YUGG@;e_m<+NWf87pn)Cl95{Mimq6!j zWd$F6t2+l0TcJLzv$fA0{{emruSr0w+HBxAJLBMAZ~kL{ap#GAdr}6@_GV^});sNs zvQ(iF4yxH9qw$m^Y-!s|wpXe8Mhlh=G&`XONpl_p(GB@vK|yEJxA(vMg_a!BV%j8k z2dkOcBV>lU{Phq9RbuOQAt(Ail75z7DY_mKHD?|%+79U~qa+Iwq;j9QpLAM=TNICg zh{xMoTqSQ3)NpUx#vXHbb`omnJGCJV0{u#f{3~WFEib>X=v^kY>2=HDSkBdw~HtOXCVRW zKG}&%Zrv~HJi?K+e=H%ApzNGlC-8mX~RFJ%RksDYv-CX-xWGLFSzV&j3-~lW5k4NS;I*fz^JC#kU`kq{k3A z9vM_)@$E2qE-3=i!&pTh>OB;|7pTBPCkZB+s_~l{YWsZPr_Q#p(VoN^K{BUbW$&@S z*`^fwNKHNn5dRKF2L?0;uq{Dc?^IF1KL#+39%yR=rqRbz=C|xgYhz6|Mq-&YF9@!n zqudXAd!hP+0+4+NDSoDyIan0<@q%WU0-95U2h6JaUwf(n*;aNYg8Odq=(W)k;04qa z6W4dM$FkPCu-OuU9(dXE%-*9IglzROB--wwtqiaQJXE%u$gDw}WWsmee(V)ph*#!QM?W=6r}Sdi2BZ4Q4+W zX8(6CD=+Wc*qBlF-?+0caYPt>y8bZ=4*4%vd!SIC8F)m0R8j=h?%(+tsNeQsG@qR& zpA4DA0RC7=yKVi35JUp40c(9Y%ch`(WIjQ(mlXt@H z2&;Hrly~w!)s0oh|E2a*UcGsF!R9(uIrS;Fn_-;43l53mr#|;a^tRMNA;RZj%0}NB zUSG4XOy(zU33j`E=IzQ}Bb*Z+|>D-+uY|=8BgH5G+ zcW1T>5p3_*PS}jgvMMKlQZ*@67s)8#Cx@_`s3be9Fj`PJ>hBZ;xp70e#BVa~VHcRb zzYB~Hg@d*JRXnA1Ry^IQhyDKYh3e(G*JdjY{$S3RBODmjm$`S^zz!W3b=ke^rISKd|0&4itRz5oup=KW?~ zSR))^7i2V)XyW(=S*I zIMIJt9@l9C;V&6I@{O7s9R(R+&Hpzv^l9xjMXlHCVdD$S7qBuT32B_xzC0G#mdBn3 zjw2uu0OWbCpd?;UAIIM@`poF5ATIk3mCq@NpH{4gU+VakH5%yhvG!8mFK#Ttv7dBA z>}k=VQeh$zqcwV>cW(M~>sE=g{CDLU-m*14XZic$?8xkqS5XMbd;hV=Rc@EdI8lZV zmadzR>4lgyzu&hnkbEe}{0(X_=KIFgjFy=_z1Pm?i`oall#&c>UWOtEJESDhGFegb#Gy>@a=6Zn!hn0-YIr;)+eeTccks zzx-Vpg551q$|Wl}GE-k9W?K^%BRJ5j*`g+uOR=*zJgEi%s~(1zjO3K#6;fnx#BAJj znNC&N?h*LOAuMY1GGt9%dq0_GdvseSd*;*CSIO7Z87cH%J*x}-c)X_Q*U}`JkG9?q z6ueHI$E-@6hae>r@yTFIML201-P~t zZF^N;);WXHg+HFxqV300$hRz@6&9{8`rzJeo;>@rhj{)`eF>p9LGXB5Pjg?v+nuDd zqMqIJ2)Q(Trqv8%Z-Y~up`HXPv^I}-a|Kf7oc9I6&q3F>eYS1=u57}B4CV)`c6qdJ zN*M|kUi`ScIJfQJ5hkMISlw)Gkrz&D4=P2{-LZoCje|UDsD>0Y6}HzSl%vz@pqW?1cg`M^ z*GY{Sdf7(z88}`RPFP;PQ#gjY5B<2I$scaCrl-Yp`pYKtOYhnW30ok%Qj8^8m+8M= z$-jed9_Dm-k6hOXzn4-j%KRMx)E>-xK;Z%ZcE4?6&3nY_`D*!wZwpxbB7mKQp~Y3S zBp@3aM)?DO9p4s5?-w54zAW^TMG<-WTk+YsfT{pPgPj;<5im|7TYE0GfG$#h2%Y?} zd(3V2csZ{9k>ouV={>q&OG5LX*Snbwqd;x863gQw6Z+TPm_uiDu4L$8Hp9s?D;Ey^ za!fPt(lw8Y#6RI8=8pfGIPQ&(f#~M;q3(dQkeB7+=20wtVwGQIhrGjY8{`IUuzLk} z9GV#}F+?ztt#vIyM$*LU4E?!<4w&=pr`e8%dUQ3k5-*dnO~Ma-KyedtC%UrEZ*+&P zo9wb~dnClrZahsW$aR{6n^>B8Ik(CFGyVT*Kui~hK0s57uT#73OpH9(1T|MAvnSI_ zwobzJ@pZmF_zkCIZst)`Xd#x3;O_+8dbtyP8o;n%HJb5wf96(b1y~a~2(FXgT@Cmi z<1QWu*NNes$;Q|>ZetCLnA-C&h413kdHFr!RUr={*Cp9asr1IWN`_)r^)#5hoea@Odd!{v{vAovWe-nn($LzMRakc(;e*Nh&Bq8# z?r%o60^sZINiKVPh)rtU&H!9)lmM3>>`zq-bk03Xjhu(-&4ULvguk=I;+Mw)GahJ8 zplC)czPjR0?4d6VIX@DFzi|F~A0#)s~_&&kXJAvhhIFp!54cEin1M}&R1II`vBpc%;M$Q0r58` zGxsj4-;C3*uw(D=RvQMz=cx8<;u*;nRR#B}S3qfhDc+vrfiw2{4J(v@bpDl-8;=1i zUh#W^qI(K01+z07GC=<5RuXZL(T62;&zU1PBa%NfH$<_W zm1Z$?LY_iGTZl!noS8jNHAjR)dn61!T`NMHdh1%NrFGKOee#Hih$*3=+z38CzGxNR zW3M7+3Q9^~pDPIrcM*vZD!gHLx!-fnC@U);vpINq-IkM=*B4;l`rQ!Oz*V1C#wzO;0@LcyjDm2DQn{!#fjKhl}{ zEn-b!PCT`y3pZ}W`p<&>(^b!1y7`ubw~b0rsas1&UKYj%Mt3;9@}(S^Zh#d-gi zy_aWWXJ@y6Gte+p_v^uic?f!gCwuQ-(Vn^5t>lPTirWaC$O3_YShru0pU}YHtgg;p z*!U_@GenYMyWZa!ZspWn@>D#U6PL67QPS->M#b=`t^YoDySYu=k@uhPi}MEuJE-q= z=8B)r0j!qZzwoe%bu9=!3;A2|xm&!|s&{MP3Ovtqwm~jfNgg7I?y3udQ$peq(2zg) zg%c}rD0}>~!CHn!kp~7eQJbTzg)x-LlneITCnO@Cu+~au9g-#tw#zUhl6fQlCc){x zkV@LU`$GI?EjC|6v3wusJ0#3UQa$HJ_VS^T`&rK+be0hX;;9^7 zV6}oj!Qaxl)Pu_=T!JjY>01*c*o(Y-r4)+O?hRp;zBeoiW1M=c_MktNPeWmW~+YZ`Vy;hsg@dkoBr|os|=@Xkq}7z3Eakk&q59 zbP|{Pix={h0FWP>n6U5p^P}l(+yw8HL`gEO=7dTT{$ds+k{WhtHO{WtRiYw6Y_MB} zMO6cH_=trmBQmMTfcV^!GcjYdh{1RuCc&>Xg7`Y*SM8f`rZ_D%p;n8Bk=uQC{w&JBkW@~}TnD&7`B>Ko z-EfPc3rCM;L4SjX=6BbGwX8fnOCwK^8&FrA@Cv0261Mn!499}Vk(pOvbza>OsbL_^O!!=I#ijk$&uIV}Z= zzZ`5H-9w{r?{42<_dLdT*EDKm?j36ZG75Zxos{Gh@^_V$KDuq zkB5_SC?M?DW4YX4VREgg$`^tLv&<@{A}q;2o+RrOlcf3IfG6?g>hv^h#kR;(6^;Z; zOT9c@@^h6LCiL0WbeHOQzdzr(62+XuzxLo@_r;5EJqjtt`{fo9*dJe}=RZMGZ{sok zD>+_g7P2No>Hjh!$$4dRT&C3+L(v{Pc)&*lYpK3l{{JG;5%kP)i1*AP8waFtdQ=_; zTY|NDYWBwOW+c5lbjS->`pjBe!3b*bdiWgpM}h1 z^)G}vEZ#j@JpjPCoCs|T65hIbU}sqq?U&yD&PqHxPE|yVMc?Lbe2zCpBAUryKs({v_)^WEO*V zBCaAYwj;>>wr!r&{`W;imw-7y&*{+~Y#_w7{ zW#SX!jgWeVcnzOSr z_Z)*n0`-*}3%xN{^fVnqbuwj-&q6L+1xQJ%I^geMULvf2wxozJ&v*uOUWRWq*_{q1 z2&7`efSeCD3bt!cucH)H-7n9RrO0`zHXBGwVZP5o%@N`f02WzBC-9E};48ubmk>*%ge z`zHsx4k6ET9L1LXZWJbr4v#f#MwDjd@Qo~fJL>*{CyiGSz2{}Rf?p_nOXsRpj7K}* z#;#b2R|+%lRH7qf((es5;QQ?u(P`arpX+Ko{;U0&HCXU4{cmxzL_WH&Z^^Oz@${sH z;6fCNiwTm!9QTZDCw3yv5Kcdb_upAFqM1JoOeU4+Z>Z^Sz-Jry57z3bPz%rM3BDij zuqjNNa(j(kxKp%Kf{xIgl9o&Bp1yu>!FXCN3LTM|)-9Gqxe==ht8-~xJFxqJwb8i7 zH8R;Brd-D>ko)ez@;~{+h%FT-h&DvJFl~3)&q}=9j#2zY+tt={$LVjVB+3`2>}+uT z!6P-H$hI!-${2Lbjr8sYJ*rEC-LcLrmm3mrpUXVDx6uYg?&II7@*JICdBQ9tY<(ApsA!Y)+uq1BW81Zg#t)wgNamv8H&sjB zCM8~rxpkaLhwK+}@i5ca_PoAqYHbpwtHMh(K`U{ELX#*jhbXe&x<-EK&*E9C)6PSX z$j8MwZW{CKIhnr*bNBdLx?2$EVsHIZ^;8WcEXL*|($#ZJquIf8=Ki%8-L*g04wjCM zX#D!@*z{=(cLU0Yo?P6+;aa`~Sf2qDv{~qIrHjkhg5pZd;QZUjpGwTdM9F;qyaO&{ z*{EYedaUN+fDz3#i2PtNEHD_=o7TN=$JoM2$tqFq-CHYVe5}aF7!S!x$Jjffl4em{ zOBs<0A&Rcr#UAP+#$oA+X%2yr@$RtlfhYJgPrb|iUY<~a|M~V4=4)ssK&>~r;>pTRo~LG zf^WTWSkR!9Is4taIbAH*1UnjFMl$UsR?ve|&9G&i2{91OG>i16!dl2}xN;Xll zNja4e;Wne?tlBZ_4V|EE#V}>!qkTLp-|5`(Qb*z(bXfn=71yiycv60KEPP~lFI9&_ zJpEmaPR`%j_~NJ9#Gc0;{g`Klr68LA4lo$Zba^Vv-)pDjUKq`O3nE~ZKqC|`a1 z_*UsQ`}Y-3HcrlQ0W<1+yq2!eguLv)5pvYL;E;;m;3s3kJFH^&8|Il#8F>T?A8G-) zp!VVlOX?o)KiozNYa`}C)@ZNdQ^RvD*$F>jr29-NPzQ& zf#%(R8{O&kSOjsynPvX2Q1@Ds0WlU6#fjotK=@B$l^8k!A4HAj(kmF{mZojgM46Wc z7x_+(!{Y5e-t%(3&S(STyu->wCG%-UI*LVc77t}N@$>2y4%Ol`wdH~-a}{33$4`HR`~4CrpZ!Al%V#1zXL(T~ z2NMi!TB3#u%%toVA7^2001O9q%ckPwzNMxJ*eYyml6g@;lt>(S-*ycYu61 zd`tn4%IC5g=ij%Ge!Kk8jsuo(7pEX?l1=Uupt(dxLe#iM*KTh% zY49*oym-{#@i94BMr64G(StkGKI0Nc=UEqbd)|YkzC~MpBcWRxZ_tLebSbGm!P0Ti zDpu;jdo?*Ht>EhPKQ>TLV4#Atv4tAYfB`QH6)e}iSY0`~O(+B(7p}w^Qs2EIcsZ)) z*|TSzKYucetVw}OF6l79%+Ev}Ok()(;nn9(PRS2$*qRk-wSr1se5-A}h6d?!^LiSmU*$?(USBF-j(*afYA?v<1wmGP3;v-vUB6sFv=`L1lJJT-T%)-mxNUe=e8c-U;0xi&fMTAR~2X z&Ia#PqCS`p=T`JRZ$w3Tn}2`Gud9KJeODlMwCYS3Xvj4ie|Pj`M%K}j>bu`+i~Ox? zL45BbF&^&SwHMDnCLOnoe)y1T#gmxn&CaLkSiYaTt7cf!+VxK>iL&wW7h*QnhOM*B zA$Ol+u$xbF(J7MjTrgG1LMUD^5}1^FXKplE3!TQe*!xMxg``PLUxCv@-|SuK6f3G8 ztlinLfRbqzP-MO;^Y5M2aq1+UIIWsAKLHr3u?E`FF z$G&KFp4V$Xs>k-fx3?*4(uE}pI=JE*oJks7FO4|b4D%vh9%Ww71H0$YlWodd*GviX zNpC^KwkIC(_v?mOubrgGUSJI>wQHP=?0&}4Pfr+4PMZ{?xB)}UffaYBz5~D^gw$eE?fyb-t%nm z%1+IBamp{i@;YZH5N{w6{cZ`La@o#|U6^w}u;x;y$*pThMF~AncwZph)4IWhJV&nz z`W_NYY_6x$wM)J0Bgv;PgzK(JiBD72ZW(CCnTos)LL~v5omH8nM9(CU(Gpxp z;pOY9^)3Cb-9|aZh@s?KYq|I$Y|g&I#8c4bDvp*)Bm!laD^b?2VVD`QLxvjG$Ro`_fx}DpQYHk-tsDl{na7z} z3U(dLv8v32bU+=GEY7SaXif75!}>E|GYh{v47Tt8tYjzV2O~fE%>@Wt07e^?EzofX z?8*NIUN6;*3c$k0oNrpmgjYY=`vy~$ znTBL%>!?Dy*{Jz<~XEfyBukg5HBvyjLNcf1>m${gg$|G{e@ z*r{LCT2gSIoR&qT69gce0iU~4@5Sf5B+H(6gB55%S(p#HQq_KZ^KcuKZmHO}x1ZXr z45VjC+Eaj@E$!yk5EsH7BHm8q_1&6^1W;Y6VeyB80+QL;S%l{@73j&#&CT6^7iHRw z|Mxbl#q)Z(4TB~4EQlzP=f6Y^QwU^MPlBsj%L>S@gz`&lD>^u zY<;a+@^f6PutFua%G>p35W$bDk+o8W+C=a2T_WJ^|Z%v$2##eR< zwVWm`>uel__RtggHw#&K5fMTBlFja&iF-&UfmZtBQfMN?Ox`iwaCrq$;s^UEN^6!x zsaISmA=nnd7208{!uw7&_L_)h`UqR(fRks*44Q@=LUl9Jv?dx}r1$unSVfdXsKDze zd|x*E{=`IKK@B6QT+wQUt6N)rtE(l6Y1ezA;%hAcQBJPh#v{e`c?W)vitINt0u-l>3*SbtgpN=Y?T>*ma_u@}ev3|D`177-DV-Dqo=9}$b$!B~F5-1$@&ZL$huCRTS zypfc>cj%uDxoPn7%2oh#h5-%e&`XUpIZ9oV@hPaMhBL&?Hg@anKD{)1xSP%q&Q*t` zU%hm9Ry6tk$9pV0&s;+O%Zt@9vzyL(2A;300~B(Kj7wi!h;gcq!4GHHT1!ZUlQJZU zk~)d9`lioHVimutrQB?>XU4M5NvTov=D>en z^}{Pa;OvrUirZh_a?c*r=1Ek%eweZw`6p&W9ZsdBPH=$xRyh<*38`)u4>;Leo}%$@YT^Hy#+&elOjGcVe10A8Vs0^myD9$A0G0on=*2 zEtmU^t7x>TsNKpwl*X($?VDym_kc)tjy#Uv_xf?xA8WU6Qg-3X0m!RIOQO?iHONG{ z>2H?G%EZz2=io?(+Y_EltK~ZsJp0+f^1jBvT!`81-#((&%->U%Spojos3>C8pve0^ z3A)Sus7|D~ril5pA;CP&z`?Us{XkumR*{3PlNF4zleh@Gp@;3%I+;!MQ0Rx|=4)}l z5Ye{6-Bf*5jh9iSP#-`cBE#>U183UY;;IW;wG+Cmwz84@rY;0kbvwVbhS?m#PHA3n5paM08!V@xL0T3)}N z@A)PD=lQ}upR$yC;!=2o7DLx^p2hTP&$A)Bc#n?nnML|N%XvrJS#`_e#;4LJI4V1$ zJz{7ce8MJp`1n*!Q^fh-Sd@@g&wb za_Vuqvx0(hbiP(9vgtpz`+dtXeZd65gt2w`HfO0Ug<}eunK{G-)=UHQ{t)6=FL7=7 zczhxCd_cVr--0|>a*%j$l{M<0lb zI6n@{5jC9D_E(0?h&o_a$4B%hyafYcFuVSp8O6cK34h_YBRY!WFwGKqR z+uep&<#RUeu;5jBBd4z3V?-}X|hds}VFtvwlv?yECe-+%tJhDsX()1Nv#Q`=XAQ;lStXKdFRALDD$$%CJX z;d8Iau}3w9LS$H}qk8{xu{BBOoUGX0znR$kGT7*^@$0l5BR3Abl$`fM(1^Rlyi!1^ z_&a&Oo-$FUq{~K0oP=4KGc^<1cbQZo&fjlgNixz@r0<`J)8N;9Q|7!U5#RXq`gOVA zB$eox^K6j|C*A<9U?P0o-IsAg9L5BG`oxat3wiz}jqUB4SFzd(8R~j^(U`!rUSc2M z{^8-_h(O@*0r=775lC`=etvPf0v~Pi;n)N90QLM;;iUfHG_j~$FZHE3ybb15ciZ5b zjup3~?^oL|61j0UvFsM*JUpJh+PuBC_`Xl*%b}YCwleM($pKU8C(AKaxLYxiStlp2 zy`!U}I{_7rlT&kz$8ZsRFix#MHxPT4s6{P{xw*MQO}lMvl)Wa)M(o|+Wh?I2A~+`3 z`KzzkV3heZG#TRDML8!%S=+_G&&ua*t3P?DD=Dv;;?}n|YDgd?qg7gS7fhaoKPt>HPVi*Rt{auJ8Jb^NWLw9&q(`osVJ7__UdvZ*$!*Ns?DE{ z)dl_qe=h=My@jLm%7*Hyx+SJ#k(a2X+{csQY4pz{%oLADz4lOxnsX~htIH*=CK2fV zZk-dP>gceNc>dxA+t*adqo%O$ORR3)2##vz-pT2Uw-!w8S5|wx2nmnhgxd$eD`|U3#F+!fqkB$d%k3z#rFP?1dQ6Z!GFx0PPU?I*V z?0jaV?Auit-dfiz{VuB!*`1-kW_f|; zDT&;^3ox+t;n#TMOl-1Ie)k_;fv2sl>VGKS3KwRt`=CK1JyRqz?^!=}b+5;Oyx%|7 zO^SG=LmHpF$0;-*uNNLxHIUjsyb<=Bak-GaN1F7}pF6nqywvTC*pxL)q4?nJp0748 zp~E(crH60OC%}e0lGa9|JKjIAb{p5*j#)i#7uriyljBgADK*1nX$au@(r@N9%xI~` zaF6QWZm*78=Y`b}|DG-~`+^!F6YKvo9jJqZN`1sDV5{^gA6>x$EEsM18i86K%=7&`JQl^QV)-elv;fz-&<2YlqQ2k)Lg+6%WZE;>LUQ!S$}?VZ0lDWCX`03ij2$+ zA}=gqIM$2V6@`lFteDwzp2 zOkB(p?uYK^wi7w`LvCOu(L zDW!GT@=tSkK+eU{@@-4*0xmd=_ow5ts;Bxw*W*7Z zrgvN0+EPH4EX(xkAM+Cv8=AB7E1uV5<*)1M(G?hE#X#4=i7ucR zb#%H?F`gEQGVeeQLfR2vGUj=%Sf?;PgNZM@ypGMvIH$X41?}N)Y?H029Ve#BGMA1> z{c0D|Qs-FUc%kSb;n5twnKnGvx4teP9lmy{FGWN5RF-C8P5NB{-z%6luhJG;0ah_b zfegNakC!qTRsL;0i0E*?5Xs&%we?srRBwNJxl=FUgZZ7&)RZ0_6d^6P>xu!2wY4Fo z*OTZ6z0d+UR!^#Q|F-q&D0E)$b|{DP_GQnj%oq>BV&%3W8w4uUx`ZLIAr9LEU|2gTb&(F#jGnoAj4`7naQb|KhL4kn(1uQObL=(fhuWh}+qctR?mOZISJa z%HG}1?O)DH?!UiGTzaQEey_cP6sba{OcP>wWub-au6xaB`j$+FJ}(Px?(5go70yeC zQ04(Sc_~of#kFTxFRx4FkApFiI!nB#!_UQQTKV{}B-=SYNYvyj|C;On`{>c5?Y2@1 z$1J7Nz8Bq{w-t)bEQr3P#mJaNIt;(Jo;LbxdbRJ_7d!JZOphgAd}e1-Hjh2llS^Xg z{&&-!hJud*B)+z}@``Q0N%p^dZMrg(`u@eG{H17m|4z{&SVIX{Ch^@!vMi2P3VpzlQYAHGl>Q$eDhN zLbW@KZ??V{VnROst$A}^ia48MsqW+?g4tg%cnOO8;i~xI6Xb{?>_=#5=n5=Yvw`>k z+2qyV0dw!M5ZA!9bOgp31g`qpGQ_ibvi{d55F}OgTr)uh7u3e$ND(q2Mh=nPmLVMH94JrWv zN`Tf8ksrPB-FSX!N$mnt6CMmVu;Ks#n9b zL=|rFe{OVqFA|N#-95jp)ycJk?=p4K>>r+^_d-4W*3#_asY$rNL~X;-*k9T+5r16L zHFE0)+vm~ktD#px4sv$B2)#IH1UnG3f-rNvS+Q^!B%O)i6k1=;{_uej*q)mo?sc<- zCEDFWj#91fnj4JCqz+3?kBP@l5eQiR+gfbeI|IZ#L7yG*X;=L_TK4*=2yFs$?JD7O zg*j_{59h*T6_rYzW%tbK)u(F`&bod1KIr=|V!Lf$xxc_K1mS4oJ!dMyU0aWAa!o%)@;k!j;wl$ z^~#@>j1GywMtBUh?S4TOKX2RCVqIkHyWw)rcz3k4hxj zICf>Lq_UEkl7Xw`_4PMyE0e0fhd$WTPLL#P-r4P-OMo#UObLe@@OA5@C+(pmWSMKt zlt)#OlataZ)O3PI!8)Upq}6u*sY|@ z?;q+PZG@2Iw$_bW>hOgj@Fa%A6$T{EqPZAA)gyJg1~MYVI#LqKpin@;SX)_RP92x!H(2$qD*Z}K)94}{;KM8RtcFdLQ6^MO9%Nl~%#1z>UfRQ} z%dZY$pg%lzjm3e|nf|eA=!{lVoB#d01q^B%ib!osEpj^C!R_{cw%uqLd#NUrZ!q3h z8-L^seb|&-OwYofwe2`S8Kw5Q$F9<@T`E~SD;*~mi%yTa?_$y+FWsTC_(ABhxxx!w zm0u=X_*HKonJBDSM|G0Fn4Mg&XNPZOVGzl$4xv#VJZM3jQE)KJKYq*sA~R<-zqV}u zrAF-Z7iPVPZdW%_^}TQA>qHC^U>hGFef9cvQ;pZs zdv}65)V*4pZvZ<(SCZLP6HN4gJIDIJf7abEE&({3pPvU>?D;i%t?^u6+^;qn*L7O& z^0Y0j>9YfV30R`v4VT|5_G3SDvmCS=5$uwXV`5pG#Uf3D^m-u<`j^qFDobc~Bo?udwd>I-?@kZl@MO_KXt!kzbCn|@t|wBvpTSi z(|a;T@oytiq=75dcWrJ8AvC&C6K~J_Yzm<{MIW}Ih~x|@@zc5J!C5Fb<9mtVdqSKJ z6i-!=(D|yU=)al>;H`{|4F03%{uYU#P(9jUf1SdLhcVxmE zV&aq=OC+;+D4fg67u6gG%F%7@#%rS`pC83%TdA-4T3TyNg{aO=W#1$9$P%h>HT zq77I$ssOt}1@E?8w>b^FgFZJlk|AoGaiKm>nr@T3_9^zn*o3uXS&!&{R^yV^@~I|u z4zlHEuQ}~KvPi*duD#+MH?W}0@)qt->ut;B{m61NK3=+vb6i}XhQ423P8sKZarVe^ zB*h#)#zfcYnFDR2SXlru!&}1puNi#2c^a*-urROjLuk|nA8y`&BTxkAn5aKjIDx_9>%e4Pj$qqDUk9Ap}+0Csj3!^qBw1HM|?ug zx99e~suu}fqjVN)eVIHzx=Uh8qLEvi&C}RB#X5^LQ-QwIU!7lW zK8SV{63kN-%zBCO7;eYt1kUuXHt-+DZi2tENJ$^nLFq!63P^U=x+OlySQjK4D*ld} zi}u_|5+MYgR4kTM!!D*E9UF9R2rwap49!P05SD79#kANJ0|CsXXEB$OK?ZhroEt>G4 znLQmP@t2uJdW-@@&sND(`{KLesO%YqM0R?C2XmpbRUEnXxV<^~y)j!(?x$KQE6XQn z)@q4HKTj7_z8y$;JqY~`Zf++brK`%OUj-eaUbDKi^b`mUFD3whVS{iTd=Lb^6wuSR z+T5|!br3uuENtxuW?1)@i9Wl`1MaoO#OOW;rjX031Yzo^$?_bXMgEBux`4__7Dt^^ zWBeDlH}T%OYrGq$vMf97_a5Oyi6Mi{yY`FeiP3vXfox&Fa}jkPsyj9YXbRFMsO2Zt zsrL@CH0N2svhE-a_YPP_~<3+N_}nN=D38y;abd2h2EvY<#8FLz2% zAOFhjy>ZdIcUOU_mTz%*^6As3YnGOleXcd%n@uh(j++3S|5B;T}&T6BUAjl;IR1ZN2BRdI>s~I|)u1|AogQ&BtFqOBtpy4*cQVuI`we zRmV}OkTw@?{XKze+uYtgjdee%rxKUQ^`k4}ihu2QhMkKIDUB@@Wknacj$GYOYz>i_ zyCC>d_eiq=o!f1X?8YRs(wjBEAOTR}1oWDq40;c?L!hUp5J2>_A69EwF#QuH?6LM_ zxWHNp8$QmY6|}eIUc26}bMw=~i{R`#6@JC))>-KPnv%;;JPKBPXbOYByN{h{`;~;_ zL7N|U+xc}5bVv;ukV-_m`i~2mzt*W%t1i`JR}`psKU(XL$6KIXE3mJ1hP4T?%mdy= zt(};@n==JGL8ffG>*-yB2_iGkvN=kytfbtlkx0dYhswg9v(Ea~*?ZkDLSQVhW1uh- zwVcn&ISZeuW6*rT&0%Z`^^REmmNf_3$B zR6BP2e&bWNy;HC}Hj@lBov8Ke-go+oBFc{&NtE8h9S>)H9LF`2aTbYKMMldmj3?fv z|7cmjPR!c-8D7SBTZj1Zeyz)1o*E}6-X^5$G&f4NqSCgEF4JY+2>yPwi zxFbX^HYRhMcxdsbfAzz#?sADID>%BHq1ZCF_c2Q9wDX2`Gronm+mjK zK(Xy-gLnJo@e}fYr{%&mLUrVuB}3kt{)<#>DsuIge!L`B+-2Lar6{mNa(6FOF3B1Q zI}~VmLXcCq&J|?QskDPh(#|O^*0)&@GA@|c^s0&Dyx?5LiS{`O*Z3QKCxpTa`B=V3 z=i?EyB6?QM+&p94D*vN;&sWeEK=lQ-81Bk~p6{^9+)fy!iyM1bY-BIzV7Lb%atSrU zm7W``$e)kS-n6}Q`Y_HSNy=dL^>&nx)Jw za^r0y(tJaE+)JVZ_>9=8si_FPw?GjsbVq9a`!scK;MbOS!6hML6mzwHt5f7$%Dm=! z_9G{tfb}1lh@SmO*Y0(E;%z+pGc1a7nW0S&o%F&i%!qzfrVJYqyrV6@(oq38T){eX zF3c6rxa`5|kXy(8M|a1fhv6_L=w8A#|LCf_m$vb5Qx1r-ncvvrMmw>kbz0!E}W(`&-S@hNuI(FH~iGx2A zD?dsC&p?F=VoeoH^?CpB&uvc5_1#1$vw=vQhVe9CQX2N`0Pb^O{80RS z#!zzkkiEI_t_g7;0Z#y)8Y{r2ps(-O?RppEMV1S#$!Gbl$jiy&rbL$rWJ65u=b{zK z&ZyISE9ji-Je(uX61nD!*CD4WE+1=E5Bl^Njq~8OXG5_SHJEL$wNpoE=FML*9zHRE zb~~v?&n@)~I6uTge7A`Lk|r{U{!2;Fz7t-~ogDZ-z?48wuq`=Zm|@X(*%N5#vbDFW%lw=_u1l$ACd46uX>zTEd8P=U+E0;!6c)dXOt=2Gl|Ke z13t&8z5Cs&)oQ!#64(tN9<5m)X(?G%95NlAmpX$|5%mggGp@0cV4}_eW*DII7bsjL z0nmQM%QJR&cenbriX_`1p#ylEP>eZZ7S+yQd1JZXnfi#6O!mRAVA%b$H1Fj?>u#UM zLGWn}XIGjJ3LLho-5kYVEby8+TP>KOYyWz{r03_acz^r;DFL+rG{GEWlbbT~E04nq z$7?@OU!*iJQ5$PiueEReI)%VAq@l0ug8j6>I9cvLqwhOpic(1RxjOwuy2In34lA>! z&^GcdVXeLGvJ6g@a?iY|VIhdjW+eqQYeyE{cwZ0cRNEJ{Y*Rfqns~97TM0tuJ!Yn+ zVZbmVvSnLml1Ox!D-cPF-hW%bTz(>&l zSVvs!h;s%~Ef3tV>6UOLyNNaId5D_VFae*cE z#KIvgAw>GvV=b=9-c$+2pjH|0V0k;byLu&qk#P1P9)Epti3VBsC{{H|4yWUTweb`E zxjLv}&#bBGkLe27jGCYpuKB4ivZ8#Qb15x(?fdIoHdZd%fm@4CY?s?!scuU)9-Gs$i+pk1EwPhi8i|9NkR&)%0q zqLg~4#=-9)t4h+G2O4eHBrjm*UNIX$FcZuj#}4R$=BuZthmccX1Si30fI|E0ZIm!j zYzFphz>olV6A;D#^NC^B(t5Msy`$3>`u_d96>vok;5IhY9_s)0&FyEr7HSO3sIIR5 z{%-T}^73*kfbSxv#Vt_M(~|wCZGnhHgKUNd+z!3!(MYVsW$p2Sy~Cwp{~-cN!DQuw zh*y7HgV@M5s~R< zOFEU$dn`faxpsjGAz7gf&>EWhx6&K7(?2XWS9=uinF^V)tUa$J(RxvtRC(kyWel3M z9&I!tb&UB9S>mo;U5@wE5hg>~OzQ@ZF>PNxOpkKp@={-YrXpn8Sk9QKU-*%iGPrcP zR%u%qb+%nHRg(`v3e8~*Hp}C6Ks8>5w0nW+GAPr4$ZI}*0#W}IbqG@DB2y8nwx%Pm z85=)E*k9NR2#iD99oM=Lc+SPHgc*Kxye7p(=!ruX2L8BidUt1i;TNnNM4Z7$IEH|U z$W^YcB|XIU&nM*{!+e=*a65~O#cZY0A|ekR^mTjOU9Na=@nj40nmbr*+4tW}@aKPd zflu7yV6x{n>$bI&dQrPqdsa$7N^6=R4;|xbpFuR}Kwo)tUeF z+m*-|l%EpteE$M}=Jce;(L@d3&TYkXYw~V;Kg(5Rx8Z9ooOT794twiLC{g(ONba%k z;dpCN$EK4kstUOBa?ZD)6S~G}5_idy#mplBjcSy5Lbu!06k?!c%UD9lUpNeiANS>; zR%m9&3eG7#!t7JOkXwPD9lMK6vU3{t^k9}tYhT*1gp&B~y70XP zu4R@k$8%-W+i;dHHkaPL`H*2#xh2=?q4`_;)6W{LQf7_ zJfcg!Ui01;4glh>`PSF>7$S*XSMn5Cd)kgMn`IlAR#sNp3>KUF%qE#4=8}ORLrXn+ zEMspKDcUSniabGaE3f%EAS!g zTxJSO;y^g2ch=)oNl6$XQD1Py_*JdzsQevBS-JunjzSUV3)j!Z7}uBzfSM15IOqs! zXf6%-R)CEF^~HDC8p1(zka^8J(9x@^-ws1Emn(S`dAMSix^%-rLnT0IhSm%)?x+go z?-~f|9GU+VU-f{%?&`9h?3c92AND3OM@BFa6OkLfz4vXxCG~bO%|S-G-fZj3S~spq zdJ_2H06QU$nwym_oQPm>Q}o{YU7>slI6TOp1c>$^X(|LM$|w0!^Pu*7eUoB$b@#n@ zEf()omKxvjD5hFo3l?f>cd2<+7@D)ZfDPqfY}0O$UX>1%ity2#KI_+pRp_kH@fJ5) zp>GfmuUrZ>^@&%=*wt=rrYhK$=y)*j!NoZ}Q&P#PUvRH(qU|^tnb+1g)k5gNH5ARg zDc}N5uX;n3oZ6@H|20Ce6j#r^kUWFf-XGQP|2Z@yY$dRiNvO7CF-+ujapx|8(2ng7}rPwo}!((@) z?Oo49&)^im^gx*f47DwH=_1v3pwOL4moKLEt4Wffq1gL6hCOFa2Z$eGjGdRFvat{h z>gkpsI;YZJreD;0Jg|GZJ-%s9qm$3DV3W^nZvVWR{!hB>^Z8^-T`zC8ldfufJyF}w z&`VPPlgg1?ruDFJetk2hJDN_nwvGr&aw99K5MC|2k$}_aj zEB$3UZb;&KENeVcJAn_M(y8dfUUTos!^JX8|Z3nO(8wi}>G?v={`LH9e35ywkt;+qtYYpWX+>Uap+Lx%mM4#rZ$DlBSH&J8?xMMLluI%MTz~Z z&;Ckee{6bLP((ki+=H{1vi4{iTPc~5!Q0OENj*CZxpdS>6))UejPu0GPm)# zh3yWrUrM0yB1Mx}EyJoS26G=*m^8U&aJcq~!C~(Tw})B04d(^x8(;H->!^61zPC(6#ko%+6o~2MZ0Y)sJ9)eaH4ekIYP}?E2v+UHzWM*<@ya=JTyu)NRy}7$lCyB{oKuY2$R%sB$r#5#1_{YKE zkgi#Xh4xA`7E`rGKA%$5Bs=gJU5Rz!#F;RK9@C> zYWCByOf}JHxaWnO`+3AEH`|qhRBj3?8xK02O6o!p?-B4i*_gDHuG#fEA(%=az}dKP z*P~S@qowULN~Fg`SN4c&ifa_fUe7OhD{F%B%3hPP$f}p#29EBW9s9zWab@bVsSV=* zfzkF^E@i!*-PT#r6a%~fUcZb}OGDVjYo%Ih$kS!j6D`VDieu-F3X?tp23B&iOy3>H zE&u%JGbO#0mcCD0{=bVrr;s(O&Np_pzPR`>>OPh#?=Rdu$c(YW*cYJCi7>(TFGrYdMDb+%0ZuctLT?5jQUFE_S>nWi~R!?Q2G z3aem#>Tw6^Sgl1#&pUZE+Uy9m+@CEDt#dlQYP|6$z$RNZBnn(mPU2;RH0;TU1Qv-< zvsA2h?j$ITlq)Ta23E+fEa>opIF8MepS3D?W{0vGDw3O^&KK9NY9rXEP(P!oZgV^` zCWaowk8Jq*kkH`k_cz9A5O?Wyhh>(0g!0wR&F8gMDSxF;~lM|V|zaI~*0 zC{I%J3)B7=RUS$Xfks>MDvE<@RrPFRwiK7+uNS1NL-|+|8Y5*Te8zQAH631p4Jl}Y z5XCEe*#(%@W$0;yC;U%fhoTjl^r19>huk@h8g4w2&AABA4EtKa0yR9PZ=+W@utWd& z|DD?b*aqNOk^HOv66WV9uw`1xsrw!rak#A|C}LSC#ZbZVVTN+Mf#R20K~0ARBdn7p z9dwo-DX2HZn(>`RSeARenbAPWSPzxirAph!xT6nQ?SB3q+L}<_I)d5U?j=-=xHOm9 zb@e>|fiMWjIR?CahS|%bj-PYQ1+CNjB1#umx^VW=TtQ{kk>vtq+bNDh(<}e;0(c6y zStTg0XP6!C$)hsS1Dj=8_+DL`#A}%XYF|x8=g-k$2H4!#BcrAX`$;wlp?T~Lh5>s% z3T=$1Y0`$FTG~-pAdJl!{}l0kVk1;}e)jmrQMZQduUBZcl^EzJ6;c&%zoNUvZ7C?g zd6BbG;FiYKMbpgbNLLrezqwt61;v_2zn{>EHNuxe5Fh)j5!`8dPK9S6GG+sOfT{{{ z00IAsEw3gd8olLGz@GTeln}6K4r+#|WjzO29FSdd5dFZR<+eSWLTKhbkbu67NjZAp zqDi0#Oe3ZtWT_^k3|a<;<}z(ZO#6{GQb^4{Al7s}F0lyFMtoY_(A0ND)euA7=J$@tWk;48q} zuz+QQX)sV4g25p5lG9npR|QK21Ab7;LoEZ2;R{~J%ttf3W&z@!iu{5dW^M{hw0Qnr zmG5*PvwaT`Bmm)oZ}+=sC_(F;oZy+5JD5+$k20)!z^B-qC>yIR9_c)y(5T^(d8)3O zW2#|$qF_g__PlRe;J~j1tR-Un)lGZCuaj)mk-#qpF4zG!KCNU8$BY?xS+xxXrGS0B|uc^@4ezQph!3~u;-zWZX1uM zvFP=2PW5p@kIsgM_g3tU_iPA4$+r1!I^a5HJ%?dGXe{Kvo~Q#xYD#{W9v&)xvZy2a z{f3^>{<_ZT!SPz3)1!_V1!MDYnbI2>K^mP|{V}Og3gqFdN~q!XCeMxIZj^S1eyYx%)rA4C4_|2Pf>rEneqj?mk{4)?e<(c;y%Y( zc-1&PC6@Ds9fGZBy>u2tcfliJKzNCYMRieIj=eN@OsQAs`VP068$= z;EVM&4OJ2iv{KgqDz>$~63Y+Mok~g!G-|&|m#agxg~AhZA%_2Qtp>e+pwyFres^tO z+7}A4J6ojMP}yJ=&r}n8ym;>cFO8u6P$uwU&Xym^oyRMO)0It z*kSri+(&XFem(5F4!%`@v$a7mAg*gxhW^7_qrZQ4cKnboi7HYnyQJsbSIGc2z@A;= z4N;c+i>8QB3m|DDz#1^b4s8921sMmin|>azdo;DSEdjFxed;VYAj|-K1q<5EY7c%{ z=iz4%S&>N-U>rb5Jj6N%Y%K@$G{b!#E}aKg5^OpMr&hRR-}HLD8HJJ?+rIadD$IDl z78A1(PUP25NWbIa6sOqAUw=*8am;SoPF~*vmGY=odC&ZQI;G&rxf!p$iQjd;Zr=x! z#19-V)@hC1K1KeR?y}}va*F2xZ7d(;X89gkQ^s2UmMgNIBWnHN^L5=5xQ=r#xF?K@ z5FFtneU+Jv`^(A2b%QimeOG@`(Y8^5SJZsf{Mxnnaw@CJ z5r|rGSy{2wof>nZcnH!WA(iF&9S|?bZ(7LlCjKH_{kFJYZ6I%fcvacSi5pe-H&C>W9txI=SWOGtH^lj{Y$xkvV+sl zG~-lhq#25M&RmkxeLQ}8|@Jg5yl|sGmga(xX<*sJ=VrtxRYQ&D6G@aSF_vur-;C$b!|p8hTbqu?*Y{RGnCr zP>}$sAPd=LW_hBV0sm=&GJqcR%T*mNZtSxT1XNN1^NA$Dl;+A5-G@!%q}El zWV~ydKXp=YHhz;;sA}eizGqS!c1F8Q|7W{ofBbLL1Kk)sVZsx>Obl0phpLE>BeqDy zy!<1W*`c@UDyPlh?8wkicxGnio6DSLA|ER&3GXV$n?P$KIguSs1Z=`iM3hjo!ZlxC z`5VxU0ODZ&-n`F5-t+eQS=-fv@9)I%Gt#(Ko!&gDx5iKSNE5RH>7vWGee?&DP1t=E zj@_wHE705cR77`LXTJ4j#jT&>*Ol}9irH<(gizsUu&Zf>vrDoaOy{fnUf<=E-#$ zCKw{WApg}X>lcK?k9z{q3`E5t*MzW{!&=%N@n`A2Ts7WynH+0mRn#MH7{Xqv za1iI&#EogRy4SZ2nz~*C4Z}x82YfW3A$oXvUb}hoIZy}Ixog$U#IUy-Fy<1Wcr5Fq zz-x2r%IMl{8%|J$4NlA22?2ZCx!sEB^WGV$;*EK6jH zP}j6vuus$dkHQ+yUVl;)mQi>ZLv!UC9v8O z(?$S=2!1YziM38nS{aSXFF??kgSc!`#o8$@EzP*Sy?x>0#jCKE4zUQpOqhwogH7;* z8oC$3l{aEJMJ|d&7T{!7wtIuP5a@|quF0niuN5|+hoP>{+_wsDvlpZP?cps_e{Sx1 z%s}Ov_qI4>9YDn6zTc8?cA(;SD>D{65uOBNA!YHs_b})_*+wbh?xV8Xc+@uK zc1}cuMqXb2f{>7^ogF{ouZB(L?<%hYRSZwz?TyNO^j9957(UH2jyIgTx8*m>@H<@~VU`~@W?PQiW04kQ^7FY zkxi?Y+K}Y7F%Dei%(Q>K?(z4yLcFbEsEKTTfcY_!xwg|K@9k-o`M`YDqgjm~H4&oH?cY>$$CB^igLO zG4mRkj`v*PSOs~=J}clXj0LzXdbSy9G;$ggLuQP45__&M_&s`r+_lMSVx}5slA|st z_)_8E(f}tX#DtuxDi&}cwO*_oeNt8?MWzBVY}|)HXIATT3WohuxlLV8z%~E+l}bG} zTxRsk(tl0b_4FCD4Oj?>VfHl#ndjS&A0hqyM)~%JL2d+vWt4E3 z>{bAVTg;;NImE^{?^$fW@(ad~j+&7Xxcadqp^#R%QNm&hA)UOGCp?1P6*Ag;d&8Qi z4ENO4ts?eaDo1eojH?^TigNA-)?8<=R31GoqNWTZ z92?+IgdU5#;8MNcgUr(5**n;5Xahz1dKOHtLJSmOwdoIK*EcX|Lps<#Q*xg>c>*lW zZ+>kj*rxk@nl;l3ard#nu?ikE&=XfM`MBJ2U(MN*L96ehOavox^cASbg09?5?!qcu zSLIsdTRSl*c$&cc&%*{oJoPtTKZOn2R=uc7TkMVK=XZ<-E!T_py7@lXDvY&OieR&Kaw6c`C6{ktgL_6@Yhw>(CCA?3-IpcIAZu* zk5iEk0AM_lz>e=97?^taDLy47thN>n1Of6IfR2aOf)yV$ynQWgVIj7V5E#;9eGF0J z5uO2bn}+RfSLj}OTl?cvO-J!?~f|S&KPulOdr`^>U%EuB1nKGB>TjO>t3LUg9<~r+4*0G)W6!{eA zs@rfbE@^XFaD*((gaqERhhH&z;%xp%FHu{){ol$#4k_}#2|*#?(ALrlkH{JS`7;^I zhdvw0gF-R;`uetac3ut&YB2iu`=R3H9K(d%O9~3qVa+*WI(mGk;dGN_$2j25cPN!< zo;3{6V~;KCwX@V@Z5bd2B7)JxXLXy3#&!ALs^zXaiqh7$|5tkks=fKLO){ z%uCSE!bBe&1fEHlgqC*Xa++AaxWERcn*Rr|7C5OKS*U#`<<` z)26B!lF-;CWy@V%Db-H&*qX`S+a(6Z*fnq6hK>ony=>!~zTBxhnx?L|lFhg;&~2{& z{NW^}EwcPF+?K+CSINiAS>`U&`9LDY#|+yN^eKU^e$w$}RQ;4n11{(4>Iu}%e(&*# z)m5M2?0i4ZHrm^8<0N3DQ6GqhPo9uNW5Mf34&Ym!eE6vprV2pU7$szK<8(3*m5`uI z0vU1&B69oJuPs1C0i~K41t7e+HJZH?s074D)wmU&4T%cr3x&3lD}Y|$_nFAmmY2(T zm37W~637GN(#c&Qq<(+seeE;;jM9t6bd>_7sh#$UT_nRe7%w;)+}f68x!4ml zzG#<9-8pioAP;axj9u|qutwXXq`Q!%d8NNSbImu zXRkr?Flbvtger*0>QEk*{!PH^3u^1=fI+rIVixccfJ(%1ItnfO+JSB_z!rrJn$bxS zD|#Qghkf|^fUy5+H%l4kf!mD#?YSLQn6!M#HU3(L `@3PvvPwJmZ=XRDmRR@3KT z(&0iToX4CMw3jEupxUw>R!H=ahB6^eH&MM(vSe4x?y-MQ!&2)vzGkD2>~M)#s*?Qs zVSD;DgpZRW9sP;!0TBfb5f~gF^U?ZAkLf03B7e(7(&Y0*@dNp5=GbvcTN&K=VvV1+ z%Dbax9C>T7FubOlEW_H0eAz5*^4#OX{4eIhMI3l~28Ne8Ia9A~Zc+p;{JJB-Vp2L( z#Ibt&SnC;;Rc$DOSN!VWr?Xu%_?ehh4RngRk2qH%6AF-CnU}Gc2>APjUiw3iAk@fA z-*V^}UW3MP`PMB~BpyKnPBye6A>MLeGf&30UFT|UZiZfU)5okvlkaXUT_=2Q(|=-X z)G2qU#Wf&gzm6xi9XY0iB8d_ianr&B9u_i>?K?cpI%fCzx3g+5$pzs|Pbi0Wgb!YS zqCK9XKqg>EQBoM=9nJu5RB$OLl{tJEf-?j3%swXUdN52y zX`1A2;8Z#Cu8BK-@D%I#yBi{4edeGKTck8{dA_;r|Ko_AxpJ3%fsDYH779aO%XBh% zZsy`dW3z97mhM8k5Hb!E?hT;*RHpjID^TcyrK3|CpO^>|wpo?i5x8{&_00cA)OQC` z{kQ!aO-Y54tU`1oJL8y@b&P{UiHu~Flzr^klD#|0N)A#+DjA8gS7f)$V=LoGHoxoL z_j#V*{m1>seXE?$`MlrPb-mWb6yh@8%8q0m=%RttjQG*G(F`!{1KyIN;LU7nYuo3( zx&a7`%dfBEhaZIb(olE$$JW)*z;Uzn z8l?z`+wh8WtN&_@<%6>0{Jy``Z&d;~gqYaaVCYtm2?YQ|N$6;DrEQ}D<}u&H-O0xK#heS&0N*C62Mq4!__;9)abPs z#tPQm0g%YF(rjFbU(huxr`XqRRjPMMJtB*hP5H+}@xw zbCm`N!+4j+NFvC}RF2a?(K>H`(1N`3>#h9-|Hir0jKA8qZpQV+>A5@D34LqT+jg~x zNp{A@SvR`G_d9A>S)Dj?#`K2ts36}LQ zx&o)-TWGoU(r3ISgb($lXE8Mlo-H=f5ctWPKD8FNn3fQm`|5|P{p#1rSE-!7tLCH$ zo3-<#9BA^#Pue$^D*Xe3a1xk&tk_FmPu>e^LTV|bhHcWv-KEdm7xV?GnkNH|jj#99 zsW8xcUv+M033&UBe30r&l>eE#)-{ULB=sHCJYFMbY_^xi@Vox01ouNM#wn-XNd?D8 zL@@5S`-yD*>d*Ur#|E%`qBR(PGgk)B13rO#P9y!EgKDOxPZ%ih>bz8##Kjh0uHT={ zN@oX!2X(w)W14TV+#;Aas|`>`{ag1BQ&(hyy{KX%n`%SpYlLInrMw>%Sy#ODvG%ue z6l}bXae2i)@G3K@radu1zm;sXMn3U`)Ur6Nm2af8DzJ0H8f(|~qh@hpLxeWfk!fMj zX5A*$yQ<@|2JfM_Ai+UYSxbwdMzXmG8v z{f8@!J3i)qAai!se?_5XEoVxu!oOT!{`ki1&oZRWgMov5Ua^h>OPV~M0iMxfoTu;7 znL9Y(GjpZ_GPP7cqL>7Dy z;H)iTB=ux3#5f#cS1wH049j5EUTqrNBKpK7Os| z#YG6SQ3uHq#2rvC!4O|n$oL4%fnKAr8v0;`1LO+?MlZt4F};6bpelFv+1gkwr9{a) z!^8e)_huM6rhhp|?w+0yS%S(Jl&t2X4kNa0hOWQH>_YJ(&Z1V1lU<4DyqhLmxg@RF z0S(M%l1Uy7cBEHprZbgX*?3x+@Hn!CC6p~!A+GC>@&WN0Tn@|R=&95ICF@ zfYt&TOoWdhU?MRw5%f1kvduS(Uv!mYDL$sA$1dev4hEataA%hGG;6T^=7j(CX$K#H zv2whUAy=uvmGP#omW_t`de(tQQ|>Ewov^q8nZ%Pbd@_yv9;DaN6B#XrB~i`qnwN>2 zXU0I&F6HvwiUk*4pX3%3Ck$H*Bjl zoPU}WG3|OtFm4}j;%$P>$ynZ;#mWxMLle?;r!DVrF@m2km{{^Dmm&P|@C5y^ zrUqJtV66cqI(Bd?BeYJ@?7X*J zQ$`j4|D4UCL-gxhWq@}aqg`6G9ppUgNuF~JAFzrDRZ(Ci4_0evz+ zRR=>=QMaCP=leG(r!dZdUdc8_H|sbxK&&YzR7F%U{=7YbSJySFo>b8da5KUQ5Zeyr z<7=r4-#DIE&acpVj1nW8`m8`MYz1-kx>hu`czXj7ZlUC*@0NQkq-k zSXzEXnroYW>XiHhamv3S-hLzc4{exXnwAHSy>3RQqB*ka=e)zT!vIrx>05|&0p;f1 zzL`3hbYn=QoLK_^XOPex{=M>aJFvyo)zvv;Q>WiPX`e8ZO~F5?rMMJNSwrj0xGRx# zwyISe?jnc-0kpc#SSH^#o2b?-)uva`Uw+n9NwBQ8!I)agd1bAowe?=tl+j{D#5cH4 z;<4XkOkA<4D+AkGgDc!Yo9llOt_AH%%Avq*sZftb)D*S4)9={$ltkzQc76XQT z?(UV;Ir8!#&SKQ&7@Lm(P_3S0yMmbno%`?R4BNJNdL7F(W|gsEs*zC zbzrI-#EsYqi&F17|FbN=>a|w0PS4$SI9Q z(wOqx@p2>Tiksn9g#~u3ku0l~ln^#Lr=Zs_C>T$7eNDON`^y=Qq-C4&r}$kgQ>+1N zzP- z&%ib=MO9y#|N7qSoxY`;&IQsBm(22rvX?(f1$Y(Iem6HaSHsAI^vJA-4}(RI3B{`* zd3JB_gBwx|IbERu*4h4SZEaPxx5re@-xs|KvmnyXz}?_7-HqW?4&X%7AUywqu$OqY zo7b;jx2}(1MD1}dcY%0<`>DRZ{y*pN@REz;wB%kzNOrzSOG_O18q zf>$@r1R7WTi(SyW@6#ocXRgSJR793bxpI;(?9V!>cyBg2j&jO7Y&5iGj6f=P`ud6% z0))`UrZ{}FpQ#N_yXIA2IMRNK`p@~^kPYO9@fVkTU%(VD2%shN@f%d{Gen*>%aAhy z7X&I!chRs|3z>hbuwY>?wM})Oa#uLn(veRQ@DnreClog&=n4I*=`-)TJT;#YDo|~u zz++O7Yo2S|e9)9G_`Q6yqu#p0ZI4dMTPTGUN*vr3h&s4OCs2|6q(AcE|SYr*1ry=HX+4RH)Yd z3x8T~7V`qgfIcR$&T#g@sgc8~4c0@L6%UiRN|}whjvmmZc)T|-H4PK>pVEfeuD&ju zZ2@ffnV^M+Dlb%kW$!8LNI$JY=!n~t!eU>DNRMe9nb@7H6FbsweWAIslf5ZRquj_y z?j*BuRKudSII;QOpUM&9uz0E}X zQbCTnD_VL3Ch(d<%Xbf|mZM|A_dP?T=<)G!ut`G#!^!)5q16C3JjDkAIoK%1xu9+T26vKL7ar zqAr7i6Q5-Xzg>pk)cdC6P9vga0klnQJkx9ENA`$Jlo^;6I8<=jLrx(x&f!CzKM!iM%dfieK1oam1(OZP)}icC=nBoZG`kR%cF>No95;V_}3C7WNB`2L2VlnA*qBh(0A~TDx}l&c5WrPy$9O6!$EuTd$H^!x+hqYw z%`Z;BX%}}LtK$@B3u~TOxPJ1ba;VF_OMa*~n$k1OA3A6g;D>LD_jxz`RLn(EZPvagi zhQGi)pr)nrzfnNa)D}8~s7g?R&RUnRL>_8S(6QTAU}E?s3^xO;dXnC5P!T z(cb2=Te!p!;f8y~gr%g=?1+Ctmp@7T82;7jYo<12mEOHhbSVn?j)xNWG0-|qt-kct z5V?oVXg`c$>6q)JL~zWx@3Q(9veB3$HQJ&U->JW9v*X=m;pVTZ+!gMjkAe2mID*-@ zvp0dpI4bMMZx3=-R_^6q8kq152!uN$BiE3u7ybivUu*ci*8=a_cGnGcVkY&}j#eaE z0{{f+ucoG^R$!;@uIPq%)^Y2rS5>?(8(dk4)uW>cU;vYdjS6GVyG4 zyuzXmLzZyJM8p0CY@N>TU$P5>x>YXLcSfyNIVN^eBZePvW1r~|bM~p}hP~Kv#qXC+ zgS4&+fw?`I_3Kr!J#bBdlETW_S-&_Oe;W2)LWAEUP1r(gARK>aFl_AXUd*e()zSR5 z`a`4F2luD4hl56!`Y_#oKUdV_e(lb+Y4p4C^G1qvBV)E(Jl&}$52q(5oLH@N%pY+}%ArV{f0R$rZEk;?ggN}h$RTgEJ(Tsdl8jDR z;jAJ?)YjDe8})ew4wImDvans1*fI8Lka9w-u{10EP2Lqtoxp^FQIpnH6UQTNNuqs6 zn$xFSC^xzmp<0e+2sOk^@Xhe9#|HML&c{)z#jRn6cTMk0blyWlOlRzuyKsAG20M7; z%V$MQgFPOmw~Fnpbz~+yelQ65F_^%C7nYEa_|n}?X8e8l@Zqn;4s4ZcJ%vIWix8Ox zS_35&5K+Tw5hG0{2HFeanJ~Z<0de{>VEs43qak+`QSS&>2FDIGnJ{A*;F&^ey(&E8 z%I-BF-8xXY6u<;PR<9a&=wbTv7`Je1cCKjZ!U*-Ayntrs=aXFmuWJu8uRC8*sM>Q; zkWCIh;&!1|t@&u^$z0)pJ4S+if;VLf1(#C0Z=c$Kz^QsYRACa(Qs`|Efe7Y3Sx%JeBGvIjh(wGZ}lycML}z;~pIr6-ImEO`9|Y)!OkLju25xP5=n z;_jOuGRSML0W^f>Dyd@^Uq@Oq4?r6@->y1S?&vuGwtUIF;4Gn6FX2)A-oE+2^9rkO zTa~ydkGI8{@rr zw4IX%r-v~y=4O*;4t<`P3Ty<@(eJt|6mZSS$*FVypU$VTX=w#P&p;i^ji*TnF@!QL zK{f=RNsB-DmWf zNTQ2en%OzBQXl4y*}^F4dGm(%Aho=SZ#i3fYFa3Iq^lH{70xnu!2Wp5>J&}v=mGAD z#EGoMchZ=j1bc~KVL5Ksh{<)>?LwG`+6DXwe37xBmIRwU@bhOi5Ieo(b1@Cni-=p{ z=B@|i@m_|d*9RSIySTu3+DF)@sak2&BKiWeE!+u`kdP2WL`S0U31W#(ojO(eqE#;( zI#6VMl%ok)ZLxe-UcNT{w~lg(o$DgoN^ESnSGcq+q}zZo?jbNHezR`r7d$+qK~4;% z4=KA)oZwQQWy3zv3L3c0;QXUxzpqt++vF%bJ%u|HiAg}-*=-k|!tr7N!z#U+64+eS z*P*(>+oG2kz-uBnV@C)YTf?-BZ}RsUm@AG+rdD(mNA?95250}x5lUZ;DYM}}#@Ib#AS<+H0{z3(T zNBa>d-ha3sT#C@c!rdwBK6wz}2T%n=zpxXGN#E56rfIs>B2Jz>SvvfH!x`!?%KeU3 z{QI~(@Qzd3yoXkWRBS74Yw4rKRs#^i%`nvPW$k?uvTSrzqV8;+OrFF`G;{!hjLLTCf8 zT&Oc;Wo6%A1FP246bDQcnkHF#${?Sn6^lZPzaJ%uYTJM+VKTHD-YBh`pVve)raS+;l~cf0yZdcu|sWes$R8=-^#D2I6@ zTy!h<;$wtJV9LYD*G{nU9xs+Cq<_iW_~eLBT8`Ns@*(^k`&0=G+rIc59uNV%S#h)A znLVW5J~f#oRqguhU5sEvQ&3A)Jjn}O=a()$l6VGQA;7zZVq{@lpkbTS4)aWb+apRl zUPiDOa2v2$YI_%g1QkrDvKXU1GR*J*L2#Oom}s@Rw)9xeO+dt~Gzc+u;6|rG>gKa+ zGY^|%KHdxHVrTMFc2UzKiO%Wy;H^JJliapOc6nN)HF@dIO?l}z6dFA+auuYL!`_vW zF>BNfRUK(Ay4rvAi|6;C;enZQpD&&)nmJ0EJ4=ZlKvuiibgoOkQhrJf=GLlKnOWLFGBp{h_DB*RyubIKG{;)8HTm9vS!8fDN zmN0b+aH-R$9jYY+pMhWlZKjv?{VOaoHxOwI`PnooftEZBYTtogLV{vQ7Q|^Z0MLQx z1K{mo*7*qI4ye~qejecbh(vw+t6V@|3@f+7vDDJzUiccG{0VB7xkKcu9jP{5VY{(-Ak zk2k4^{-{-aUq%vVf72vpUvxPpKK?Eo2^9YdN!2nS^>dm0^6!|z2L}VVF`j|H&%XcJ z<948hK0!PvGHF&oK%lJu+S_V{B?Gn!I%G~dMqyN zDrj|5`pZ0s3mD(vTbxk6+;XkxR9fQiz9zFZ{;g0|UJw=p_03%LdZP3PClMsP=`Sta?%|Ll@h77-864EojMgy@n~i8nX^k( z5mzUBDMpKNRfRRS<;4~SYPsXQg*B=i8?XBb9#diwxjgR4{>tmF&_ z;y=~qPOsx84HwJ?OPmG;edaPkxYwk@{y~}O;&9zH861f}8s8c7=uvjmbezlO9EE1S ztR2!A#k#hxGx|T{Q+$8K#E>k;jAQ~79(Pg)HHS}R{TCT|d9$r$JVSbNMP~WZo6Ew} zchqOk)vX(ew7M>21#kj*3Cc|*Rya%-vZpY9y8p$fliyYw_=Y73o?yS{QQ_2wJ3 z-Pu6NVFesO7yOuWFGJaR+-8$^)FQLf%TeEe??IZ!eq_;QFTNi6{ZxEtY#yW_--Uvi z5_QP0?l0iUOksa{*fJ zhR7S(%>mWoDC3JVoQ1!;>79nJV?;^XdLsr)AvH(dgL#HZI`+A9np-h~BS`)OX54GA z@adGOsNU3+5io^liwB&6TIDT@asV$qO4)9Dt3k}g-P?4!wSa64hheM1jvT}mL$OfQ3hymaUSUG`Ml>bqk)oehE zf}%`deA0XVl?7liE5Hm_03(79E53JM*OO{x-DU>GOl5A82`OqhcUF#siJKs&47sH$ zOZJ#h-M-!AFJ&p0C8-nnqABn@!$*>}PaX0iky;vrptKiSQ7?&#h^Rw?w`1AZ z5kx-15%pRb4gob)GGi&gYe=8v?vFP>jv5{xDD*EyH9 zEKcaCR0uEJO9}MTDNB(UR_b5TYQNa#mMgumx~Ao`yZyq*skUwGU4`~|rycWaP#%dA z)vOxk0nOgJY>S=t_yM-pvsk%ynH#|TxJ-4POh`z0-sR8Akt%|L+^35xgTFmq8ipYk zdtsplsGjeD%?5Xv%dXRZ!p78h)Yp}wS1H;M9w?LFbT0{7=YLBF&EFpZqg@@$GYJ+~ zpMlOCZB{^X!}db=@3c@T$#*_MisjLl4Huj0=d8~1ysA^ z;^J_WV^=pUl0ZW;40)~w8M*vS;`xCaGOH2Or$C4QQY12^#xG!+^Rs)Y?=uN^VnURp z>t^?GP^detc``YV{!h-HG5Pp02TYgF<>q^OM1N77u^{H9yF}XbvzKgz(WAi*8M&{- zkSPeT60Ga##Irv2_Y2I#_KGn#CbC`962sS?Q&MbiY}6k!JjLQeI=$!T*Cw`|7EaXf zW5*wz*8iyjMdIQ&;NPcZ&m^j~KQ{{tY+cNH{k*{SQztE5*}-_)NXD&?D+^X&#UQn0 zML9r31N1e#f`Yr@Qo+@$HH!lLbSzRJ*sgN^kY#BOq!heWmCYy;J)Sq&RiLG zRdm1ux@I6PEe+*x2o{Lu7=;%weVJn1?`lP2NZoOZ@GYk(uDvWaweNzE3sz0vM`HSW zfiEa{w(%AAbS~6WXBBfk)0=ZWXRLIo-apTo*HZL_*3&TAX5CAvTbaOpuw!8cu0Y@g zpL;{r57NvouEKQ#|J|Ks_VbE6Z_M=<9R4!JxNLBPk(>W^&GE}fN=N_#goY+6)fLrZ zPe+wJwgy>2Y+vTfZO|iM6Q9pHD8(v95JGNK?MB#izrIk!b8#miy;2Epr8hOEClcz z*6U26dMT_>c(y^ZKaI2OyjgS^MTP?cnVFL#h!dbvep6G8DhdqCR|G%s;g&^W+nj5= zvIum#VUar8uY;PqV)5T3*c%PAy4XXB)boPLx(wT@?Kb_R6+OjWsTPArkU?r@Bcj)zO#G#pS(k!fThcs7TSMAskmMf<*=S<&rF z$MT&TYv?-{mV+-92HNI!Hg*5SX$~cI7;OO{svfBeM-;{E>?}WpEuUm0;Jq0aztgg> z>7g;a3a}jNSw#gW+K~lg&PA{NTHqex2nE#LO!a$lqFnBORJ*ZJGC!fp5PpEWI$;k+ejj+Bv@KT_{hG0;^r8GcZ(Ah zqR(%;m&fN&azt}CvEJ%q2O-+o?}npeJ&dyY`ua~t=GtKo91L-g0c9xu^|yyS65xY) z4kjej>U_E?Hg#`M^|5;2_1s>}H~f})vnht&p3$8eQm+hMH2`Q}@jy}`l+ywWdaXgM zsI{E@5au11&85Cf;3cL8P%(!$1Cg<);Q7FYho=ya3iu>SFaWJ4JONbU#UgrcUc~ZE zsU2x4U0y?363E0PD0rQ)#Qy?_49HuDXPC-g80zk4T|M?E^?TlWYEFiGd9lj0SPB`h zww+_D=f0#_$5&pgcu}6{msKN@jZKoCn+z=LZKAr*aLx(F4}fr_PeUNWx;pnY&*)c8 zcF{mStueFMu>TL!N<3;zH7Tf#{gUN;vh$;^3k|V;_teg7MVI3~iaC#6E;jR9S>G@( zu%Y_6UKQRy^GAfX`4fxc$^X>?zyJzQa_o%ghZ2mUXu4(Gg`!R9X%YDapObM{;dj-T zt7aw6+VqNw(G3mOxa)RyLI)_9g?FX5?=JbVAB3VK*^65fVIjEToP|+agU!Y(ia zMy~~8w>V|~aI#CxaJ=^y0heEu9MC$TTCK^1K))M$HXd)4N$#$77Ek=&2S@ zQP^3pOl;R#x?hw*-#|Hc{GjIdJUnpjWo8g>!Bhzw_^yFo5hOexVc>8c zsoe{kC#(SD`7h#48@qae2sE(~Tec&NxPY0fi5;y)hYTnn;OoIDmht9|VX7m!_=yPJ zL{5*6U*keV?TPZwf}y*~MdsI-baaVKWw7r@7X$p~}Zd12Z9G;2X zic8pj9r-%7)Be0;)YPbQ!?=6!I#_DN1GoI3n>h|%D;VgGgzp3}75Y^GBM}-6-Xj2$ z;vzn}N`6)qFeBX*CfWF1ky^GBX5$-@JLVd;Fo9HE||+uS3g1%*<|QqU$E z-R(Z|QN519{U-Un{55YYo`$8xH|X<-;H)C!?hEUn~O3ikWuVb|A^M|TZIt`aigzv#@iL4c{nF^gex?q*g_neHAN4yK% z8+{C`I_fS+C+h}VW9hJvvNk$4mizTd=aA;+IbzNhzuM!6IVGm~$o>izM!4F53IN#D z=sPkT{{1UNIXrfT&8q8~E`OJ{SiZJsZprLM>Ut{g;WwcUyvj?PjhS%flY;8R}}?4_vb~ z43D6Mx+R@lej|J|l2N{H-I6+@y3z3C_$ObXc_+frQMWi{n>-I$&SrX7I1y+Q4sfBF zqaCWM7Q^td63+#KGVfnw0vQqJiN*@t4Z!p!kgzh2+M*xfA_MyPBlrnHI*Cl*Q&XQ{ zC*$+81@Fy7P{=G85)57D*VoqK)~-Rc@8wrl&k^<t07y{KyNHa= z0I$zOF4i!TPRnvWfM_{G!}#(Qt{?`*^S8n0g3Pb594-hYbb?(0oQi}KD~PrMg|*0w zgf?1Mr(^{(k$V3-M!a~`VYSj;N$Wa&|5pP0&!ErZ_eOE?twZ)>ZYCOX?UQ9c`G@8j z*E**5ZdEcl&960{tdxuiT;Gw}*9ao(T&6LoyhMeR&SOHwFY`XwxEiW zT68Z8riIu?c1{JBZ^aPbAGuJJi)YE281zoHQEuGOnahcbj}s*niyofU>~X}rDNNkb zVDB3Y-1bL1eW6JJHA?%z`!!bR5x{JpezOvE;Shdy&cb3K{g#<0)C;f^Awd-2q~I;w z-mMSg06e;cjBg;&z0!xfK@CrATqN8%%UnQs*yTBOPUoZQ#Kn`!V@z0Mv9jU#X;toL zf8=R7UiN?hDOaH#csJQ8J9_BCc+rZC*+;yaH=?jEHHp~p%V7e@3}&O zu)e>y1?Ta`qfh_H_rQYF6Ch{@_#PN4h-!e$JGd!Itw(BW^Wf~PyH|7<*0$WPIDFj-0w(YApaB^8W8z+acm!}ST2Wfb~SP*6bjs)c$3#K_8;Or`jiBC=3_g#5S#pj!F8a~C~a zNNYhv_a+5uSZfK(8Gg`~cNGWs#THIs)t(d{su-w9pX?;` zn?8%T#s&;gYWvQI?)L8YPA2}Is9NwNRtT0Jr*xE{?fk^Y0JzJW+rYNREI9gnqJkO1Ow2a;MCz#e*>wgTyxa zKN#_24QEp(yaI8*J~o8+>5jKF5UBi~%pFZyTNoL3veGrv-Lj8PaD~h(446(HzCk)s*LFLctuk%0J8cWe=gh6O1kl(FWcN?-?pQ7B&>Ah4k$NOZ15m)Y`ehc zG{yC*&9Qe7ssXYph|TW`BwozE5jW~Ai+o*Bae*y@p$Q;(#F#+A0MH9ML}N3_{UXTAteBSyT*Qz9TvqrH1l+XXN0DzHlERnaZWHG?wqX^?S2I39IGXgh_ zD;EF$fZD8n|MP=wx493%I|L8T=}}j5UR@R;Y1gSNuWthC374=|<-DO5^yyxZEr+s{ z^C|VnBm`FxkQiVdKp5aZCo2s1@TpPsG(?CrwzXYa2Nq_f9MvZ`P-L1vZNs#5 zdhQDL+l8W@%#Is`8&XkcDd6bY`aL(-0JO|aK{+WJ%H=f_l#I4zL4qi>Lc>K3+%+&~ zblbUTXzW(tjt;AXZ>Ws*(TJuf?0f~L>l{GRFl)?rrEjrous)y&*4ZSn#RS`D8;{^Td=_>ht!M2MP^R75n`hACHIrI$dd1 zlODUsV8tJ=QP3K_9KsacxOCyKd?8;}6F{QN;%B9$(Mq!XZwi0HZ}|#I^bVYAi@o5c2KEsq;u;7wD7xA6;^jzspy}J2OE)*Vq66+_4z6>j`H!>1MRHQ_j#Iey{rK@X ziSxaEe+m-3u_j{ddA8LeuXW4)Y~-@BPnyN^XUe6r2i+fsF5myDKdc}Y%b28djBB$* zq5zT<(83JlH&3K1flX#VfrEq|La3ibPaznrBOIV|K)fT`nha`bplgsQ8n&IP!ab08 z=`_^q$RCdH_k%XUYa~<<%EP}vCu9Nz;RjmFfzq`>PqebuSEY2~ZX~R@FlIH){WCJpVQ1}LDSzzD12-@EXU|HaLNnkhx>>^ei@%q!DftnkbY7vPI|2q<>K@-7nRYA20eI970xWFfL`Q0sc^qYHsNY8lXGww2zJ%KLB>_clzy;?A>Z zEwj<3OV_{{3YDP2ckV-ooZI+NtOhqNjaj81J6a1nToVFpC_+$v0)2J4!mFrRkdui5 zW9>?lUcen-Whf|o1(4$IIRplyHS};vWITOJgMJH-*`K-fljx@*hd&%KEKu)YG(!tG z(Q>Du2IZ}yV-(mu2g3$Ez}EHYo8Qu{z=lW@1oZg`EW`mD$5D9OU~O77{cfhKp91Uo zXW(?s1uV-W)&gR>k*gI%<}gnwTk+_21S*#GJC06FAj19Iw{K`dfCw-&f(#5qLE#@; z(tV&z=eTi0Jl4pyv_X1#TxzeYRtv5C-hk$KrM>!wN(rKY(I21G377m<7(ounqUz}^c^g2 z?6_g%E3bHHH+{VM)ssPwg&%*R-4k}Exl8;01J=N_Dkjb5cbfOpz0Q?r7oNVNw7cL` zbjoi2s+piKHUX5Y$sFxvY{z?ak9A`Hmg6z_ooS;ReV=a+h`v5!b2Y}3=5ckErY(#| zm>uQPQ>@zNt5o?&OHcv9gdHb{;z8lw7e{ssR#tNBvMB^}GeG+V#{mijmfPcJ|FKAL zyUf10JO_0jCPDZK&SfcGAt$gl#UbJF(B$b zjAd8b`<|+=1k_aXVsc2Sq_-6F1IYE(rJA*Yy$gE0T4UMjyG;bMQD|8J#CS3fj4ypVR6Xs z2$_~o-@au9b+vKo+Q!>laIt+*R9x|M5ohKP*;;%9IlhwHb0D0Y(~C0%2Lc55Xh38G zT$G4dTpkSML6Zr*HWz;Y;3o#(J)Bw!x|#4PvcVv|fSwiMw&1T^Kikv~X9k7yL5gs* zuVRm1tW8|5Kpt;;(yKd6l1cONW(_)v`fV3Q^mJ@n)}~*D=YO4SIKtM;p@{y`fGlf-AkYT?Q7Q@%V?{-mPW#}%Bp%cbRlwj!h+rbiI zaQ4FPsIC2o)kE9ofCxk$GQ^Kh=jIrta{JAn+gP&PK8x@iSS3x10)o*$3|7vOshso& zpY04S_8@Trct`J%ECbk~(T1B&v~p#HeBn3xH)`O(F2Dl%Ay}1K3j1dkKGGjJWq0fL z?Yd8Qcf&!QZJ_k(I+eWDrqF}NlD zNYpY4A~6t32USLo?irhi*+(dww2+brjs_<9)j>~j>ffelQ7E}!EVz$CYa!7TJ&+-1 z*?E+CY`MK;DcGZ7_{UNYt~w}p;!wwdS_8j5Fq?>eA^!X_<<85;ccJMq%$j3ze1{cA zoCCzEk8_QE5m_K)32$(lS z=>QHz4;mQQqG-!Gl3_8K3U555s4J^L?_MtTkd+1G$qK@lf>%<^*>s|2E<+#hPAfrl z(fj@a##mP04}jx3mRw=~eoOktMUC?~5ax<^x07$F@g6$t_8#82fGSJ&p-}g$A%;RV zVMeC5fZF3%#e-!=So#gFn(XG%B>krBqHhj4?V2(%={aR^;!|d;Wtvb7L{b|6;g-1< zfBkqOpW@8eI)OH4VsxQB(O&2R^(p58r6aCNi(9eYn)lNfIix}W1}Y#NBnDj+nyp~U z?QB+xqbQj?ZCRB&b4J(PIVCwc95iA-VLwpmOu>6#l#Bhga|rKR?(hD(TsdF?<>mN7 zUtr{vz5NP9kn;OQ{L?J8g#$fASXi<$uv{4eoa+mhEtJxMBr)*lywHjs5T-)fBI+k# zRs$6};uQd}g*|&gD7VoHPXqT&1FT<7SoVQ_4BGVa99{sNK+K8SH5wHBgXR?a0}5z~ z81M)*r4q)FR|ip5uO7>>boX`-!9l2pgeJ5l7ww8Dy=ieJ{}OVPfatHe#pt@!2?_Qq zE1X|8@nlI;*RqcjdP3h++KClsRt*IQK?osnB`!BI+uMooNO!3>D=Ff&$l$Q|G;4X& zJHtwPGcIYJ0`Y7Q>e*`&#JJmF^T4^J5G$(tR4eiGYq-3Rfqc=#fhuer2(VgocWlAT z9mVoi-F1%G#P-wbTwe}WN5#HOMy@CP)&2&$|J1yY)R?)H^M{=R?DXpTyx`lhM_~lf8yXX^TZ|le%*YF%PiZ zU5XQns?7{-qMQy><1Z7m6}UcVW7YYYlM)yO1`^w|gvEL^+KjPvT7Jhbj3vDa=kGEV z?0PKrxK*P7_gcj7)(x}9Lni?7L8dnpTmwzUHLx#kS6vmrqiYNlEY1glt|)D) z|Ag`;z}@2R?*806SuK#|)%bLS{<<1Pq}G7VzsxcpI6}Py}5p zlKhE@&2NA8U7UO#ZEd+B$@lq&-COOvx4N=U}j)@=BBMi(BVsA-yT<*&sX33vXrPdmgU0$|?6s9Kd6wcX* zhabxBD(-o%s7`$3)%ox`wFEEF=yGC$BfX@2Z8Lw8r@54yA+kSh04z8ld;}0CEAL=k zZS7UGr5uMlr=`UJ_=?NgAA6V){w;Dw+5r$JK7M?(wzhT%8kcJHb|4iaptd(|-bCs} zak!lT89{oG|3tI|q935&2`(6=n1|!TCZn5OTiT z*w`G$Vo@kOifnuyQMuuTcXyY9GM1yz0~|~^{Ov;^(|}PANgDbp|DNR+6r`s?k+a}? zL;Jj^UyIPdov`w~uQHn|K=Brn^*DqFg65jFwbh$%&X6vpTb|x{R1WeK5A*a>+jdU_ zVF}uvXwksc7ELWJIvV8j0o3Zf$8SPC@v6?#PVt-gs*N$x1rW}p!%T6f$p*#9Ami;2 zRI2@u(gjTJ=l|6LM4S^mZa5c=i)OUDreyL(>3Xqg66XN=Z4# zI8LCW$d>wLV%LzSR*Km#Z=c*>GY^3+s@M8>b%&jo9J!)-A9JW|Y0kVVc}OcOiOT=9 zDRMw+d{j1}V%V)((;#NRZl94A(N$|vCK-Ub=DN1k$pqNKKZLRoA zY)uHfzG2ib2C&tc-)_;^eE-L|3O1$~f92ZSUC`ZabW#-R1F~1boJ@1{{b&V*ARsv= zc%~i#=!*=K4RD!&SPKQ_gVN9%Y8Yi&3aC_+&47rthKxSQ4%7==>+)LvU4md*)U$vf zQv-TMBrII!ir#iAHihUGgY`CfudT8P_>(eMn;@tP#TCOhjP&-PAw^;BHF)ZwLrlN3!{Z1$*e3GX=BOjL6WbGDdwsh6Q48yJ>2 z8kqJ!X&r1@gY1$l?Z(I575xf&Ww<4@ z5>NR4^F$j&{mdEf*K;0)%sXJvV!+Aw_3LGn8xMjr$c=$!tQ1xTU%q97)zw_P1mqN2 zgo+Ri2n`0{P!$G6s?i)sme|s?1ZlRe$V8R7F*x_wtCb9YTFi9ERGpW*b75AZGJd>Gc6_VC-l7X!#UUZ? zBflqzq#R{;Vn@G&T{1A$8rQy1{YW-pvEbl*`f)d%7s$fE(YVLjQLVh@rF&C2euS$NTki;F*u zj8xOnVMJRC;Ns7Oehwf~@Y>X(2>}Kku+b1N&jGHqlkC)V2j7hbox zHN%ftd1#J9)D3_^l<#7)vJVlI1_lEw;#<>vMAP0|eQ^E+qHBV8bMNuxX57`Yun6mQ zfn|KKv;@^jz}yq&aEP}?fnobk%LoYUf+GiF!8eqy3Buyh&pTwjO4*pgyz@MUUg(dj#5$$n3axU*=!|KV z0(VE;7LK#(2R>H&1z>n^`GWeBmIjCokkBEYBj|*Cc3uQ+PxFt^>8lcv?6;e=A)vMf z65vms-09-tqKU`XgL6C#C>ozc&iDar3OOXm@zYpPQpKgbOE2ku08R@vBs4S>e)0i) z0*EQ%o;8Xp@GFpl?^|g8`Ql|sUanITS~>JI>d@n>_QIx=k#@!2hl8D8kADg>61MU2 zY1qHdk5el~bE=H4B@*YCH?vZ+ND2x|Ux^{c2WjMtP6nOa9cLtXY@%HIy}N%NeS^A6 zQoY#V$EVj*(ks%`pI(wli=5Wro?Svw?AGbtnS44gj)N>a$h5%gjX3 z)OwZ%jny0DnFrmlNDl}nNnBR;sE1!ENEJmZ=IPLt40Ht2q&guDtMrSw_;_R#hDVPQ z0ie}~N(4e1uI5|BtBm zj;H$X|A3Lw&=7@$vZ<_OMJkzzjH0ZpB3n)<8I^3ZQdtQR84ZPmva)xYWQU?dWph8@ z-|KhZ_w~5`xV~3?kK>&8=kD!x(O7@u-9+>liqJ0 z&Xk0kMkKl0xXOuyC+qbM51g{x!&`QotNuW2SV^g=NqID-PvTRt)<}(U**{k^L@?U4 zYgFQrbXeEectcEGdgALKHK1Rf5V7i>K7F~#u>{vF6^fStxe}_x zySgkT%3Y&n#i+&ZC==Ga)rNJ>VN>x{wJ({Hqem&_;e!V0^K5bZnau7Ancurr)+M*{ zyL?FXDbw)%wN_*A*Rq<}A3C;jvIb%9?h4c@W||s-5i|@`Xr;Wof0l5BqMm2 z6>PF|c2b3BTY;0|RR#o#&q%Jd2G$Y7$lyhWRwK zC^e+dBiIO;ve4XbobK#W;YwNaz$wND|EToAhEpJB9RlQL`!@Rq0WZ49a2c>3EhFp~@e^J?W*rU zGL+wZ;^-R6x5c}Rqt-X_wB2^H3$KnU%aBl3r9c9J9DWCc;GmDimLNo)qy!N04Jux&us%6n zQc_Y_IDo^W%zhbKKO(~gvjJBnq)U0!bs;K2L%tNC1h11XF6HwvDJ{0`<+L59>cHEns*I4H@`29Mzg?GuU>BXHo)> zd6&;29U8X!t#g}#6q*I@Pe;|H^O=^ZhNR^&9*U$;`qHP5J{l>xG8TI}DOzAUm`_aL zI5WGe`x?PB7s{HclLBMq>Xhgq>ObmV9Ye9`T6v%Pa1T?nL_Vhnr8diwI%jKbH|~!f zRW&-?ZFbi1{b5lZYxckV-Al9cIRgy&t8^-TH{s24jz=jHI+}gk z7=Q1-u$D`Mb2=vy9S{&GII%xF0Pm*BF8l_pfd8dd1b^#vy@+A`^;kI-Q}Cb*57!O+WW5YjO?)BVgI0OsVu557@bq< zD4En|(phK3nKJuor&W9J3yb9F=<9g1^|wG-Mt66rZNJpywZad*Hc zmCN}q2o?vDE4LGY@W4~oZm_BMlEZ{VzF`EwqxNvhoVT>JBzZApHpV~>6b{cXSpY>4 z=Arke@L~hCkprM$YXIYu^eU((G6FT{Mv<+7JincYBO$SFPORd?Z_3~jfp%LrDSFL2 z$|^Zk_o{`CwbN{Un?DKM%Wn)_X_=1qYAEUGm1mc2D~h*|AB=pG@AO9c;&HzAKIY{w zwu)Ut&NtTyW?S*GOE4)>#$PWcq}*C4Dw+V;v5X+stt3I1#L7T&g$hjW06fpkJ{-VW zh{qp9CDGXsHUgV8(D41A6I?q}pEeM1FH}9-8a$rKaFEa`rTMl&lPaxOzbb64Hh+xBdP7%V)P+Ks-v|U&uxI7stz&_W%TNfvk;W z7(uCgKi1FZ-=_;tJ*k#tYQ$4%RN^j-MJi}|W(~VH(~x^HF)>UDdyIXWnivbO{7VBRh+rJUfR)=HSbY0SPek8rqir=#eE9 zVl;lZV9BabRE8RG4=#v40ZH9Q$S3^A1ERs7uR9i#s(d|#Yy z86bZdt^r~ygAQ?cKH$+xd@DvKDzXpz|Cds99n2~M{VakZ(5ZBKAXq7HO0Tkhr~f&+ zibXfR@7V=+UXL#dJ(YSg?HrU&do#jL?}q?Ta%4oI^4RRcvYt&})`CPMJOkM%fNKKD z$Z$_Einj-8vZ}=#IS6eb!h{qQq0O*q{!&vOzdq>CUP-#8#3J43h({4&VOiqRXsLm7 zz5V`u7o9)N&&#i;UUu*EOQ)eT+?X4yI>Ii<>i+GzW`)6ZuTQ6)Dx&JSTM}08+%jr5 z)O-29LNuJEv}vo0i%O7EX4$~4^O}3M9lxR$!X~EtA!g6l(tJwK!BWOL)@3u11M)7l z<24#wuTj}fuhHTiid~7I{{t?x>lSnPx+#SS>%HQ1zf^5h=W|zuxBt%M_`=r>ihc_R zM<^OM==r{5Tcz@e6XAX9UgEceCmA9KGJ-+wHD?s>1~biDJi*}9XK}zu7l04xfR9Lh zgTxTD1Td=M!XKFL`d`W<)DXJ0QID6%s%0&$DumwO20BmZcf5}HJuPgfAyUBtkf?Fp z!28GoAte1-oI6K@>GK_kC$8bY+ER|6rEEGgkE3NW?(*hKj=6CR4FHY^fd`Sfv`_5l z+g+z8zXa~T(46%WNC8n3Ky%-1=5QZbeK4r*Ja}0v*Fu4hrHSEO=@Iql!F?$mB`b3Z z-|bFaWsH?gd)hc1KRGn}LHO9Shzd`!eMyFyu^dyc+PwR1Mn7*4=AjuR$|4J2KWfC69o)Hza^(Vk-MYHEpvXwID_7*dI(Zl| z+DFe|GKX}K_|+rM8R(qT@_G5<#V(9o|FboSc<<^H;Tje>a9|rcYa-s;%FIj!hNqg; z|L+RXTj_E{c9usmKJ?zJvcr5zks9P&bv%=9%&y!j7 z0g8x(-fPdKLD>%KsR*5SdAC#|tD&0ea+9%^iri-M1|Z(e1AWTZM@?e(^qDDn8H zCo!82E>7%$&lN|fFa%_4p`JBYn!9y5U&i>VMR%A8 zcGO)?+S^SHZBgr4lUDM><)QAiQN{dx-4)XfOO__CD>*4wnK=7_VP{ zcPl2I5>g#Os-Z%^BRIghpFB+|i-Ur*e=?QA(RY)S00b(gEPNdSIvVK=u8}0r6Cn=C zRq9LogwT!x|uTtTk2oF0VrJVv1umbhM-9&W0)y*Aw>lOrw%%=sO*lBf0GVou@q z{7y?&yp6i|*T?O_fGqC=`-pb-CbDoO*=v{`-9C{VRmPY7;U`NY>Ti@{q%(#SOJ7Hk z^d7qp95_`?5iHX=Mg%!=Q`-0!e`S|R;jguVqfVZaQ(yYhXu0g{58iR5+=muQ?C z;1$BG5(bs1dte6sjoh&9G^8$&RrJIXONBX_XZLPeDwR6hc;V0uVf{xH){=eyzBt!H z0~i4*7<8^_`T3J27E3EUB!G=vEJH&vs66TEeA{?3kUqVS2mXw2$`xV@i~)I9Xkr96 z&z$Ay=XyJ6s`WrmWXX-n-|nw)j?nAb`61&LD;9=m*$=1Jtm4Q)VW5BJ{64LDF=MxkJ7~CmV zuQR!)ZEj}%`{5^Fogo;xSm((+zWsc&%v^I;uXTzloq>GDVUdI0s{(qa=Upma(n~3D z_iy`~@rNe1W^<3P9#dDLez(Aj6f$NI-W6&|$yhewy@`WYQP*>%LoTymF00x0==WN9jG$XQS9m%QcTTHb{(#CGBmaT0C3g)Tm(# zU+46s^IB!M+ru9}Y;8)1r;qioG84QaR+-Vd*e^(1+_9?3CW-dcm0}LZKUSo3mw;Fd@K!CVcqe3_rox-=G}8mevQtsrqE0#3k`*$Y?kzdDy#N@7;2 z-r6!3*1|ov(N}fA9%%$W2VYg?DC~>+dQvKS-%d5^+~Jm?H_|g z^c6e-FnA!=UgnBK|v#-ZOzGwIXhSB0EYecUFMz^QblTzoaZ_>WrONM6dYtc!OqLv zcH)ai$&h2d?S1^j2^I8^Fr>A?!ff4%P&~54h{*7eOcK-2q>Jm3$T84b20GSjwC4_$ z{HrT$x4jfOCDGnxy<9>$8|W)r)+(36-nUU$#yYu#Dpnr#%$7%iRm1Fu=fkT4UmnGL zD=AUU4&4;0a=%O6hR-8@$H!z1@{UXX%~{)G9wnOPTE&?wZ}7AnyLeFqCpcfuJcP*s(>n*p)e~WJ z5G_hhoB^9i9+3p665%IdFs~83*<rFo{ZnKzT+U(R6CBkA3U zEi8Op^7i}3U!6b|gMx$G{!tLe*E<>5be^M|6>FG<>rjc#_G$ER09od?k2cL*nf?RW z@j!g}B0qG6sJvu_Eb1k$nLyJTzVLjXa;3&rAsM?8Jz6w>!w=^J~^x(oIW1${!7yEc9{=Tmo=1W z1e4l!vFvy~Q{f<;vt+PyQ^(6< zmTI@Tn0I_T*;Z9 z=kRKo9w{m1rIoKcF8VrHY_V#ca443U%#F_Xto4l1O>&kx_F24x_9*AwPFlxLJ?ekk z!?~MTCkoZ6ojDM>W8D-8kg(T+w>k)NMm{5`L~Wg&4OO4u!&lWB;Wr?uh-5nkSr!XhMSM9T z_DSMDd5pnj2!tF%M>7;MBr_8jS9q;}c$16H^b~mDGf342T+x#`F#`pM>!&4y~$;GLm@lDf1 zf?Zh=Uq3!Jo(xhybYDw=KSn4~XmlfP6clz{qw599)t3IygB68^Q5E*`vsVTwxo^Fl z@~^|@U?BB=2ddtE*Sw7bUBBAoL^|7NN9W9CaV-Y8AZ(Zyil7a2veu zh|s9JcY{FkfL`HYV|-X%Zl1Ju9C32XM9Ji>%8oxS~A)Yww=WAG*+hFmT!ozyVg!CS~R^f zTVAeiTv_ljpK3ov@?l-X=A@mGH*6De7`DODWCZh5EIw%x+dU^#`Bh5LE8`cmL1ewv*B6hyTNZXaP*F;pW?BUuYfD< z>oPR2MkC((`E&N5`q86w(6_W$;S|r}eT6}BnYECsCBO_Ep#Ud}2;Og5goOVIje`1|@B;S4C`g*(|c;af>Ji7(c+*jMC?mpq95g)#vz({zS zE}62cj`B|yF}COKkIAU}?Irnl*o*zzaU;8t2+jhd8uvKc(A9S$#Si1Nc=#}lX^Ba6 zHo-GbXE?gvemBN)JcPbKCvgc0at^ELLAWNZRH7cEw0~;qe&a&<9lY6{n`#f39u}!{ zdS$Qt0^$x^2DWnb%g-oM>jS2t_v^c3?DQ6L4svxNALmz8Mpjl<5cPN6@qJr$!;YlM ztA4JSGyXj%ztnyE%P&<-ns_kJK`Rdd6N<6iPxWMaq4w8DuQ=3IYhIa-?u)1u?2gi= zb_q-F+!;f6>~BopdH2v5`mfefBW5CtYo&zitYzavE`oQ3B2Vuq<<>P$4X=mCTjFpq z*|u@?px%R50&_{WM`J4nG!U^{_iWTOk)SRteO_()FVnkuL79#=nbkM%;Cb85%otjS zM8Q7_ThvPndY<}~1c6O+0o5X~Q;FpT=>heCdj$;4hnwUJ3b=iD}hc$(}Oe40f zyDmW2w#cU<#Ijz0D?YxsRGzJCJG$=GZWy}7nM5ZtZck62LHC4LZhOY{eQy;Fx6Ikx zhlaoM{sDUzC_ZXRpn3Qe}_UT03b6$4=1a$$1V~#7gQv8t6*C+?y`9`lngkqIi??w~MMZ)f5yqnELgFc(gK& z0UPb}Pfw&@dC4-rTdSb+`CMk9pSioJPARq5&9QGPazNsWs?GFoC+||dL*6G=!qI#ztJp0qefo`Hqq^CX&hzy#j2&QH;7Y(j&@^{@{S8f4CD!^Ht=*K( zOKr-E^h)wd0jOh%3jvgyiJd0TSab+Wdua&6dlS;rZq-1l*RHo&6;gMGhU} z!XKg!hml6sVkOImjPcQR(A0<+588T@u30_G&7S_vJ|8jpG)F|Csr&b?1T#D6Tc#w!<>gq%>0~C}N5$fHV zAV5==eqMO$yW+ErF0!8Y(2TnWZ`Wv5r0=2?A!5M}j&U8ixZm*y7}~deE?HMM;!2xe zSRiUloC6?H*_Y8I5I*k9D`&FE_yy%PGz?fB>-YBU5mZ9t$npX-LG2^f@J(dz2_AQ{ zdR zP(#hnAt{}hf|fnRrsbE)RUSWnj0KPWC{JWBxV*eUqm!2gugfWR{xlAT21)4yzBQ4H znrSj(%A(iZ+D2~GtJ560;_sTFmpRxV2~83B6_oVbU<(qle^Nz-?9PNq|4GTmTm1zw zBipMlY+h3vu|1~!k$xh-4!?R-D7Rrm-R$|ovt3NX_+TN?1VoViaol~%&zbS|yS<8m zgGcM$%I#~Wzwf?O9k(k@#h2$sW|Z5mh6mCv0m0LD2xEb>y32TnVo;hWRxZ zX8G#8GkD&59lw=@xowC-K!3y_681P|Q2}V+n(0qbQ|mc6IRh&DDoD@^4A5K1S%PFrpYo{(B)bc>Uj@k& zc3!W%rq2_DfXFqlj3FT*osZ){e1V~YY+Sgd9e_P<8w5Zrf9u#!88e_*ETKyyaaE98 z+3P%M5*2IRe#7 z%_fWHETkR@>J5gm=+wtF@XaNz3{MK)w=a?Z@!2B%&yQG{;x#V(4i6WH);!ToqVz1p z+*^=ets|%-oD@ad`onkr^o7#sW0#_b8I;}}6VzOrfR+=2N)Vj8F_ZuJGc%Jj&!qZb z%JZtbs&R3i-dRcOOZisG@h0X)T6~Pvirqu!g)A7pkDcEekQ@r^f@2W|PRBp`+|&)v z>(0D|IvpZGJQ!qk3PE?57G_9X;`$t!$<0Vlw&lECqtP?tJ}(HJp6T{6w_;p-#LWr@ zbeo|f%ld$COh*^{*lvtfDt@)Als`;M1J6r{91KpU?o_=j>2*6a zDo($2XJuAibXvS*K`puD`?amYUqdE1yOcdfs*X8EKf4*pko@XNXjPb-cEeL{jWw5g z>ZmG?4~v`s?*1hBRaoPePgKvC>N7LJ1otIwy8**mL(Z0r#KCKae`ORnkv-^RT{%y^ z=cdZ!_nEmcfj-rZvr&{ zQJNyC6QZn~KPrKhv=H^+IChYQZUtC-w)pdcQsswSW0Kzob+};w|Ik1=c;@Nh7Q>-L z#Y=18Ss`I0c*-Z<%$Nbx4;$}*@{JJq1njG*@atb?E;HLpQEA@><)&YoaC<2e}x-{KmR4HNB6*Ld59IPIFJMoJ_H&+>RNJyy6P=9OA` zKCw6IcV}U%l2+s2@joluiD0W75kbpXpOv&6EDS;uQWz9+Vw8;Fn@ObqLlbsbo;6$H zj{KXEr*{O;-c)z#INB7RM1OJg-y9BRf$Vt2tWm(C%uHj~zM6EY7zTUz>0n*>FV!Et z0=ds9V=QHVbDhbY1r54|ggS`fDQ(_>2)`65DQ)^g?xC-=4uWaN{z|{y)n+;n7y~=N zdQV`hSbKtYF0QR*t@B^LeN@C9E@NNAq$#rFl_F}Z;fy!Wg(WM-rn9Hnf~I* z_;0aza`~B{VtN%Y)Fy z@?Eej-~^I2dI>b{OhyO`xZC&DT6&<0I`H1vnSq8J*6zj@NG{;BCP{zfq>1Jk`I{n7 z;&;;Ix%ZQ`)~nXtZ#qx*#4~K#dDz_C{G%OXQtGXI=V+cfkNoMbQT`mvy{`NjH+pkiP6RIBi;o<)X-`@4X5#doy?hLW`Vbbs(D zfp9>MAPL=q2B3aC$!dqwi-DnfDt|Yh)7LoFji%i_+F24nCbM}V2~g%9I8%E zSI9}*Mi)hB@?cQnuf-jBPC5atWsO%VD+>$R!AK%Y@X3(W53;WWLuozJ5wiy(;asID z?k#ij^kH=bf&m_5v-U4`5n%Sl*9z>P=nzv=Q(ZF`XG`ABsR|AVIbxiGbOvV)1x#E@ zDqWk-!`&T%5M#L`?>PMMHQT%R?CONV+Yu38F>2Y~n9Pv@*{u_j z**Wg5eF}Y}e9HrWqkpy5$@1QKVX|sac$-g4EF)7DC-b1jp|UbIs-EC;>(}lrymj)N z&S9RbZyuCss|!Ve#kFMtK8}#@IC*(kq_9X78;z7|qTQN)7EAnEOg>6NGh`G)}l>N$7*foq04& z(8;3SX5mL!LzA|tKZJ#$H-Z$x|RzVq`gv-PD07qpv) zGV?}layHpuDwAiPIqsgcEc_S>YxIiH2NSrfK>MBEm82+3L9y=-(>(cHGAxotROaeT z-8T*T=OmwrmGQa}#WUbm+)4LNY-2e69l0%nHo=zrKHPD@^Da7j%_6k##n)e#GGp^PHr}JpUJ~#n>zDlMV>`HJW&5rCJ(U;ZDSec|1Uc_g z&44ft=^wAY%J!{4L^Y1q^@WC^#p`j_)J*zs4Hez^b;|dCzCQ#xek8}7~47N zlBhEI*xO94z60qk|D(Oo9O2RfaRyPssZH!Gy;x$;f{`9uST|H21DK4>pf#A=anX@@ zKA0+fE1+G7+dELh`%czC>D&D$`$K-z$o5I#dK`@Z@(a(Wnx*B#^_#7v6JP{@?jwsa z&0v#PW{1ihd|_jM&Ut&6x}C$JWDvi+!xnTkSEQgrjDP-s_ph#S^9rPvJ1HR1W#a1C z7u3Llj&yhGTH&|lJx`m zyJJ2v&Q#El20L3Nl$dNDH)+Ywd0;lwTB_5D^{Mnib*~MW+6Qe44ExyifzFG3B82P! zV6mCx)1i`+)P?%pkCA!^6Xs`^5{##y#c0WZc=*% z5Vvh}TECW?b*nzxRPr@moo738Qx*@-_1J2Se>j(HR=<&V?`{gy8P;!?OqVE^RJyrL zm!IV-Bz0!Gr+45kvM$@&F*tNd3QsB_O&-@cV*JX#Mml7?UGlM~cF|8HPzi)AIK(5_$aj@;Y1hk3Qbl z(7|pWR^jhmJ1tPTYO_lEKrgD;ghSg7|} zyj63u77PFUn)GI%De(CwuXRrnVywLtf=Y85-vd}r8kmIf(AYbbu`l=ZxVkPfGc!NM zcSm+Fklj4+24==)$HuZKAnl51-*FwD@?14$RkE`TCkXp_KW|JbEmgqf^thEC($7i= zw+%k#;0!_BBA^bf`8R`GTjF6SES zyN}zZA81y0!a8ITs{=IK4t~XS2PXq|2p>fmhf|gK!%5!9EY-gGkg#vk#lC^8|fI}MTmPF{P{$UM#S#$`I8ac zJ<@0MN6mJijCqb>1q?F(`pY4s1V(o9FH`Q-SedSJ@NuWb_hKGYYbE_i!3e!5zHdCWQriouof zuq!18j#}0~8)P;~6$$5%iFj=|>8$bM(*VtXMsshWgOZP+eVJe*}?` z)pXJ@NAx3je-^1eH*tCZW_<;*{y)3L+W+N?x^0RfH{oH=Ym7A#IrB&h-0D zo)e!gSgb5fk|b~e2f$4KO{$k#6kBx>l8duS$lM`?2Vc_f*cZlX=#{rGiOIyfPliu* z$;na+&jwOvXBM611l?zq12+yL5aP@Q&IpO@v{;M9H=A_E{_IQA7Vxr;)vk?EzpMGE zW2xy2&%&v|g}k^tj_&*pRI!!VV^1q-t!`)TcW_k+w+z?kT6~wRUjM@6r0i`${}VOm z&IkyfJ7)b|&_%s`mA_v}RY*idG~E$RQLkqZcyCFW@5~fWsV?higA@sY!0az~B{ZF< zNZ9hV*2{4JFy`U(YyG?0SG%I=Vxh=nGuCc^4k23c%dbtn?m(#^^u1-^+?2|p_I}QF z3di*5DQh z!khoPF_8P9G+mkevgSYtz3(#xo^MI(zX~0(+qeDrM}K0Tjqo=E%xS5bo7XKGiZ~lni}9fm$Xh#^n{Z< zZakrPS0ioP(CcEG#3;ldnB;BeE@O-$Rx*M*z^&Vr#9eU;*^g(tWdEQE{9g(#;2_!J zGKqU6ssZx~Iz45tjhCFw<(AXK(&m5ka0q8ahp{|Rzf}4DF3)sVMwesIsC7=1rL{qM z@Ko#2g~7KrRr`6D*@w6vZ|2SDV&C9yb5e*!UL`&;@k#$CjCDjb2V$JK@JX+L-VYg4 zeEj_QvbEVi3Wps|*KCpb%E#?>@5L>ghg|^F z37ZZG>?6?vndKX@`w}lP6u7Zi^@~9pPv7ajoGb@Pr|u6Q09+}{9lY%yD$d8wGy3jo zQf-Np-i~ng9y3B3j6uiTxjG252L21kzrI5Iu7BWk+OuNb^&^k5IM3WXMPBi}vj6+P z8i8p;A3F+Lgp%64L!`<_IjI2$YtwE|$^Mu6*9H|&v}?S}YO&*L zJ;*tH$2_Y zE)Ne5J^(pG_6VWwL`6lV=8pGOB~yyN49DuN_IP($m)`GbcW66f2U}Zc>(dZcCS8Ue?E- zQr+lRHgU?|)bW{$L52J9w+>HB8(K+1{x)M#Uo<4K2CnK=))Ur{|0x zYY7|PlJeZGqit>4kHI^64!n!Ud@p$kIdYe7QrMUus(q)Sq+T-o&(UvJdss_6ri{ZtV}EOTWS7~UjV7kM zG??PJ&cw3H#QxZR#mu?ny*Lge+L4cl@PyheFU&$7wWJ26HL!PaScd2VDuPRm-k)m@ ze`&zQFeG`4ZzO=8uOvX{5j*r901$!X7%)}<-~lMY$H#{?)nwbHze35$P?mK`YH?AL z@5e>nJmBvY7G1}a{!jO1FV~}T3EZLmniZAg(OL9Qd`AU2ZnPZZuHkLUQEy}EsSf<^{u zRi0tX(k_fd09?u1BGflGH@7YGlPjFk&)My16#m5JSHQIT*_M%>j>LLJ?3B9>G4QEK zphtw21WZb72;k&n_3FFRF$_ai^8i_B06HeiR}O(_qC&T7Iob2(b5WM+vG~L!2qGPx zpW4A67E7OG(jFB>b>>kH*47P|>gKIGn-mu9b)x3E*&X{oN=w6n7x^^g1m-RbezNEL zGITX*Yrg%BsApo`a&>_xh0+z|(N~hJ8<0LEehrm{M0%087$c~Ie7%hblLO5|boKbg zF=(%!J63bS=YCke%!@o`bK6aB?E7@s-7@JWgmb1bg(S%jYL1sCm@i$;p`hTF{Gv6?Jli~ zk5!^lK=#1cXpxZgOk34TKae9#+|OxZeAt7}>tT$rLi)OJ#f#k6DusAW%^Xuxm; z;(&_5{!O1;#-m51asOWkDR6BvL|Ry+UKV9Sk||sw+kkw9NDs1|d!obkraQM-b>M`h z>$e?yYDbQhgzFwERX9`Dc2)F-pop@M*xZAT0D(}`prTa8c2Du>an)bDqh+<~nbV%R z|LTfzSgDO-?hYSE%`(mO)r>xu#IfkEc1K-z|2-`@XhepyuoL6pu*vLnc`(nulh5|< zTD0VxP)@4QEzM~l_Y zt@@@yW?fp!RYsjPE^O3@`gQbl_%Z1IHP`*U@&>a5@!ZiRD3qNSazF4V_-lG=T<*Bw zw|DmR^EOLf>?N1$OIq&^+O)nh@rr)nS2{CTx2FDv=dN+>NoyZBpH>+?CSIG)wdcla zp3^IrGJg9Qzg}d7R!oiI8Fp|yt=?FeDCS;!osaW2zmCeiX7$IhEbD$Y6rWhRly(IQ zL(;thF0jBYWFcX*!ZkRvK>c9sY*EWv9+cASeW~gNsQ4VieB%6tn4^K zYype(=P*tn-BGbB zXYLqe3F@&?hS=*EcvqWbhH-Qmznb_R-cl!Y3#v2`6Ft;ie3+z5gj&5H9_NbJlVzc( z;i>RI!?uYEMi6zfXYXAlOp@DL4g$qt|75qZPm;T6M@qc&+UetkUROQ6DP__(oAlet zpJ|oM?3R$wHKjqby5adJti{V2K7r|zn4Mt3edi!Ofaw$bM1vIw?8Ve-9p2y{8=@{*j`5)q}zM^wAI`-;Z4bpYR2teLCT(MgsN_+W-%f2BMuU5}T1$+WA8jkPZ z7YonX@lCs5+iUaH`p@cb^Oav(C`EV=T1oO`A7ljy4+ZA=t45(MC%-I&bY8H};TjOv zVhsj<_1|tV3;;xd$Z>h+^M4R=h0FAaOXaPqK+sSya_-FQ40t~8O2p@m4&D_vC@-7_ zh$%zRPsqz_WRZ@N?;&D>MZ-oJ)4pKB;D?#8J*6Ud7u=1M)W# z51RZNQnHEk9)@~av&tR2! z6TgNse{0p6;*->m!QTFYl^k97O1livq5`}IPrYO6JjQ=GNr)erEK#M%ZR?7O{R|*} zTTYB;^_!;mSzPOW|6o~_d}~@;WG#@-pwLkL_={~+>zF!v*u)txoS!!Osx-BCsC2+W z#QnRbjP~FqyQ7MH`EB@G^AUo=}dr7C~;<0px(TXj9H~!^TI^EL1zlx#P zq2Ied*?gxh)!W_bZhY!~mR1j`8c+E%+@{>rVqTqGmw>oE8%j3HaBBQ!Tc^NLw~AA? zGwJqs$vRN=K(I(?3r24kS5KZf^H{NY;S~?=V9?S;D&t&AU4zItD5aieWv_>@|G)GW zYIjIP8|3t`mf!mJ+9RjHgw${ZcSEd<*ZGZfDw@L|ACZ3qxI+^r?1I2CAhJ}R$2Vzl7K=qm-`%pB6II}^-stQv)F@cjOTl65~nj6R#+)TCr zV@bAcdxa0Ah$ImJ#Wn8e=CGNMZH^B|YYLjh)Ai4Jo=tlAE>1ViJDf$(i}CD;9M|LI zl47B45^`!o=Xt~`vzAP@Yq00)@5s2mcWCIC<}*<-&fc)FtI@VM9wYPtx2w?Jy#{@2 z5E>hdsTuBtcc>kR+6xG=L)Zu2QRmX$o9jGFDO}M3Ey|)J!K}}kr=(J}{ky3*8m^)@ zn#gjM-HB`MVp@~+jxW2$k+;*AOmatol69M1-AITWRCvgAz=0ZhDr74;y0ojlg8d02 zw}UhXgw|-fPR+_s&^Fc@*(M?2{G52!Z<=ZYG;JWwA>bnMSV&6<;nfkOwR`ej z-$K%Qd)yx7IQ7LXb`w;e1Df1+i97zjZu3qrud8UDeo*#cUft(713l-X^cfS;QI~Ru z_?@*?hRybeBIL~arfyDa^)m=R=garp(c`m&^=7KI$zOFz-FlHv+ML|8mrTEfmBszy zKXb&RmC%O(4~Pm6eanM1JSlMJ_5JRvBm@oyLq-}5dv_0AyYjJQXE1@JzJ4XhCNbH9 z5()|I+~lOdg;+PV*kmW|04~|CVY}y_3M{MFoIx!UDN{JllKkz*bgNWRw&ZdnKw(wsSOIA$(JeOVX|6 zIypt%;!>^UD;4J@oeE^>3bU1 z=2I_h^%(sSsXp5f^#6lbd`Ggq)u<|?lA;i;qP_#m-3_4(W)*y+$WjrF^%~8HCv1ex zxe*qPx>kR!O^J^q7WG8u6E^s0>TuAqjCW$25Zc54Y;|}FgG!6tN4FB-oh%QArUGr0 zMe?4VCbtc*U`C+x_miL6x%fUUrZ#oNnqDC6aCqCRK^0}Qa~LJSXyO~ekG|M(qu(B( zeomcj!i6QP@62qb8jCi&?H<`6VR+ZwvFmRJlTJEMP7Z_c->qw--KtV_x%70~m6tYu zU7G;gFv&0K%07j4br=pGr_#n6!HZAQO$i;c?00ovbZtkem+CNu z_)semG1?UzjS`1&05}EyLx=gWy-fv*5CU0|;pySSqeD+&AjNsw4Xhf`ywI5*Btc?` z#X{Z{m>YYsUC+7e*XU4|I{liWg>U1Kcf#nQiL zqFBzF2`F}W`P56RUW|$0E?IPcW;Rt}t9)3*wdC>+#g0P3=qUxJ&4i61Zyp;CLH(f> zlXdNev$P=)v?fHA;hOPn?+?wz;tD*I@}r5S$othSRC7`PpqCKWO3$(wlO zmSUOq4{gOdw<2n%^^Qw)p!p0VXa<{p&Mb5-9Y9P7oQp&cLW$y--l^pBe6dRvDmBdkw${Ec(+cIofa__53mtrEd(4(P;33t%>ESZf8K>lWRlpxJh+q`dsu z!XqQaTImP(?e0F$+upQKZgTc+e@jMcK)K*vKCx3Hc5@#G1ede4vN!b6bDnNzf5gW% zNQwQZ*Uz0C=q>t1M1s{L{r2=pLA5MrM80*EX#9#zFjKvj)nFKZr{;!sbA4}AeZObe z(X(<%+7JqCfW4s#?V_%cQPyB|Itm!El#^^PfPPa!(g{r;Uweq1&OMv)rZ=GbDK_0< zd0-{6Dj^vimc>1$A(4V53l}lbVn`c{)d7J_kPBh`8a4CCkdSwX>mj1z2^SiYRYx3= zBF9qFuPyuo={ma#Ei5e!Q4>NReFF(iWS1ib!i&#;qg6YC$6@=bQwFE|Ga`L_N51sd zK$WfwlK>ozT03Uku+%cB^5dunA z#${A)HWAR`TL}B`PksCf-xF(tN1gWWv*Gcnm7-I|rtBroyhHqRxmR^o)S@}{^1Iut zJ@++~p8o$)tZ1ovYPp8RE~_j5ryjx@6QZ-Iu198-h@&{$&4!`txVMfU51rDMI{V#@ ziFeEUH=ArNx@nz~jI=&F>BWDq%B#VVRUXF5 z3#yA47!DDI4UzXWv1WHj|J5#yH2K?aH}h$5E(rNn&7hG+lhdY8dS; z^B0zUXj(;B+kfl}-V+BLwK$gM_yw(Y_5|yzj~%}CCYmR{4+7m?BkU0y`6oR(Bt^>L zZqu-9rcgT5F1DSa`8qwarTL!4s(v~mcb@%HNb-I(US8)XYe^0=8SE{eeuwv6lGxWy*dN0K^4|yu zgB%hn$cp-aLs5?CvyPC;1{)8Sq&oUoi%-Jb(szbrFp$JZ-0a}NNRB)XUjWoHNYmnX zP=0`knw(DHG^D-(M@Iq~J!2-F&r$wx;G$t^)_yyDvZ)M9y+?@tJ`1Het(> zrXx-+A$&2#ds9ai6@4G^rnw2GDX`}XD~R#lJNL(|*;V*?SlIb!hLYYW^?21O!hbX_p>R-vtn}IMvirVzhzZzZCYw7ZT{lQ&ud=pv9)oN`NlYXZwkfK>G*CQUYojY z-4?pt{}kWXaBXG&5+nYUS@5Y~a#&1ayv9%JJ*}VdUH>kXey3usY1jGvuW54EZaGS) zq5eej^Q#`?<1-7&26LAmm)&t$>}hBmNUl7xbj|$Kw~|wo@gB^y-wHQ?xh2h7N(wg# z^Fne7z)IxKJj}=l;P^0F=1_Rn)H3Ax(v3pFE6+kzFBG0_+SuFp{X{u)t@@(izl}6n z0x`$S?bLTrhdKRp1NACwDwc~Ysgz9_dlnMff;jv2H(&f@!u&RACx1jt zw1wu+=ZzJjQv$9VH^QcfvF2><=_{2He>LigPAsT7Cj^=G_isEF)m!fwBeYqV%C5U? zF_|U0d%#grUU&ZKWk+ca4>ODLBRltGP<1aJN278lJXcHgPTh5_GHXeF7pRi3b{FU* zENC}x-V~|_0;!;YLKg^01D9xU(;PmWpI?iaNhU~!&D9Bhk9;7o@Pz8z(sGWFG_7lB z*nkZ@Z?QR%c(X{LHw++bSUiqYQNRTcf4n(l*Um?*ZxFH)wUcJXb$s*~I>-9g`GPi@ zFzOp0-@why4NPR(gdNv9VLma-xFQ#XhL>vsnaCuz8xG|3U*@GQv^&Drlxu4ES2oc; zI4GXbM0U=>g&H~^&hhlp_-Puyj;0g3>_EAQ3KmScnzM8M@t(Eo`#(qdJNSf5hn88b zL{e*4{r zRjWX*&?+e@O?=~HHu7&vHK~emcAZW$O!(+bBdU2%^FV*b+vq!>yUFB^sPv#O^q!k) z)t^j}4-yj-0u46nu&GnKY^8ovss2b%Fnn~kztQpvjseYguH1(*VV+igBAYbbGyaM{ z;NU&3sS*=&X76_J1@w4Paq-(6F^h|fMbwly+KO!&XE>hOpL_UhqInnpp)}10jY7Me ze)2fR-V|id>%5wDt(HYa)o_i2*;CK?3Cptfe~+is$1Pf_=EQbTs^oSX%Sg(f9E$C) z^K0u)+QrA5oMovQGa6iz zKZ3Dj!4SSTbcd<0^oFIxn|k`dBLcA3HK=K6Q+6zk^W66N%1lfQq9 z1H>XpL1?NqVousg?ZC9S7O_4GUglVl6Q;_G>x1M(J%J~HV@HV6(p(FTAH}|#BzX~82y8<&*P4uP0xYqm{aQlV z(7QC@;h&junVmbc(!cn?0dmqX{32u&ybRgF6MOX|0ySo5XCGk9grunTVqp++rjQaz z9x06&fj$_Z|BFvSYmkO92RzA}{PFJPX15IKj-M@HA0fu;!ppodt(UdFFbDU0KNK1>***_lb-+$|N@@C}=JHnl(rByVG#bX^#Z;>1Y{f z)*jU|6Hd#NWf*n7XcV7oSi)r;c=(SqKku8ON7mD(xu>VUL|WzU{#3LoO}YI2pv=8Q zzyEHr(?*Iuh40Iw+$wdL^dqSUN-X@ehKZdM8|>;?fw{v@Y93 zsPy&qsh>DejZ_P=MM&5*_HgcLD}w2}^wIS`|0D~53zLF!^*@bT^-b5ot>N=MLf zl)CbxqbxWZ@87F)X@&$i-II0Y0e?#*P3S1^Hk~I^1ftI2v}O-TQ%ySp(IlMftASo( z_#>}{%vqE}S{f3*OIit_DP-Bz?83qTk{}NW=p=`cy^T=(5A1dZky$ma``7?GOAh0j zA08QUwVG*dZB-Z2{x22>MRi;4nROpGCX=WuNU(7)ufd_mfxaDgFSwvUT;XazJ@RoT z>>G*b8?g!SzyR=6A7K)InOr@)k>X=DRHb*S7mrk{14CU&cs(YMN1`k)Wb_EcM{isa4|nM|q9h^pE&#G(g+HyzRsy|p*xOAONP@cY=O{J0D#a2IAJ1yYc4n)@ zFzo?Z*|pBj&J((-u2u=jLQhWSU%p4Tcm399;o)!6*1a~`JB+mrv-9&jLPBf7=t0U& zq{!NtH*mGOTXieiBr~|198>nUeekHBV__dN)~O3QE`$ZBfX-%3TVt&=7aVm5R&jW+J9XNMt-t2p9D0i~CZ{^exBeXCkJRuigV1{E z)&DrFQ#fUVJcIrQb2;(6v9>z)#m4F_OBFdmwUSCo+-QT-#vTxBQ7K5JBFgxk(1+Mk zN02Y*=8tA)Nfh}k$&<1L+1CTKMFKH({I@bb!fB^Ej#30)+W;=ZkabUqkqeSiT*!xf z>FDU7WfX%{A=wvob?*Loaon=V1jErD0L2AYN1u-nWsY= zP|JX${8OA}ERjE$vD>9LMuK_ub&< zy3X_a{mgQN-~X?ik64KD2NFOTM<9Yf&f-Zsp4P$*Z!#%E`uMS*+l+!sL}UjDPCU<^ zK>jd0lC)er`ytznf>p>~WIFY`j=X56DTIXM)#`n}13?}oEHXh%5VLc6VhLbA0`is=x8ym*spC6p^`4aVd>8j$; zoi=xk61w2IUKin3|CQKpAIqtsT!HijA1B9cUv|OQ<5!tZFu40R`|{t8_;}YroSt1z zMem7#-|G9e8zeskwTX0l_S}a@48P0K#Ra)E1^ZqlkJkRw`x#>4s_ZLuxK zBzGgM?t3Q3cMoQbE6YdE>Iz?S*i&8M5OM5%T*MrO%)=W+SKnR4<8Rtq836fDH8xe! zlx{1q#=wn^Y+Qqc6IawXUTS*PQ82l5J<9|{!&dE#$?p)HL5|m6-XYWl>bY=|u{ zd+w#R+jcm!a6Oj+$RH3W0^}$6r3G>BM79m``7n^-ntSp$3^G6R&LfBdhY}3gByJj9 zjZ)TsdGa_@2|z>C8o)?Mst<-CWF4R{u?mhCo8Pr`?iv1Gu;blXUkG`T@$%$U(fbc2 z^PQ&(=PVj*7A9-FYB)JRL?W7}23k5Bn4n1VGr9l=ruc?|^Qb_WPX2VTC?^HB^N|=D zXukjK?%n=KmRj)R{(pZ344;30udvu`zR7)6Isf)7^G!i_ zo-CUWofdK~a^vAMwsh^I4r9ko^CvEsJ5CfCDQs~)8#fGoa80ehvyic53J2bn35w!d z2^=TY#mw6Jwo_BThF9=|iXh#s&cXmjBUd_n*HD2c1G;wZoYo|42gGHS)w#ll%d8p(f_9fnC~9Nov*LY zbmGJb2&3WQ=ouex%1Up!K6pUrUqR(MNs~ZBTla<_Dz&DFzfZR1=#;TF&GQ%rRX4h@+jtas zJ>0SSa+96G&~y3%_T6xVG&ZV}*idMlu-=@XQAaP}slSr`a5`WfvmgEG!?`-B znpA%TQJ`R>FgoSBElbYpq{XF*SKaHkHi~+NsY+7! zC}rKL48I=q+2_GYBAt%3z2NkL_DJehdnuCVK3RV!g~cR8`Q^+0xJ>*TD(?-jIpM5| zVEKfIIaRp=V66L@zXM>hg>sUJyHZnq{c`I*)*T1%=zdf3OvO8tXzj!k57J(YiALIK zY9BVH+!N7Y!@!Lbfq5AJ+1@??K{v5;s6UgY!wZMM@g(NcTkW}C*muWLBss|94wBBv zaF=CnScg_9vyFMRBlTFgM07d7i^7xEq{okCpB$==H93{3L?wPwFP-h?gWligF4)hj zXR217{$89Zf5FIHWy?}$YbztNdCTEf#Y9Vu$ph=feLp{?6fG$7H{84l42K3^>_OXT zi)Fg&N;CH@rkFnZmD3E*a2Zx=r|KMbum77Oj&9`R$hJb^5E<7no=z`n>`2et@jb3~ zJM(zz%`dF(*iT832IO6xj(t1a1tIO6KGhIwshuxQeTu+0)I zJ3@rIe*Jpj=}EC^)23rtt$kx11??tYJ=`2}Lcw0r4C2p}DTDp9q_3FY4%26JJ9v0g zz|@|8v!H_#K^*(fSkR>$;jdS*+xbN%++2cge)8U6H}{v&PmJ$hnY%q|4v&cR@iOTu z=rb~_JNA}+>4SP__-ydYD}T;QpbCJ%8psX8=(|$y_h%0=lR)waboNA2b1C*yOoYcy zZzJFXtJEznno^*CfORk5DiB)@=uafqFBlCv4vvQj30zoIjRBFsSOI!xi^B5A;Yin= z2z4VgG!_wLeBref9r=m}suP~$UI5==BfNXN>lwbZEVhL&aj&Ds#A*mdHxvxS^wJ) zv}DK3H-rud4n0?!-QRq!nlfUJ>jG!^LX)G@^T$Ey%DgE{7E`YtX9`x#yZ0Q|kHVqG zQR;EVxZ0He+0d-B`csK*q)ZVCqOtwTrQqZy71wIkkAajdd8i^KI_Z39b92K#n;ba4 zP~_GWg@n+OuZjddBF_z<_N`!BqKAJVTI`R7cslA{<95{)mPwnr$;qD1!4c-}zx}H5 zv@|pmuMYv3tvY|2KH|_xB?*e0V$Gla3CX8q$1ZT$^?!q;X*S@{bDU3Ch=@ocCl580g?`Hoyx`H@|3FJo< z>;U2o9*5^BP$p#+y;&pZ0Q75kD6r+?tE{b#|_%)JS>8I z^dwAdn8?rwMz((443bFdG^LD}or3hU;8}nK{sC@PM$uKsGVix<-(K zn0JHO!(GuBg*2G|;(iBJX{AiRgJ%IcJG{}H|0sZD#_^1-;Cp4p$MB4j@e`;vp#dS! zlndD+W~#IPJ4}NVg(J5M9j0-|(0N4ecPy-!ve;1hj2s@e4}OuD(;+4&k-Ko1Pv8HX zbC*XOg1>##y@iphsdw`!`T9@G87EI`8$|9gcm2tJFh{0?Ia%`edoeQxjlt@HKtcsA?)L6TTVucjgzHja#RwwSyyhp zj@jHRm*6)_qxkpPF$<1z^JwzgB-PGkqxWkOG-uu_ z@D+21^@RW2eU;bc)h3;_gt)&T36A5#CrRqcDk}NEnU=1bV8Z<|S$FF1rxKSL&Bhoh zT2hExDm%^WxYYS$sE0ZjBIfXjn2u*-sVc&6aSg4Z^(7p}8l=tZU`oN;jiH6@Lw2&coT;0vgmiH3^!IKa7p zZ{tXr&UU@%T*QHqocFmMx^aVkn>Uu8Vv^TZ-4aQf?nvj;>eAh+eaX0j7iL;Ch%y~} z+d(6(xY85do40J4W}3w_PeMB`Ui|6SAvZBGQHnpEJXs)UrWJ&TPWQ@1zBHLT*G@ku z7wL7QiJ{+$@3QJ|zdc*ptZi4d;<$(3$hMvNuJ@Cw-)P2qQkG9a?1}n5_YAv72YQ8D z+N#{^t$H8M2dsupzRD`U&cW2miI!iAbrCP8(}yhZBJUs`LnMII1f5nV$2y3?b<&?Q z?bt^XWqejX&Qmn_+6b$ycgn_hR>zWKD1&R*0Jsy&Bpk)Jd_v#9mn1n()bT{no8i-T15JqD074NEeCFu2Ql9b&O*eo)Y5>v zwe=4SozIU)Jb?#2)6YZA}hlBsO} zE*|{k5^d`vOjR1G_cr3byrvjKE9>UDOEYtcqgp;u--X`uRd@^gZ`iOQO3q0fW@!W^ z+=g`1=-JNs&1gg^$3kb*U%xl<9U$Le4g0am;v$z&Fu|MNv2azB375Dk><6k_k7To_dy1 z$wQ1NluQ>Y2*9dDD^F+y@|>asN=`W#VjEe??4OaQ%EgF+!vg5``3E8TfG5M8V zqZ<`p#F`nS$O*b;Vg5OHWTlZfG>SMKPJow~8}ACiXaGf7ZsobuJO9D~fqfZ|J4^pn zNt5zTP=I=JTD|}9p>MX;2qzvRR&i1*3Y3-DoFSNpbfqu58Pzd1!{0?nkuTEra_vW1 zGIfXbrY7oP%D~Kz_Th?P%df}yIJge&a?1MRoY+^^+5C=M*8It&4&TW$S2YqATDrd0 zCYy8Zj?m3+8VkS1mvVk2o~AOt-D$L-U^Y3qwtnt>w776ZKpB`eqQ-;Cp|~rD@+HD_ z$GB_1rwn$eU*+n&WlD9|{>5)Q8K*(U=B>P6j*rl;*8EMRx&o;${)6XgejkhTNr{;^ z=N%g>Vw{|`E(UhKLC`A65+`+~1vB!vBglu1G|*BfhQo2`I!4u@S60(FBE#L^UY3~? zSE5;sS&b1h*=QZ&l=W-Wp0G*C_*PI*Aa@pSZCrt3Vq)F5V~!1dR%7E`diLp3n{_r@ z#bvpz^gCE@C^Y9+x<634&b;v@ zHc%T94BJsv!E75`@3>7QZQp~I9JQQq{SvL1Ugy-VLr-7tiolUh0(Jq05&I%0n7Ws2 zYyWU_iR~H?-fxSi)D>0H6^mtCR@h~qt&hBE>YguIV~jleqwx8;tsER2go**M$k9%L zX^q6tTD|+v3W!FQ9>2h#g9p^r3=QKmQ+%t=}|9siIz;tHr%0<6i1}k~BJ2BsQS%NHFo(a8($QvFkyn{1p6b8WT%+;LygmmYGR3u?=ek9P|81@snVZCp z^XoLUz&ha}BKZ=E@NVphel81R=o#gfqf!38n&rmnl@Q?GGliNZxV}7AnG@;n$Rxm#dg2 za2~yfQIwp5+bH1lGk7&1?yYQPB}g)CK7T&{Oxkv1>#NJ&;EedsKE03RZW5${pG%M7 z*u|F&SQcT-xd#9N@Cvw^Y#?=26Bi*Rk<*nq!y+jmQ8^Ux=n(~&9Q@W>3kinBH(nj; ztlB9I*3=8Xp0o($-Puw`f!X0`2$f2CHyV+QVei*!$L@};hYXLzeeuD%%RYcl1ea-QqU(`%v`M{!eDM2I-MU`dn4g&FcH)a#IYB!EkT ztU_9-jwNSc#9BqKI_ZLyB9ee$+`w=&XeUG9MBIgvF~OW-uVcJ!(3(p;_MxF0@G4k5 zR--CupW|Nl$5X#VJx=o}BTbZENm^Q3!?VN>t(Eo`;_|V)JR&blg5RGRPFzhH_Ed1V z;(4XX+|~a}K>ZEzgsDbHb7N+OnGcUM4?I+?3Vo^fgmyoo8=&<>*2(v%#pL3hc(EN= zI~{w}@>Id-#+;>ypkY)*5yUhwkVSLPHt->Yf1{XK_pwD8TVj6x z()xp91EkY#0eZm28!R11s^k&VO!Ibj%j=?&o zk0v%n(bWM}#DIp|s}w;HB)bzD_q?h_68A|W%>YZeA7S=&pMdE`)eN-^BteNV^9xeJ$%m|2P*nM(M>^- zYUSI96*o609NT-XIZCA@rT>D*3)Sc9b$44iqsuO)Qnbie#J%FFy>F(uXg>QTW=GY(;d>E~6ZaRDbU7{Ggt3)p-@Z+sUS6V0)-{v& z97mAe*GSQj-GMj~0Jss^OWeMr2M*8>iWhX~^VVTfg!*5!7F-_yf;5ec#(RavZKT_) z9j{DGRM7U}L6x&*VHL#%f#B0)K-O|{9=pWk9I~JigB(P@jbyjtqrUIsW3qrI&yoAv z{5Ma$VKnqqb;@g4ImARm#AX@X5>iuBNmIHC>K{sNkLi8nm&fO-g3ac~PkPF?fsdSKL zBaz$4%J{D`t|Eun4H(5z*2x*%Fz{Ke!?j4 zsP1T)kYu8*%zLQfOt?1F`KBAu?E+yp!@o-}pDVmuQ5;ssWyWmtLqyTJlqXE@2Z!?U z5!R|m7T*_aCzs2XjulM`#o1l<=gQEo?hCj2)ETh4$LZeV!qm5nf_1mwa$G2~iyg9) zff|4Z90|ZKB>=uBl$2DP*M~P^zJZ;Fq;D;#Qe=$xOK4K_4h#(Vp%BZU#67m*(6x6g z5b4*<7thP9$H_7OZ&-+8f|;B7hb9P4#jrFW7vecE7m|o36KkM1jAVT%WC$!ABbFj(j|;hVFKyngd$6`GRI07MO} z8MoYcXjb|W|_Cu{ZY!=e)Zisfn>4ppDp%N@O2RZ1g& zvTf8Jzh`<=N@I5xPGdGUnxtlbplrCq%9@&JaXm5RGxFRM%9ogvxf#-Xdapnm|GApW zr(Zk{E_(4hi0}1z8UMJ8i8)85rE8031dGy5;@w0I&+4V?XeG(St_R(EYe;3vw70os z)_w5w^1j~MPR)xs4w<*EaYZ&id0(++dHr6;?epSdhbZOt*X((UP*}1`X6U{w$9Gur zrEJ;pSc-0i<-0_XaBsAm0EgGPFUkraY@ro)zvOy4vxp{HE=WMd{NJHd)i-`dD&vtvJMo<^8wAa*ZLCuNM<;(1P zPna+NU^+AKr1Z_;vxKITd}l3J=o;#O?p;ikP0?Bb|54YSR2inMG^OvVpXy&1ew>=; zoL&4Lrx|^|Y7t_5eRFlH;;C5YO4-J%?$1VRhW2$$E~0tZT^cg9gc< zJS2NA%0cMYgY-Ts_ARyt24!t`A~e<5xRj4ue!B)eJNw6?HsrR>ILoi^WI8HntYRgj z8&tiA(Rr81r@JZd1V1T7kMOZN%#G>~YbE>q_>PFjGjUv@*4a7g)fQa=Hv1~$$Lpn`C-a>h*TK?u^?Dm(s51_&CiKKQBqCmj9Df*`|egEEh;M%*V zT~V>XhxpZ_N?VVFZ9z7|LojunSqQxbSj0)@i~0E)gySHKBp5OpNc_7YQGj14AY7vf z(rr{CwR;6lss7oASB|U(=xpyQ1)q{KD_HhhNPEK1#bbTYPqC6{dW_39c58T?a6Pdx zZp&-eHgTHv3cVC9a-O2+1ltRVz$2#|;xoyDPGIigVec|yQm>cr?HZU+(*20C15zFX zNfs1>HBcswUzfv7Lvj)^%h?v`1*8d1QmDxC?P{pIl_dCbOQ@cp)3Z0u7T05^PRy~t zJfj=`xRJkCQa8S%?)*qm<0;Xw4rLn$e?fO8Te^97It?oEf_s@=iDQ{>x8xOEPTS<6 zT|J9|eg)aSB)28^v*!8po>$_Ws{3U|@M8HxQCxOIlJq~53IGf#B(fOz4z0oh1uBIn zW@ajpWjl%Kgcou(PWJ_Fyht2Qzv+lL6MQI%btJX}Xb@cI3%b}Dd7US#7>T%@r2fLm z>)Fs?Dk9`@{1bhJf&xT#83G0U08I_fI?K&| z)h0D_U>x=QkJ5OPZ?ZR;+y9O6s{UnsbWHm8#oBangXrB+GVXkOXCg6qk zGKZ4o%Lgv!+qJiTjPmPl5G@J9f;f>;q^@s4{pib|t*%19g_(C%I;htrsl{U5C!=N! zhl~1TAeY$fh)IaFNTfjsF6imp>aWKCHe2o5wTl8A0ORu~MQORsXZ>d*h3|u9z{l1u zjl$1LdVehzOd1jLOP30%_^Bs&RtKe!hZGkV*S^&vTc5BtPzFJx0(WZ#nxP=j6fm}k zv&cNKV*~dC=7YkU#0{*N`F!*;wIyjQ=S|mzI82LXFJaVAb%w-!?*E?_U{|8rAvb};F9K%5ojL+I zSnW8#QpY7rz@bE9*WX&v%{Z?Lu9O@EE0t@g?Y$><=Ldz=J#X4w3t-*C&!FtuyYgEf zrWLjTgT`(MQ*%{P9P@2f78U|lja@!jl>I}-#5V!l7XgHbwmdmb6HEZ!#a!pvf6s{j zBdO8GVqO@)PE`&2Ev79T)~t66Lhh-hAl6ilB&z_ulxE|7p7~?6+I!1RE@5HnH+N;^ zKHTP8T3*g;-Fq`^@*Va{VupgZ>A##LNK&|Yc}WB>nSX&fLFfR|k)5C(T?^GxDm_TU zy^phmU=)A~2+JFY*d@GmfHR0N0H$TkW~BarCPK{zzY-&MS!=7qR}=3lQ&={Hif4bA zQK;Lrh)HaoXFnbuA0 zs=2=*;u2Gnxi4R8i4)fT*4D@pvkx5@hK>Ju($}@UWmY|x!H00@{lVX_0?yu76mN7 zFR*Sq%(v+OE?rqb#>3p{@gPUdTB@&3bRnPfptjtL6~1~_yUeP^7xxQ-2I|?|Di;=e z3r$C}JrWOl{h(F5Q=etNc+GtDwe=5{>G^q80|Pb^VoT^Kzye?7w4l?le6v{mEXmwv ze(W;oiG+w26;!HF`?N+fp-bl)>9oWpq&7^BMKm!J0N~b-Tj&A6rbX~1*QKE}bgLeN z?iIR70>$F-!R4IywWXzn#0wLf?f(cu2)K!#H~w(6KRk+#4oFBy(3G}<(ipH4SZpPz znuA<5r}0G~6FJ8!5(a_p)yT&?s*RlD1+;+bKC4k&gsX)eZ>aP!DGUHL2XD?)_PX<biS9kk0oB*5eCv6SXfjwxTF{t^w-wjnK`v?Rj-xd|t&twq;* zIM+7dk?p7MCA$yqV55~@Mhx;ve;xZH^hh8Kes(5h_cj|av5Jyx7?MtlkCB)+kQ#R) z;~S1BN($od9sTv8?*lUSh|u=wQtk1*XDnl+&c%sO4M$#KT3S0vP_1?N`CvYQ(d^Rwh-a3Ukj6PKC{id>y zJ?95?1QG9(YL^2H4Y|t;kW%P(AM}j_`Lq{_H`Uj(iilk=a+Bd#`je+kD1XPWcStKY z-HPu0i_HwC*B;R8rRd|@GbsRhi zvEVyMOiJ?h)13mBq>|JVHwbtD$Z$E3AnYO%)LY(N494rj4FPP|rrlkKotLpNz<@!P zB}5BiMNGEki+>1MtYr0%6ouzM`}Lsnciy*Q5LLXg4hKo!SR2K>?iI6-uaZFEu>ub# znpjY#Vz#}?03=C3HZBhGi$g?k=hMb~q{423APyon+PZZslTQn(?V#2{%p+M8@o#tq z1h$Y&Ry18BYjXqsA!th|vrqzw25?5)H*g*?zvDOZ=-cs3+MNvr;uFwe4lo*3;(b^s z1VTS4$ZG>ao}@B^V<}Dx06KF&fI985DRLWf!%{j%w~dAW%wBl;53@wkD9qQXLnWA%cwXC-XHDtrPpmRb*JQ1ql z2htwZ-rDL%qQ(J@CCzX)a|tHxh{zbUzUVu3V@X5eQQ(#v2Uc|K?Inp|5r^o9xVMnr zRjP8j-6x_&hw;vSDGL4F$KPGtfzK!QT+O^WgEt3-gRgPn1vY`~b#dks$sr5BhU{)r z${wCVm;+>4M5wxzhUR{=6{Mg(hFOFU|8}i^)!0#cz&ra-ntJu4S*4-q5tn0ewc0l{ z_>}_h1h}adT~5CtP_LZGR{Qt4c=`wf?W{VZ{BNOi;>9NhG6eM=tR}h9PhKe*S_m+l zp7AVYSA5P@e@EOYqS>oM*=(B^q?+gT_5G1vBFyq_`0roBPJpsB#l1Pd_j_0w&ILjq zK}3we-YN4~(}U0PC_?sZ0ulwBboC46{!CHqzsJDjYHVtUY7S@3G^;0+LHdYABWXlG ze*Dm!ihzoXOpQ?IBRj7g%P+}U1MdMn4){<{7*#=Z*oL?8dE+`6X@9q!;F{KzSqf@UWlnJwq##37vd*n4z@{3NK_x+o z%_BdjV(22BeYnkv7kamo;?$6iI~+`+z_}99w1bR{{>9to36&4R9iwk3>iw(`3c50$ zT&TRFqWeMc%I8Zb#vEVMn7jBboa5)!v=La(4P&i(UoD(;KZZttZcsY6FGg)eduV>O zv@6`UV~A~1VPtGf1>hwhsp7?t*7>eU->wmr01hEr?m-B~i69ww2b9008`M3;5j*C8 zju;S=dD5nG`ZYI`EY6<7|4h4}K)7u*wAq~s7Cyi)0eU<5IiU}*%5J(!o- zerd85sR|PmYZo0y-?dIOt8&_I4sf#AXmd#UaKc8Zz3%A=^+76`JC7BI`rlE+u7>mA z3H521fe9QC!mIi);mw<{n&G5-;vHhR7cko8(y`f`m8r8yjFF$sG3^phDpX1G0%Uqf z4)%2{M^5D|(a-NSSH_mV*jKuL+p;mC>&jw|e!uiEi{^O=5b zfh!)OjNMtZOgEEL`a~)&%{}|pcW!9cQ1Yf62l1z$W!hFOY-cU*M1B|5K5&w9^Iod- zo;cr7x|%c3`oz7|p9!eBY{)R0`Im9CP;~dd=3?|$Rei3$Z_0j`sg<64k7@UAlIcd0 zaihT1wsL4(zK^`VkJ>gF~%iXuHs2f|M-BS;u=wxC=aTMtj0Gmv~% zd?c83%E^_Fewrr5bv9h<@NAR=cb)uU7E%VG7J?{ulXzwu>CcFa!-b9*GPVAv*r6~H zOhzSty%b(`p}8VieLS9KqM#)>dc6@#bjlV8vt4 z9W*rm1x6jFKpFxK4owV#ct!}}l@zoQ>jm*{fRJ_aXW>J__*S9IA0vbW>^d~#G=@{I zH+RHw^{O=NUlkF)p++71`1mck`X`OKL$Bm+w#Lqf$@V4qFYBwlEV#=%XEc(QS-AV- z4+ku$utPwyuL5d}_`oVFmDOV;gE@^`&hz|FS}%e`Me)VUUdya>^DRm`%A_wJ&e6Me zc7C_+L$``KSIdbja)RJlh|8YT%;5*{;q3~3(?kX5+AbKDd!;NZS0D0gGSb%`&a!8@ zb>^yp^3OM2y{=((k>}FF8g4WSnOa%-H=Kq`4|gX|o~}Xr@$i>De2e&jX1L zvSG(x#BqOl)cfhrwuqL&JJH2lo&0uEuf&}K9&Wkp4Yw%%%K!CE2h?zSu;Kp(N(Dmy zJz2Jevl~`?s7$-57U8?HZP)}5h#(F?kS3}ajV4}OeSPuC#$w^u4M~LPZH7?2eJ9Te zNb5;;1Plp8{sXx%4i9X+9`ga))Bc!%_~5Dfbuk(HjlA}kk_B>=qVuU_r+^74X1 zL>b`=0G-E{Wddc9r*Bhs97e*lw1Mjx9&+87nc*^p+(6 z!ax;F#Fz*o+1KX{j)B7{>|NbbX`$`aS{i1fz*XuQ-+Q4aQNjQxP~96R}?6 zUT-`Yp_TuNmW=SYi18g7E}FNQ{&TkYJ9do;Xi2ASgdvddJBh9@pqAd8Tt|;GJ2^S6 zJbicZWi_S{O>J#TBzs|eN6-SCB0*DzAY}+F2}J`aVEiN?H})b4Hh;gSgFZ?6qwv7C zkxg2^@jJu<-L-TFjIuX2Y`C#fEhXkUZcL2$;Pml9Fz;o&n8LD6>M%Gd_^2Yg#1iG= zh3}0WtL{=(;1)hGmzYH}u^DgnY7cE1?DTy!Q#?QB>Lj|3%HSR7`%o7_QS$FEWe}{4KQ)f~ zA67p&IX4FpDy63;_lo(nb~wFxr{frnh+VL3?73UgS9<6X9D$Zbf|!GlIk=A7Q7Plw z?V26@m$KKIy>I3}y!wmB$n4WD9{1kjv&;Jqzpq_VJ6>nZ8#emGnqkhT-p|zk82=mp znbbQP1_f%vMyLID_3vX2x#K|jC^&+KQ$}G#_B++3CUwg_PRY_c#ht=7%1g8k&qm4I z6@~~m8}&)JrOwLSq97Fvh`Zy&$p;Zx@A3>DAF`*z`1PU31TPziAsZNYh&>ED7NE?e znSJ@={%=Rd$4QbJ^y!z)xBi^Rr$|O(DsQjWh7(d`=Ut8^V<$TN&F z?=MV-c+gyp3lWhJ0hZwb-m^G_Lyc50ZxAg?7M#zcL%~{rDXx#PnFF!Gsd+Ak=W= z>M1oA>&8%n47bpq;qAxIpWj8S2*45Iq6|~C@@nf!2i-3H);6nC6nEd(*DCII?(3zi z7uw>^me9r5O`L!H!Q5q=+qp$=!8f(vi*{Q-8Z{Cx*p?EaAF^;RT*+#AhC=Cp#=Km; zl!e=_Su4KiZyf-L2uXpp1-K6H&>m8u0WUr&9!4NiZ{1D|bSVOM(9?m>eikjBbQ{o( zoV@%|%9bHJvYZeY54tmAfyPKxFs@!T=2^wG@^7i+Dd+Nad`l2g1hZ=3mCQY=tgPG( zIH?L=#p+nO7`&G>mm9Xz|#LE?Sq~G`hp*{5wkfp^InEF%ZfFINz+!( zcNax)KF?cP269$J2%l4@h!r!r_h2K0R&d|sd4B3m1Kf(>7aLI#s=l^xWs?(i(mcZL zBY9A3>t^(?W?y`XWdO=UKb531JPde8u$?Se2dhv*$UwVo@E^?!%i&LS=(Km&noBU9 zSxhUjh$$F}9+~hWzkEDia3o+fu=8H#j%J&(r32bpCwuOXwW#^J{-n*e=IMALF33Ug zSzJ8d-;U8o%{ewa;)?HMfI5UJ$6%?9I5|{oEQp9v+ZV(dS-e6n24V|Hk-KJB9_9O1 zJ=lK%e*iA^Yqqk}bWW!$1u{ptNUTA7=s8^+9f51a)GWULH43!_30!!tl@4YZ6 zMF`4f1TXhcn?O(vKvbF*UXv4+mi!R&0%5#*BF=8;kXC-rO^aSAsgNyANGJ)>g>dm3#HMs~yA316<`v8N*gWQM)ISLzu*MJ9x zQ_E&?8oC>3c%Po(`N#f9AtIV!=0@f;UIFGqp4-LXXNa_JsITwt@Atuaj82mL2_u;S zh>#=mW~})!-W?B8aXmToK2?<@BtbIP#C)R(@)C2&uLJTd-;Z+-Hucj4IO)jN3XE zbkOJ|Gu^O`)}QKsjecwN&YLlZwD<7$@#V~`sby-psIBN6;2oA7&64HyDsa~>ewF;W zW@3v@+Fy{{=RK%SlPjXGGRVn=S{GV8*Zbg#J` zOzcW=Q_j>mZsDtETMzx}i&CgI=d;gfHWuTOmS%$T87jR2Dtr4k0d)_)I-arBy?9AY z#o^);j?xEr1wUHY-fYQ__*1<5g^sX$LfxOu*JJ9+XWnl*^7XZYj*;=*ddGA}|I-#c zZQPV8FEej3XE7{pO8KB}nLOfS01+pc`#h?iKc|A)Im4H^8yhW&y}{->3{R@xjaaME4)(l8SUKS^E)0=MW3R z0(UIDz&MP^l`wMjj!N}-=g0S85D#n=8#P>zk9NqDCF~X=^++rRCIAk}us;sAGO@W% z)BFnSD|fCcFjJ6WKx5xEc&4C>!1qdq6)b_kFQ{OKD#33i4i zX1ew|5j9tR-EqgkvZYhjjk)_p`&@F|)K$(~)#BNYq9MK$b?*`}Mzd0iS zT~^6W4$5N}##|iL;H-K|y(mF(v%bj$-~r(yi5fswJQs*IV5TGpm|&VtQ|5qM(B+y~ zRKyOfQ*JH3WvDQ#YQ=*EPcXP(l5z(Uh9nR`!&M3AfAJF~Pbi)WAufTnQW?R6I>LL2 zL9H=PJ|;fgu)ux?_8urZa3GT7rJa9o627dO!z$M8xpdeoVK*ZmI&!aO_4?KUiyLjn zPpy<-H2C?ColZAD|LBlw+YwRCqsjF?BiDqNMZ{eod`(T|k31WE>(SeTf75v?d?J{c zn7VDHP9p0{!$;G(wC1NdM}#^Ps+ceffq9*nn(DPZ8L^2WdP?>9fixXmT#tes_}&r0 z?SMIA(+`Lyw1xBz@=^;B7HFQ{XV}OCWGd7{NABkO4j3eMu-J9_LvAARj=K z&x?vW_*(DbbwK~ro_WWJi@|YYx7ffp{gSly?SI#r?6;?nNQ$AuB1zVSO~d&<_bEOE zP{4mCvBnY+Xe2?WwtJWSul=RAw%czTisVT}7C{X#EJ1Ak)UOBwyfOw%fXT!J^U7du zW`>061EWlm8^+#4G;UwNeubST0oMr-@PQAOo}%(r#J%}!{_gO1ZV`(u)^iD%tpIp_-qcW3x> zU#`j0;9h~=b58rJPFgl<{e7_8D0Gs)Esm$p=WS5XmYnsPJKuiA_KMyck&T`VW^Mv{ zN^n|Wy=Xhq``aUk?E8m`Ym*^llbP>LUZ$_`splE1J`pe$?*7&PBTdSIbW?EDq=M80 z)y!rxYb(D>R$0kO0|px0_>|0r-8%M;$b75&#g6BcN*{kB?$XF3XLe8ue~YZX%~iJ=lMUf6*j@SCI@8WyYQeyM)>mI-!M+{Lb_bkMah+D`}Yw zeQ6Px^u^$x$2-E0>7HXyQ~7!Z zc7RdsPGdp;zT-8I>J(krAKd>xEr58N1{-DeWqZnf2ui^sreESNkAO)q0t#clT<{NI z1}sB*uV0qG@k_P1}}keQ1&lpI2&jStr`q;!zRZ$N_po<(zIShbzdyh=|BJz0Yrh4cZ!6DY6uF0m4p-=8$C~@qVn#Xu z93=Y-c0}^@KpbE&zW440m2oh5IE~e&x59?ci<1yoBgP%_X8;wX1mcEio(CK-0P&Mh zYQtCX8D}^om%tav35gU3QsifDz7I4Mj>bm$IRx5_|KecekIHfpzqwM}g_|$& zC)NFYGJ43gh^HxR_EM&iN(Rsq<~|wL733)*u80?};)h!ufIv3Jd8{qke#>@Wbp~0{ ziy`{=^IhZ-9(Ns(C4MIy$xuWR;dlVOz(xuprhs^Kc}ilvU(_Q2dpj}NK|b&JH$4qT z8Huqe*wQOu>iUm|$jqdH@2wJ6n>%X?z^aKxnj{ax2e}oha{U5(5yc&B+u``EuJ}#1 zDo|cvhjQg+_%|J1n2rBCsJ65HbF`Tk`se`yKM+3y|veeFjMpM zX6P$H9fcrD#gA&3_BEK6Y}vdSj3@^|-{7w#B_G743kL=s0zA?Sf22x;Vz&bl#X(Ol z9Yh&!|A_Pp1QWu3K!Vgj|A$0w-@0|7>;Gpn{{4qlgqwR8!`5w&cAa2-{AkxHE_*Yv z2RBQ9c*`s8)`0qk`HH3Ka;0e9nO^l?$B}?lQ(1fU>Pf2VAKkC(FMhtqaO}j^`}UuU zMT^GAX*K)*YPpH@>>L06dnhic*v;{+reWMUy? zuL6H0a8fSM;NSuU#>48=0;;JZneTNj?vQ~Hy$=L!5U|Yn=U>Aw#z44lHXBV8 zmkV9&O&!D zq>SSaQ5W)w-%fiC;NqfvO7EQ4L7&cl>hDoB7(y;xWH|11IAE#&PRkos%FGsBwUFH( z5APSS5NEzSMoGUkw6GwpqM~9ocK7k}Q7$geR8Ae?h&_ytr+jZ-`YO8ksbqU0{e8|5 zsVh`jyi-ejS@Di{!e3v%x5;QCUnVa;NPAEEr+Air4ey+#NB(L4=0Z+}*Wymfoslqf z-!Wmguj{nOjU|q_*4H<4Vvg;5sfCV7BJ;ojHgP@nyk5pP0{PwQ$oBzOOPfzwI=nux z-u;GN;58Cy1^aKyO~YP{_D)pnIZLN`Wl0wP;Myq8`Fk0x(*$%Zj1U2-rR+u)us3|! z&;da)h1ZGC$s6|!S}yzn-$NdQBMKI^=dibmw<+6ulA<(7!LXh}EN#~p*qBz)li=!k zHU%adDLUl~I`?tC^bR&BIZ~6%jBo7b;>>uYiIoHGAlwftq31KpKM8CC+}as(KF`50fYQLjK7NgtxvC3_X??L^L}~bD3_XF z-6W88{Z#W`!|tr=yn~Sqi-9Y(CMFBK%% z1-IA4>@3Et1l663Y4PsPU!oS~-XI?wj$wpa0CB?6KucArBC~s-A53sjuRP`9iL_&o zfRR!}QgDayO=9oX>$Q`O;lT;L$JKW2?)G^Veyoq3nTNk=|Fl-sb;r$KH=7`uw35&g z;Q4is?o;NZO87qtMSiHlJn=liCktoJD(2Ni+w8!cQ+3AdYjT~1Q{1~Nf7c$iO_pKX z2}F|EQn1(w6B$MezM8O>I5LA*~=dA8)7y0Gh`=$Y+vvZ6C5)wcbj&GPr( zvynqoQY%pOQG@IsC(6ip-Z_O(Z|~7~LCZwDlZjTEou^O4g=#texUz7hvgNUqL7jA+ zGxyHNP^}Z`0m^9Lci*itGSQ8qNC}BeVRaHhFTV~B3X=H>;{4MXTf(-1Qzq#qSm95x zv$&eb?minA8yifbL;n0Z!5>Bv`mJu5`I!4Y7COpT2_ z<2sG6rnC%A)bfTncIQLW4LP3{@8d#FE$TezCx9tr54>_W`_T3ok|5B&&lK&pmK0oC zXz8~z%})(OsyvD+NxTx|4@r4>ZGAta3K*c9M@J1weKb+l!`6i&IaECbOitQj7D)uV z1db?d!2qu~INfd_ep>0Tp;f@mNeu3hM`MRlyafiF-iY-Lhs`Kp39xpb=C`0^Zr)#b5&oo)Yc}YC(Rh^9u9rE zuqo4(_nhQZ?BI67ULq`%WF|nTqZap=?l@>@g~i|WBx{C=nR&8%GBe3Qv78gOM$!Um?371r9JH4Bw@}qf6Ft_r(UIMC8j@zKMRX%5xXb*mKZ@RL*4B@0f>(8)O!O5*=3Tj}zUIGE*}MjD><+oZEWsG5 z;WGhUg8xBL{I9mscgnJ`nz|Un%HGQ1e@66wOuimHGr1x3T&+Tl>{VsC`_DYhhXkk< zjB7s1B-Gyh{)*4cyrweiLh}#D&W7n@bZ6VfR|+Tc>12&E4L|+4eC2B0E0LV^WXP@| zTEf&#-eEw?E$4RdZN|k;mQZMVF}!s5^-;dmmCf#Po#cVwlY}ddP@MTD=R8_&_NHS?2jJhE%2MLd>YyO*VOhI!C9TGHkK%{>k>C%A`2f);^s`qw-C0AoGjt14(2jO& zSJeoq`N;|)D$=zv*#4n2(U?g=Zw6^7!>fchTgQX4IET9~|B6(1t-P6;8TkoeBTi@; z;ty6lc<>>EDPPPjoONUr$A$zRm&hueula2P#%sgwTWECMCYgv<$J!P%8&t zy`skT+IjXGzCTn3?n2B`AN#Hi1*uNmU3AT>JWglb2Ns#K9!xj~pZb1gNJ}fnb3j0A z%8S!m%B}GdmuGmfK<|;xW0jG~3$(vPMXx0PQB7W-c-!j{Lp?B58ef%Hj4pRY)x&$< zUKC+i+xAcw_N}bgKPQuKEG{j5Nz_{x_1dG^clk?xS7Kh z*}!)v-5oZCD(nPA`~ii%Qo7FCX}6E1G>+cD_zI^#$zt?sI^v0d930| zuXHx4`Ey}$VGdWI&F*cIPag90`7##Y*d!$M<0Q{{%s$VXtzOV~pb`dZ{8TR!Z5-V! z{~AxW8GFRX#B3>_-+G{>1yfFIgVrOS3Q7SD% z$>&B8wOePkjQU@#ipSE{Ta6CIe8eOEv}W7UXmww_G{mGW;S*=&eyUy&BWoA>gFeN} zl3h1>f5bvtnfKeR(@#fk5bKhWi*xD$o^d-FTac@y?*jWFhU?TqpMF*IPuo6X1t$6! zG-SJL#Xz2g?+U3oDFPRZSEkOid#tZ=xoEv)%`dN*{|){peblzaw1C^*Hhdr&eLe>Sc4Lz@>dnr&jrUMLHd` zq6C|ZN zH#bV=yHozDZ=pSlMN*W{IHj)oO{9PjL~85CuC=)j2)Y?L67i9Qqm31e^C&8ICB5Ge z%8A#JJc@U(ZKd5O{U(2JdMs~b19*@0ICC*3!Eva^Z5aZ!q|T;HZ|HqtpGdi@@JC|C zPCsu3uhtayl5ZD0w^$eY zu78@_;JUZy)pFSB;cXu021y!TL3%a z0tY-3!EkuM5gq zGw+9PC^G?&x@wua^x#tdmipD*HFi7=7?UjXI_(%T0%i;=R(_BB4#p}H&VRWfc)7u@ zppbiUl@};#)aviT)vRZ`xlsn>8E0;C=R^*zOQl#LU6cml3h9Y}{5A z<}aVTP#FR2jFd31TeFgfe2+KrunZZ9kA=2Wn=%^z9&0sp{@;_MoHWyI?I_()(Itw@uzjg^&wWijh9TsP;JkpWe0>q{+LF}23Y zLpkH`$^yw7LwVrox{`*^O;^3a!9xN%Ro?rT88q>?F((2`VqSt$4pC7UXh_}&zDg)` zt}N>5=m^QkFp`H|nu4<}>n?asRz0)Q3r%|jB8v5*ZUDGrYHZU7bwylmIgVNTxzCIe zAtA1L+w^gqSuaRoB3_SMTf$?%OU@dm?RWi$P9f#F)I~M?mq9goI)cTjy5aTfeJ6h|EUZq^A!PUF zHmskxYcww{pJuy_mL$bH~A>1YL4KMKlWp9c+*@n3+~7m{i&a^dBQT2R+i-3 z^DWM6Bb#Ii5-oppmlAsn0VRR=4U46};3Y-#&KiHXVb^i#SLO8iFlHPQo8~+$qCwlv z)m=>4i7%3b8emo-u$1zNEvZD};a0UIf$1EoSSht`hgh*A=~RYe+NLj9(*gqmklZ7+ zdc8@aqXd;T(Rzt&HZiKT-vyRGR*q>eFXpcJJgeGr-fT`0*d*Y)ThSS#=TW+i$Maml z{R3ODR~a2u7s;@*%X&7@Aet)}^>A86mOK94DYkjP_B~DGoK7nrpI!5KJJn^a7WdEk zI!JLmh1;U%cDViSJ5Ujsm#JvGcaG)I_5=+N3opnu@sZZ`{{7l}yu0KChG1>m880n~ z6h|jtF8z3c`X;v^_CZHS`LAMBx6TAE$rQd#7A=Tdzb_|KB!AzBhc?mJnvOi6z44YG z6Dx71KpG6Pe&3ec-#t}!f=|XdEUK(*%~kmm^gM9VfTiISfw8QR$fQSL#i2dA^L%}K z%EtpLIIjo_f*zUCJB~$U)CIwjb?43t(Ljnte%)kG;AX*~DQY%0wvB}c1~$j5M?v&; zBtCpY1~&2Y<&xhS*=&PwuP=W;T#feHTEt=$AFrhifDv^Ou6iJYJE2>LCxt$JoT>;= z^pVZ&n3?~JYa{)TY{<0w$HADkX|H=J$O3kWZ$YC=@5Z|)T>~YnaB14YK~TnKOq&l;U_*v2JnR&^D0G{gry#X7d5F3khe|N#vf6%O z;p6tmMVNHpc_NjMu-6@57Xt43dr^O{qr;8~xQXHGP@=NOT?woiyG|DC7Z$a-jikK@ z`x0h90R+Lk8$AuHm!IEKU9rP@vSMOt%`YVcD^M!fFRQdHUm_jv)+&j>hfhJkRDx>G zWf8thvT>748~l6cS4Z{f6JJl8P{pe*?{ND1Rp4rdZD9jgr3B1Yl%MAU0{FIGTf$s0iivf4)7kD zo8-Tm?%NmBa0KiJABj&PP!#m2;NJ2o{?|17&b_s^e!u}E$DpRp+E}Ah=BHoJk%&vI z_T+ixfwrhNhUwVvo`tucIxgQk^(1@06e(PS@DZ4SWkXmpMJ&Y9aieDR%kr=1;`v&C(2DT3n<@wz_WNXA zz)8#^$;E5kN*7$@v0rTRqrcANcK_2R+fyw0VY7J4R}Y>ayD2`b2AuR5X2%TmMPwpo z-;a4}|8uC*A!b?CKsn~)ndN{|Q%M2(p5FUZKJPwzjy8|+-LQCSW;cfxb47@&>j_P*3zXtG8tS{(L_Ip>>??oK3 z*f0lSpilhulgQ|>aJagzIWiGTIogqd>gpOooXP4V{3uqQGL_v8(Iz0^x z8g)J;F9#5Rv#zdg1f4{>k>!?aH+G-l#L-P!H;B9sdZq0tjL`AH;j$OZ9c&Bvrq3W^ zB#RUz+ImxvPC1I4zf6NA4r*_Z_C%n;#ml=F=m1_$R&H*hYzCj--Z_9d6|c=A)b&&; zuXQbj6Mq?YY^15lPm+XIwMbTqUeNU;Rp<*Uco<-G7Lt`U^L>f17zg+>G2G6d4mBM~ z@7EHWw6+!VsEhg`F1^wa?7Xzwjj^QW^SFh#Xm7Ydwf$LH^FPZs7Tqt_h6+~GYnX@d zN2f+yRsHMB`-Rt_drY-@L1Isi{i|o{G;%v=f|JNz)E~Su5)7_Xv8kAO-^32*D;s1q zyPcQ(yS*E|o^VNh4p$7lL=`N5tAVo4?eeX4|0bDzHy@?cC+QrSYQJCbqG4py?$nn3 zQXG%YOSzBEJjyWY^JBk}?c`c4;nQkWkugROA&5eIal`i)KHAUspIL?1$P=BTF&zn+Lt&E z{TbPyOBq(~;k_Y_7hG+auShu%kxas@3hrkwNL@U)e0g1SUyjQE)dDb*npC9Z3vfo)Xa5Cx0!T{BW#bx6Sp5j% z+um-Dc?oF^eZ)-*ikZA}h$Dk)3l{#bj_E`qg%t>sjxIn8q*3m>PzLZC_CArRhkJVi z6}9IeytdlV2k^qG)O$ir`NJN3JaB3g@C%U^T!Mmm7oModFw&W3zOpn^+kJL8m>A#; z3~KO^!Av7DZAMAE87ExZ!{Wv14oxDMbxf_jCyVgt_Ip}>h)4?1aujo2oiJ=5gpAQXR;RX$-nKxkPP2q zj+#1IvfbAvrmsHE%t$ZdRpV>MXUCXvs*ul)L@cI{kTu##V}m}D%JoqE2G zrNXxPJF8R1`l=riJA-2zl6>yZPO4D18@}{!r|Wh%{`)G95_@&{)XVQC0E~%;0v0R< z*N-9i3jMchtJ`48fkC}y81k|HQyhl2kh|f`nMPWTrGGt4ijXD~jetbD=@^o#aODzv zOH546+t?Dk5O0$zfcHRYi1i3xT=?tZm(XBC8;WiR*_(Q&F~viqm&1EvYmpW|DGos5 zEzUp(N5{NvrPP`dDT5l5LBW5Z2E`#vxp9MjVYaRI@OFKHkYEHx^j+}j)Rail!b>A9 zz5eJES1qWh5pqd1{>yWD8oFqoN0u8a7gq!%-{^k7jk7ZvUDFW4CBOp?>;Uu)xvEKI z2eA7qk`o>mE}%1>J0?D!C~cr>gCL6_52QR5@Du)i=k8IDXBZSlc_g*|&CrAT1y}tg z#?1uZzi&)gGY1klJv|*kHyn30=8%CxUXDx+vrciN^p%QD)X&YBA$+-~G$$Jb|DW9nBS>EIdbrsum#;W9$szIw4+poQR6BVK96Lw-ux(f#DwOIoj z-CWl`Z#kLWo)4{vyrio1$6SkidwHHa`=x}EOq6azl}%^jTN~eSrBcGkq$bXAi%1B+ zEX(qzxw~&8IaCkjAJ6vGiQ^a0?Rv0JII=DtsBRz(#)%WK2OX? zSV&T|0nzWpB1}GML@k(0Hf6GVzId@X@J>1n@X|lqwh>nS)cXjz$B@Je7gp-crk6fS zYLeho+qQgO5zt0V({2FrskRU^jG zc~lgU&K+4r-nAn3fW9pDvbR0Lbfw3_fQ9kB4{Nt)YM2OgsMvKoRCeq!Is>|;j zD^izbDXf@b@On9$$7i6mgy04HrI}%v8x_*4!HVC?h$^5f@v}mQ9BdT618b@2aOQt3 zI!*(jhRdB1RAME^`9SXSa!zF^Viqjdej6J#=_9|EuP`nyMa!BFHKx3tE*;5i06ssB zv<0c(?eY7khEp2T9kx+|hzJ$eIDEmZw4pDu&-3o+=aWGQ7m3RaURgf%NM+|wK)Dx_ z)3@2`hXi(2az}{JSk7s%Se!NaWg5lwIzL9lZP!&**@5>xQ@0on+bT?X#H1Xq5U7c7 zNj<)8w_b)`51$*Ai_WelvnsG{_yHLG7k+N4(y$;#G`qjw4+B=%%o!_LajPrWS28l0 zNu;`XIkW2$zz%uNg|9w>$jF|g{EQ^ZO`-_J+dg+M_(kTBqviXlk{BgNYXO~CMlR#t z<)`j%0;F^CR%>r>uP95UqU4(caqHJuoVo6nqLZGavKzwC!NEbm*LtL(X765PVZ?%> z!+oNCXaCzTZxEM>J4w{*-s@rOH`gYN!!qAlD__;A%PDkg-*@leBFsWXHr2)`UoLj zz9Lz(a%}&>gI9169H|~+QC21{|9_1`A6{R;2ZJeZ-L~t7-x3P_)=**ig_0E!NTd#l zL?$8ChyXF9vIakYF_NZ;?+GPPWCj3mhV!3Dm4VP0t8_se7YlIc_Jaq}%`P6lNsb(@ zQnEE8M;E0d>Jv!^Rp%Cd-2qb_oSD#9tYu~~T(C00c;pYB&7KtqYb`2SsWyl_M}iGf zkchh)q>iw>eDXPi#$gYV|AZLHxj7@aO_3Lg@L>7%vbh$K&{>jZb$pzl_yE)EB54J( z>OsnEx=pA~o|x$`{D9=VMZCu)|J9(i&BON!?$scPWR3M1nUKhZ<5<6lJ`RUoi&>jC zLgWY&+R?G*!TayiaZ^vil7FOlJfB&1+F}#_=*8zFKimS2cD~oI_|-DIpQ6@MHon2l ztu10vAwIluelYYOU$w?m7R`6@$v+ZQrloXcq%VGvd85?jY)^Z#&y5WOjl`zrfoqo6 z^Gj>wf~2pc@BVHTY9ukc^?W_!CQ8Q}nNbm1S%;OZM)@AdN+%jq+^bgNli{k z9z1Nvx<>^PW|9s2%fQ`cw05loCz?N_O(g2DMaLFhmBiqH;S0he4X6mk zPtE3CM!7Oe2*H>!%0&-(9QX9l)1yUZxr-6=p)pZkK~>-VH%iNI-=-pwuU|QyLqQMN z=KS)aJI2G7LC?r0C(_jWq0mm2J3SM*HlQD}%gRy&mI@0C^JeQF`d>5BP5(~9`2ou0 z@xQo^L~h5-fXmxb758pW5yf_idLm?@5lJQ_Db)LP#@Y4x+-FcB_Vg>eUl63lr&vT; zsqoK8CKrJLAQ!{u1p%DOFPO`T9LyMskIpliPV~ z@6ZN~Lm7$QR<>eZnGu_fx!XksXe5M0&u7{zp0%fr>niJ=nSkwS({)me3bMo&~dc-M$y8k}kX|jXN7;8kxr0a_QK1 z{R0P*8_M-OH)E{?Ue%9I0DWY&Zsm;Dr}#e!gnrz1~sd!x=#ie?ycUXQq*_w-EWR6yY?j>x-` zd;p7Z$-V!pbLO&Lo5jUA1LuKXEF}ty1|BQv8`EppD>Z(sE>|E}<5u>q5lhuVvFA*y zJgpb8xz{-2*}J!GwORD4eYojzv`b5ZhQbL$7>NXe7LS9p*mtW_V>7Dm zz`hJ1uDTAwL9CdnmzlAkOant1KyPK06Uj#*95m*BGm4z2n&E9goNe~koYCiWofrEY$xX4{oG3ijnj0um>bhj+`Nf?E*K!L(1NxZ}CT0PtU>CHKyt{l(AVCE%6o*Y6g1>39157 z321<*0}*vMS$v5No=Kp5_XRN&AiS5<_arI21u;adsGv<8(esXz5e8E@_v)c%P@8`F zVM*li4w51c<+G5YqL0U4*%ZbmW;#v;F~P;xoN2RtGj=uHSKB-vlE@frhEiL$WQ|9? zO)L|v=uQ){e%;JFlQznIy>QB#?{(MWd``x&Uv|XdD9_z9O&{13o`*k@Ih~q!=>V^4 z;qdC__S9j&fNGKSn2847^hM?4Cs<@s8w2aEvi+L&`u|&Z%}9l)ka!VQTg9mA1?OwW z*VNr`C@g(u+#Qs2qk>+NLTTNzz0qgI_Cv90jOx7lp}xccCD(VX+;T_1L~`vK@<}wh z5)+zpeEQd~dUyv&Pa(7o04(07MX3HP=oi_=Odr7%ou9@AAPvW%ykrF+VCa4j21fp6 z9GYYcXtdAbDAg17yRO)5r5Z_HKOo{US7byR9J_gLIqf3*jD=B3+3s4-&jYb4?YnKK z`$s~lCbypK75;EZ_Vi(=xtV6JGw%}3axDx+A966PgSuoR&<=REoSdA5q@~BsY>G`| zetK*>RBhSMpYz01S-F>S-8=A!1y~96LuBcS<-PvU<5^nO1yww$Wc9>C0*~*9x7-p{sJ%){B2Bq9nE*UDJI*-=!OeJjAFM?PM#cP8hCtRp7<*1M?s}HbgK+FdrP$ zc!ZMD#s`ir_?P@R#Nb3q2mm{tSK=cJz4v6#wl{5t-@ucG@^pmx9IFc8#!PX( z{44QDktzp#Cl>|X4WLCL+Alx{IHu2Msz$b??M-Z?gEAFUZ*v%+!zySvF-2R{#PIOwJn#iZY{`L(6a%*p4p*9^`@@;UURg)h%m z^lwRw7da9=wYh2Ed{VtW{-dxG5H1eJlc^dSmVME*H97}ekhKCv;RJr*cD|l~EnEV2 zAI9`Gzk70&D_DJ+`OWj-GZF~;@HonAcbqKk$6Q4sXK_ei8a0g8Ds7(%I9e0N{>gsF z+q4O%V|BuHdyY2ct9jdyAdlW&L4c7!kUTBz@;V7!@E|n#k?@+!jItMW+lra(X1<;) z>+B5wFW(IcO~R@Jc8B=`I#noZ?gb(CgAVjF4M(E{f1!TKZ>I8}cQ1DNrRlcH2H6x{ zOfK`WdZ+P6W4*QzvzD#TNiXg`nW{S4yoB+J>`a^Tg1wnvZ;Q3fRD9%3_f<2L-#(Mx zXP_{LF^k|hKuAbR8iIT_b;PEfwt9O0j@a3}%YcmV#Pq@84pi~Q+qVh&&8C;DA=tqU zPI9lnF*AOifjSZ67EE(w&O!_|eic!9B{VtBIh}*__*`#QEa2wvR%J*2!O^P=7Z2R` zAk3hX(_u_2T?A-D=y23u<4D#%CVymG(1nFRZD<}L0lRW?mb-TM9>Cs*9sLr-&LsZk z%wRx z1WH56gdSPjQ$yq9#$G2qcBx=gL1ISYFF7iEq@uz$ovXam^l9^12h$UFrSQ=v#8$?4 zZPS_D;ih3U?d7Jz9G^|ED6N|7yN+6VMe6tV_i-HQI;o5z&y&3KzUzm@kNUV>WH)1x z<{z^?{{J9Nq1@!Cw2L~6rBRapvVu1op6LG+WmT)7h_bm@#L;m|N~h)WaTd(%o9d6h zxh6x8x~a022i%cnGTVm`$L!4pc4Cj4$!3bqXrLtauC7dY-n8?m<2P&AiKtAqm3DP2 zG`*s3l9}`{;b_~*6N@eqf*a#m#KlhFPFFU^?*8*{(|&|W6v%~4X6BYP<_rJczJ@YT z+oo7Z6~S~qsHM1>Zzs>v2B9ER9aGj7bqbrv6&C;4`qbFbgwv^iF#&rz>fhP#%M}4x zKS45GU4PiU$!DfQ9}Ka-Bg}*ps8v*XZ-Zxxbi%3nrc{X#`V#RWr;M1rZ4khKH7VBY!XeT_<^u}YOI%qScs?qk=cVmU`8qB^%amn%gZAg zd8`v+r=toGr4kE{3R+STgtvhX@Ep7pGfq02eh(S4Gz8*pxnAF3$;adNRhxj8IHzGG zzO{0tg0Ms+dIu;09$yRz1OS9z7O$+mrzZ#aR&0Coj|l&XLIF}9@$KMA#yJ$Xt^PFP zmg`~Ct+KH{?P&Df_PT6@Z=dJ+1qtWHUcbCN#g&#pNuHF(+jJG3@hQ9&{o7B-mwL|J zbxd%nM${|;XA>O!{&;Y z`S+OZUGeE*efj#Zbl{~g&X13r+M@ce-8c$^CpM$bM^;#gkZq5@E>>oIxGNlIjgmO!Z5D%rr|PTAvkZJ#&*3`0`-bxAyp#L!E)bZHTE2h&;pNsUlHbRR zAwY5Hv$K~*$+>Gr;^e+ZnH)|6-1qiCd6PPBQ?oC9v-@{Ei zy}i7#snPVdy{X81zGZ8|nk=l=Pd$biu=tENz1-d14M$qTEDcSf=?Yrk?%ci|^1*}P z07L*sKo!V1K;7-Yv#oFW1+`&RxP*WJ5IiB-NSx#~lb;xO_KY4*cX-v|ll=Gd$a+Ki zDmpq)c*}(Kp>ro4YG(@V9N8+p_!Y5H}^`#p-r(LEREl250H7FF(6wjl0@ePM>vi+#Hx` zWR@CLX4pj2eqmWotER`gP#BYY^>4Onr2W~)lVC&(40LK5dBC$>)OY8UoHKg zoB4M;S4Xd9{Tyd7&B=ZB$Fw!4Y@%7(GQ~S0^vWas71Ft`9K4?u z&mi%3c-p>8JdzFO08f61Kfoy2BS4hcvLSC6iwv#iAci`UKx$$VtAEGIUgUD=)2CLu zHjC|Gjhscu)!TcH+9Whbb^fE{$LC%Trk)|gPXu@g;V!tiLS7GN(Qepre7V53@|K=M zx2pn%R1~1;chG}gA`byX#$y%WV6bEL!J`fKbTiNA&MTyYR-nc$_|MVhncS2x+B|HO z4h|xqv~?8wfgTZ$I@BIy=oYENgY)iL(C@iZY3hMIAOwkh0hAH8a{_Mj>>Tzk2OVpU z;KJQ!KG0j{kw*@+w)~OUDLJTM@PM&2tlh~5K9b06iF6c~F#BC!{D}B7$v}c}s((Lp zqKr#RzCXL2r=iEU*L4sf6>x*t%mgUkU3m%mM_g&dM+qzdm^cJeDo?+hQ{49aI@*{f z9t%RAjh1G4MMcZO^kA0U7!8j$PbNM$^Sn+9-SS;tV_x-Zp;BMh#&7Psxe~KZn(w26 zPMnIgO3|)V)He!bj6}IKG&{FT${Ody7_stOk#DK2>esd=DRXJ^uEV+#28yb=&6is| zDexeNjaanK(~=suAEml=-6QKOoAw}N4W@-K%oI(J>(8BI3yh@mh;?n1;b4%uX4L;` z54UJ4&sF|C?Yj+ZxDv}%g@o)aSe?C1bJOT7;y5T(bsY&4;X_AZC-Uqho9FrSZ)tL5dNnpftdx%CC%Z6X)Rk{~n7%|1~)0{m|M{OHS>2RZ( z%zLZj5pir}LbQs-Ex=4H+-hTYT!qh3m1!(#(h85P zyj6b-qqq8zBTjYf;@3Av)Qy&QyFOyEn7Vq)jODYui4a*umv;@dgrec$)6EyNrH}ypX|_F!b>$ zrdX{O-d7@`#_|nYw>AECT3MW)opb0~Yj)IDtK{=U(&;rtw4$fN6+eFb(^R<}P&6K0 zueIfOrcKw6-SamPopX20&Y-`Ipd7HQ`}SR;Lq3dl1a4O7l2#2VU4TB}*(KR87|(U1 z#Y*#S8n5m{zy{!Baf~=*HHTROfkk0=MJ|Me>Q%M*uWE)bX_{s)g7rHcu$hB{WKm$L!mmK$5P1iHNRf8{QvhxT z;%vZTK+^gUb%im4y3*Ecq#km5m|GA=0+Q*54jqEU@JD&;B3sjGtz}^ZtVkG)KPk4% zQ1ch-;$_4OMecO`(J)|rYfWcF;M?0fd vbsMQp52>l%HEG3kV)wyZc~NN>308%; z(V`0H1K|+D1uoJJd<2CPEPut!#Y@+JfD4{g1 z8e0GL=%f6`{8!B;8C|mrhTJ|PRa?ac7gxLg=qI#-!Y|7WI5l&HM_Z%t3vRN8_g-w$>!2^m%bLQj~ zuB_u`Y$`Kd`RFNUH_v^eth^lWRtb^T&IeeB|V zW96X-@3UR<@rC0-hI#NG4M+Hc4?Tci%Ef7GYR}cRGDSkS9JBVaSquG&i=J~>5tFDs zUi;ARkdO0cj`oTD56yLQKNCa6k zjg4!eT-u5A$glztL+6JYS?^CK#LD6Mx+S2qe7%}Iz1wliQJDg(B8TqLsiY%_WJns!zHPsKhmZq zRsJxwS?W}mRzy|5x}5xD#E-kpG4HhVmOyPWA2`y2#!Pw#|7_}>usB=P=3ASpwoZ*d z&Da0>q?<~h(To4bRBIWHNibdW*-t&t++h)O@Vlbh<=7KL%RZcD>Tu$C3|^5sBb8Vj z8KZxhZYLMevRH?2+3%O$2}8y!)m>2v5xo{TzKES{W85gx!26m`v2YyeOo(_mJ2zBa zD!-O0wMFlOEL->z)=JX)j{6rQSWIjzb%?%LIf~|6ber|^4V44wTdW4#QaeK$EQi)Q zjAYos`|;z8k*?m%Q<~elc9q;e!&XFU6X_J1qj#Un{brye_@PEDjy~}>k^BHzfclWc zyINQz=7@eo5zPNIt1#AO_0rZtjyHydey}*^8{% zE67d9|D654quSh#1-oppnL)^(-j#_A7adLHU4r+9WgqPpck>S7%Ps+K=W5OhS%WyE z+c)Ubz+*lN8Nug7B;6kjvD=d80f;SDWP+*!PywAz6(VkY9l>iRy9^o{8c6*Gv~TMf zizURxg(W0tAwYXqBawPHr^XSu6R32O0nkr-iJpk&9ajpggZO`9FLijv7fl^7dDFS? z=)v9Yh5N1|_lW45K#c;8zl`zS$43#`S{fo+$8SrV^Eg!T!_m^xl1T)E8No}D+XNRw zrog#f+}N{NkzoX2{ky8L{NM(m`SJ+;Y1K=+w>On$%`f`<1${GFnW-?~FxPt+{i==k zrPGfeYN`=gE!MSGI=rklI)mS0JwDtUad+16J7TQ-rO{1UI{gOe;-IM!Q%>Gz4!6k4$Edm@xkC8GUb?$X;F6ksr5Mr`1=u=WV@b zW8A`rgR_eL{Wa)|&Va*l#H2$)SnyO8c?=s77t~#AVVo4C+5{Vc@7fe4K4v^@Bx4^* zT+<0xpsj{RRtt%#pb_Cy{bAl2(x>+${OMCA63=W^c8>q7BjR9jt`HaEhJbuLQPS-> zef{BrdiYf;d-kZA=4@1fII%Xnb^Q(sryKTj1WL^+ZP**~MmXQkWB!Zs@^@U)z<2GZ z6UBWI8-Uc72$1%0*A%>N(S;8)2$E;D=@IX8&?B*k#_7l7NkRcPZ0WN+FwGpCm@z!t zrjfGs9LbFV?hmx-EypDU2fsulf!bmKLe+_0BrI$#LQ3C0dpG_I=p!k3+sMuiAO0fM zWW_8qP%}L2#P)!V_|T0H;^MnEt^WP~K|zjjGvU;Dr78+oE6?;eT^nV;;hJ~xOlRstp^lq5L4$?H-Sq_~67`mT_Dd9c zJ86D>9U9h^<=L#p>9MI}tbr9xboukSL*a@%exckWznR|DFfE&`DLhtcBqK;&yXL{1 z5%;Mq=SpsN3)3|#JTmsawP4ja%~ovHMWO=|4P*p-L;|b_la7f3NOWxJF-yBIHgGi8 z!cT{Z4r)5^etNf!V$-E0b*7!KZK6zzv)!)9hROeJ#dp`a-2o^dk;+taJ(aLuMM%E9QiWli3}#b$?Dar zx6gVI({r8*SG2EFZ&l$nNl*Nf&D)RFV7DRX@GawOe0DzNUmw{!BiBOU;;8WPJp@k# z1LR_Us3eFUyOk!o!q8-dg-KgSC#>OQ6Fyl)9m3{7ZO_I+FiB(M=(n0(ryqZO>Mn|z z_|(un>{OT6F%s-A=k8r-MhDIePr02V^~sv9$M|;3uTQ_Qx~Pw4Gn^SOCcH^g66xyR zsi1JRtmh&lCT^Ux|4UmeLdp@@(}5KcGabyGG;W7i4_hPxiP z#E7j6v&hehgU2=kUl~uB=Avl(7_b45)-8|Cvc4F8?)jEJN*C}*cvX5}&oWPD^Ko6x zC^N(UQE#)M9OsF3Pgpvb1+Q&+8S1q-^JINBt@Yo?ymg=Nx`-yOeGF$cG1q*2bc!9= z*hW^?ofEPBq$&u16Ef!v&s%uZ&>=`~w(_^v?3m9p;>E*fNTlANM{-TQE*D~Gz_W`n z7XSBZcsPOT#U$9$YVcSReIex5(20|F4jdQ=0nE=~vPCNvu{)rX&4i(qfNc9$ci!BW zq%ff43Gty0tgH<1mi5|H3pn~T*uZ8UU9T;g_4S-0^f}O?MS;j-nC9c+s=-e04#g`p zm~VZe`u3TgOq5q9I(~JQJK}~KHEa2uln<|7H4leh^FZJU8j=Xq{g;>?#o(89TD$w z+S10TTM^^7w@w3ViAUzy)JeOrOhx@&uk&=I|H*mvdQdF4I%2d|UG{yvVxYNvxX5pl zE7ha3w#2JA`LTHLjK-f>w*bda6a^^9@z(-FSaAvK*X3y|`x4d$IeY2Q=o3AzIqVNS zlguD|(TtI$^oh5dZ9P{|(xNi3WWaH`^g#8HiuFHFl0&QvPA-d4kcQiuEypal4uP z8rCu91gE@)mR&18GD*tI!D%fWohV|K!kPKC(YDYPLGq$9SLX6iGWJ~GTpVmIl-S5? zZW?si!2(kNX-t_6TG;bl)uHo5(PRlKElA5x@M3tdCRj8=mEzP~L*?a3DC9)_n*^`B zaU%j;tpm*a+q-nA3*ipy3)ff{#v^>{#aC2xlR9Ae?|(ojE+PS&M4(D$2C%`Q`_5&c z*BJ98B32uJ4*c{`fy?S&AqTu0Ts@E0JBy3l&Z(KmIDZ43wu30wLjL`2{eb^5zvWnNEkW5I{fZQ@;MEq z5X9iuVuFsA1*sV{>`WjO2y8JCxF>HY~PpygZ3^LI7 zOOd`?()on66H>Yqi_2;%@unjdSaA7ZMS(x! z^}}BvSS<4%OU>NeaC&2tpIe+zP7b`1HVkk|-~nLoXQ zWypR5&-KD?dqc45JQrxa(I&Z|^exwnaCXr4{{B!Vl+-l!^9{_y-5++pr>h$vR^2)pYk>c}rB*Z|K$oJp#p*_+Do2ONPU zsx$@82R!zMyAL%=(}1PMC@?@m=<({W{Hb2$wF{VDhsFV$1_)emE+V8hT-nj$6-xBneU3OhTyS_WYLe;Fgx)2FHVU;l7Ic%~Ka2KB4S5l}w$>n1b|cN5He&B3iZ>=E%m99AnvlsifH5HCc>mSQ9K_NBQWCSuZQavLLThHy z8zNV?ZyJTOZ`Ph7p!IWvroif`ErYD>!|8x4_10p%xvq!jdHe-~*Mz+{&v7-neo{oa zmPXJ-gP-?M*q+y-*3V~Ek1)`=U8300t!$-?zlYcPafW|s-bh>fUox7$sS&f^u=Bds z%+>XiYlp7TGWM+9w6tBNb({FHoG6!R{Y2e`qRZFn(|4;F^16m?l&M=^rQ1%eBlpRsyDCI&668g@U@B1MvPS~mf44KX-A z&=v8{i*2VVA9K$qhiS)#ms^e&ylfnJ759F^+bqggtiBzdZWys4myLs}i^RZ?A!$oN zHvn@il(o=_#BRLlD&paX=h7}{Nt{HqHEHs4bH9L>ge(joXP_Q?Q#*A$T{P?`Xbd#* zUBdnjkIFO@jZoia>h1iBY}H^;AH`?7wl{fEklv0c65$ zRt5Sl|I|z5AZwhLS3fRbA{vHXU2;?H(51Jp5zq_$63HS$XpcdyY3l8%&#;7ZX63aZjK4S)&}`3my8cN=n^tvJ7;s^I!10wfXW^;p2*hKi+Eyd?1Ah2(k$OfyiGKtBbo1||WLn1B@?jb&OANy5NMaQqg;P{@~KNp!i)CLcuZ4u#Zoy!XHw`{=4jYj*+ho; zoOaQ?On`HA>8AQ-f}dO!h^+~QE(k}``+^T|F%oU0;#P5PJwKZ zf3HVkX2e5V4+QBBybF+|6B-$hKK>o-86*Z`>Wy5R!2mBF7-A`0Sg1ut;r0~3mf7$r z0-nKwPd;PV4?*ZbadVDI9g^DSR{yQlG(XJ9j7f@7hTiY$? zOqfKfXMB@Yv&=|eLc+DK=vQn0PyY$qiGsq^G)`a44-OD;R{89iu06Q@$S6CzTC(uX z{Gjc~%HjxL9~0j1C#GylnI!09$6&1;D1q8+2*A(G;dxy{q0BzMo z!mX~kv;C! zAv9|kauTB-6eS=+H8`F!QxO;}I=U9wJbV_ZM%{)Xj$%=AY}18fGrU#jK5QQv_O-@3Ev9BCH2CgO#svv%^~Pr1py9_dnRE!VHj=r5(+BNL%}Ic`$U?>gP>2<rmLm|HlC8{}oDu&G7YxJUin|%K^(sHx?HTzAC zflH>^84a&qA={n_;|wW(ffNRWOwngaRXfARJ>%xOF?!A~KXm&iS=gst+9qn|Jb33vg8#h`n-u`+nuUW1;On3qBGH>r9Ep+05D&=!88$+{8B4~6G zASEVig|HY5y((e5l4?ufE^}evow1X z`KGZkLEZ!T5JgBW_)-;^8pH_cCCU2#x^mFA0~14!@VY3h@L08pMRWA+9YcZrb+gUA zy}=@FqxI2HyXiYRik@^FDB7idHo#>_tzc zH?6zAIqJ9ME+<{bl;7J1N-Z2IzpGuCbx+*Acu0rEajPvDg60)JJFomzqS*lCFF%ReJp|D#5YZ7$CpLT3JmlNzE3Aw7sqaz3 zem>*Z%Wu`@?LKXBTHn)W7Ib?{T)wn^AN(cyq;UK8?FY;TvIQ2s_GO&#I??WL-^<;r z-_GUx_lD9-4Cy>yQ&Ll-fj{E@GrMUS_cmTV;|ABq-T-z1 z59JQ3<$)0my6tw}i-(q~UJrZl@aOKAD#A&BWIJRM$UY+1I#M^mnUSHGq$MHk+xt)5 z$wN@&-MV#4V%Ss?$#x_T0STWZpqIF!;G976B^|h{JMe-LrMq&6b>T(Wd0;{#&=V$h z;6`|5JyjF|vm)M_?(2Rb%JmwZBk8baIZ=^ikYD6agz4TMFNiHcXK+K9`Lh4xo1C&tC9#h{S(KZ9)F8|WU@>%^ zW5Odfhvzda^1})XC)Wzu9SDO5mIU5w(7f&GG4=a^a8yDox2+#A#BGCUGay)SQ0n;j zl!aDFro4vZa3dENeQ zUcXNL(X zog&4P;I?qwh4xtHzlWt{B;5z=+#Aa$SJ@o6=MTJ+Wu-01dq%G*^sB_^v7BgfZ{TpG zU=sa#p+U)vgE?nEu%}d>Ec={K{o)+rRHBYKs`W)WG{vQc8OdBTg8vI*MIuG+>gp1% zNZ9Zo^WlJSE>&@tZ@e}Y=0N597!4rhfqZQvbd+vxZulklm&>0$Gnd_NKXBf7O-ac! z%RJFXhRWvEzM@frG=A|G7hdw-vj|Ra**0zKEXwWMw!wRwfwV~g@A3`$^CndGoEwF% zKE=Qay9|!GtKkY8kpv7MP&`I9p5}c_+?WG>ko1ygmadI#qhmuJ%fIO~G!X?02+a#& zM>sUM19hOrv(&q~vVf&O#3G**$`B|5qQf7()tLf0y5Ep@J%GUi8uK_ymJ%Fp&|5G- zxXvu3y!6DXO$tXe+>y6Ynki7#^l-0&oimJO_&s(Wr>~x-eL3tAMzi=rrce_ZbhV1k zWuM(wR{}{SSno=!4`0YI+;#m(Ga}uH5Y@TZ`ccVqq;uJzyj%WV>N+liJ$OK|D-zKi z2my(-`2VT=P@4HaY;tfEoG=$e{|2brAX;j>62XYsDt%T|uFSIuz z{8JBq17|RC@*ysV#Qy>#1dt0|HNhjXkx=d9`iTfUf)c~beg5xnFH)sI60C77x#RzR zlc~|0pQm9AqX-d%{p_tat4v%f-I=4QDxL8yW+Y)etno;{U%0`FiI?CFl{YsO({vq^ zcJ0b#vUC3HuDARpLi<5Fcb3HknG<~)F)w`4OhWz(*&}PF#_ZBAQCX<0?{!meStk?v zQGSbvz0JFajUT;F2FzZlYh$56irL}pah*|_DTAu8psHTo%!%pf^&CxHXW7o>34aPw za$U|&j~|mCDJwoz^nbMg7LJa=v$xk!&o*`|!ytocl1R?5-Gh7iswp{PfOwFS>stPRvu6i-Bw$PQITYBbx*REvt+~XtSqRWk|OA&k)@uO-RtMupi zY#T&QEcvuGf5AEG+Fe2-Jjo$qx8VRC)y-qfe-@Rnwnd1VsYg=!kJHuM%u%%t`o`3v zVfv~`PZ0$Xgg{VJv*F^_XLhKD1p<{BBkNeJKa&HxHi869f;EIHrp;y6x@b z<3k32APFcz@KnFFKBOF2HR*A}ElqTONSDSoshm?F9LIxUjKnlJ#;aY$2K{p76>kLP z^|TxnelCY)tt~R;fexZM;Hk;O@9XCc6cn&i^YgEW z0}tyf)^`l}Sx=sLCpJ{dd3br%W94;6(K}gf0uGAF_}Mn=bI+>AKCZQ9Yci0|7~1#5 zu*tH@ul|3uZGE;aM+S9nqhTj02*RAsO-8{NFpHA#u&RwhWz$u}6dCx#)(bBZC<@Jx_KfV-sC8^FW z{~n6m9nrn;IzGCsQ$L1h;P1;SMUVJ(v$zPS-yyW((H*IzCL*UJgbo&Dj%0TqpG+$;?&I!iy_CIPj;pR=laXUm-gB&O2ek6ti02XRdHL-Pokmc`r zd~7@XE44VHiXo|Q`ZA95@gq7)02Dy)$^YRxB+l3siCzX$C=`rlm6dh%Z`?Lxf|5|| zup%JgF&?Bl1#GNQ8rRywy6c=aOf!q~K28))rN}HLhcEfzzUXJn79NbUIHJD@z0+>iR1`m@R%}< z$Y7Gq=a5G!9iA~F?Xxvb&!icSO4Q8?a3-_;vRpe={I|c;YUU1-XB-;C z_o}>wsD-*IHF#-Ds=ig^`J>=sxx!NGcgGUQ`7pNq=L3W^Hh9x1;*!=>+uLiB)|GQaytr6Cdv%Rl80(3vUju}?eD|ho z+q;&Zx2l0>xnMK4USyC+9dt#`D!yh?35Y*41KV_eX@$kh`P57nZ&TgLYy7f*j^-cG zhQ&VH{6ES9C)eD0t;CnFPCxE&M{ncP^71`lXJ-QkHiw zylhq$JRh(+XyquR%(V62*j{{_L$|Dox-k13_ic7q>(554le=!J(g!QWIcPUPlv^J7}11newhVLLLDQg9u<7 z8+$3nVKSR=TVTJl8{Ps%A-M<2sD7x_-gr+i8ZgO3&_PW@BRF#nups2yME(P-70z)^ zCaOK^F3@k|@9jy9+>jn(ti=|H(A$LDjyovOxssMJ>}B?v?`gCls$Q1EI0a~f=+qP#vdf2rvDa>=>?{r#W6A74e9rqSM@8N>{C4 zbxu_|?qxA=N6qYM{($F>vYkZ|r3RAQU||jkyMFrX(BQA$3jUq6iP%OsrR^w)14s>H zwRt5d#P@g?O*da(woPF{?e89mcC(WD1Vx%vBWZm+(o4HmWPi^q2l;aa4!I=qhRwjdc zRF(C^f-8!>(;Ruv(;iRfqo+i_;};X#j4~x3Eq1C9+n#(boG;^P59TlZ_ z81S&+0V8%jC`FrwH?n+8!LkeoA5$Hqw|JtFOOKQfHqqi`ar}yjvH>WaEvNUeP-`IuhYLaru$HK;+u}*(l1go|aZcO7@|n zUY!<;Evy{yT;i8{Gc*l{37L}u0_aJ-42~5vU*m^G{<{sF8BFr`|BFM$MMwPna2C*> zaK^76!3kx>%hko2vdIX|L$5#;&+qS-a|u6)uaoIoY~L6&#H-L_5YM&9xi@~Y0^@9$ zz=={CJDocR67y1#0OkS81Q}1+Vv1bF3pKXZeSAwbp|(Elw|CQy1D7YJ);Dh+O=`f^ z0{A;QJNx9z<1)#}^&+vTl7;La*+s*(l5C$edpmyU)mG~IWXW?r`}jd)7S`?T*)|IDtlQ{>lw&2r9$9|6%F;VXrG4_Fs$)b>S(my0`f9pRUHRPB zJN}d9&H>q;Ld92({Ee7BQ}W2s3u%VLwG7q?L;jE4M>|qRT{ahTxc^P%75eVech0Ib z8}Z4zm`n~m)kY`450^O3c`ddLZ_g=I1)P4xeCK2Pr_!VRDQ8O!-h33LPEx%VdAeji zXH=r#=2u}oeJqPdz>_X3&!l{e;}mvpqIJe60xNb*bhJU^9KiYc*==s z7y+6{a)GyOvFS)5b9vm|Zt9tBf}JM#=a7PVBgf&~_Jc=pdXSC;l2nN25+S;gRd`kb z0VE^ogn5 z9_$&${j|ZYR841hi@{`1HZU}t!_;Vp)LfDz3OfZcHDFx7zX6Z_Zm>244CAxdh@+Rh z3$PIqdJGvlIKl;~2K&Y>?Hz4z-kjhcQ_P8Md3)TNC_mA5cl>yDN_t23( zg{(R)_5-7Z!`}_Ngnk{azNlKB_UNX-@1@&;()EsxG*6}4oOXxoAJJabs(Jb{MBm&h zt*9v8w<|&=?rewy%XmoY@EU-u^HwvXC|CDwM(6g3o|(Q_47 z%z66th0`U6Jq?0~!|xlL5BfTKfCvKC7%|D9*uFzAeU!~@yZ*=-Np2*YZYx<=l2LDM zt@;=U;ouLzU?;{L0C7PFf*D+N@ zF`-RYp9c#WOz;?`c4ubSO&*xrd1Ol(Ki(%uASAZ3_ZBu6!@4tePl58fPnFCdL>j=>c>>m)jO3@O_SD?0w)Pbw+~+XDU$l&y&PXs zf+ExIVK1rohQc3!5d$f0xzt;L_ksuz;C&%gG>9U>B1SrL;TE&Bv_#yVGCnhaqR`05 z4fuv);o&1<1c!6f0!8)M+i|Gz?ccA{Ld3ejinsxWGI4PC{o)-tn`UT+cahu<$4Txk#7$J5>c(4KLTY&Ql%2xGe}L#ivZX*oB6ws7 zo6*lYUD5~y3l!n*0|##WOZ%RNRcIar%*&3tsZFbyLra3qbpCyZg!sY-Mf?wMY_;c& z=l@cyy5dkisOI2T{>NsNxA1{zMf3iKvnl^>Y5iGy`&eX3QhrK#)!LmG=XIl2GfEsF z4I&|8z9rA7=A@Ub1f(dI`6 zBp`R6(FcX$im>klPzIW^Hm$ejQ>V1X30FOl9jC?`=C%f|t#qz^LAfp>27n|JvYQ>h zavBPG6S4ZC1rlGqCkni(MT-LgU;^DIanGdiZl+v6&5+m&F~tlUp858_Gd|4lN!lX{ zul8f9p-Q)(JIt$Lp?(nCr=7PJ0DX;ihDHxF(N{`T;sT>dAI!S0$^L8k zU!E~9TE_VgJR=e9s+)yEZ8&TaG@Yo+^FDm2|6tlIQ{`2~#a6w~9?u{CSW;S#n7h4C z7RCBdnGFHjN8M@?(f}eFwLxBA%)HQfX7u{Gi3H|9LEYFAsQNK)2a~j6&?Q7V{&>a* zy)6^3FRnaXeRu93X^&O;L!9vI+W|nbY0p2^0@`akw(eeh)v6vI#WW$8m`_Ah_m7W{ zE8`r*Q#RgkTvXxF%_G)2M%z~Vw-=WTUtHZ%irO?9?;U;^9yhv;?2nf9-;oME?q~RX z0zixtM>Yu-0&z-QozPqmlkGb+Eg!u5*BE1RX;afyd}~DFS#ldreiP^6Jyncept{jQ z_T-)`rfuL3#DYL{!3aDcI-l5SSLs~Xez2rX{IT_L3EwWuZuKL?y)V?;0M%8Pn}^xi zvqC~t1fr7XziuV*=aNkfF`vQoK|0FiHhmIluQBf;Kof};&EFe1h%#Rir2-$4K+qg1 zhq!c!2Y80SL=lb{Y#6DKjb0 zaZY6YWxXcaZEd}lA$}UU%LyUnyfc2cH{FR{&QrTCJwo4kv3_beX!pam-b}5DUHXwLx|$pyuJDGCLM(JMzz-E%eC3ThjQyk%j|43vMQ>Zc zef8@k_X!GhfK))Hwkc-TTaOPVhcvw5=vxX33@jVTEDk=KdzmhQo`E5ymd@tfG2UEI z-6YG|*#jvafR5)OgCq~HR7-j8l<~!jO_@mE?3-gunn)4DBaUE{2J3BRF^q^hefCUwi}BptTm`&cC|R7f;ps`^!m)?($`n#e=0D%J zY~JCgviysWg$aOty7$u>wk)jY2SX?n8#`~dm zsyc1JZ>_lU&eq|ZNlv}}!G=qXiN*WuR^B$7s6bl{Dfim0jEoFS!e}>r=}mPOt|e05 z1@ROr5vu-ur#lCZ1V^~lZ=zF>hnyny57v&aCgwq$;z~9d*H^RT8kA=90WFl%(7E83 z>;Stn7qdFFtU@)sFSCM|R&eobB-^sSnE8)NcwuvV6d*}|@Ag;x% z5@^@6q9w1HqRjVn^!2#i&yk?z%Y5rn*ftvF+j*VU7BDW|< z)uQPU)*hQH( z;^Id$BW!<^mU_R)!w&njl4tFZCQjkpWSY8jB9IIVNv6PNjK-xvl%GAA(P=0qdQ>c? zXCT!lp@b6^+@%m8fxQOPLh8*iw8MYc;n>TFWgN}Mm?M$2UJ66&>U@P#kD$_mzr{uL z7~jJmcy%a2?k*ERlON{cGfb!UvJvgpe^swW8OHvY_foms(H&U|1+x${uIjuqCp_oM=q{KbA=uo@Y4B1aoyV8h)z%3@Nm3ghd%;F36woC$pJ9MPsb(!v{kOE z66;e*l3Kv`_I4d9m+}h1NeK-#H6E1Az}rHk`=A~X5K59A-~=HVCtM8b7WEY#s}e;Z ztI)Qg9&Q|*aJ_vKMlZ-zz%yOil7}iz;-$sT#EdD3NyyK$s`I60232rk6|ZUJn=ez6 zTonF(P4-z)mk`=xt@iRyDru(m)wwb`#+z09=Zmskqt~0O^{1ZC973pI#5>2Q{7nLh zB!v%u-0fZ2rh?4wId1$@mDIgp7p2^T)uz74iDa$Zx%@4F_n#JrFP*G4hkkji#!Z-; z&Ft0pRUKmKij@|mJfpot{Y*TZVxFRCdhbC{a4`6&Z29K5_n;(uu5cT9lj*a{)MhG*54-^t4?f%_WyYvpXR9!B_e!KR*T7MpSHXDVi|vS*n`Sfx5%E`;T_Vg!b3qM-3D6PLT~4UQC&& znm_)%{k4=#W7G>3kJDZG?TRV3te-73Lt8{ukT(jgQuUVPl&pD*Vgd9DvkoeJ`s@Jq)%u7 zWnGBBIOx8%)M>u5=)Y18CIjXVlB5cP4U37qZk+6WKv@QQ6f?=={W;M@Y*HMXvg7sM zHb1L3ynM0SH;9anepBYRbV`1-Jw82L^s3&pJiTYOiCFrUI_G2ACSOK#%f`*U_&ekt zZXFOY)&86Np{>eo@;t;d5FCIiBSa6d-%~?Qq629iLQ7E|AqHXi7P5G$N-#*_pipT0 zfx{2@<_>7Sz}B_3wV^A~QKGG4-Vh_@aOaFoLW{KM08E-G>f6cD{fnltjp{u&k5%kL2<(>QtybdT*WOR@b{*0t zflJWZI3#5C(*WAI#=UDMhh~e`vurp~D6!64_pfJR(^mq(SV; z=ZN;Uwl2tFppJQ#L=D7(L~(>u+KN3AUIcz{UC7zY@9*cQ40;0@eZ!Y>(&ZzlrCN)Z zXVNs+{d`D~7E^XG6;bzoqizhSuA^W0^X)4exd3R_%Dxrzm&XYVzc(mEhoD zt+e2IcR;5zH1Y3QoisK3+-f8HM;=F8-APX`*nK^#Y<1v>K^WJUwSlE?snnM&g(fB~ z`*+LHrigH`ATjPfhXdq1Z|Xo3k)`vK>67Uo%|gC3rva_$T@%-W#}%QH*d&Y})G#du z5E{n{j-nI7k8zPthn_|rK=Rfgb-t$ks%`^=+E*Ft#5Y;$;Z zf5hQuDMiQMg!OVQZ!P4E+ z!&`O{Av(ys@y4`Bn^gmXv=tT@MqKM~o}^m+4!s?k zqJ)K;SW%F!h{O5*OkRF|L(R>}>r*2DqS#P?kocf<5}rHaWZ+h0NUqmpmJ@J*hLaQ- zLjwW{iO#I)y3lR|>X@-YG7Qrq-|7X-k2pT~-@7y{34{1%r`(u6eYSPF} zjGDx=4W{4c%HNc|Nb$gn@bcx$XY!BRE%?m&Jk*@|MddL2-(gaf_4Ml;uk&AhxG2Q? z&bIOGKBxG~)vd!`NsFqz5#bk-^5J00op9S_KWoxjeDS?|*BFCw=f}IEFg^s}oF$4? zfE9?cPU2}T@%i+{U0Zcww+X~pMNEn1HvPob_--t_|Gy&l($Nx1_H!m$N z;=kE-=lBI<#!x6YrQ=SW?YS8S&QBCJ#psh4HAn z2QbJ|n@!2p*vM=f7vP^9kDz9bWp7VsQI>yQ=|=r7;+ksWWhutW<*>z;cYapl`^vPO z?)>$n+k-kr011z71n2njjZIY0U%exuKNfx3%<+5tk4taQL9O4_-@iV&ej^;CrO_+P z%P;3->25x*Dmu2JV!u5?_nQ$J!&_~R(c*PvC#E@VuFm_-axgl94aLT1g+=B?6P{;MEvl5PT6%5l(Upc@q zIOTzRKB3N#U%zf$SLxcKD5a!!mmJBc1I)w=%QI+(i@&@(uf8=~TV27^PPVUX+dt=w zU8hgBjg0y{`pF6nJw_2Aq0wB&P9ypcPZ@j(=CF^Dam(1)I17Dn`7&sIB`!ZmOCkCo z2tN_O%m`aK)uVOp%az zaBFZ}O_%BKyY~cZ!$Jal2fZT|iF!)+f9rYN`()~=E#M6yF_FAr73nRU>rlax0>B4J z8`;QP0pAY}uvgDxkrl6EAdH=u8XBhdAZ&w7Ja7SMQ#V_Rv-9%tvCQmFm6frHwE0Gw z;_r@isKFS3n}oB^)A&H@)JNdAFon`Zx-Er1GvuXWEq_y(N?W4(^$FG^1f}b3nm_;< z>7hafI+=I}WBX6nHU#^5?wyUU)MWKCEwJI|r_Ofl)iqS=)=7_z5Z6{y&+=0(h-{`$ zVURfKl%}XPyjOmxGPR*=Noi}#*B6%NBYVXCf~0wyTY_9WJgxfochb7Mx7_6oA2aY` zUp5|}iEtn9@Gj8E9@<&|G-X=eBr?M4%z_T*E59~NzMm}~dlG8i zr#uM^&kUnF@@-Ot=+$mRRK>P+YyC@cOgCshFt9)11R>sMe^$X0r%!7zXI^eRNQhh9 zy@+K3Eu;QlGzuo76A+3*n8L3_(RaeFfvO>88ygX15kOc1aFM(XKzGnBNe_q=8f#Uk zXK@vyg2VOqgc~9_$TdJNc}^@Y==I5EJW&sZmhJIuT{bq z4<)-hkG?)Qpawh%SjJv_PAHa+|Dka&3>&+FE6J)h_Q>VSFT}0~YYV7oYcpWq7!r`W zMvI9I8LPcv8eC!1?t-O za1GsXOISuQ2}e1B(Lp`IgHZbG=~H}xWg+g&Ukkxl@dNZ%SSSuz z_+EgRy*SAO**5vezzgXRNXeIk)P{_U#ld)C&8oZ$<{EkMej>bxd|QwZNm5fnH+Z(X z6toQ{Y+Xr+N_1r}a!$=0FK!c=W3JtPG2&Wi^XTg~p%p+5Jj)ZB|@AGUwLw zImbs`<2}o_lUa#5$z73Q<$~7;m~n#SP-$~|BH7qyZ9ZhJ1Po5m%s;kNPc|lOWq%4n zQk=bKW<3RpOJqS~D~Em#pg;MVkRI!c-wokgAPEWmMpqsV+;_d{Mo-)KzYtLJhb^|) zW35QVdi#W@>2_5@u9+%C}y7H1YYdXLNev zvBi>|-X(oBVQ0E|`Y-7|a(ri^C@5dGrj?P+H7fso|J4}EKm4(ecQ_VgYn3?PKS~u- z1K0F%WWVtk81z>anf)ew3)^qp_1n2yRhcp?yP(stXCzUB z&6WC9#Gw*(Ek6cBE8i8EU7*=z+9m5_74M`z6f_kTZhW8unrcLhj&@O{8@*=vPn!r{-9o2kM<8z?jmcys!bE{A%m=4efU5YF*uTm4+3Or+Iy)5Up%8Ery=pL3hx?157D}%(a3<$ z%qK6;iJAXPa)=^Ysyj0eDP=sdbIp2Ev+=a>u0T7eiML?U+p^^-ABViWJTa{S@V$gY zJP3ozfV^-Xrqxs}BX(k}j^AYj&AD(?0Ktb|Ly)}zv>9f{7fxzb?|(pJc(>DSJ7gEs zhCUh}@pS>yf-ZTY*|Kky*&6!C%2qD1#^v(&2&L%c)F&awmXk9O6u$gi+bwKy zagy78AR{LgBk*aHxITdhe=|-DnEz*pAK6LQ1aE8G0uY*%2BQ z^#B2tJ-DZn7t&~HX>ZPtlNJlj_?ayjL@-<65hd*oprP|T*5JSGqCxHfEjlGNAm~pw z+Na~C(Ps+99$6ECo!Poi#bDkk2ev0je{#Qy~&K;N!b`5K-y0#)OFr~R-= zJN@~`yJND_d0@)V)!{UQ2!nt*VBLDrT2X=chMs4+cn`?T4(_5(e(GDwM3q?BodL8| zAIQ3!nZhKj2EYhlFTN`jHfexf#=@&(+lW-0d-tee8`6>0&^Qp)SVSZzh*Ad3hKq?L zj+2rBd~w8;hAm4{_9lLjXiP_M>UM$;kvs)_Ye;aoZ}j>LE^xBdz?GxKw);5K)9WZ3 zrj428u&vcRR?)q1pxQ-s(MMBvs_xk1-s-7ZZ=W+VA`SZ;xvJ)#HeZibaAUM?(xw2#%L{8O7Al%3=T}B+ivNNlc3KoM1 zO$)yO3iZ1{&Af@P;g#kA+yAa}?SoM-bb{+t**vf1{NTdG#BS*idC-1WmMtpS-(N66OOklicZu80c?yWEdf7w*@kL4oeDd|`~2JZ zAHT)Y8>8d5jxClCuvs?KATpy@q3QXfQ&t-!)-v{QqbHG(0L2??W{M93%OW5GIQLYi z7cMR?B$5W2SVZxeB2|#UFX}u?3jh9Ly>cY-z=elBi`UNskNW` z&l4~c(+~+&0?@&%poA3#_9bONIqzuvob7f;R(`xrLaaar9CF3hX9r(8Tp?t=$D)nV zQ3Zc426nQ0VM!#D6{uOeTenKFxR5f_dS5p)npYVaOc-?&G&?_sVj9E6hldPdl6_fP zUv8A;=jD}@meP<_nOLxhn9VrvgtP}NBt*A^sY9VaR!r5sHm3pru;ol^_ z_h=ae^O`!jS>|vy6zFzojEqGJ9ZsIj*IH!fbe@hSrEum>@Vo%?7Wyl z^MejOZVb@K6BY@W_v3y*5ofYYsR-s6C%Ya~4S*g}@CGjurf!1n;Kmwy(wZBj=|M{2 za0FW=xZFtcVCFPLknV|vzaQuS-di6&ru`6~mUMeS)kYRx3>HkoH!GFGql!Tl)35tO z(s1_gXT*W+`(M~%hx5pOw7($=5T1V0HVg9`a3d*3hpYX&nasvc5ZvMj3L!$rWn z;Z!F);n0xvGWfQ5qg}*Q1;7U5&=pO6I0j7|yVnz_O1xFo+7|w@%XRUL6!LA71O4sP zb3@_(N&R6L`~uE#^M9IClEqE}!LNM4O=<>_H&zvOT!KXtLAE3(qay^21f+Q#2yH0< zAPYitF~*A)2l|?afYFDzO+Q%Kyte#ivz5sc-!VOpg>jfBnl9P)QpX|gq zRX1+hWIsOJ#~AwWzvuWscJ1<)h+`JPW)i4Rg z1u4YEu55BP?+#W_X)FD z*i~ylRHW|{z$t%1RZYzo@E~9`u(ieQIf8`6tx*tW({j zL711YrA0uXQrf|Q-+c=oHOEY;&WXEEGKij6EBj5Aav*H`f%8)1O#^cD=~EoDHVJVv z35DhF_C0@}WqGzxOEO_}?d;gicTDw*s2A+L>>z7m%U`>tPwKVO#F&4ahJMJ#Wx-C# zga$R}T3H+*t2xz=lN^O=_m3V~5b%G(>P9o_I6o&6trvEqWQ*2)P%6h7ec)Uo36dZe zpi_rP5M(_VJ;}$uuyq3u1CWD#xu)vCZ|=4IT56W#o$SS{sxx8P4;|MF?K>6aH^-7A z?{}d04`r1j6nMepBx&&*C;jt0JV%}&RuSVG{$Bu!4t8eQzy5%iQUj`XN8au)pR5`p z&v0y$Y9Melv=@{yuTIHe*g?6>F@BtfooUmi zqi8mU4{lf>8}^PEQ8?q^)+Oe%AqnVk^N@poL8VM__bttW6$mQBo<1e5>O&nK+-cva zCivfO{aD|Gahc?)r7EqYsc?f`K+ZiG0>Q*Iu*s;}@>%tuz7Z_wC5*%vA8vI8StxA& zHAHOD$OXp<ovqhV;d!i5tPKc zf-3J;$(n@~jA58NYPai&v@!|c#BPQG2kHX*C&y7pjj|S}HkjK;I_oaEJKrl$L3JA4 zT#PFnuZW~&Z|Qd;#77!D?94h3`8N;qiO78XtGz8?e%ou>EdJ+8eqYBIw~Bt8SCrnz zr^c(GnX)}+Ie1KPiSxsOLv`sQcP<-DHmkaIJM2HXD{09!hWR)S{d~X*^r8ix+f5w3 z;x!S5%dF??wAv@A^mMun|6F-36K6Thl9zB^!&8#Py-#i!$9Fj{x#2Njd$K>~exA40 zx#~UotiP|12<2@HXSRV@!TXALSiUNTL}C&}E-qaJ?A~`$h8D>mNZrmGa}G>Del{wX&0=|0hz-w${6r!f6&jN4&VCWfBwY1xzZ^Ap(~sZ$wobb6Cf zZ&W@!3zNN89svV7$Er;I^=3*lP9ILq&zN`XEky*$c9SiG;5AR#b$yc$F(|A$o9Gcql2Plfq-A z*<*c&YlN(tJVV%t9#qsBc*al+K!d`XLedL-(jMU282_^U;xq8u|9Q-T_xRvC$w47G z6mulg6C@X2i3E>T8Ss~+mSi_hb!@~8?{2goyEWHY=&~K4fv@e9NdP2)cyURVaeq)* zD4d?kh_oU`2GD@1zT0^|1keNjCqakOvtRe^P_no9I!I&!$Q%Ti*^nE!F-5*Lu2Xczl%*~U1Q{>IgE_|E2 zDXbE)EA?e2Z{{WO8}{6G+Ur#oYvky%>ar)jXn!xbk8jAeW@>TaeflYb#@#J@O5~L2 zLiNaPUS*u|Bia_<)|o!8N{QR7>6X4-j{bL6emJCGX~NLH!+u8(6a?KGAB=T>J;|t5 z@w=$9yx28jv5N(hBy`hp=RqBVzrz(s1Q|H#@Fk|?Hz3S**S`AgxVi*~kJU~~zH^Io zj2GLwyN7|FNA|CwRdlF*UpuRUXV7Fs&q1i{$grU2KFJE^O!oQ%L8QtcvHrXFXQy9X zIlQm(|GyTXrgM42i}kSc^|aQ6j|Rc7qy{geZD9a5DMgTY;IDV3$n!tyqjmn&;8iO$}Bl|32b{)B$WMtON#b zPx@7O6{{xQ?-cq?Gl%`z({Q)Nr7v@@_|yHR?@BxP)>1h0=5t(k@$UM}o>!w(A?KGp z645z5FsOP=)O^tA@k#wD;c%X1`C~IGhTD}im{mNs+O4eo{adVl=n*h#?%yiiRZUF} z=dPHj^2;)Oh7=T@cBW>wP4^pJpW_-f7#W4{F!%MX56*yiC|)GijLWtEt#4q%MCjGQ=+2vBgnAxEtC4{TYvf1Tc-$J_2Yqa z8hl0~;50hpKy_;p6M~0_4_;8o;EZ*;r$YZ7W6p_9a`s<^Gk5jxfxy>RL7AK zrl#unfX@XQ%zYKXyHo~fG-#J-ymRr>CMd2?<$D_UAmaX30K%#8m-BXiKl&ca3|S)q zVAAaFo~k)TYf_C!}WIYsQByB{@5~^HKAunRl&)FWFpFeU`m(x5XGuMB&r3 zW+SExGo?H3>X*wY>BehvJE=VBoZn8hX|!PcR=Ij9Rq$ePUWrRexst$g0|=FJIP@yihf)#8ix_c-wh}U%@nw3hh`SF zoHyvzW=wSML@wEwSD`>uHOr12n#}n~u}7E^?5FGSRQzA(CC+R82Xq+LAiIWRXcODc zpmME_;?bQwOEq;8=OcAmKV>k# zK(H|)fiOp4z}{M(h$_48&+F4^LGEZ>&^`5{U`N1c&Be;QhVEG#;!HoWM8H-B-6`4arA?qcp6ts?%v+XZz-By}2oYQ?tD zl^-tW-@#z^c+a|XN4A7-e&%-MqohQ1y-mZnxd+lw5~t^OS;)B+DLUPb*9f`X;WW0` zF(*>&@>iygOLpDdKj#%|bur%Hq=yF=0FIA!H3l2}T?mAPC9}S@RVbeBE_DEOT9{af zh#iXx;`h4<+z+rwB-X4BAu)u$OG_njHHa~qp{qE0%^Wfu;@5utnxK>fzQ@aN_WMU# z(lU^HtPH9xX#l;zO+Q1KG6ZWqE0QraK)c}xxB0hL1yj9R?5m;m zkPRxnChT^^q4=jQbCMooMuPOso<^eyrH3$vuBCmggAN&^`%=q>@9T8FuUomIb-2LL z_mB`*ijTc|%@NI4-W<`wDnagiy_-BK)gQXQZFOk%FtMufobi`Ox2uEXH zo)~}Eqk_zr?&3R#xH|4~Ra}@o%5NFV@yPIJFME*0Rk0mDVagp!ZNIdSk1rT77?$&` z9mu4L<_M`kGCM@6n%H#d?A~Gx0s}(yU}8q_n0^_csoA>ABl7XZtLN93SqB{%iQc3g zT9NU5-S>aH>aH z{uV348lo_}11j-@5GYWReS7gxtyh*n=_OPu0E*lLX{hQ+BM@*S5=)G50O0yy!YVMJ zxH52?KC(iTZrA7g^q;4m1}nerFh93_ZSnW(z5Dim!S!5FRkvCi*oK4GxL zqeFx@w#J*TVcJF%!U;Gta1~zS*I&X-*Yo3HMXy(@O?eof#(3PAtH#-j(Bpt-+rQ-v zOYtZWdn~jh-ub32WEW%*gNMWaZZ)bRu**U#su*(@Ap?;5EbS0vh%;f9Ra%I^2LPCi zM%LAmmV#JpfB<#F)`D!i);a=0UO(KI$qTBGR08~M`vAOQM$3mj@DTrS^zw!3l5nas z`;+z7$J;BWPHs6hq5d?}ZgplijlRHs_T(?G-!7)TQfZ207*89}uzWTpYr&QNZ&t*h z&ut!=^1R>dS8GCk-f|Dk7IleeRA>u0`_?G$8>Or9Zbolav*GoZeLI*LRTj5!3*LSB z%)Tw{-iSV@Wc~2pgaMvZ8tO*qa>@1zMp7$6;8H`17DBwuOPEi2EZlVp?&~xh%akup znPaI`_vfp*EWyb{3l$ses{#daLF&mZyHi?54#()kZs{92zgp*@x!_baV)A^f>Y8fN z>F0Ot+|<>KD^ALARR%M<%44x25tC@G#jyGEhxtl99=_19FfV|6n7~QN56NYKyw7w2 z@ZQyJX1*@#X%R+^rd^cJlC>J7&u^Mn)bL`{-UQQ53OsJS=Mxs*L~?o%5cjvEaGx^7 zIR*cz0yMR?e~jM3KPNjW-hv=1eGpE-&D{p#I#_T|V0l9`y`# z4>rC36$Bq3?0shpq9~pzDf~p?DG;IMlPH2{3uJTvg(qbplmxO%s4gJeFo1s)a}Ao6E1)td?|Ve09`P;{Rr2`kTXkhsr;Cs@&5KfW zfHFsoj3Vuo(;sZks#hC&-oF|XUQNnzqg*^Yq<8T|)jis`uYc!?#PoNj#VT=}KXq9?Kl~y0 zwXpQ&`4MlU;^pD&bGK%04tZ#wd7`v^@$>eg@wJcitdd7q*In=B^b}*W=+#rKtsd!` zt8C8eKGr;c(%^9_*Nk_RfzvvB%lOXY4pk+xQic|kj^2rlc3SI$sppQk$($9MIo-k5 z<;!zg_ob3yyr+Y>A#_Mkx2-GDUFqrVuG8rc66F{bZlHFbcSvpYhk$@8BcdK$H#8W$ z3~HHoC1>;7Z*1@7QxU)~n{%wM_p}gin{-6;i%8yQi#qPBuMSSm)HUy$GaRJQG-<{2 zq^!Fp#5XBd@~eC93Kie7)S?JSCeW^8RFSUzDw!dsm$p0>pu6e@1`*Py2;57qL6op5 zYPbnyID;O9Z{f@0i@~G*?<+UDlQJQU?mz_`6}VJ~XQXc}N(RCaX>&NHt^gnif#K9Q zyl__FBGym%Iga2@04?RZ<==WaOUa#Irp|+4#5LVR(-9dNx#;uHgrod_(Q<_Xd5TvW z_<@Tv601++uunxVX^SIDMa)G@Z5%M{0Sf7brQ)+eZ04?_S)pLz8Br{PV})~E@ziz@ zwK25+BGP9fMtFOznPiF9ShWDj>#YbObR`(i%?FPaX!+s8lOnUF5`(%mI=G;D_HF=wOrrnI%3 z!FNB6E7jkKxENliNj3>xHxOXauhHGLuSNX`wuX1;2k4BNEngMZ6*CouIr6W~t1 z8kZLQ&uiTSui~?RTkt-9t{BRs$~9~ljJV`yiW3?O?9`iyJQ@_2c7h^_oG^>fGdVpu z)t$emSnv4d*S9S*_MPZ-adsw$?3SWmP*Ts#fQ{yYV=SxH2E7xXUE(+eZ_CE{Rq4t; zDxORD`FND&K;})4lEAAgH+y;whELja2)D<^Z|!sqtB?>Er$!DYY5r@=n_#^!^$W)+ zv36lu2M2fw^nqFFV~a8fNKNOPGP`ce-oFurr@yO!dpN2H zi6n%Ktngc+Y~~;eA9ds9{c+l%@r$I!LX&kK9183GHiy}hG6SeWXLpGo;hlC3~^ zk{|%+nw5<7=l;mu@f82H%V}hP;*z7%oD7Ij3!3@z=3=Jyrq@Z#K=z1c>K1&gFh2E= zLJ{0k$ZzvPRSjv)!J$1(6(Qs`fCuTz3oSguZ8zRmzP>f{`xFi)-PSsi-Pn?KBsTo^ z2V)W{gaH(y8XRJXGLjdVW{7hSM9>B9eUe|_vF9n!Dk!SLqM`&n&Esy|=IgHfW!qaL z)j`Z}p+z@#xlcwUJp1_Z*PunhF|G~k*7PfPj6nibfGkEF zvdESfjkzdOuE3_5ZQH4c%!M9IEBF;Yk#!Iz#DakV-(-p1u1WhNR7I(axJFCIvSl<$i&bC%nU~+yLn*f>67?cL6emoy!M#q z&x~VMP46ds-Pk7g9^Djn#I?tpdA!Efm8Nrb_C3p%oe!f-oayi*6ce@PU7;)|gIvqo zYuhoS`d(aHYzBV7Ht}g>WP~Wa5Mr^h?x-mn8{8ozi~yrT8vDN6s4FG}AWrg)r-)w_ z5azsN=E!YXyda4$UX)j``nmVULvMZ(&o`&eOXp?j$o&_CEh$``#oWQQx(DBzj13*^ z#NCfceld0v&H>&Ri}=v@y(*6ETRngf8RXZ_zCU>VU&-Y^ovZsXhvTKL2akl3s7vSu zJ0|)8S`t#q*dr}IQHO93EUuR@TM*GL0z$rB&edxL8;(72K6V+p3j75~8dc8W>nO}M z#%ZleJzuxBTz9kL?VPhl#Q3{+?|N#$lWJ-COTW@x{->yj3&KdSMvZyDC3gm$DRPy0 zq5YKiu)Su-i5THtoq&Wi&wavtw(?V*LlRMH;-bBi>T0VchdPR0UEpoXv#>MRzGvjxsjsMCOXKeb#bFp{B{^naR6=htxuD49xjrR~J z@u>?MeW^TCpD;>Q*Zh{D?`xfYf7}5%vGMO>t_AiUeNH`ffx1&CYsG*^vrAmw4GtRE z0OsAJz6Sa?o2DYEcJ04#)V+LC!4LxlmJmLuWWFi%a|Z+ls$$wBM9<=)7>a{&v2_>f zrryV|vE_Tzj7d{;568{|k8{_~y=C(6%g-wkZY~`>el6JgpRl6cbqBeTGjSA|W>8Xy znU^yZ%WJ7YKI;C-hH~cPo&5kN?3QM)cgMLwagrTo{`TC>;f6i_EcpF`fbe8vjt|#)K1% z7{CZXjtCmcj`d{_F-~CPXM*7R$wBiC#4nB62B4mXXA7o#JSbpdO7S5cf0%}%m%Mry zN(n=PcN6AOTrlqIDLuD2CWP#NkXiR<#)W`7*8vIMqI{)ekf|bFfT+Cxm#0*Da?oqp z6@{@8B%qvvj=l?JuV~e!&SCGU6Z(c93{sqwTVam*3<++xowVI}*Ae)P0{Ev)#$GmJ z&!fUeln{{5ML;PIUQ(wE84A6^!;a^EejBx;CFzJg30e;%E`PZ~m&4+aU$1iy{}r(% zk9qvL=4iR*E-7`0YKKnn@w(4u+0XLwc0hy6$*Qjp`%L%e`{WD4DZn@2`R_9q&!y$_ zdydZ+8tbuK8;g(a?R_+}!Q_E)$T6jp!<%wkACE;irKfW*?B21D zZIQ>+Cl9B&w|0k)JP}qnDX>4j?$@HEBvpnU!6Fj&ggra?$HtzjQsHfX`?<$ohJ((%rAJxrQ>wN zN**d7{_C}klT)PNw#EIx_s^-hER{VoUTaooJ<6=E3q0&<*x@FBGVS-e^<5wD7*4%> zo7g+137Dloeoxrq%9uw8jyTtzSYhU*I=8>KFu}2PwD+B2gJu$Q16hEQlU4SPQPzFO zz(ZO!5umd3wb4JMZFA)vv?LSbrOe4iMIC}+7jT1z#smO=OT-ydO+ktVogTOI81^ZK z4c=X%a(6~IA1u%ji16FDSk7VFg$EHs3y56mu8;nM_8(55@D3ONBpRx@#iUfx&8=`_ zu0C{EU_P{;im%7a0bU*va%vFTQ_P3iw`{f$+aZRd6c%0JBXr21qx|J4#-n^@x-kJs zwx?sMsnnY_)zsEgkFmejeLzDVMli+Wq^Sq}CAz7%zE!b2)q}>5L=fV*c_ME4a3~oi zW3Z885J{iTdx+EJ>eW}$0(utjf05qXz(58PaIdE@^GL6t3CtNv6MBK2DIT=EvRXX3 zJoWP9En50%=e}6k`vj}GI${*N^z*%^ts6Zbf&uUD?m$f-UOH%i5s43LPo{K{o;lz5 zB82K=+chZXKE*;s0Rv>lI(?+%^|rd_3(fg27K1crVnjUN25SB@`?kC*Gxpf(M4kQF zCUqYpc6Nrx3&K%O!d#i*5vxVj&2RelthIMKG|ex+&72Gr>^iq$N8aDw%(Z0++C6#h zWqMTOGX42azlsgcP2?E*dYWhaqKwxkQZ|akj-2kht*mtn3mLdW7_v5bf1NO$PENe8aafZO7qP?1O8jZL zk8r@lhet6vLI_kgPyieW#~jKNhHmKx7{JI%jy0Hv{aH`oiGu7B_;M-kTas9WxEusl z4zdQd_D(#@c(*Npal@N9g@EVof7>DBCO8GomyIQ}vwwbppHoL-E%0SBJceb-gIC59 zKsNDUE`^79F0wn2@|iVk!u1SzS}#-zJt>34oeZ}c{=vQ_lCXd$w;S{4(LsSCWe*&Q zPb9BwAvi1+Hxg0qGsnR^Jnifn;#OC9n-1RP@uJC1IJ>#1$NNRy=%`MeqNq2!Ay))0 z|7?gF3CNwE&Hy@w;uw9^v@V0j0>GlNvpVFBRy($N1BtoMk*@a`g#dC=t(*S zyvsL*f8t_ATBMZJc7!g%j;Vb5bkz6LUiEh$ZkZGi5Fo7)FdtW7c<7pO6g!_;A?m(* zYaO@J0bK>`kR zrP@5Ix@78SxPkXVujkV?E?O@CyhJ{F=EZNn29}~T!mJk8~F>AvuLw!Q>sWx1X8kUyNr6Z4xy+-CZVpgGq3&P=g36@B_ z2h%a5vE*T9;*|GG<=_a5iVH$9Lr;kpjo9jt#uEuRbKNKCDJ5ZQ0qd+^HII;u5{=#6 z^cUx;iKeot={`2KfHR3CT@-ZV3*ER)|JlgDebc7Onwrra%WS$jGt$b5%LWH9dX_iZ zYT+Z3>`*)(p!-TmZZooNmVDHp&fAD|P6AiMb_u_M1n|II{e+Y!g(w(fE1_?iSe@vd zM-F)rZT*M;uLZ~|n%;7`CO#-C-3ZGUNgfyMq+07;-sq|M%m_+EXz8(te@X?cN&fO= z)#@fu`*t7OaZzC!es*F2QAb&D$dDTV(X2=Tz?|#@{}5hz5@w6eiDNd>;}gdFMat%i z=M;#OX2xgT@=WJ4V-a$P0b)qyS|$Ja&Vy*0y?U&Ug(eWrbXA7&5z#*(U~vs{dxlIg z<-fD<|9aC_n>|P!R6CXd^&RoXmlyfAhD=(O-8A9xK2xB3Am(kL`0B@3?h9NW>Lv@W zOk8vd6n0APX+BpTeRX-YoHwc|oconb($bY=%?%ZA2DDbcHAnxH9*R!S9e2)~@`_wl zYd$4NZ@KG1@zkVS4o|Hmi|z5h$;Te_>e5cSXe?4SzqOzwjL683F~xkzE;DsaQ>p}>QD#91QzC}U(3tNcFW5f$J$Lg7xMOPu3;WN zgUe3QQf6LfZgTej5%u2jShs!LxKUKfNRe!bqKH(oPRS@lLQ0}S(;nHQtjZ=y;Utx) zD3z6!JqnRj_DWK=Y<}$%22{L5Bq39ttU1K_2=w!f8_3A?A=5hm;h$dP2n z;!FjESpigl5Q*?+g+;ROz4%cX=s(8u@*mgb67It{4uhi1!d=jc$kfF3yH0l+c7bj@ zzOFc-V40tnI=AdvJv>dKmV9Q*`0c=v|B(oR)v<`PazZ13PN<7oUKyRd_; zk~~E)enH`{zI}x0G`G>^$pz`Pj#tbC`!ofup#m8=k_F_`yBhC$|d9{(5?FV zL-jUt-r!$RbI>*3yGlS3rg4;xmO!us94MJ9TQ}GVeA@iNyxk-az?C1@?k_#;YF`CN|D1?@K$ z=JNNqYn_m62ANI(37vP1?x;1dBD2T0Z#$-}5^TPl-VHGf;!0(mezD@#3Bt{>@RJ1< zf@D?cIiiw%8qWX(t7yA<`bP`SPXHGn1P_YX-qZYAm#w(M+sHhlLVY*IZFtsLK}T)* zcT>|bS8nM{{qbXY1(ZV7CkJXgAKHFXx@;nrpz&4ht#@~;O7|PRKbS~-Dj#Yc?M(w1x7^w4e z?&{~-E#ALrYhZ2DrFHV9F+L;KI$k{tI~l!d1d^^>ltg*7ut&}uyz$Y!(A4#)Uh!I* zK?a86%EJ6B3MF1;_kV1_18!&cYK$SL?JwQ>pBgQeP10cok1g+~trwdR5Zn_Q<_1wZ zkwagWS=VrO;za74(BZ&>+jGW|F`K3uslhqL3k^Hk*5O@*;Ieu>BkhwHUQudVp1h(eU0x=-mpQ9h+2vjnLd zuVI%Z!7dDbha8)ggX!q#^-k;EAhw_RM!}GRe?Pp69BsV_<|(x@&M&lIe$Q1_q7+6o z5|MQvWNMGwgatp%9h#^3p2>}h+ZvE=6$zr0*$O2@?#d{%9NxA{cheY_o$v@nGr(_AF0Tpne~_ZJUoqQTm{@3I;xUnEQVwekdoRx z1J6bIWCLaN&G}PEks|N~z-ojhY!*FKZ7zxT3!0^>7N0pzPw{Q^G!YvFJeoyvM-z1H z@=S0{tJ>O*Zs{i0cajNg;nkVJ!QXfEonheHb*|BKLblO9ucl6?NU5Tu()O6#eyl@kZ6#H2Z z^{ibjQHAb>or4w|sg7IeLvK6LW~_X^qVRp~jpb(>9iXBlG9+QNd=|)!kxb#@jqXy-A|ik!Y8cmv{Q(OQ0CU4*^*lTEMT$P^*v`2sDjo z-H72DE{!BCb0G+>d1$p*t4gSF|+PS(L9F# z;e9Gc%368hrmx#UBKn{!gr(4X>M{Q(eJ~DSVeNql(|)B-5v_$nhdipE+~R=1LflEx zK_g>*bs%xdVS({urQET9+?AE4o4PVbjS=*@MKBHkXL!2GhMdR>2lDq+p2HKnC_H>h zqT0TnSG~utgMr}ie~l=sC8yjq4p?X6^SF19gE}Yt0OK!k<AtF{Lh6k~pAc1_hLqOv_7B*?E`$?21dZJ2B3+ znHu$1FmCkfxUG%6{ppXCx_k!FmMe1k^_F>Gzx5Z@EDcVadg549&n7MTli4kO|K&v! z=9;A_DmzuRJ2J;xMo8SiMkReD8bxGsZWMtuA1_!WCrltgd$T(oZKjwP!4JZLm7PxfWo= zQ4x@8-f40WaG}u0&{}#bMSeb0?yPcOcjA>re;P^M)>(cx>t~7biu!y-hcga4`|Iwj z$`X3E`feTfZsTdYvN*rTrkR{Nsq6^JfdHWl*QC<^`-*(HtIEKd+T(7ge(RXhL1Yn0 zD<<_t_;l6Fay{v`;>8nC@9H9*vhkW&JPVjIp-{PDyvga=xr zHbPHTRN|HfX}QDm2C#x0Y2L`^PQhA=y#{UXrQc4vof&eHBm5UxR0GqShg5Ocu~3jr zh=e^=U>R`Ll3^Cwi%<{Kiy!abX!V}cqA590JiY;loq0o|;@I-y;2MY%hx`QSs0&t>7la~r_^gy+2M5szu9@WdVP)m*kS%Nt$7QkY4`(qe_YVBlKtxVe z7c4w{_<*Q0Aj2T} z#>>pl3SK;R|i)J?O!<(`^f*6 zP0ktNkkn6y=7iH;usrkDA7}QFOSx(yW}1{QG5nb?Ttn7x%sa|&wNH^kF^IUWy)S^t z;Jt4BGbp+pd_BpMhKNK(9V-De%_s?4hcux33U1N_KfsmO$B+Acb+vY~HR(jgz5JRh z9@HG>SxAw8FeW+5@(>L#e8R7s(&Pk!buz0WJ_Qn;<-0J_3M!JJ28kl$r`9ed;Dt^tgOxYbH7%aC&q zU=ki{rR)dzG>~cr(0a_sXWHn2v-h01*@sx#KR$n?*p}6FR4Ar+qmId(K@|<*gTE#! z%8u8HmxyPU4B06UQ23!Bz;)1bn}P!F1L&wkcLwphEAX*kLnQbdz~&^J`+&bT0V8^4 zS;v7iV{TaaDa+&GYA1~3zJJ3qK>lo~w2f+e5EKMe&T)UcWM{QS8GMTP1XK}ChM=5- z83!?Q%>JY-(ig4m_9>p)2z3RqSmWERvCSjHMU=InTiAdH zMdFz6Fi|f|T{?Q#I>FwxO*~gXJKB=`@Vl0mt_1Bj#Kci_Gk`-`s zu9*_3Q05Ef*pgz%!nL9Qpt`9sJWS>xM@RBh%|*E2Na#Wk1wQqHI*zb_eJTdZq^a9rI-uu6)QLvc3 za-Y76F;i_zs#Clx;ksZd!vk`c?_i%`W@|96Hv&w)p}E(w_f;WZ_{1_1I&>Cr!T(lT z*ACAtN|FB8YL3N;FtNVFI8Kn>?F;l1U{wX%5U{Rp2<*QhOUw7OzY(?&WChF|-Rc2x z&#^t8%Zqae86q&PZiuF_3kX9i9Rd&IC7Kyd%MeO14S!mx-VTSwip!Ea)h)T9hB6YWm{Ei@o7Ki`%qC zqFqHPwRL4H-b33x;Y`&xV{hV)&$4kChCa#vnos~JY+74bZTA9U zRvH>rx$q^Dj~cUz>IIqIdvp|1?6-)TBtEN6TQ41FQ6$*a4jDx36uf9I!Afxj@JiN*e00soPW$03YXb;3LB7{J2rypUappQA_^N#ql zm-*s#QrB=@eDl4MM$Cc#O6Ne=+t~;Oju@Ms(X)o1IAa7mjyg*Yoy%&= zEKSwFKZkT(W<=|^f9dE5#i30$HlP7Q+I8~)__6!14F9tpP!9w62Du7|+f~n7hV0T30gI5t8Eh{hkjRiuH#oSlRjw?Lu1M@}!A1$Busb>^ zkhF9_uueWF21dr@=1?00tO(~mKT;!cAty6ULjlfFj`Oh((bF}4|9k@Gq%#_n ztwwp+?EVKTY>J{jp`6hxs;pBu!r#;SuJT#aK8q5wjG)Pbot)m8f08q|K2L8DTRQTN z_QTv04%^nIOS516Kcubx&n7BF|j`|TZ+E*G96q7t& zr!F_sDMS)e1kYiLj+#mxkt8c{X^ z%z?2x0MahLk$%Oet>Jv!_&b|v-WPmGHl|FpU){-9P_VemaQw?b*6!=?tAro)Pd;rq zpd;46=$26JeD!SW35BJd=T@Br@zhg(o81*UEt$bz&5d}@0%oQz@%ivT>g3uVsqyMU z#X10ibN>GGvS0APk=9LML7-e_!;d|L_rngs-#k<1-?od2nqxkq>wfJ22p|&Jb~{;~ z>iT+h(9KY0lC28zXf}Cvn%}>F695WJ(K_?N#^l4WE^JKl!c7cE=xgAUmSzOCcmE|w zBw<1ff;XxGRpL*oJj|l#4?5rS#n^Zgu{NP5?%Hw@G`~34NO}fdHeJB?Iy6c3Q%=QFVO7@%`?Gm8rF_JR@$Tiq-kR zhMgATD8XqMm~&O3ApYuJ%%);2*E0s6W!Rq$EOOL!=Bn=Z>h8I%G|%D#HUX>uJlesn6i1YbXFhGq&>KNU@q?-cU8@z$o)-qH}zDUZ5B5;cT-cT zuFqbM6uqJuXrpO4oH!(s12GTU+95PQz+&Q%+@Tw`2HF6nIn~8N?&bZJEUP=d>|G(J&8Hf^Zv!^J^jsGsW>ziO9l}Gk}iWcZBu>Uv z1V0~pB?o$*tVf21G0!q_d_kmF3MH*vMp2x$NWo;i{0=d(iSg?qUTwf(VNN2Q?Bodx z-I>`utfzlA^i=R_8YQ+@kV4u0{<4!yhIk$jnA0n~=H+MPBHxXTHOHBznIM7MHyps6 zZs#v6O}Q7|;>|=o3zjRA#sZxOu_l?B@x!)B_9Py8z!m$IMdRjJ)MNfXn z7>=98EI*!4h#l-2a5pSCo82<-Z`L-e-7O-dd%z(3p{8!c@aNvLzSn(u8P6W<{r1NqZ za5-&%#XGj|hazA2Wj~L~M%gr*qJt%?nP%P&s>J0SyCXCD-ip;BqHMU3zxCk{Bexfh zEZ$dxJ-ldBOa(TL#+NA3Wf(fn+J~sNc-F29@eFVK`|tJ}TO@Cy%L?L9Hjj=0hY#oW ztf7x9ZG*C}F)!tC(fYL1-L&{BUIWw?jN0T z(J2W+IDVQ4lc~b`ph%(02$1FbYbOhv*=UYr{{RX+z#&LE|2DwR-b=710uX%Wfv6f7 z+v4INMWcf3DJ_|FW=rW$rIbMV?>dvMJ@p<7eerCCWcks+OwR#v5V`E8(RhU5Ya>%E z>gw$JDmReyW;}oBrGWnBFj79S1tVK$ydH)*D6)@dFMV(D=D@BeBusBDef-ghJ88&? z`DxGn8w;Q8)Sox9tGfA%=8ln`hfWmfp31DcKx5|Bv-(%YS@s!^LQ||Wy$`zXoM_7Sed5=+oVLr)$h3+hW|Z6|Xfcf5g0goTK>d;Kg0u8u+kSG|5c z`vipvL;?0=AmyGa^yruY)WwZUq7vgSd9;Y^ywH>=#IaN=@y%gC5VE0+D?j`c2n+(1 zn-|c#X#PXTEQfitW5KikWzHBx6qG&w!P@vy0RNLPPED7;rD>U-t7*Eg=T&a7`|Tu0 zTo5=_S$nK!-J7Ex8ee}*DGaESn|ouzpY(TgMwXA^wX?yD=~l;M9FsJ4$3&l7&h=y} z#vDuA8rv>vxU}ff!ZYEq7^<70|Mgm>7JK*n|BPCvH`1m^SAW{DJ;T4wccQxb)|w?j zCYF(7t7ikdk{T=oXo~ox#8U2z^qrF*<>$JZwI_mhV|w&VTIGNlrb-&?O?KxJxa~YU8Wo-^3!IkfQ!iRy8vR+osl-`5=HfHsQc@@BBXq7~$O%p@HUOGL z{{|Jv`JA@ZTeSWsgMn5COyvBAeWRRZR_GORiQRa8^TR)$@8LBX+>LRm`; zLYPfLJoud46^$P}BnogJP2HfGfmqs*t$k4O42ScQbTm(u@#8|-xC01#g~k0c(%w%0 zu~GWJS^zKv{-PJaZ{Va{#X1N|87^UHQg9=LJ-5X!M?_~BkRX*6b!B23U%lH;%`&Ol z;qxVlO$vv9o}E}SE_tNQA{}M8q&FSfDrK5-CQ-EIXW+eprXQE54|wODH7%y}`sPzk zKmN@WyWL@Xz@{h%VA7i@(d99Mkuee=9)Uvwm1fS$eW>dI9!*_l? zvs{;A1mHl;x0V*ZCLj;rzWn+77Yk0%=gaa26fjG9h=b>tKuQ zyIaNECfp4QnI|B(Nj{)LppWW*3k-p zLd5!ehV%3f5J@zV;9$_Pa4057z# zus|muGdLr7N!jg7F=gU=e1+uuPw}#Ncn)L2MfH)ILo<{}h;1{CV{N(cx*MArkz2z6 zUNM{dhJ(%Qd9hdDh61ntHT!KlLu3p2R^~ES?qGu<1wmFPInbm?ay^9p(q>(P3W21B zP#=4WDSXb=N%aG2kJ2aL+zm2fy%vFl9N(!R3h16|>g2OdUv>ixE zQ@B1VL#K!G5fX$3tjg$x7nXdW@BqFTfke!_W0`V4_3b|26h>xx5C$M_+~{J__= zEu%fRs#iq2E)}piv}Ntm|86H1Cmh@7HIs8AtwneF?8qAmul94^yit}YdxwR^t<+)0 zp_~8tVo?sx9_#h@T`Q=u+q!K5gpGfYB&B*sg6rrerfB6888p|{sxW8MZRtz?#3emr z^(a4&R-{$y=3VZq3RCOd6rU^W3VpxaD!ss%P8RTdqF(WKE5#<6-XAGS??w;qz33{LMsyv)u;S zp?=>K1Txit(cu`gES1`Ass3CtD=W!)tDi@Gjk)1YK^e&cuNH;chIq5S>C5j#!?gwk zKh#}zqhpJlsSjY{e1#B4M)$*BJXmhZR7ynS`m3H0&;#EBR$IbI&adbe` zA3L@sdMC_rP{fhHy%;=+g+@F6yzy^`xT8p^-{&d)9x?e48(iH z&i8AT0KAJ^&=g0a+0X;<3QwNG;#ir`<70UI@rK~w6reeZ%@e0ZD7Q)L@HA@Pm44PI z1Oqc;yAzU0k!Uce6iu?WbBJA~SkYEN*bjA=_ zwbuOD^9?@g`&+hmJ*Tr9kehod!7pEp2d(?kIHZ1n1p$(`26Rk&rc7&7 zSHJzbLDak0lUh7|v=5qu(l;#^-+aIwi)f#oo*qKGz#@3=&3FG9XiC`!b`~E4;66t8 z&%IDdZg1pznVQjvcHI`|<+Byxi?q8OI^KST#-Y;nP4nKLd=>GwP$#091@8>|%Ift;h#J*n&Y>BrtE)o{x1_SOgI$jxODuqB%n|h( zqe;_;9kn0+g)FWdaygkpS@0V6V(Z?hoY!)dc%(5D?7isdiSv!9C~#S=(!g zXbdSSDH`?YCZuwl<5rK3jfUO=o|#8b4g;Kjz&A;3PRP3v3Y`#PRbHEP;l zoTgB-K(+FNjAm*UPo(OmIq@30ou)KrNmlJucgt{Fnovxi=u4*D9-IeRLD9=YT<>4q&x>U2 zJl42n9nzbC_WY+km(70O9O@oitC?waq-h#)f2dvxKmTh}H22uCiM8#VM-=w&So;#Oxym8I_r{>uOVT@cxi}{+bCY2iZG5>O)j|xG3&4$!wr0MP2Xd=hM z3X z*&RaS7sVQ641L~({cXN)i|7jY%_wVgJAwVTn)!Hb`s4LW5N8S2;`M}xt2#?MGsucd zEb+wNe4w}C^lA%YPX*FbywEW^Rw3!FcRB~=3!FNnR2}Avg%>;B2T@)N!q|H%h5ryh zC=fD$O-Z98oY{n}rn>Vo2kGXr{H`Nu1Te!*n*ZFvQSx@y^>XU3CJ{UVNDUx`0YFUQ zIZ;a8HG7JYfq@vRG0chSGJ}mEJsqV2s{}&E{<8tnnjsX}%hgU@J#g%}i!2Y3Btg=w zW_DQzt`VIZ|!lC70^&mQ1X%^G!O<4Hjz32S?J@&oI>QPdm9w|8od9#QJUBeBn)p5siy}C zrhXZY0SqNxA?7|Z;4siHW#amwu5&o+wb10*KPk|-%*lNNL3(O1Lz=lY$WhuFHkxf^S=^w~B` zqQaT|YH*z@Ur|_WZ0q`#vJc#1b#BRj&g#t6ED0afq)F7&NcONuGE(}aHotM^nP`G? z*pqt2k8|<%RU5AQ{qE^1?9>}|S$9T5nRjSMx{L0+>#|o8R(;8@bk=BcuBK0zH;0@I zj|faNz{yBz1NM4EUy}T5sF$UZAVVVKkdvI3N~&GaM3Q~==a}@Pn8a87ZoyLS9vu|H0Z7YHrMUFiX{uyzr)2nwcaB$K; zhvbw*x1U_O;XEG}yU%@O9OKlbY`A2e5}r8XB!@ikkvmv0V684|03+zi0^M_#m|$;2erj+RAniWSl# z;_5z}+8kPQ)DiCouBdfqd}kj4yUHnAvPJ~Gd1s;b@>q-!;&|3i!koA=+xP1Jr!BgB zprIYj@PzmR@#Aw7{B8=)e`v&5RTgKeg~m+!;f7tu$w*3|fJKTuum+M8(B zUM-pu!hN;Xw>8zxjqi z?Gct@YJu-%CD#{vc{W_RPqJMLjcadOnbcH9^AyLl9)0~4-(QG&%9wld1|FLo`r6k= z{_dQ)ArS9HSQw zHCzUUL-1}e%`t0tR2>G4GTZIPLU3%h{D7}J+}2wodH>BKBAWBxzmJTL_QUdnyLMfJ z`1dj+z5_m)yv&S*xAs}_wv^pSLnag)$^Jo{33s4|hX`#u08%7nhm-}eKxR(#BWY=A zcwlF9Q1AdK`_`)aaJZ2D2jrqZ5={B`Gz~cP)JS^L&X#i0&>Ra5B|s6`d0$%-0R|*d zfs#IRb!+thO)0r4@R2-IKoBJ468g#QVSDQo{Hlj}r~il}AQ9LU;b*0$f$fmU9|%O0 zZYv?PC7jq~(PpwmA1RCbh`|OsJ1r)6kmtZq%}5&-l=TgI%Mjcl%D`qtK(&jJP^G}Yj`el6rTq(=bfz0%rZ z1MVmugMThfYIW6!@u|Da^+!Ki8$llL3K&ccPszRN1|@ z_+~6^c#kR;MU7kMnzT=F*bIlOkT>R2(q4j>lA!hE*aa!=s@wdN=9B0_2BZ?seT;eW zaD3Fn=VW190dqdJD`hKHJF62caG=CvRG(V^uoDiyaC)Vu!57Kgp@DP@sXnDM#VcN) zygj!XbR|PQcsyaH%J06 zwN*mFXMliV$(~ABIYCIRnEIj!|!>C&U~O2?#M}QGV7N!RM5G1P^{zdKBYWf!;T5X zESn)+rLm$ki#rPc!v7z9dIAK2Q@$SS1K(*lJP@>Y>sy30J45Bo_;&et?u)**J2sid za>(xBUYyV~PtXzFq?KP8dcvka&rM8}epqaDT@2&CcZY>Nx~tEvY7w1D$oZ71fBM9P zYw^Hwxi7kMKeangS@=h)q@7TAmG?BsY8C9LqQ2XeJI525!=-ylT}r*?J`W;Qk;ViV zt3)hR@1I!o;9Yi~49{j&Z}^)s)~yJ&4(Pf~FtU!XNZ%4{DAXK^9F1+guURvBiDz>3 z?N^`!Bnkh-iHX~~jcm8tkX2Ut^0+)i5g=U9+pLBZE!{k@=->)d;NQhxB}RP)`p_T` z>bTKs%B7V&va=sOeyqyHC$e+rT3}Ebczu9o5Q>-_-k55z7%tOlo6mni>|T&1bf_)VJkn$TBMDnHWt+539D* z9%7Es@XgZ{VIA$Cu9joe6{#Pk@20<16Sn?~?NvV?(ZV}NY#ui7QdyX1?GhWNDH4}v zha|m?wKAylna!b<@8JVNe*DIB`pU|_jfMk*X-)Qvg`x$=TAU@`|C$6ij!k=&^0k~c zB%@0~ZI8f%Tk+cx{ASXdQL; zxI5Ie#M?N*=T0DDmK*{Do<7Fzi{n*fpMX4$Hp8sQlM6>V9ypSW3AD)bYb4qmAV9rv z;R1@a=RslAYihHlf~xn=d3Qh0(EE6f&GqoQ4M1gAe_-0b7y=txn$rQO@- z)O!xrPB z6a!>~{NCTKdY6X({#8Q;8OLs8nUVg#G^F2!$a4tfe2M1Md(8vKKRx;V;EwHlbVvGx zG$nTK@gn!2yz!EL%eKiQ=|&P|ZPBB&m6g`9)8e~LkNvIdJ27p>#B%&ow8G#@c;SKY z;0d{f%HqAd=*z-->BMgB$l5`7M`*{REumT=pD$-$yw;>(`@rcKbum%t@932WP9E;8DG`!Ks$WM5^zut=pBCo9|CW2-FKR8L#-2cBoR=30Rh+)aZ=?Nj;$OK%zR4FpMh92jyq=C zM~fCD0Fo0QGCb zeT&`2YgX+Pjkeqt#7%8KH^A4OC8d6)dT8S4?KMjI;U4Mwan%C-13lJdqTF$hMa^~g z^F3o0%XF*_%2DiE)*c^EQ>HY4 zusMv)8C*b1LQZ}Uj>%zi6H1hKVMepySB2y77;l2lpGel*>TBr3EGB<`0vUFwZud40 z-%}y@>#FAFefKBX0sX+dAO)A);CVyDc@bYh0)_wDNHM=(4s+F`iR;&|3xV1NxM5!K z4TK@uT=n9WytaZ)25cemSZ=K?{m6zReQh8rkooO8Ka{#}0bQ*88aStak*kPUtw{>f zuU|XD_$j1<8T=NAg7e`1akW)o3Jl{pcoQkYQgUGmWv1?PmfhgRXpFeGzH%8gCDGCH zzJCVlq#CzqBCAdo>=9?X;q%d>sZ zqCuUran*eH?os!vb?6O7O6RQre_)s?uU~)u+q)(f7Clmo0!Fd4&g_Y!!Q;(d_o@o+ znVuN3TYh-bJ-tC;_wEK^)9a?DhFou_gnV?io3y6=_ISTw$nf^P%-i+266z)uhRh!X z9cgVoe|OW#aPu8X{Eh9pf_?qo5evtecUIMik3{b9SXVbUku|9_DC_UPhllD{^Cmt= zDwF?-+H_RHj#;m}2i^%v9*BwF6SmH8T>5!^v7qgDFign#Mk|8qpQz{sqhNuaSuG}( znuf9LpTTQsR8OO1sA9{|(9jK#I;b7Ow^Jb)tWYU;USy&qbxa^@IZ3+CG$HHq+1RS2 z7c+)enhJ#bytXp7n*>H$EIC&c7DF}e2#gRX*dh| zXJ$M`Zx?+Xav~#$QSrPXJR&_rD2>Ap;xYob;Irq<9D?DRKpapImxJRVYYv@VueDrI z1@c?bsD}NsX(|M+D|HeuvBTTRX%of_VmxO3uUGzcGxO}Q2ad#0lKu!yGm?=$AnnJ7 z`-dogSbRVv)an%{oMe$i!@N@SQFUQ&0}TzLY)sZ%78=K<4DkuDFV$*&W0P$i?WocL zJ3Zjh0U9-4&4952n%iv$4{{+W@a7Iu<_QEYR}|J2!WQElEtfb}8h}E>v6&eS%%Y_2 z2N?+=+y|JM-}CahD?ZrDJ^tfb<{`7Qy9-KhtIoW4{uFK{vjL%xD;|S;CT?J_I_E?y@wA_wyFGjB zvrj%5s88%&F>H9oQ`cW$!MHYGXYTSq)!=DE-i}ZF4%{6ZIKJd(7&5omiY2^APg$I^ z=`Y@#2P3yXx>ZQW;>wvC=b*A1*s zRM#uq3Gcv<2$+V`A&UFFak(JvmGA7vsm*y2rBmxWszMKOSvk^2iipwWwMWn`Yo2?) z#!LF`4*q2`%U^oS?J4(uC}%LOy|MNCY+tm<%-54#RO4>n)P?|GVQcQ6_Mhg2hirQ9 zaSG;+6~&648rfVmtZK=_%e&cf8_V@OH9CP3wk&k%(t;H?IHvP>x>|bdLdNej(OHP~ zLBys}@ND8Zn`-*7SlQ+++;X?gQuoK+2-Uu8->BiQi*!Au#j(Q*^S@FaOt)+-G?mPL zA2rA{Fo1G*7MDLIXJDCgMRVpk7?%3@m)4MV4VpVJyINgQJ)4p4LWUhc^W+-B^OMwk zFsBvOp;G&QdG*OX!{dsvnFz;4UbR60ii``fBlVcuArgSynTZHJu`m*kHSxl>6)!!M z?G6sn(2T8rLY{vZImocFFk0O8UH7{D;*@*5lJmM{AjnYl$7UJ#<=zSZzgmD@9OP>< zoBM4nGDZ znSPqOHR^Bgh3Rtz6!2QmpO}7eN4P~=-LQB(tBFVTv20A+)prO+f8h&I;8~-&<+j3)gFmAePE{6p?n=A0KCbcJ=-_As z`kT=f^Xrn(7h+;VEhA2Rk|HZ3W5DY8R#qO?19Wb?dU!BNM~BlU#;y~sp4AvRaJnmZ zoAnOWLcPvn5J3~ zccMbQJozc=Bq^u_B8qJ+czui*@evcg)6N|uDfozec@L0xPRya$wMymZfk2yAhNPy7 zBAgJ2vOo4hm>s?cj1{xH4GqMOH@$3NWZ@~ndZ+eK`^&IBp0h2T-e>&tC&$K0z(tOu z&4z?Wu1uS)5d1BKpTbA%QGjli(RN1s-?En*d31ExEy4+NgLwllVXghop`qJwJ9I;H z*2~%krjJMy^`B~g0P2T$8NurUC)#koqPE}yNzFk%I$+MKKerse{oP`_Klu7jIghSO z)Sg(|qT8hHOFgqn{NaI=H*fU6{Wjpl_d?utU|r$ZKo}Lt9wFK47(Bq6VHoHAA83d& zTPQ@J*b@*F`<+o~kL#86nj_nNJS=ycqiw2>MSD^{HFcoL#%4;IpE^>T8gR_QtG;>A zF+#yC;&167$4lvS4mN}PT9&r8mdC#*EFLh`b?f}{n`Q1`%i=#br*0o{hb5|-0!nu= z5@S&A{MSj`pBx-whvqOE&-C+)qA4C|D=IliSqK)mRbvr~$-b}oTAe~SiMy#pFz#b) zSyei8TIb|1r}{GGp+?>B)xCUr?aGf8Tuc*7`|Q8?C@bn>BjNs{3ab z7ElatX5}Vw0aCB9ahYvViQMM#r(%!pkS?gPyH_Y;AfUE7W7bx>vD-mjK+xm2-qw*d zyoPbJj>e-8)6ER8{PU6W>x3z*T+U2dGL(j!cP|2E(i=N5W&9(WE(HBv4 zMtocD3HmnP6GU)cAqBV1a0-3b`F~?e!@bYkVPiAiWeM;Fd{DE@5x{Va$%? zM#41(hfc5~HUy$@cv1lU$vj=+*Mt*9GTJPDSBKzc!`<ivsv?aD1=%&=V#bCAFsNa29ifkABa& zt&E(V;SQk@@MEXh-bk&?u&;AA+gqEdQ4ciD#}ZqIo-qBQ&ZH4va$ ztTb{e{&%=Rw_o5kiNv0!hO>brQ_SDdh5Ek3A8r_;Qi0}D_2Iv%sqV5fu0&o5Z?;6a zJD3MZwqd~*v9=077%YTvaR<8a&<$JMzk{czp^@lkbvGL+R;>9D)|IBBuzu`S3sB|ediAS z*#+n|Aa+v==IF4Wm8T);w)la8WhLeHov1T4_Ke2sbFdm4szbQtEDclij`1QLOvvSMRiTK(D)ob;+?2E#6l+AgaI8`7- z;01PCI%bSe(V~f%%v`JU-;2E7%a&gS)kN${$h)A!APy?c6AS@~5X#9pKrUgNU;zB+ zKsgazET3CH8*vrmG;l>r=l|Nh!9SSIH^sJZWD+Kv6G=9P$8K@1!G~{h;S$v=kg_zS zOOQOM(!dVx83SDM3jM<5Y9voNs$j9Ajep$R&_4dJ-NQk5q~>o0vSZHefoYHi|AY{; z@PThPigj4U%0k#_70TBu*3}4ZRI;}Vw;dUJ{3GmR=&lF;1_J{0I!e#95lH)BlgvydnS%_2X2#Od?&eE`}m(j^V&#*n%mbhYRvvb z{$^l~VC3pAe1O0SU$lNr1+VZ4UrF_`vI|$@?Jgv6U&x{rrDrgl>vyl7Zb@HA__A=l zQr73BNV>ty#CQ^2xHN5&A@kMe(6NvQ4sTual-+evENQst31kRo8bLllI+HvmFWbU^ z^$Z{9RPO5xn$W=E#esAe-^xmL9%$u>^c@c+nVL~=h?fdx5&^7(h)0JU0;>8_i0~n~ z9c-$C#sb>TGSHD7e2*VMO7!g64#+Y;V8FE6Z;r5ZY;)v#Ap*MBhW9JE{=OAB;k7hB zeSg38*3xh1jk6$@h00gmYV+5j_%jY5TyHd|5=|1cl&U3HjyrB_#b3+Y+}^|5|5|5I z_&yGkJ(ucvFmwd_$)!>G@lcS7|8Nc>p+IK>04>Z4(aSl~1q2hB-NbN#ToYoCn*p?P zd-qQ))4helec#cfONJv9UST&NZaY~h^N>?z`Q*tO&n0L3Y&td%T!oF1HrZ_meI|ZD zvd%-I%wa)MG?&>LiAkP3p*V4fNf4ZA1+8O$hbfZ$Fnq;MM3dYF93}YqiJc$WW97-| z7)`3HtCca!;R<4g0~L1$l;HUvMTIFV6_R%2rK=x5e%g!1b`5WDCGb>I_+^noM$8ow zZqWR}90dj1@hvN2(mGlO?#2TN{q;Kx*sd8rved3ok5OQ`7U`BgU+q>iS7&KBr0`O~ z=2G}rcIyKsOYIcRhaAgm8zQ#dsJOr;6=`|m?7%yboPE26+}+%6Z)sE5kmn=IkTNy5 zFHBOFw$h$`NPZ+hC- zlNrB%XcM19J-+z5Iwt(ey?ic{Id?)Ls@`2?qf+YHHrTl*EzHi|Dgf08Uf375Mp9$| zLmeJ@0Qj=Sjo;oFzZ@GMzY!iDe(Gb3JLkZ)^Z?nbx-E1Y_&sE@XAeE`9p<8!PQ$R+ zW$BqR;W;>v)0V)f;|&b%f5CF2D=(pR^aH3O1W_-ZR$s>=0>)roioli$7%oSCyrTwH zBV;CplfwY1_2H;BreV|6-3~yy1iAA>28}@ogLNNN?nK59oQVMVu?gpqKYA0vk#&;A zA;1vm?E*~}ex-ziQCG1aCH7uS>1%Fg!lEaQ_Cf zOAys1p@XR6QQ-Ill z4?HRo$^h`QpfnOaaXt7{O7n-XXgiU6;%jjNlQCay8xJ}kGpttp|fUnevF z&7eWUv#Bso%99VH`nzrFEE`KT9866zYX^S1z1Pxu!eaQS)FOS+z|twG&)}~_s*gO+ z(ECAR=RtS9}S@qV3S@vpz|1Lu55rsR3^(?EW@ly}+cV04S zKQ=3NPB{3g%Fk6XWj!Em)IcO6`vGvm>MdYl9u?f>*qz=u+gC}MW_i+(!(I2-&qOIN zMA|NjYR@Rsf8GAlT}NA5)BSO*5megtD#O^Sow{Zjdj}|J$^vFg?tr+sIFfpMG4GuP zl+#EKgBglK?qs|o>&$PgFUMyYvamb@9>WF?we{_e{pU+pK@Z3SgW4fzKA+D-c7*Nh z=pgy{XFk!U-kAHoyyQCgH)kATA|aE^DwqA%DjFI=bt)18BH+}}xK?$bc<$K8`%KkEJ$^NRZ~e&k zi%U*}FF&b?(B<*z4Jqdbb%_qI%h+o$^jy{OWXq+~8fib2EjQIV>vP4rJW5?FZujTW zL~rlF$xki_!26{KX@<(S#(S<;<$p6~^c}o+g6r`Y{`liR!)Wh{_=Jr_Djqp{Sz^Fn zv4@E-EUdOcvC{3~q)bBltHW&g$!PI>km4k)wio!8?0mJjDLigz{CUyr-z=cD!=NAw{=)LSl zqwHhGU#YI>5*AAOMnO}-f56c*;62|=g|3qxzA1>#piRqKa};6St98}oEFdh0wmk@_ z6^{CFLQ1EmYJ|K&CDApxM@WPcLZsQBJN>~Mu>X>W6Cl@U{#n?&{-mT3aXC3I2mSn3 zXJ2n`3b!v_d@`1m>e6PD6P)D&$c&6LdU}y--h9J$j@);kO6;VCNUz=|2V5XM{BJJK zr(R+8L5d#h=FI_E^>hDto;cV;Yi=##@=t`*WtBX&bzsUuL8$GYv0JUI=Fj!B`?y-4 zy<#q=#%jbUwFZb~+J%|5ueD_wDSuiU9<0gvzRWy*zCCSGKXMozM~nlQ{O;qO_Vn^X zUV(0II~rF>Tn@=`0)L1Q1;REO8*e2@0J&B0LIW(s|4FP-r`OC`wv==v8J9nu7$5(D zcM+=2Q8611H=i^M0MSHcLWo6IS68yM;6l7UbOgy$n*u(ZD*>=U@k!~3#)fgX2@e?H z?ek6q=yZrK$+Eh8ZKpR~lZ8N(RP91r9?mi4d-@7FaF z*>xrONP2!o;Aw1a^A1sI56R0{-E~Q6=ndBP?uO*TH|El8~PaTu=WyBwf|anqMX2j0ga;o$*@k#gLaCvv_b5^f`$#4 z9|1TdX(gmt6U8c$PUBaxzA48o0*&$H#~J7YC>i}lzgm`QZv#fwkRl$vTOC@AXL z{o92)!w?E(hKDC-y;I4RO&eHP%xl7U(L!_xWX6>H;K@nU95Mh<@*V3X6Hc}j7gQ4E zleovnCMU~q>Z3r5BnCrFbq?DJgg&f)O^|E(;K5d~rOMwq@WPO=Rk$4fPgg0T=T7`F z>FrGDPea%R>5Q~O_z?U5N7Hw}bJ_0yqd_VoAt_~t5DlAzRD`l3ql`i&BU>b^A~R_i zsiagygzUY_OvqlTWRuPReLd&*e_rSHoO7OYDtzzzx;~%x$xX;Jth~^LukZpcT`buwaXyBFU86TbYZ}6xZrf<+vAyOI+04C7 zOlah|hFQ($(8>)-={8^49kS^RBn6Uf=uM6rR90_HHR8+pYgm!5mrKRKnXHpwdgt}f zOKDd5;pu;UPOr-CH5RGt3@-ef=84jEa^Bn{_lj%Bua7l~J_mNWwDrrV4ayJ7G|Vq6 z%jioU@3)YuywEvf5Z7T9(XR*JB*m2wH6jE+-Ap$0(jB(= z(UPnXv;&}-ZlN=n`pFAX3UMAjeZ^0!-cA~yJ zisx*w3c$FdtfaKg(9n>?Q6RE`SS<0)JYOY2;;ydQ=eFBP#srqJVq(EO2d{yP(RZvb z$o2w#p?=}Y<6BX8FBt5p{(Q2fZfeEB-AJ-dORh3L+KH*KwTmiGR&&BZOK$LUmAi&z zW%cv)`pge>mG*+FLc&*-*M@HB{!9BKp}VK&zq6j;K;5nbTZuUicMF-VfNzjEil9w< z1q7-sJI+GNg%`QpxeJ3)v~Cj)n378$$pwzjYhrd*1*|C=Jc+){=<|(DxEBjYlms#c zL6_i@{bsbmi{#^AH1k~Q=sAwh2p`J_kWaGz+RPt$vGVWiA?JLj8d&Vj`}mZC@)E2| z9^Bta<$OrWUR0>4rTI?N&y7-YrFV6UoN5IHuGv~lZo0+CSfKmJ*TMG7q<$ZRxiSu|s1eDF10(}e+*5 z$fpb9R8G?dQjrF+92gTbNCL9%i@wE^ZM)*GwZ7e@+lw8O*p7vPJ!uWKn>Y8(tlyRI z{8dGDBQ6PipRQO62_B0{j<^UhW+AP?4^E-;pYgjAbO`Z2WKl*(FBBO+AIVS8&X$Ar zwOgLI?+ZRQyx2f_8<4`b_0i-f=3a@qHNd^+Py>i5&EFo@PlNTyIUz|;K3anmW^Chn34c`vOegQj$a<09nu%2hT;Dz!|? z_bF4+E0%SH4oE*<|7>X?;l@<)3myKP<@9DB7CLUKSo7U+ft~e-_WXZKHUbZMdFHgBm_JM{bvhS-ST5346{$2_8YuB7buu`4qQ~+P--mi)l&YzW=WU2vO(A zDK!<$m-MI&B{HNzbL`%hJZ;FiU4JJ=-_kc(Fe-EZKhrJl2{am=^6S)TR{{Dj z={EK9yhB%IB{eJ$N6{NotHBmn%E`jM@49!y&XE7l9hF}X}6jur|BF%I(jLeqo)3{nA{ zR&V>|_;RoZ#x?!WeE{-Lz*hyB8NfK2lvGfA4S?w&Uq!wQTw5dp8bAs#y1h3tm*s06 zA3nU#J#vaosPXc9sW^ofyoPf%?gpP!be)reJ#;L;HCd0{h)oX3diylkC*!Y&?$aqx zi}Tt}@yRjqs;h6RW-)Q}zR&8W>XqI80(7Lp+Cse;ZXZ??S7a&+45rU7ENoJW=Cdl= zv=f_K-^fT1zNymIR#vd-U|2Yzq9+|u7M+GCmpxA4(gWE;>U|Q6Suhq6>&rawo?sA4 zI2X*}YH&sAIEe6JU$hq3BNgN%Wch?oJ8*OH27b7B zj5k3N0lAGb=2Bt;hPENv-s)pJ22kk0&t~OzaClBAB7ZC=<|L7|;RH4B`s@V!r)HS1 zMFw3q-fLd6>-OGEJ9ze$-j)`q9pKg^t)a)VI262${BE8+eR}u6eF-2f7?{%-et`DD zsYoK00P&Ke3YaW~Wd0RLM@O=HSyjm5_kSyC_b~K~;j^cQtRp11k7$_tQQgu=4g6|T z4mu$`^D0}M`yUWyl7H(Sr5s!xULz$xYHd5X;y?fsVgj8bMZlWjUQ&g}odhfcVyCh* zE6vW91f&jy%QLt-fuo)>Ffw`NN=-1yXJW6MqPOJS3K zGQQDkuPpyoFNQ?cB|B7`T+DjQPS0C1pyAl1PF;qljP|UvGD(;Z07D z4K=xW^UJlVjhDyTE7P_NaWZk<5-RAQj`(gXvieTFZp!OHewSO0RKfG%H#hguHx2nE z&hL2f>1To?M35@W&JMB=IEa*G$o^a~O4)gN`Nybo1&WJI%AWE^^gu_5UQg_;@Z$j` z?fuNO=%N2ir;PT@GJPqww>Eo4Q?^XWgl@$^=1D%WYwr>CwxIDK+rQu7) zWq3AX1fuUpbiJVL=bJW*b~-JA#UTN&Ab0i&3#({qh86{iJMRH54OR<}a|&AtiM=34 z1?Ep>nP#>lAc#rMDn!hR?#mY zP~XY6hb17d(+I#(f7k5D#hXi`xpcb^0TqRkeg`2^5t{?40E@8E9YBht=g!q=GPtl% z0ny4v&J}JR9_EOOI-#y!hLn$99A(5CpRJhM$}JHdfc_UL^1m1`L_?Khd>R)t zSw&wd@nc|+`0SeMn7_B4Uhqu&8QI+}%bvN17H$g4C8ihZd=mL>D3vNxd}(arUa+dg zlA*sxMosUSbkvzoL6)A0r%b;R@1jPnMTb#bVLqq;Rg~1%BIW1j}BJx$7vV_3n zQ-4GX+QGkZA>4$*4q7%`=*W3wgrgUE?Z@E+!veJ?vhd$T9J3AKy|SeW)_7VuxHv+SZmsp}-pN%nCjl~Ufl z=h?3uK$|xyo?H=p)o$u?SJZul7gTbc&mg)j-?KVF4QOcj6GwHtDzGH%44j`9&-TPa zdWLb4kpGBXA}2TQ-^L_RTMX$?B%oU}aw6RgAuT9~6%O8G6NH~B)FO!3QJFppy~}|- z?~x0$l^i#><0ENHw+uQzzTf58q66Y-B^?H7fT&EYrdx7-sV%*iMk$#;bnxK8Gw06j z3$DQ*L#jt$eL=r7nI1_a49;jg(qzPd9@uQ;Jrun(8?;eP3pvat2P=q*VPBgcjMO|- zI;Rel5@JIr@);L>%#!P&WYbhw$>^966~rFeKnaTzLwya0KaLZ`upb4Mu%9K!wGQ?_ z^g@t$42-^FxHk}kUog3qRVixb2Z&PQb3{K>5rpy(wc&jn*|F|2M3#5%-&a9y%7Mib zq0LJgvl=KRVJ)0j3C}u(V`1{G>Do?;iC^5I7Z9;Zer67}lD)yz(s(z(YpawEzmj$| zKmA>(sLfa>c_jVfOG}Ez>*C?Zou>WDHE?+B@Ydzo;GMcF z^ZgVQ~bOT7^Z^)}q~T=?=Vbd`~F-^!ufOgb%XA zK^^rhB}GFrqUuxRyXhO!mtEsQbP=gYYTnenOKV7FCQc^IyCTEBh|L7bMD9;7FE4Wb zB8vo95E6}ie*7>baxv)Dk3r@K{-&JnE-{V5yc}Gcopx^jYxG72hIPEtgKCm!0Z02~`)f}yu3V8xPp?eyA4jriY5v9$j&OVFj8p2G79D$mJkuk9lLk? z^WVZu8N}e_a_XJTE;_>PLV4TCCUPBe4-%h)76j!JtRe^$A}4K7iU+eCwC=c=r&+M@-R zq6e6m9}5qw)K5CpWUGs0J&e>QX$>K|;N^M0!>~eG1$hUa{QX@rm z?<;dNvx>6jrU>Yg8Nf&Y4+&`7h=i`d;dpP-NDh+-nHiDORc3P$I;D!xJ>L2qMg?>E z<9!GzCOjuDB@(H1@BLvM1c%6tMcgHTZSX%TVFU-#sLa3eN58NH1Op@7!I-{r@=Ik| z{|9le+NLAM6-w&_VlQLa>+5Sac6R@X3xEHK*iKB|-7^0+LAm?5#p^~EBXPdLnT%Ts zn}+zAUW+fNpAX1U&EL|gTlVtmgIY07%hFpO<+YKIXc?+3#3f$;c9VaDN|PSG(+ksw zEK47+lW*bqRkuU?^k6#W*XFR|;7(*aH%yD$?Ohj_MLF)>uBA=6!-P&(F0<&t77m@( zA!*0GiIzw02Tr{;{>`!T>6God7AiV#y_7;)n#lr`3Ii6cNQ(Em7s%mGvqob8z)mAZ z(g#X`zQaa1J25nnHv^MZsNBCt2OP2w9XawmC4~;ESg@PhHmbvqqxR)&6F*>aD;t|8 zo>o-%O3O%3z#nA3v|04R;CH>{dTvCZ5aTd9AObLgB7nWh|Ayqv#Y03(T>4AcB(JS} z-*cB6?dg{D{j7y|Fs>63B6cSr$t8Ai$P^%TLjwb8c=B+L2BZIb%Hk-%h<$Lw~#k+<1Z19`0vjiukGV63k0WOH12QW@_Kpcl)#EE}>*; zqOX(~oyI-j+P3Y??&~iqp8bw~F?(bnppKpq->X@4F*Fp=HQvLb8@*$ehs6FNlLN5z zxLL-+{QQLyzfDA!iemxY1GXdYEoY{c46Fsn=|dlXlO<%dqpKT5jOH(XV(IV;=#xGh z=W#-3BVGLE1v#VE8b|h(Xx6EHa#2~^>-9}$w0{fd)ZH*XoMgjx+o8bl_q0RRwM5Hb zHT9pH%MGp9X^3h*@g=L{@Gv!4KfBic{^+28e!dSoy}+8SWeE z#%%k-`R6$w8fVzgO8zx092GAvUYnk@ml0Rwa4{SRtEqEoYQSf(<5qn99z;UIEP!K0 z@+XCkgBd^rh+6F1@0U6GjYC#JAnl6Iu~6*OMJ*Gs-2=}-nuvXF;!*mpKz(DzTEN}r_9!b{s5 zrEj7Lep!BDkSVQd1YiNkZya|)4SSb&6M^oSoX13CoE-UZUuH>|-25YeiS^!wm?$Z! zb2xrMVh%WW|NZ@25fCb&(eTTC&J6xLBNa_iXH4W&XhKcC)VAwhRCjl`$d8P|!X94f zQXnj(?n!p0K?x_*aU7C(704As8rseHV+6~faS7n+o zSocX{j(+uOBQ-sTGX7+wEP$mk-jz%-d|MCx4xsK2%)@r+;E@%KOZvzMCd zb$}G%;8#H7(}-IX8Aag5FzG@kk7-A7e+=H$K0u2Y>GOofXR*(aRIU;zYbyPUB4>R& z>n$RyHeWZ)R{s7~P-aTQDI@rBXWwoEi8oD+>Cw86lxAZ)KJlb?M>U`A+utoRv#ZiQ zc>}${;DSz_X=3fT-l}z#Q@%+kIhpGf)@1QsW6mQxIBWf5AoxyS9P4|e-Pr7G_jn+< zexiyy^cf_N_|QOGIa zFv4F)N7y`$Y(gACb=zGYW{5Zvl)MUPloPj^mR5s8S?L(@JUtyMXEiMY2t~S7CM_V>#7u1tXi+0~U#$mJW)R55mP%+@`cdrUol&UyD2Z z`h2fpxW0N&fsKb}YP|q^uXJo(`E-0_L+81n$b_1u`+tsC$h7!+q}JN2aG@Xxkl%Zn4NYitzybcB^^S&Shxv&k zNDf9u8o>`BS|O!rh@HYc`64~t;Y$hg{a84|$Tbek_=%-}uy8r9e~Mm5#u5D#BSnbw z&<()NY==pZBqUt@>GzKy*#%1wmuwHI@j)2`v2kOtCvmD6I*2U= zPJBuV4)0}q#XQKF3W;(CuR9?LiH;ajk~2T!rM>05k$`0Pi@oQliklQPQDf4ptFV^R zame1mP(<<(z*_{dh?HRnpA0fxraH)6PlRT~%L2e8hy!E2qOEPpr8Q#&4B@IMg)#~g z9C6{@NCKaQkNLsiB2*@%5*W{h*gr@t!+^x&&?mMT7pEOhk)MPkX>5KKfy=N}DSguq zx*G1kCNgr)_V4SsVfTQ@@N^Na#DpdT!QFhOk+nBvUg#FYx1Lm!XmWAki8b=pU8

    #cl~t?U7*r_WoQy}Ty56b z8A$T?b@%GHXlQ6JO*dQ-Pphxi?>6yM{N>ipr2kLyVcMRS@By|Q&3)H@w49i;AD1@K z;D|Qi+iVeh+(Kbiv`-Vxl}1xfpU4rOmPgH8=UmTM4FqKc+PrJ@F1f1w0LlmXFBuC6A21!X}BvEvlIeSv!_MA6%eL+P#+DeyuT zFr4;EPEMI^x}~f!0NcU%{gT}>`%QpIq%ca~@oR4PkvRWdD#|T6STYTp;b90+_;}(Xjh8DLJGHxBz zck2w-Qq;vJ;0H|ZMf)S1XWDy>u3!23d*)ru&&W{)uddj-pYHmWwKbN5JqwOmrA*1- zQnqF1e$3NZcr)?%4_i)w;U~VVcDHu7mBAzVv0cf$-mJ&xe5g6*J$SgwtPUa5>5rqr z`0w8fIi-1c6Hh;m%N5Qvv~0L1wox)mD|d<5NnY9FW8UQOqWtNiL|K_m|=#W=FBuZEHnOfLY%Y75rbK&n1x9++_;SplWLp(~4 zWS`DcrX=4zqw+zUO-HCZ&uGlADUwxV-r_yicd4Uc(?i#|dy)j7)@Z#N$vVi;|Y$h&Z#0+zb$eXw_8obvd z4+wSPzr%TMSNhg$2mH|Ww)`)vkSwDx=9PcHSkxY8vE}Sj`Yl^}p-(-R>-_%G6Szl+ z0Pna|xp6Gq4L~5tl!FI@9IsHEDB%nTI)$`UqWQ(i2hNA{Flrn+`s{kK2$dZCf+A=j z84$#N-SI*_skIayA5{+zpX;8b*6KZpf}czF;1KM5 zIBu8c`4x(jm&TN!&LgodD6!aly+tM*A{ef9MI|ah6rBq@Xpy^%TxWRL%M4U`4BdUa z2I7ZCbEn1)%cAa```MF|Ryllro155K4Yi;!STP6Rzhlq*p{O?eCgp9g`TMCVX@l8! zHXM_)v&ePWgWI8Rd^{APy%>fN*MS!)H_Y*d7iBMxE(}52Ozk3`-q?BHnqy}`U^Dm1 z*Vy}#cSW*zE16=}4=c;b)eakkuuC3~Q2MCl<@wHjn{kEE1JU@k`O7J-3+KX>7|uRk z@D%dM)ApFq3gFqE6l0d^;o%V~HE43hM2}H&S8KJOA4_|w{mZ;N*ku|zI)ru^VUkBt zg0ky=u0nylt>L4CQpwwFu7o^wi`{pcW2e$ctX^hdOthy$Wrv~i{mwB%_uD^zpcTEZ znm>No$OwXRdH}RqCMHN@_$&SpY0xBG%|4jlzHL;}u9t$y!9hdY$5DB&$;!zw?%YWW zAT-)nno{56R%;;3FXHb(Secaw3kWq*BY7|n%s1s^pxn-bmpLA|NzX_8R`^$UUz;dg{LZXNhT{ZDFe6X0gq zOSd+Po@gY}Y{*%K)0nnv?qA3C0q}lA1W(kYfPWkLjP|&>yTjl@!+#h1-~j1+qo;t* z;pF}@&_sQ|8eiBVYZDS+)ElT`a%xLEaqd=~%nTOXTy3i}SD>&YH{8{$I{g_?v7_sh z156!`FQO?5-+KZ-X;RCL9~2pRaL~@k)P7iS zvO|_{U%W+*9d{`E{$1~;CI32D?Vz*Gv9H;BE{>0X&o4K(rTwW{$+94N-% zfr#O8;k6VhmE?cJZWCTn_qEt~l9hwbMQqy0wtv$8__e=v^TXGQYOS(5(CK{_j{uhX z6~{flerq7!HRrbliVG_SQ$e-=GAdZ(PEF$9e7sOaxx^(Xb)>NY# zp`Gy%|H2V^Cn&TstbL1VKF9Fp&1rB*AyTF2>JjeC<+RYCtrwk}>HMx8-~WLFXD8|a zk0O+%ZQItPJ52HOf_I@5&n;x%>x;jC`!@K!R~%V~`R<32u;hPHA7WR8Y&Oo}Q2?OJ zge>n#f`>qH3XKumN!x}HH%t<;@q5*|Tx8Gc(Wre8D$9TmCZl zZ*4(=JjAwQUk&#De=Wd8%(R57GBxdaq_k6D97)6I1TlwS#=Hp$AC+(yfeaU+;l=1l z;XU~rZz-041uB&FUH4{J zx-`Ap;}_6b{A`F8oM1MeS%uLITc%$y#oT%StvcRB$W#PAd9O=}E17bAHDaX0BXPjl z<=(Q%#M1nVEd7GlW12{(f*Q1?g|^;rdbXhGrJ*+H-gq!(i&jfePg09WOmAd-RP$ai z@u2wnZw&z*7W-$VPNhNbf(8|YAmW~Rr2a~5ePr`9F|JBOzQGP^>=B>lTNw`t5w zUeWOm3B9v_m}evZE2-}OK`MUpLAQtjVR`x*IDzRG(HT^BU3O2CfJ0$*(AKH8zPNvR z`)7g?UU1T(N z;n+203z@`P*27kvRn%45D^dc^{L)GzACpfH7DRU_Z#K8i6z=PWYhjrng@`@#YL#h% z4~>{_am7KhSj4Mu2vG}=$BYCX zg64;-dXL2QZe`LUzM?Yw$?$zit~)-%Cr*>o)1+2_P$0m~fXfnC0Ahna zo=K>F!J;k_;dH+^<(W#EBznD^CLyZ~C`rZ2&Wt6GXwK#e=HxJSme^(u!08W@oDwX< z4va0$%}fB7aa}N9UPg%;2^#_)$JqTH8f6Iop;@W`a7#gPyWy35lHF^t)&N_|ed*>=Ne_h3*lMOQ#;Fv)}nnti?k{-SJ z6}Ti|OG|Tv6a6{L;E2on{{7ud&2pgVF}xEG9|t9hmUf%zY3q_y?eE^=E#ov(9K!9GxL7F*=6V+*rAs`7CF4W<+`k#uv{{);BwMz z>;SEav)fpsV3KF()#jQ}d;U7-^v)m^V$hUZP%tE%Mw@wPAK;tq9cQXvLx&~&)cf$#mLml6P9OAXShtowyJK> z$YxZ%R@HH0jEQ+~GgryblFr`KN9uGcIE|yH?Wn)$JW~?#e(zwFxXCIor*Wz#>?Dt_ zfsW-%r6?TDf#|az*u#lW6`mG4Ty@Y(V#-nWY=k=vTnj?`xUe7Ls6>hCHj{V?jDzD% zAx42=_LmOroP>>}Z6Uhwf~_{wrFHX-pT+fU_f z(+u$VRVeg?tanIa9X#@&Lro+;CZ#hF4+8uUm{UvfWON4jH%CANYlc!jEXBoupixT+ zx3uHM`ELS5MvMQiA_WpLjVFjZ9h^5K0|P~1DI2xCw6vk0xf=|aM3Ih&Ktdl7oje)X zQ5-8N)HsdeUX}#842#hpnUdbCve>x9r2oi1^IBV7c?91VG#jKEjy2THMsw#hMlWPo zi@=W$1nQmJkOz|}I9JltPO3ulG<&K<3vo0~ING~BsgNok^S z#Qx9VNvMzdVGc8!yZx>b-Ngj9#h$AwsYWh@jt+KQU1ewz55{?n^$MfB8M>Kj)@cvJ zZ3d5i+CjjHB)F6Od@wGZ(b3_dyEgvk4^bWxVFA9pXz|A9R20N827!|+197gF8PMUP z!(d(pzP<974@^Q__?B@!K(u()Y~wcJ4*wn@(f%oq-}1Wd%knKw?s}huaweqwdc679 zr?b$7*V^%adczXeoSe%Nq7$X5R#|(ED=ATTk6Yu6#vn(I*Z&S*6C$-DGJ>fx@aCSi z&7q$Zn`>kwZqM_m9N$FggifG8971A6{ix7hj1bmFcn)fci1-*as#TdVKRtyH-gyD%{R z*oSTG&a+#z`<@*=xm7{S8C4imRJ6vPb&i)FIN14fj#{3-eplUP9_zW;m7BS;sjQ-x zVEmql+BzgEmnf`FE3Bg+PD4Mx^+{S{1cbBiUk?v2jFJaA|As$(%8s}j2GqO(l6~=y zwXn#9g~e~nLT4}OsU^%mFYoC)yW6o_!8l2Qo89W#HK(bt?<2FAa7YXeN!Ng0oq&Vn zMxF(NeHW=RcYUj&;KK8FPxg>F@wGw)f?dc?n&Mf$7iwsT*Bt6W+*Xj4gr7^o<3+wQ zQp$%%Hz|z!!H02mTM@6>T2n4Tg*{IxiCb3V)J4d}Adoe#2q*;2iI>J6)!-RfS(_JA zGvln60g>WML|<&F--NGptVUVb@X2$Q<|WwH@D2Ntloy=fP@rkpo4paH;4%;~?sEyg z4=#B_rK!hO@3(h0z1;w0)pc!Uj_9xPE%@krxf;QDkHz7u&>wLqi%4rS0_1jnx%9C) z+vl#Qy1(Z8o2e?5nN~DON#e#~Bd_T+2F0g5wAj8|a0t|!>RGrI<_Wi)=Fpc_D`&Fs zs`Htqven_+!N$he?Su0V!2l3Ia7pd*f6u;a*Y@teg9nQ4|1k3E@8i;`k!2gBykqBX z^y&Fi+q|tJSz2pTGQAtOc=etZ-Z%@^;MT`rDsH!*#XENBw0CRwH^6PC55w1kh2Bb>{~G ztH6vaXnstA<_L`Mz+K6ngwWXj3m(4`qZ!-^^IJ`BGJi(F;yGLZIA_zGM)dx#9G)EN zSf%~Hf7gQ=0<~TmJAR-`rx$+v;NUGdf%{wvmv#eujh)b3I4eKjyDrHHJT>M3Xrk~q z`Xh4S;v~o|NGgW6Kk@BW==yx})Tt7j-~hD6ejCYnRH3OCP0$z5fcQQ9%PsjSj#xq{!M;?fkZoue@NOVAXP#N zqCdAH{sS%=Vg*J+!ZXO0P(FGlq_L}OH{pj+L;+DT?0hO7*oH~(EQD+SS=hEUs^MNG z-v%UaN*F=l3yBK23Uuh5Q4UEOGwWfye|#`jE@)4|JeQtvL9i}`*Fvo+?F;FAY6%Gm zkkRJYOE9kx{Vjeyw(bL{n!*l(-Gumk0QVBxA*6N~u}NVxW-j{}HS#@TF-5%ZMhqL| zP)F*(7JMz>4oK@RerWiq5@yTw_@*qx*=74Yj*9aCnblnq(*99pY4AiJx-6l?MYxjS z&}HcTa7dsex6InuQR_F4_%+>8?(J z&RkmkWO4DY4;Jpw&i56ZlKA#~^joN2u94p2p#zpi@wWvY-7a*ub8)HsST7%hmk^)F zohw&?CBQ=Ck1{(*&b0F+V{K*k`#cQXM!}yLTzNJ+|4tQ!x?g-H&2R;E3QsMEI>IA=m$iS(6XEvEkUEaoF^;eMd zZoRGveco2)I3qV1tFKClCu$1qjn*-3Jv4PrXS#7@7DPS5Q%m45aC5@fF)cz=YsdJaReY``ATYj0Ei$ldD|-ZV*>$D;wkYx{q%^nyRgE_Ofy)R zcXxyppiRY}juGrwaHub?0mSO#HW(RHu{gAo5#fw*mGr?|TL~a99QH~K%-A7_HwTKW zkUML2t+7bbp<1_&5xZ$kv}pzFKz~C^`z8u5`Te6RC<8;L$wdfuHAV=kho>2{&|VT4 zeUXywwQJkvntIMu0dZ%2eSIOvC48O)qAO`GMA8Z|SpjS!q$%N`5qweBTJZ1iml!D~ zg{AiT7};s5u*u$EY37m>feIHeXks#&9K9T;2sYjXzFIhADv4NdUgP!Fi{FTW7~J(~ zY%w(BTE4{;cw8BeVRc5SAUkxwZH3;24!f&}5VfpKnV8mK<<-!Cr8~3E?qA)5-}HTt zTBCm_vaIL`e3&t^eOeTCmM_$IPL8eow545S{FO$VG>G`(Zx>8Jb z>nP^pUR^eF?q6X@$w}he6QnVh_Ho0Wz`y$yN9|u6kT`DV_O)+^!j7K_EAvkt#L8qB zKN&DdZ7s#(k5kFc(UB=5KBD-_s6>=c;J}%RoGnv72FJr>EE?`Be{A1E_)+hh=!9`) zY`(T5B2-mX_2QwOu@l<`O)mG1Fr100;P0hP@AmI4q zdq)QcqDLbGLD8IV5nvK>z9G!#)7AF=!RpiE68bb*_|>Hg2=Whm)EK-ru--~Nx8Dg~?q`x`gb_)-^uPEZYrl#!l1H|>LI)`%e>uNy|3zKO)=^n$UcXX9%ey1AP5 zG~z9Ge(7*Ytgl&Cu~kyxUzi{4k*sfM;?`Z{@p;!#oe?%|5;Z0es`jc+JT`igdmzB~ z;r*j(6^B3;4iw2LXHQkGS@4yyG2K6@myu1qeiM`7ar&qT zF7{*ry4Q_XF-7~aiu>*Tn!0mpHM=pcvVE|7#GzkAo+C>9#Ir#m_^xQp#18m5GA} zVR1Tq`qZ~DQ;^6ez-ULFp8mTI#zG||(GnXVgm*N!=++j$T=olOp!e_n`Ew)iCL&mZ zT?&TA3coOJak8p{$?d<8jz~@j>z=f>kZK)3J})veb^kKsRQubN%ZhqRE-4#mRkI1&!6>2X4V) zGuTzwq~3kH^ZYjp@w>_&v7WlZeghhl>w#YHfYW!Z1-LixiXf@RCpT9HLl9ZngUZoY zMJfp)H#Q@q6*q|EsJ`rY<7^X#Jh3XUq~Qlq`Job*|oS#O`8HoV85^jOgMap#fYyPXXc9eM&; z;;ZwrnRE)e+2QtF^-uq?SMT2bF$?Jth-NEcD5hUUmNi7Lk!K>=J#(%WyK!{ATeo*h zzhU)h%RGBGnp^u+dvbi&SFbbT>kTkTsj3wZ`TM?ZN#8B_t?Y14LbQcaH^s^aV`u<`;uRk^`uWM?q1lg7JOk)B-gdDL}L5;Dg z5+T;@_Q#m-h1H+;s`ON-so?0QyRH_bSM6x;FC?6!lJbJLr+VDw>eVeci%3p4v}Cb# z#(bOc5QumuHSB~N(ad-beiOK<@F@A>zQ)u`sz;1+owuUkp$z;5KAo`W=)f1Mp@^c~ zjb92W1;Z8HBfCOymcYtK!kI}p$k(+cm#df)HVuM8w{mL*To0YJ1&A8`HA|VJP0DmQQz6m|%T$1U8{0OMqc0lz+ zo*@$Dhu@xr_2|7j$GM0guc9>bO5!*N!;X+Z0<_nZhNBaQG^awp-p}_j&wKtp6<$1q ze3&gv4dGQM&iu3b23fYd$)uy`1Hv1C(IF>gTq*?Y0@k=~JkmAb9zSNoK?=T!Eo>H_ z-$q=Kd_AAvNk^?8c-L^H>d@&`5t+D2=OJnF*p{Z>cmBQk;T9(Q!k;>4SCVEjIu2N6 zXWUVKav5>WpGNk_+O#G?i@!lU`pm@~FNGHj3v+mn3o5STg zdIB;Oesf`0DTcdGP&_#9CQo-y=F~NZP*Jzw^~smh`<3clrCKgh$PFJo#jC&fr1eWJ zSxnKGx|v;{|NHgi!^4ZQKVG%ng9QsxZ-`PEPVL+zD+t`;=t7%RoNM8-)XL->r;wdt z$?fk;VRFB9sAyS#xOSvGIMlL3XIi(fILe`BsbQy3W&A_2z}CnOZ>R;{8`3Jo545$p z_Ge&_B_XFs$*7T9%OPo8@T}5U`s97{nap2kRNb?Q_m=4bnQ9?3B~$JHW#mB};$oeL zc!Oi$XK?iSH5Ox0L(xK!>K>@7%{x128L0237w_Pjb5hN<(5t`+D;w ze88B0g?_d{^NN6#emH8+3MLlKM~z^Z?lZ82zc|x;isH|&Uq@9{sc(hO#p3Y8gn|(` z&2z!wona;|tT-A8PPgnuUk08x1S~wheXIy;V5R&rL*e3(C=oclT%7M!#pHoqmyzX5 zpWU5vG0JM#3WJSvor^8R`!J*s>Tf?wZRJXr>1BYa$lxrB)RdPh&ZhJHYxy0;L{=Qe z21$~$dT*IACMlgfc~@)VR_N9h9IRkn%E9+HE-sF^N*>xyzpicd*NYw3t}!3_2wDaJ z`ni}#G?goJMo`oM+aax~c$CeyX6NQ|;~j&yjbvt~Sv7KzL|Q1XP)(8TGR{F(e7uQL z0;MT?_wU~Vp+AuWH_K=Vc!(PhKT8aL;}tpbCfMKb9;1TtPsw5P!HiIaNNX;iFXuCU z^3U_nT6kLR{u{~I zjxXzXK0|6!T4byE{n#z8%VEZezqE~Qg65#9i3y&XiLqdjx2^NY@qC?JJH#!2q-8Oj zsj2p6!~A@n>&^CC)!s=@CH;gxKdxr-opO5p!$Yv4KWkaS;7GsIubW|t5Qb<=9x@D? z%8lya&$DAQ&h)m_^e)(_o2Mt=IV>45mtv!EhJ9D6;G-|2J4!U68vZxd6@;6{^1L@4 zM6l$2CoBP2XnZ{vkfijhfs=$^LcdRnxG}W(A;nBbM~CRwFo}WPB<3WTNwJ4d)Ci^C zng5Y7N3-v;8sGz@1Nb5eb6@4a*jNa5#ODAJfYedd<25Te5DPyl@+_joT8xWPv3h2v zPNq%HWo%t7B=z7$^mz()!8ne*Z~!Z4b3sl}@TL%UP<|w96EaP^A2sj-;tn8Y3S6
    H8T(YHGT4OkMt|+NFLp-t*!_v&`KxfiZf)&6=?PwSa6ut6W?15%vYWUZ zd*Y+yM?!y_vWj79(l$(tcHL`Pa)nk+J?G9Mz=wscRdEqVvJJ z&9~mG1+biH9pRV+igSx(R@9r?j+C??O1u}_Y%;LSm3DO;Y`o812_06{>=&fe#pkb1 z2`?m^J^I#>5_#u|`={`SF>S}Ec5EvPV1y4l{~?viY->myJI^ltULNC z(zL6;qJG49Ao-=ouc*nC6cR!?SPCFpH_zii&tv(65WvcTc`A9h%$ET6M@MrJ%D6bg zf2_{N|J`z{MjSGfl?uZa_&^f^p--mo8K@b7hk&?=XsZG@0RpZs5ZXg!KrR$3nybid z08k3JdrXCwfXEyIDs70mqJUvd8vZa4s-VgM-NCi%*MF=%c}y+=M$ib3F@yvU@WVJ$ zYAL#G_0^7uI7q!nOFgG7$CHl_a09k^$}4b~5`fT^^Z+*6R%PPHrUJ_x+ktx zPwc1=ewJtA>VXLz5?}vxPJW!O7d@5@7joB;x0mUOO)svj#O-fhNROy?AKh@Sbo$Wz zFvOhkPk~q^L2i7gJ>811)Dz8!Uz3$A6V~7}gQE)v z)+^&{mnlQnN9Ci9DD|-SNg*(QUH|!_j+FuP7R6~*RgIpb2ge3*t(0|eD87WPhDCUN zL7vT3VH-v-64^r_v^{?M6b}cvZUNa43~{HNH^lq^x&^c5KV4bnL2BMK@-Gpym{#~A z$g`1#AC{?)77`N@f`Czst_6hZfa%QdTtj?NQX-200RN^@NVUgd={UC(KL5>-MXYLm z>Pol^>0HUS2P9%7(?%GvdkRL7RvxKZ5wPpIMGxyYlA0dw`!KcV*T{K0>a0x%@_(Vv z!(*GMyvX3Ia~gIK99_TE)2$n>Df;JWjM`NG^C&;s6Lpcnt<6p3^#NH*tDYtH$ABy# z)DQZXQ2T0Fd*z>X&#p>0l{+ti&#n_`n3yD#)oSu`eV+J++++KhA8lTfK8k}Ba#uIp zb*@Fc2?|Mi@(r4FKNj`-4g~s)x0Yo8jqf;@`8}Am`A$aX=q*7$H;0*rW-eNZw#;l8 z+H^l^ElCens$$UxOpo<83R(ODdSlrAp2UkhPZwMYdKMQm)!6#}Ad23evE=>K{Z5;V z9ovAoH)WN-7GZY+P>N1K{XRF+mq5a89dNdT=2MEvIc_;Fs#ZN#&+3 z4K&=wq4}2gbg%}6HP`lHKM`bU-c?j2MnVBZ;e+UNPzHbt3-WqM^4Qhn!hl%uJBYi3 zh@?Q?77Q;KT7Q7hxl!Z`Ncn$)Iukg(Qzpc4IIctU0IJG5fPzqU1a$Xm(;rkwx_N5O zfp1_+N=WV)Fpz)>Iq$%%tUd{Mk+AL5Stt-dnLr@y+|@oR$G(l+p6-H%M8?JH;@AI% zuviJJOv^`oY-AF0nD=ChQ;TX%#-@5JVY)V5>BQ;qn^Pj^TWkk5Wa9K#wWT*`9jQbnA-sANuT=9S?gQ0|DnBKbC z#SrgC|7|_Wt4vYShhaR6OR3dnT3XTE`d*<-TFHNP(#9PQNHb_0!#A83T2frwDAt+X zU@^I^?|Z!7Tl<>cN?(yGrz;L&xggZB<64vJi(k!^FSrkks1f}JvO zyAkdRFUMD~`9-oe2t{1z%LIcD6gvPiYME02+&;q72Y3#)U_dgt1rHFKNUFNC#h$A1 zQDgjujl|Q6M|qs?NFx9Oa&a8}^@+Mhzk=teK|n+mh)KKy=0;%q6{LRwGh4-lsVet~geAv`C{g))Y8yG%)~w{+c=t67Atw(o|V(nE2DLY12zRxs0@;Z{w~ zS5*G|uz3Gw+WbaQ#_1L3L|TDf6IE(HO;du??Egpb?!tSHpFe1xaLo3P#P_2qc@`H{ zt(aDbf~0zEs<6i57dKG1wZs_K%~Ksid?T;Ct8k$xy?EVi{x!?3cH*Z8ZMLcYp^-8s z8uBvv9X3Qpj7#fJ*Vw?FSnd*Uwro}cn`n<+`UV?S60LKhLFd*|&?7ms$^EBQrc#>S)+f%=-uG#juJ&V z|KpUS2lS}5nnUiwqM{4KU7sZ1F?6R%;Zi+Z)SU8Mq;V`I#K*3E4>ux`dLn9}aXhIE-Rhpb4{qsp2mqLfWBy>VMFK^r(~%+xK% z8sR#eH_z=}BhNqKp14Pu!IC`ZuC#GGBcd#vB&{WVzxP1op-27J7l$5~kB&<&6dCwg zLdRB_f$OE~dy#}HTDJ5*7uwD0no?CI*VN@Hzc_#Bj_wT-Yh#x9x0B@=VMbKQT$kWe z37LL5*TUkba^13VCRa>ElU)xp9;gk=WHceU6tW#uQaTyNJO3JNAE5u4hLQ^A1UkEH zIybrce8v!q%&3_x2k6rPdr-_pzFI=3%lo!x43vddG@-ft43gB+wRAMvbjFO#_huCAA`K5ZDXUN{%U8 z`_an=!`ALq3r25xqS6cQ^gaz{ zK;5W1f*o6HD_?3j%F$Z$JUwh&WW=$6pfnIaqCGiMUW1uODqKGB-oo;}5mb;~AoZ^U zM=Nha`tNXE-!}Sn5q$|@f++uY9jwyofwTqLD0RrT7ES}4KBZO-a!%c%yS2L9&%0))>aXFKSkFeh8dh+qvTrykUA|H5>FgyV=> z4HT?l7SU&_s`}ucg`(`hYWp^z9_aL3c+$TEt&fuVKx*s}N4Jww+yn!>xp@Hx2WcgBuNRl22*j_YKHHCu2WVP!!pIrEtH=s(IAHUJ>3 z-{`oYG2E0ereoIEj*tIb<(%tlRY}P*mw4#-pjib!1|OtGCc8aWc^-HjfHd>lJSj#W zcFtcTrsr4?5P?4)0Mj;L^8wQ=lO@cG5Wfod<1Lsi&}s;5yu2x(fEzfq+e4HSrqg?{{1b1hbViJs?Y?G+xA}19=62)ZL|0 zK*ECt2#p{}Fbz@BUfRiQ!1F;13>0S!V~>iO8bN$JL1X?>cY@jIAPO87VJlhN#u-#R(GGsF3NqBR{Z=?e$FE`w6`w{QW}QQlC^fsP2t^ zpV|sOjS0GilNiGJ@hC)Brxkm?DOe_|r?i{D@|S?Ta#J(Vz2I95TRAqCCT^o zeZ!Oy8|yw}yl&ldHNq%^g!KW3nRh&{rIaJilEayk9v9~FMt_Q4y8A^!e)|NM)I!#&)SqlPV3F(-WhuI78Q zLdP4{kx7(~y&dr}BXpMVyg+Wv6vU4f_;z-@A@maef(s^f#|{7&6EL5{W)fnl_}8C# zfDs|`tw(7V5YqD#HV@v&Ivy^r;2Q965ZKNHrZg##!Jzk5j9GXs1i^eZ(~TDpb028xPc z-8^z<{WQ}4Snp&;4-x&rqR|sssKSYGTK+xhd~E>stBBECg`JHD9Z3#(J<@DHp?Q0q;0$r%(o5cYNY z1EfT^41SzN$RI3!_^wVu0FLd{&wu_yc7Rj^LKR=ngDg)UaBc#?c_RWWYQS?u*z-hO zEl=ki{B%sh!sV?hs?bBCO9U7=Z$Qp?4hLa)NXdZc=t1z?3_%r-;wx?7n!4zyf^)RvJWt_rQbfyY>RTTYQxhzPncgeZAa}GFM7;P#ldgw zOw6S9QXR7tiQzN6L#9?$T}+aAJ@v}fL?6z{_Ko*8T^U*BXH&D37#9~)_vHzqNUVzl z7543i?PPg`6djE1{qC4_EzC2r$%XqgM^PRmi3PNow%EQ;)y)umVyN^lyFjb*Trt0i z>v0cmv^>v)ob}2x*iAh;D^>4ISC`_T!4cb+X0Rp!%ME+=jvd5lf_IcyJD|eJ0 z8FZO%XXvfiH17++Wn|A4&+s-Sv0}!Ba;|bbYquu+v4er#L|Tets&Z_Zx<%p`P-YqCv3isX7=dy=oTeT{FWQ* zeQ_g@JJ9-x9(G94vMuAJ|A?se0&zS2E2kf?lwXfM+1KI9Vxf z)!NgObY3V34Kw>XJWevm!IodFhg57EjwH5{DS~dTL{FzjML9kxY3~$Z{jpKUv-H9C)zHW2 zUV~tAF`TO3`pp5eVH)0F@G;^&Et}TadUhL{t?A$(&()@F|A0tIpe8;1wz}@iSEk3) zyRL1=xKC@M-5Plq2mjvLt;07#pb|(K!wZwOaO?ChA`vpulyh)YtNQ?5^B>StAs^s& z_BOAwgHttniNW$}tz;GcvME3y0Yx5)4!?Nb54ZqJ z)h)#Q`2Aqi^Apl#`WhTl*uG()AOc-LwW!P&I4Q`64e(TIlnRETwEQn}7&9 z%y+46Si(>Y(U=8$1wA&xK^mNy+?XOAY`Y#vs-Yi`#aD=?Gk;`;6!NKQxZ zSL6r?5`Ug08!TJ)&!~;PAyq5ep>1hf-#LcGGEp$N*e4fZ%cax=%LbIb%u)Qw`Nkh> zJSHc$^4;y542@KKruI7~EzQ;ZK3C3fg`9hdj*%9=5nlW{amh^HD_53`MOLFjnY`yp z&7~Ld=(AuqyF6S%ghv0G?F=4)daR}ac!{IL96^iU6APSWlQG~M4JTy+W|D?>q46L% zQOqosrDs#SZ}Of&Q&*_R;mG0-Q7|Mt-qD?Pfu#g&9oKh9tPR0GBFQolx-+mWiWp1f z;O1_GfTXImdWV%^aw&+v?#kDbLf@kHc*Xh>NdWv)05f*_v=K8L$x-)Ku5xU|5`OI= zofSy80Or&i5PGSF2M8r1cOo5Yf~ezpP|VBGWOmf7$7>JA>+!1LY=8J5G$J6uHPhFF zFCI|hx@c<4o5%9!;povz;zN@J;cGjjonp5qG%-C2i0`XvYo(Zz2x|n1!of zL(PKKU^(=Y)vtkG0hxL_eAFyJ<*FId`~;%0`-~UYDZ1#kmj)5D=3GGiST#tLCgRNV z{F%`Xu}ft6B3UcjU73@xPG${v7Q;@M9ql zm@8TYQqxl=acS){C8fqdSA&^Vy_-Y=_Em7TMg8%tIos1Cm4`!}`nNt@2{QBO z#3hKlKBEA`yZuzSH+Kmn0083Lu_N0d4}^pr25im^?w@H#HNZ*9crIq=0~) z!dfMfa^TO^mXx~V0p2z)IxBpI;aLWrVvRbMB|+DfZ668^)7?8_zI~IEe1A$#Nk|Fx zHp>Lnu@?xqZsNw7?0hRd5^T~4Fr8)}>DkZO>Gkfb7C+6nFoC_^G}`l?gpx3OU|)eM zEOwbJVYxCGr%9pW6#uE*a&PIg2OAa4$Ot>6G!irx>;toa}>C})O%cyM=ox1qzYIwQJ!CwT0Agrx?gDZD?c?bdIAhil{jre;^)EhUFk;JQK?7jb`pfk@umkct{swWy-P7(H?Wyl)?pX3!2y@85>D18rQKND zL+mAtq#u5AcEb+5Y!jejVDZXSwp6i<4>qdonp zyUp_9DD_%#!ON4|%KRsrKH^(9o^^31-iS77#daG7C*Gjf3%24|??0HEdn<=6{oAw{ zBPe-9eRHdpMd@1a&*Izp>6h6lGkxkZLreYZ4N%w^YLM^V^&YOlhk`g3J7+muESD)l zFPq#bgVO0h0YCQg1-vzAGk%8=MPoqqU~N`^+wel8+D!oLFJ_Dj34D_=`cGa;H@&!x zFg{poy{RlG!GUm%1|VJ{X5#(p-ca+wGvqwlk-;Z>%AEgR3~D?oE)bv-3Lrf4pM`h) ztxTF+V4zhV824G${QBM$ZmavD$e}C}?-7B>)w7ZkCyJPPb)ttkimn05Ep}gmSWdVW zqV_WszwzeLCa*M~`IKqRdGP#{S;Jnp)WCcC9dXD01=`vCfg5GU`2OKC@1%SE;v`KH zMky~OUH?n_)a--T*U9AQaI0^ORDs9Qz`cwYoT+x!CLvta#x6DX#af@N%b zLHM^jY<`vRWza&5!$J=dST_QACtl+S^8koel844%6hIqaR9{Yy$4`Snsc8V%?HJoR z;5vQ>Y1XB8_Yu<(s=GeWWahz?lPsyxpTNl2C}pKPEqB%49O1NtB(&cVF%1R~WJh}# z_9dP$j;?n*cQh=z((Blz;xk8G$;@I=-pk~s$>C8pmylI zUMZO$t>7bjcUE3r-e#x&KR-)!_g{a12b?RV_>Mn5J_ph#KI9oVB{q&F5p`Y-f(97E zYAKNI44fDo9H^y@NR z7Mn&k&R|;6ov&BhIT`@Q;+GJ-3iSv^SsYkDya3o1?4!oXPkWrHd)BjX%igh&=kpUR zkBa(ng!&lZ{iU?Xz~yp@v@AOtN`8^oBU+kkWV#UJ$Ui+uM$O`JBwx-zqUoPV5bQ}N z{8Ux@Z;y`!y~%9E4F9ca3ezEXjK|zK?eE*iL4)TlSVH-$s5>*ZVq44#4$|;F6|?-+ zeQ-yLkFQsIG)z>5Mz3_-&f+=Eu*$8tRTHYd#_ye>FIZtG>(BQ>Xcz<_$-YYxcZnw1$jU1}J zh=>jY{J!Y&*v_9nUnOu22j;Minrx7KGW>jT8{t7{UIYbL zJilPK=@nRee=kYS*(+yyg`AMUn|e|O2akZHikPI7n3{&B0PaIh&BC+LVLZ^(r1~-W zH7231RBh3wqmRHsbIN2`yl?7kK+~U?LB*KjS__U6?8}AcQu-bfCicazhjmIE-n^X4 zEg=aefwFzMjp$K~S!s7+EM~fCI%i0rF{7FOP$Rb_HkZnrFgd=#QOFDF)O_j~QB8oK z6BHz8V2HwWU8mLC|3P{2-F@UBd7bPXBP|I^ghC55R10C2f{FJGd@Ry%baD9UhI%UO zO$6o#^#Mx&TE7e@#g?w``ymY!CWe+_(})5L(pdD7L1Cc+hB4!CnKda6;szmS4A{Am z08)GEUsY8_u{O24&`XG92#_`!2*DgFu);%m$6$Xyo!BG_p!V8_1f-aU$o2bxIEvF2 zy=?yh5-upki1&}cWH3i8Yw|^n9#7ReF3K&l#!H1J97Xqa6`3fDA1)WUYyiI;o-xA2 z(XX!q?QO6<#_Z6>3lksLHX5ZiLxlkWUGo(=QL1D?!R24(hCdy3 zG;8nlFOr64&wAO}w8rL9OVTq8NvXpw%n)K)5F-i+oH+hj9o>SK3O3A0#Q|e4%IAUy z;tLFLeNaux74NN#P$HWMcw5mz1@I!+is6NdZ=Qqfr-(uW8ft3f#ti zeqVXBzfpAL{3F&DCyj9hy3VTJqYJX3ZC9e~zU%~!I0%OWah-?}jGW!5- zdbFrsdk@@tyFNcB&_5Nr2RA)BPq>8se#i(?ib!@Tx+INV#Uc=-Y}PZ}-l>cD3ODn3+j{ zf;7I`PRk(G?3XVsMN~bt1~kofpBEG#jqz9f+cYg_ttfKp?h#SD? zl4tx7f-NBSO$X%_!OQ+WK0bcin>*MaVS!)2UIcI&w~P7gq|H@FN5^^Sh605MweaA% z!mVIBULye*uVh3@#si-qHQ&kdEd~W9o0aoZmz3u27MB)#MINS$JjSGS zH#r_3r1ax&7d@}Y<1`d`ygX{^!i=fi%{jDdD=wHgk#{ThdIF2*#6*sE%|cy!Be&lw z0}0%j$!0UJsYwA*vLC>|0Qe}hW9Ur*@%sq@tk+DlB^QUtP?MbGz9|P#L*s~k+pk|R z&C&Y<`<4Mzu_y@s=9M1;gF3z%oc;(pLLI~<2Si>D#cVS{YSj2)*t6^14uX~-0YIe# zr9mlfs-sVGB=dr<)>j^aolF%AAW@owi zG7?YM-N~}@wRp^5K1(ZwxDU0Tx2cydsH-h%VuM^?ZiG8h5V}%hhJbzBS-Q(*>$22$`+Cs(H7ZJm8rvF%>Q)+IBx?__5BSYH825ddqp9C~H$4#wqnT`mF^3q;G7DJoNS(cre|Ip~dEp zfdh}O+wBjxlY9E^F`!^6DAQI%jq<4Lj4|Jlg1N z8;6k;*~b6``(J(>By0d4Iovu=7*{*f&r{B~E&s@LTT z7fiD&+nRYz&@w~kgN0txgSrxf1u?0^+2P28-cI%IgVyggp}V8XS(>{;$FpSy<&Uh! zr{ZVC>KDNs{k23s>8B=x%&fn5RX1T=U{(ylLY(2kPbDV z_+V#!;Lgn}@(g$p{!-fdS&4X#9b}F)fpOCdi{}1!`Gzt6jgy7zyru*VJT}EX_JSd_ zUu`ZLh;%M9o5>8OKHx~(shheyZm6p*{B%RZe&T~v;i=kTxWB3)`$qFFr|kXg){uxL=+feq6v14-WPLEu2J8F+Y_?uQKJ-jD z7XxK%GoIoj^b+nG18DUS)d~8yHT>>`6)wk2JoDS{eOUq&S~ulbq@OrVZMYO!$g>fO zvl>mX7G>-!6GieLn+@S}y^bu39x83w#JK(5Q69D+`5o)j*uKr18@HnGF`LwUidm8G zTJ|27$;#vzP4&hz=Tlt@%^-Rz;Y_romFdcO@!{}%0k0p|_}%FD3_Sg&;VBzAB~GKH zSDo3hJ>UP#`8f{x3(9DDesGTF`EEFkX%))&kk3^xH=wcKEWAWAwr?BsdAmx)muaRDd)Mc?lyBt~m z_{M3@R`&kowyu4L+o?s$djh~t|4o|+A8$LtR6U}-3*8vR0Rnd2!vL6vgZxqww$gvI@ zh|~Tus|%Q|x^=8}#{@rN`IlH)Zg7MQ&0g$+LEJGdb6_pTJ<{>H_VNeOxiG#DTJkaD z8ovq@$iHeG#aP;TYF|%_lkO0XEgOE3mab6Glus2vE-tFi8uKwjyl-`jubH%>e0H&% zDI1z)UqpTd=d3KnN*+q|(INr~^agL6;yVoJArKse*8#eRp4xoh=gUABDzKZ8KkIuJ z9ZPu955TSfG;KBuJuCuWNzUT#AA|MsWOhDsCz`)RJT<3xDvByJNHr7_dGS$Dz@AdF z+GS#HLcm&3%8JmK3m%#S&CEXUb-yn2;!4CU{QY*iJZf&uk8?nERJgWzq(`6|HlS-6 z709f1>(_xdr5ZmS^U_AS*-$9$!{$@1*GfqOw1t)!u8|>gj;}99(t<-ve$ScC1fO|S z)-1@9|3~7aT~u0o*+@M628kLK|6x`)%fd_70(auQ_@ckhlhbv3_FoR&FZ)$Tv_yS8 zENr@M_eZr-CqkP*il(KICHb&9_GcEC!z+)$7E_O?nPZD6wXwxC&b20{cL7a_EBrA< z2RBC^8rPOoWbSCzH`DAm^a`XWj$I{RMegKTns{UQr3()^8)G(5V{U1Vm*R&o;{nP+nZ~A zZ_IO**zGvdt=o9q+`c&~ikJKJ+h$ywyomFDhE-Up>hNnBnbd;s3d&2xV{&}KO+2AnuyMhS^$EB%meYL3m%>J5gVO?>Hd5HMn;BaI} zfq&=uTj^Vd_?LRHrSp;751E*Q1$#T)BVz@l4LiSgRQ+7>qD=T8)5v;io^QK#^;M%D z4aX1xp>Et(29>3iI#Ftl=qQhsG(kqk$C-k^rO)Yt8OXBSxes|p!bo_w6zt`V*FTHg zi&I>8X`bu(977ZvxAh6XmXj%bJe=F<>L1!k?2-#pa;trav7XUInoyy{>J!i{pfCiO zfa{~)KxBad5dKgq;9gzb1sXxr)FUnu^sC57873s;Pz-!mjiQ$qUbe^iEiW&pGb!mv z{cryP-vGiz^|$A{H7e{_YJ4(Nx-6XteD5O70|ITJIkq2C;_52abVCN3CwsL`z%2*> z=T4V=#nuOoY=lQ@5eckbl4Tj<&5Wd9J3o?~mAr5+m$CJHxXVceW8ucg8( zHsz;QI{_=E2W*=U0

    AXjqcZ_C3I5uH`vtT@XqT&sa7fWpUq1ZL*5bY>_P>NW1l zOcw}X3dKV&oenf=M?|Q`z7J}ROVf&{{#9YVaIszKm4j(-^8G?= z+M5-b)XMB4Fmh=IX!G>(Ja2jN1M@Dl-DW_{Mgx^7K2_q+3EsT<3tH(9&|x*f=AG7>Bj2Lj5WbV%C0-`Vmo1AzEZx#p_nCvI$^kGy;(nf-2quG3h^gA}p#Uafe~QDh0Gj zSbxbi>p^#m7&u^+h%!~ai(x`PqHiqW#t+h`fX6q{JM|IXBE7@mL9HDw@vJOTp#C5x z->IG4@Y;CXX!3K5*HJj^7)W*tOQ2 zlOJL8UXdEP-mKm(6d}x6Wyj}zOxJE@>!Cnu??V|{LMtRoc=)3*N0HioFs}1grFzj$ z+)B?8yHqvDLgb+Mja+!lKK}K3rz5e<9KX9!;nM$c0iJ#K;m0N? zo9|!EBDcVD-EY>uI+Um33}1NqU`e{ihA-o~Dqf8Kc|uT>5GS;<6iC0=Bg40zl_#&`YBg)u1LADSG<`+ghT2bSIR8X zAB1N1YFfDxf3T|PnwSrFu={4G^I>npC##-5$gJ-l7cIjr`qE~)gmfAl9A*MkvT&}&owJIiv zK762~!q9IEd!W~{yU-_HMlPAanCeQCC4~x`2B$blY6K1%2+7d}3sdZ~g*KpPS(g3r z2UPrZ(`V?RT}ubNr{A|G!E7dmXj*2ynFheSu8Ai_&;^3&VY1bSUqLV$ib1tDC}+7C z*npVAhyaJ^-PoITnUK9{Y54LUDTsYHukK~B5&{D&C}XIHp{Wh0h}4(SK{%W_zE zXb&ZyuFuwn%xDbyw)f;>^;S#<@Gan$a~8d%yF0T5LR8 zGv#R&ztND=^GL6mKFFn^{-sqobB*ipI`M4lrx@F5+Q1M7{I#g}!ypBN9?P{;;$IFAg_BjqSZ0Krf6?^HHQ2sbL!iymwCsNFBZ1~S(m-!l73BS#&clq zrs_TZ9Gpc=%Sml4l9@PHBzWreH&h60we(>h_ZtFt;dJ!nFeKxnnGi{7q1FOe2G5>#hrOKs`r103d;2*SWg*SY&N^~JXK_!L znikjk6#UEFhJnUyTH^1I3$`gwOD&@M-VaLz%c?m=Sq!$c^=)ggi*X+EQ2H4&B*17&A$~L+k1bOpY;n$y}lW zmE{b>sSz?fWivua%TM>Q=AYf|b8D*dhw$42)~BOx@I>c1h!+XsRdDi%+a)v82XZ&& zW4{iIN0zday+isujY7apNa>e7YBMtao5_I#0Mx>r;a6a@+q-9~miwb$T`w55@}zj^ z*}&ncK6&og|Lm%u#Z}nI`oaf31%fb_Ew~ugm4WS!K2LDtu!S}QsV{-vzAKn*Sa21Y z@j!+jq&p?6nh_KDqMHiE1_NH_f(f7YD;ngsuYuBvEVNLx52RF=HpmfxH2XfVli+-Y zs*6u4N@pJaXczsh zEYvLcd(B>d!LnVZ1ygR0y%B)d9-?i1PDFfQN|e?07Ri`<*w$FjN6a2@H{D5EYqZ^q z?lejl*7(UrkV}c}YF?`@Px9wapX4FqZ{SI`{hlR~L%h7LedZ&%@T)ye*5|Ef?Hy+% zNPL7x!hOlxQ#3;UCHFGjGZrIb)?Fgk`Da*SrQbZ5enH3dOtM~Mseg>?ukTg;Ew8+z zZwT?;netNHt=G!gG;g)MX=e9*dY*9kv3a3kGhb+w1Fgs{qoh|IdC9%Z`2zF`)Ft?L zX9L>Urye+PeCnJ1u=|B$+Cb+h`t8USamU3gf>xt%RnlZiL~ri+!cB!daawhqhq7?0 z8l0#m$`4l!bx?IeiCZw}PXWtKr6>#LKHI~UvT3C016EByRc6x%z3{TC=4)o*vAy9^;oKZvhLUDm3env*MIDB5 z0v-kNj0*KUIHTR{IUAqNicMJ%QLyH=oV4-~6(kwU>`r_Nm z=9sh50wSbGv+P?59%l%}CAoGkrPCKQw)E5uyLY=>AL-k_PI=Cl;dyO(`}<07$Mak>uHR>65lKU;1=-05$bVc*l;E;3^ zAx5FaJL&`T-JWZqXCoy)LP2@d&RsOtXK{Um*M!DZvS2mLJ~<+dQ~TG>Xo+!Iv7Odw z1)aM8sd?o)*R<}B!BJ;Fiyc`My=?kGFht1Z6yva85_|stzk=%Q2>wh(ig^y6@6u>4 zGUTLtkyr2UzcA$`jc27z*V&Xh&msgdAW~N*aE`v*6j;Qm9Mqf7P53UZDC*Uu?v&x^@}1^6Oe{98P2@nEEWMy;mew{{ zW@)(7pvQ&lkjeOMk&IC-XmIJ7W@E|sD(QADEj@P@*ZRY*{WiC@^H#+TqL%g@uVh<)+nut|>(a*X z^IE$uSJ3T^Saxh^V5_mI3+w?;dxzpKn0%{av=yzeqq%7zmC>ddJH6pDDu!FvsoQKD zF6sN1sWo>%uXSvzL{RpxL@P#){t?XWyh`B28cW2rSnF4^U|f|$0!p#pcZ@UH z%NnK=V`CRAQwt>`iq~cI*@sGJjX5b0{T(S_FEPo0Qb1wy>jhX}{Qy2sFz_IO!Z;)r zBYth47v!l0kn{*_JHRi1>x|6K$9_~Ug;wPOsA7%TqFII=`4Ejw_z55_exjEh?5KIDu7S%Yz`zY4sk0feECcaB5FKl2p{s!1Q9Tmb!VOpdy0w#q z`B%HrKzC18xV`ED)2h~idXMsp=My$I_wWucMk`;-pP^A#q#5}L`*b=|j*-8jn~(NX zhkC@z{_4En((CPwrgL`D^fayNTTV!(3yWv{?5;LTv?ShcRel=BJ?Hw9(UQ-a`&W%T z{cQ;?5vjz^a;-u+%e!v25*HA8(E2;RM~9|eipVl?oUeJ5K@}#XSnu^{^o)%;fiIml z5kFIUcN;-qa7d%Hraztt3GZ*SLRtr_-nF=EQG7pzIZf`SMVR$bMDrgMPpFzVO%5cm zv|pNbv%CF`rI5qcEKn|w#N@G-i!o#4-H$SOVv<#1)*_Fik6J5k(y=;Ky4D5IX{BJB zejgp={)r*^DySA`$bLwPzzPf`;y~u&{J%VTgt%wg;sj7s4m4!ybZanZLQ@5g#}GC| za42|z^8F6DAtmLB2s1`bik+R-wu!LWNAN8OdK&;8UcqIU|8)(e{G-y6hD^v%m zcG^=>>y&j|a!AKUuy2@|v>GavkdSD;@S--G3n|ad-GRFALv_ruR@yr0_G(hWDwQ|4 zmqQ!e`|?JjC1}Jmcf9REi8rAhr+T!)-`XNKw5Teufz(k;%E!WH385H*`b<%^3)+iH zMA@=cSHN7xbmGCa)HUf@ zdBg~`{oZRv(Ao#VklYHEYe!10z^Vyll!8Uo4WLK`)ea=-fmA18h5-5EKntV!T^DTL z!FbM}bBFrP-C5i><9FVHK)epkBcR=V zLrdoCj=bE`sVO;(Wie+bbd?r5wJ!-5ldW{^{hOtK;i9ScxICSNuFlrIZG^hqyRB!_ zL{6WTc(Ob}5ycQOI_T=KB$Qe_cc&)jf>G*q?FX$FoCr^cuOr8MKRHp-teQO9q!O1@ zy*pC6)z2a#AgVD&muRTm;-;6+An2%_+Qg^4+5`W2minKKtno;N_R{5An*lMU<#&!Q zK0m#SD}E7%=`+5_PBKKXaL&l$rnSKp4p#J#-xQQekgTYMXeTu7+CgK`4H1#DE{_=%P_i1CNCAZlc&?$qh5hxJNPwK&2saK1 znk_&nxDT>JOMn#;E_8j8m!HZ#;qjgBC}LbBORd*xOjH~S!Q1Z|22qFD zczjq=!R9^6U2*C#q-#6)W{hElRZZbIz7~S{o=O2XEU+ z!A+{qiYao}ZDw-&xr;W&32vtOA_@ITa|iiFUgq2JYv*0`+=G+#Q2OyFhybxxKY=9$ zmM93f*?PKHcE*FA0`#m7AeDr&hd^lpK_>)6^ftt@16L|0fEELpKD?B%5*@533 z3E`IjBLwW|EkT?gB#4E)FJMaUcLIdU5MvYQ*F~*&W^rkq!*3IS;<|z()D@BGS2u`)qh+l=7!FV16qLPQT*3!i}OB@#Hc$R!YxJ zi6dEL0zRdnef5#~-k%$d2B#n2XzV0aiB+$*=1#E`jo}g}CydT7`}Q6;+4V;*#PT7c1v?^D5n8JM#gz3u{Pkyq z&`F$EvZrEMwX4Kh?di$|X^ONW{`!8EwOG9hWC|2S^EBN=?xN;PgY6BAS-B#gA3@qI zXcY_g84+2hy9Fgm1*3Ej^$e)m0ITDbioySE<)M!O;+-dpTYq4FWJU?P3rPMA{;HtS z7#OpB0iprWQm7$YA7#2p)s7wjiDVHv7CHH{Huu3PMd~0wGT5ioL6m7XNCQ2DOQseM z(IF#aB)C0HEb3^FZWOWBo4nmarB;?Mtq>!qm~XxRlS}i}&0xpC&rM_E#*(R3*+0h; z46)OE0@&F5HH zVXBo5(fVuB2cO|@;;)#c4~HE7s4}vaoGRE0KQ2VSQVzZ|;&S-d=$O7NKDeaR+7i}K z?Op9xxc8(Io*1}%YS*AMo8*;3R~l&cE|JP|l3)-}z7B+N;$8l|GZRv-lAI6!O6~Ji z1sQva3+G26RdzfUnR=ysO?)+{-`0*^e}8{;!4q6Rz!o10DU+>l`a6CBD>){4Z$T(V z9eN$W=Yv4dL)HwSe1U?_K#+&Y|JbO^Y<81cc6ot$*8}}80?b07&>R`IeFAd~ z64DF;R`>z{ay$+EdPnr#+arIV6ne2*=cZ4D-=hKUAIQ57*?qy1NEI-bk_u^I7`yox zKNO9>tc`nmsMT56UO~KVe~g>>tvwRkNDZ)j`t*s)h zF~xi+BM+oVqy8wf@V6;28Uee!w_r#sg$GFhqD)W#&Jc*a1Um1p;IuO-_?92s-gyo> z@UF=bD2xuu(1ctzVCxG0s(^1zYQ>nj=^d8}D@BhFzp?nE5e8%5rgXu2NB*RyZvql8 z^FH<-m$KVtg|+Jp3M|E}$gvTn!l_wgePiJcO%46#6Y#d?EvZ{~6Rh5JU{pA%Nfht9fe>I3@(Z>U?!e( z0Jsy$yMk=AIW!^AlAHj~U^F~MZ(!w|xR-8nBT2=vnR~o=Rk%mUakr=3kY_F?09S8S z%^SMMyrW^PF$V&*`0WDVUlr5)t$~ga+BR*`Ek{q(f{9TAoGAT zva4yvU!ZNvBT?v$%Zx3X-eYdOk&5Pbi;hbyb&8QvC8lbXHqWX~T@7hVg}8qbj2GgK zVG_HXSTngTR$B^DO#i?H5_krlI_5-s7Rz`i_Bw)mman z)O%i!Qd2nTXc^t~O%WxzNox|pnBgJcMa1Wl3u3tUT@o~9Cgt0ss_xXL430p33uV`U zSSd)laT8wh=9G+ljxmd9wncdgmQIJxA5AGCPZ{L%fqqITD){;Hgj!cVi9@#5s;+yP z|2^fbZ%A#KdvoPID%G;smS8ksEbC(`E9CpgS|5y)J&Od3=Eo5Yb?}G?X(Y_FxhJT+FQBp$0h^kpuTR=XAxu9aw-boC*ICVpgOUo9Q_l+TU_WgB7!GIwPba{ehiBY!936_79 z&h?64w`8v=C@szRnI?`%)um{!c-TozjV%ejn$2CH@sZ^ul!)R!PZMGl;=G6qd6K4m zJ5h|gC$XGXX$TsvvvWrWvM@6Z%)6B;&k!j-D`ml;OBG4$N$+<=2G8GOBh)n> z4AU+L)qd+S7lO1y8nYaxtGU#+laS`dS2w9R&{saE#IDA>*`zv6xMZpwmWy)}l;r0} z41fJK-gyB2rDgC|ZgH;0R@CQsLpfsB5Jh(u%z@{D>Ex+Cd=(uA_Cc>`<#4ah-S4*tD>#mf~I{QCTSvqInELv%%vx+Oj!S` z^;^tDt)2n<@9q~#6uDY@lWg}kkJ}cZSIJQ!*1fw;N++yZ?K#Wop9~WQp>SN@&^N`I5`-#^v>(Cvb zsZEPIwhe`-EI{?(dvVd@WJd^d}hGdsY7;@y>YuG6)$(@Q`S1DHk~os|C#&Vqv?%K_KAX&jnLv$G?;*kn72=8IRQRL_*PP*#7Hk3O#~k8Hw8@nodNbTuuU zx|!!@VQn4Rg$vJkwBd1Y>=BC*UMWjhy9w>_WHXwWT#2#f@wRI{CapUI@*+jEJA=x> zys7^qXR-P8h^Og|mxh|dhnYdriF0>W7Hc}Q9pDw=cvZ5|A17N>HYewzRYu|F4$dAX3E%cR7Hb9t-3)oPA?NYHhCsP*2o#f zxVC%B{jV#J-a;n0{!~dQauBFbHVuKh2Kqq*Ng%+T??MmXnH3ctG+2-$snJ^q zdMqHoE)Xz*l_TiSX3yQuw!NlyYDfC+6%bx5*rnM%Ww4&>OCw%c-26W+zypO^6GL?3 zLq>|?(iRhfwQ1RkO(Cm^;(Fz;nQ7%y*Q*nj^~)sMBj1E-9DSFP4GGrFxa$;#eT=l^ z^*XdM@z=F{>^+|UveE9vlBdR`IaS=n8+n-{y_-)& z5iW>Qr+cXLi>D4X9i(`h{#h~MQh_qRbjd8$N-{y)?G{YB=e}kdzBC4qouMQ*-eEqJ4O#D_FZ{D$Rh2R1;2($z|k30 zIbe}N5p1sI-zBreLA>M@c z*kGs04a{=@fd^fqP--{W0{lzrg4SqYbP7t%mjFElU??n*wgikDV)WhP#F(hRLRxGf zu`KtKI9=a3rG19`=$lZ@|_=;78xh1bfougUj1d*#S z5{9|EpX9e1B8|_*bP!{!><%OYmu8h*;aetF$`2wV>N0I2tM^Zi27K$%z4{M|_d{^V zzlL?XypFkHyA`7UyRZ&2iA*TT8flugO+?h5Q=+N0rmi>j<`TU3`NKoydp{ozhML!e zy-hnVFs-bNz5NbbBMGsg}s4s(oVEOSFr?x6jsA>>O0+%<<@4-8g%AA1vaR zY(fzBFJDKh$F1Y@*=U>Bytee5@-6E+9^`(S#l;s4BUZ*4?&$8t;d@UV22yTLjMo`^ z7^ZQ9Sw9d`LI%clU<=FV+7NFGQ~+D$lHVYuT79GGzsRfr`m)x2mi2nUkEaldC;&uZ zL#qX72n6QTz^^wuI;A(BL8cL5=Mjl&bUer+lj5^wyYmy1x^5x2SS^*5LF_$dt7ZhF$ z#y7AL3 zqQTQ=AZ+C&D8&J&YvkHljRp|9{bM)-AOcYLKLD*SIFN54l`vMza271$HF_~6_H$Gof zB5vLTPqnEx1_)H44+_+#Q2aZAfQ^C7Okf@jb`2ywk*+hk0%3aSCg#= zr|&A-YRR*WP`orT>f^>cc*>TqGUKWF2N7&8Ha*@%sUhAdaoG?*kz+oj&VXuWWVDjA z`NAhlJi+Bqr8uUF=Bm~~x$+O_;B3P~6*TcWvt$3hdZbKaKE*%$FOyVPr^Om}O6BxXm=IfcM%Oo2CJ6 zQa2qrKINLI-JVd8UG!&6-A*8Fkf4$sG2T~@;z3wqyTt`BL>W;%!%5XKl93Z8Th4Za zd?nou)Pr%FtwlLe6@9&wF3o!kVCnpay@x)sOBDY1*{*TJRR{wk=lRFg(3cq?jw)>WS%3k( zo5}$H_ivNM!^}WBn7M0p`b+(B(wMShZj4jKx%2O1mM|{ES3!skEU@3b&k#TxQQ{L$ z*YFe?BC^EPpigxs7~(l*{X* zcbchm`Ve3fC4s5LwJiDA`AV|h@cVYCG0EoBX8Gk%mt`|enk85;$jHN}rbpqW;tlIW zzfMm?x+ARuW}EMMYa@zy82gADH@#Xf?Sp3vxe$O&a4RgZGNS?_*s z)X?nLAzV)4UeP>ONdpM6TQIJK%@@#=1#>)m;L3ab>ZKP8o$r5xkYoT10%LpNuYRJh z9|2CikZ}zc6ZK8&G)|=eCa_)J!NG4`y$ddT5O9A7(iTH<48X+NEnE$L$%q6TSdBT=5 zCX6YLMQ~d`7ukXPPS|N+ab9gA~ZKD=Cu_In!&gwrmCyy zQz=>+CxX|ocZ3-kXjj#vJW<;S+8w=-TgQD3iC}bQtwm8^Q{5?wimqH6Ix33NaGW1> za0>+6BFLl$QAekzr_b!&flv?@5Ur9)`kk3}ZE|pH^c-c&;6rW4do@e8#VO7LLze#4 z76rVG-RmhPp2G+@?9?^;Tf*>>Rf5~W?-%9gNNHdNVhP;WkADQr&1qskcV5rnfV*i? zU6NFd&M?WJ>fJ0qclW)%&4D8=&*(QHa!2j*YJ-ha)arlzpKZ_y*0M6LgTG(I!I9Xb zlwU-aZ=O!p%sr|-6!77@RQ@Hh7Aw5UL+Ng{?+w7;4j81p1d?q?>1FhBv>kAFngnn8 zXxl1qAR!1jWO_-HE*q2KEdj;r?|KiuQvy=?B{Y!Z=T`xR>;a2}g-DBA{&PVF$C^Jq z?q7rk96WpIJ|K#JiY0_5brfE>TCD7QntLe~CjX;t=b%Rj7@DKvtDG{Xc!tj@fcAn;$k8yGwU*E8J;OzHB``!4_md3dn;JtLS_K>2 zta5VK*GWuh`rHzdYrY*Z6)y$84Zh}Uc2RWL#8%1R_bav>qGi?Yi9#bs1;af}BW;M7 zAh}GuK^j~^dpjpSRlyJjCb#(o5BV@VqdKX??H`%x7=)?DfI*92w1Y?1;p)2aj^0kK zQG-Q4-2OBvU;cNkrRld7dUXD759~~L8-*4_2N&ub-V#Og(UjRx_)%AN1&phvE28`# z{MA}Uk${X9N$4d2l-lgzv(wvI!i*4Jit@jkP)Pl3{bF?V(b16&tbr!D_S-BVFiZy> zuhrp88v`bQnPr&+lG;ImxWI(k)J5Re&9C|}3ov&e=Sk4Kg$=sCfLSFBtk!fWc93~s zXNcJvJ(STVU;1sYMv_Xc(M0QOhH_7J_K{ios=)W;QN7o0uhv~PJ|xN0Zi9kKHV@4? zU#{b>mh{GrTG_z>w<=VS{ZSZR{isUoVhOxxLm{!));icP^Jw^%o88ICf`FE-K^jSE z%WA7$^zoOIq$Nq?L6~|=HN$B!!vu(Aj|RqkOMsX7-?doDIgrwH?uMZ%m05|L9@m%Z z0@+2ji}vt}ilK8fhFO(?C+9++MN98=hwe?r+nh(2+h@xXr}G=f8FEsV#|ieKydgFN z-_7T4XKmdr@??X_4vXLSRVe8q(a6jgEeJHx-PUweU8tOlJzH|Ax9cEU@I~U)Gwo<& zrA`%Uno`=Wf0J68u-I9ywe3v^ZM(N!XSd|g*GjbF%+&=?m|8>;fC55qFx1vTkXzu0 zFWX0j0mC~qZw3MwhZ@2b;8Sz6(bi5LsPoW+)(r`gP$~ir-61;)#NPpL{f*D>e5ziP z)joC*`d!DB#QuuQuf^_&%SSW|Q#BJZ(mXZ#lVx|q{ZaUIbmvl# zqa6R(ONrX+Tkgh2`H8D#@gmM0^CO<(JI3cwSMde~8`Di=N8h%(2csROevhE1%@ZHs zC(EL3=!7QGHRU>ahpa?RvO~?u%4d~3u@g2VR6)I3GsUBMu@r{C^0BzHA@HA0{O z&ay3|Zj{@S=;?^Px$=o<53C&!6tSDtWzHCLG=9x=rw4Enp+y-GMu6<00lajuFRLBm zz4Mbm0Q>u=HU)bau#GQpDgc6qWS~F?CLU;L3N^ui(BUMO0qR%qQM3ck$iHwrp!@=U z*E@lM%}EM3ml;vTWM;p{aIFcZf=iTkr$VGFwT~JttzS9H#l}4Glu6gDJ8bh9IJ`-l zOWm_?gm|%bbo+!ZVi4ic#NXDSIiOf5fj)EFBTCWotSRV7vcEVKh-GZ*xe+SOv7|^j z`Sv3~Wo)sOCEFsj_AlfG{CtHt+s<4{syM01=Jig3UIR!9agW95(yC}BqB@Mc&_~IBCTfUin5yAyv1ex~s~*JxuT6>?k4WyN=%YRaS%kN40Nj5;wDg zQQm^w{hp3+Bb9`QWp9jG1=hSY-WTMx=Usz2l*u9DkZUp)6cJ0$$4A9)!{j7`#1s=1 z+)dFw{H)@emAGs8%O&vqCuwEdlP(|**>cnl2wD(K0@%^H zKR*IO7Ai26>jZRJK=|_EVP6@h2PBDZP`FkEo%lOV)zAR(&^;M8=Ng&iqc$w^%(}dT zIhHm?%6nTH_08#?@TNO1LCRJVX>P;6mAvJG_MwcSCVj;2B@0iWAR~i$3g`G&x+yM0 zWN6-5T~=btiwv6;vF@}z;0n^OX(C-`wKwikO!l%AG>{V|04 z16oihT^@w;fw1ffH0!-sGm6CiQK_0GkCbGr?+=d;Q*rKmaCw(gFy7SR6Sr&VL|iLI zPFL5w5IW|?Z%vQT-_9+wZ632(k%ep9xzUYsFXxPtAN0FW*U`ENZvG~$Skk~uuVW0# z?Gg!+%|8N1c3Eo6_N1Tt<>yIm)*G3KfP3vf9feSkl=W&^w?A2o3^J}iB_D^>d(gNE zKnWqj2cUp{0<2=-M22cF2$KgUU{Dgqlyf5ukdcY_@2|esH}ksyb`j90YZiRs1=iuj zHO#3HB$xti(?XH?$#;Gp+VwgtEffac1?ivyfTOD$Odl&CAT~%HO@^W|wq#}lcC?y~ z{uV+0cu*>C4c(*TZC2WCr{J^zd=h&5(@ zSg9BZ*oYodhJz6)p1+4N9rk`CMI7>jLut`*-)zk%e$E`Mh*z>e+CwIN?yeu=i)n7IEBne%;uG&y`a$FdyCqWNGm6qov+l#MHEoqab^f zf{X90gXK9M{H67zo2s#V1Hz)5k|(@gG{<&&-6iBffe2i@qwX<>*7t_ud!}bgU=>o# zjnw{2wPr`%?=5rO7vQmXGW*GT<`19aQ{;miS0IT!WE2GJP@{ysj7z}v-U37)Q1H3g z&AJ>u;EMs=J`h0A4t``Y5WHgo#O1iRnVjdt+w~4DfW#J(&p`bO(7J+bwjZO7cieH6 zH7WgRJ5Bsw;p+}+vWRr=^PF>K$}({oUa7c zDeg-b2RRbstaFuq5jCh5r;|?RF`7lwfN<(dLqtmd>2sH~#`7?vK}$1i(*@fo@XsvpsXjXbt5NVouh5uEZe4 zzv2@3=~6+q7Yx3|$SKcWX#=c!^LTv4YYSS>(* z4-kdIxoPVmfDClkwm{Gj;9_P2oi$`G2Mq@_vlG#s5u&ejvd8iqe(MS6UDnIKk>yCr zKv5WaCmUVVyDrU1n!6GlC6!4LdoyCf6xDV=TGpk;&b_a_YO#pT(Q!1Q%kx1<9)Xi9OsJuFlD{TyUKys(iC%+ zlVV*-Kg6PGrDS5X_kr){NX8Ea(bF>aN4@6~#n$=GY^VDy$ARO)vhdJ!WWRjXUQNV3 zT0$#T^X=X1dt`k^%AxsPIEcLu!V{nzi=J9kC^$aQ*)*teVur>T)a1i}nF;xefjAvd zxmrTNHs5?$N)jyUA%;0{f(4xj! z81h$7n7sOcVw^{$^4Hr->X9*o7P6YkXsHR29@YHOk$%Jm+Zjm>e8@A;oPC{h;zeM8 z!_VzERk@^zS8#OrbExI=-4e1{K`T>UyyJezUeOY3Ip>WHdxf|O`iSvpDJj7imXd!& zWB(h&yD9*g?+$73fqu2_?DROU7qZ`idgUG%z6=93C4dNXKnf196NF}5AKB#@08a6a zx3?77??Nvv6hsC+Ef7r*uu>KP01vD_z|*4g&R0nbyLlaX#af1G@01l%gS1oP`7!63;;`wzU^(U0G{8^Qw z9uXe<7Dh}7%aakp&foC}(v>|<{OleqPAEUeiE=dv9Q`xuYUB$Gx4R%SooM4L$PH%} zviF>k94(q(uJ~LhNme9lS(wg=PV8ni>|S7%_jL}aj$+T(S=dE6$H5WP4&uFM^=BdL zZ4$JRs(qXqiGE5wLH3bisk*nPh-bfF9o&*f{S6{YNZ8(#sDHFh-VwSkdGIT)EicC{<~Cus{q9>17K`v z`!C-4d_Mz^Ll@AUm;3G5?C$SN1rdgZe_~QpY2Rg(CWbAC#Ik$t3)2UU@z?lyKL z7=$YX1^6TcHa#>@ty0f8bWQt3>P++9i8;x*!+{Fn^|k7O@{AM8PFJCcw6tXseJ-i0 zu*B2<6FM{7^n`4R=S}e?0j@~ybYTgt^;b5GUNpBb14{V1jEszL6L?G7hYPQYEu$=lR+mDI#WhqU2+322-GV9YESki5( zaSc->%M`zJ#w)%Y#T2Tgv6cL|7nOecsp=8m@{&Je|C?E*PDya8?N(j2U0^{n_b-IE z;Zzz%)N8B&|&%|a`` zDk^AFcbPBK_Xe%v?$ER7RxRJdrKEp#r>gSN6%PMD*P+C#@bGZU*-@Is2mxwm2{F&N zn50ttyXA>4#g8Iw?BBZxa~n64Kr z#&vroVj(rdUvI6IVP*pCho2O-9y!ds1AY+^Z{oIzoNLP+>z^lvs^XY=JHeIo=t6}x z{#D&HJY*9EY+F}A)OhLZ%TyM8f_Lj?ww-I*8E`yLKytitveae%eZsT@#O*^S6s{P< zD?F6wnC?rFF{>)mxB&|pI7jkEaBj{meTN@Tu8-9b z=I@?AHsO2d`_G>jq20XvdL0?`J3>ofQPH9DYN9{mcut6*@Y9Uj zifY{vgwXK4ABVLgI1l3Q0FtTrKZ9k%RKzRXTL#5+)X^^0mFmGZ1>*9LKcv*z@r{?q zy{NKg%@dFGbKT-STken;zc4TwPkY+u?zvO+ST4j{{K+Y^s)TuV9s6voj#ta;L#ycl z5%FN*x4(^l7f4Njt#lMnX|TDeAZ-3m3(&UC=>hFeh3gmTe>q5+fM_TZ@3SL>#(6$q zr1uZ>S$b8X=P0-dM)6;Zim1Q`20Z-pTq!ZRze`*+n^yI3CaGr_bFhKUgREe&hDh z{@HVL(-qXvGFMzFugWXTBzsf7j*AKN`0%kq)(976?|M?#JRpS8S2DSrbm5X9Rdc@k zV2iE)*A21r%0H>l{Ko8OII_a2gR)wu`Q)X>ETcL8vUD<)TM-1hAfi) zlciaJwMT6n*;N|b8ijVizH9z^`=?!VvsX$DX_Hwrb{oo$3cwpntgkx* zCYSB6>b8^34mwLT!kTb682pcC3cj=Z)kg54mD|5EXgq45M=a(h2RzS{dDCa$!J&2l{;99WhUu^ zQ7>5L>x!p^Fxt)^Z^s=Z0a8IAkiLDTtg<#BV^3sPjm|uy%>C0LN8Xb?)f0NW1_MR> z0(F!$lPZpaJ;qr`=CE+>aiGxiAOy|R41J(!r)UWMfh{baCbbICOIzt4PX39Wd&jt7 zM6frDQz$iV6?9DSP-FNm;IM-r+*`TmkM`cg<@F|=SZtP3^a|?Rj>eN0P<+oJ9$hi( zaP~-_D%zN<*Tr1Q-V)wrG!M7}5jxy@`3qLJ=!$HI#%H4$&3#E-2$+fOb+yk+vv;eF zx3|bGZ${vecFY-x35uASmMu_9Wl-3(plFK z$|mC#?W;&0_>p_FQgNt>f3mJ%2LsPB5PazZNL1JBObrqbPrs69}@iWVU~Dvu<#UsHmz^fICB`*sPi5A9{694p_Nd zu~E`r8yi_8*u9x-2GZaAH%BjL1-AeLA|L|)!tY^vUsc~uxCBkHz)*}HiV`BRu&^M3 z=p>utwJp~m%rN-UJ_0cO0%I%T0k@1<#mftN#RjAn2j^0OCmejBq$H5t7BXl8oKcO~ z06>^kIM2xa!Z*fEgD038y2XrVw-fdI?ok%A-BXYv&5`|~LN&j?=F&W+;2q(0g8^_;Yaw<#E}-f~uL zr8;j|a~t_h?!^)8aK3GHrJ8DC7b#O2)Eg|t*QX=3fo^i!^DvoEeS-C8D7I}+yD8Kj zgYAG1{AEiRSGVziU7tH+d6cwiH^*`$E-D%#={Rn&GLrY|8rNSLD2o9)29Y8yOwe4w z4G>@~AY2`2nk@e-)hm+xo{Vk%E8_C3h%H?qod&xxsk$ewgxoWb5W@t7-2-SY{%#lBAxdeDwqm1m^=kJVgx$G8-EZbOb5*FODc`_!(nPx$Az%JL@=2NkPjU4 z36(#w$js1sNp#Zj6Rw(!KYWSi7c$hGAHOjAmGwDk6J@FUQ}j2?<9ZUi;+X*uM@p&* zPA`c0NCx@I2L`rYYzdV?-fI#H(ZNy1p3dDP`9Wp66M^epYj!fdt~UJRg?OcXQ>bEy6h8cNFM_3KI9To{#T@M%C*^;%E@3NTV#=RzsY{XXeU z1XsJ!a;>!M@B_yA5e<w+381|{4`{cqL;gS{rB zQ@9MFcS%X0Of+Czcmrexj0x%&04{(N>NL4y6cAz$&CNNXQ3~We`S$EKl+h>Lw0W29 z)oMlSH4dYpFn!iPxUXRze?l<7-{aSf_|*h?Zwb$NQpS0Bs~0SIU~PI5a;Ek?VD%g7 z;U0Co9LzfB<@^VG?raoI$5Tuo`y*~XW?8iIC=QTmD$T%(#KkR)`Y7Oo4-CFi!PNcJ zhbKPjG2Y?Nq!t-XyI^ozUm7D!f)%TF?}GyG1niTdPwJ;{ zmetlM2cK7s(S!;<8R-;?t3NJtx6RN^V-K8WyKSnyoL(~clAK&M#_>NwywCD-S{IKt z?$W(`_do~tXLa>{-c$RgaW%S+;+ZM4Pc`SA;5JEnK{c~iJ%hwehX>V@a)$SWx-R!- z?OaP?W7AIq01DZmyD z)K*6+5tr{?$g58g!EPu>8}S$Wf9{z+%%W%i5E=NQJA9w+=l5qby3#4LV-Au~=TST3 z&8jW8!UIgej(sxNQ1g?&`h*po;15}6#N~f8!VQ-o3COeoz^<2V*RFMoQ`6Bw0QHWT zV4`KQQS~LDO1~c*9Bg^d)cVKvyL$a*@1Ppbxj9_27guEjo6Dw8zGO%LTBYP-=3h&b zOVQd(#_;6s3vM%tiVLd-m0o}Uj5;30e>z>3bq&fc>1X8HOb+;&y*52Lz9CksB-tb5 z*-|A^J9g~QkwN`i+b()}fiv1qLn;@2N_WqmWB>f*sqIYggkv>}Lq`Ww>Dc3}O7uEF zQ!)fvJkUd}eGZwXvw3#=8l>lO2|k`Wc=wjk%$F1tmUc}^8857?{z375e53(0K;~^X zIC&5p3MABkS=oONXO4->$}ymsn@_fkZU^@opvs?qh|j(t8S5HxxlDUD$Qg*Tm%^hO}Z~x zO#8}P@+di_T1!Jx%c8PWULO^{(QejwVajLzi2D*8&utYKj@|l8lndl12dnAKCMUi1 zkJvniR0!Y!f2Vvhsyvfp@B%c;t;8h}H+)I$OOPYs3j!U1L?-%SUJ*y1jI01>Lt(L6 z0##->=lb$^sL~7in6|%c_mvezU!c2vW`DnniZjqxFRE1helVTr=T>G+c{0DKH(^q9 z(}00kdQg|I?419;yp(V3IQzje@8Vyl=#g)T!SzC+r$&AQ9qaXeQ7sA#n8*p%Z_b6Z z6hfMuQ{*M9x~3L>o6Aq1->7{qpNn`oGdy8c?z{#NrJ&Ccb9QlYX_EV1Rz?SkGCj`c z`RV5yz4Pks9*faUn{O5NT}?03O_4v#mk~$H2S5JcmhLjTw>bWx@{4*T+4A63TU?pO zsZ`t(HN6z`<$BKv)3f5IBj`@eOkU-poh4dLv_4*i13QeromAId_UuIysdJ#1aG+ww z0Oi!8V9>D4w_nO_&y{wJetkE=8K3C&EN>ftSq?~rqJ^$}pC&B(Z(T@K4ed~{6RoF` z0NVZ@w9Fqre#|Z?pipIVI}c@{uZj)OD}aKn4wveg?w~%AS#N4SX@rn#^DEi#C(agR>Xv+P*^c0zMdKMJfbowm9hjrL!^1$C2hGiG+ytW(y0B=?E( z^xvb6{&uMLJ3eRlBlo~W)ab|O84sOSJ1#8Smzu#au9i|?b)cz|I4OIn>=L1DvrL;WtWRJxRYrv(_Px zVfvM~D<6H7aeIjtE4#8P;fzZYHh)lwK)ciqKoxukIQY>kC{c05v6nc+yM~GqXz~Hgd@F#W^+}9KWxzA%{_)6> z{xeffE%Cby4KGU9{K6+nu1RyUEJ{~i?`t$R|87~V@xl1;3Gt7M}7Ik$Ic{4e9iLywGStR5?6 z(78#;AIUS@$n_{#)$q~wf@g5-R{2P-{;{la7Mgdd49$j@%;R47A1-vet0vsw7hl3xz{xA06_uod+ZdCI@AhiIIYk^@ zF&+Gf8cv_rH65$tsciMHW8S%jIlS{6%Tybk?qXrMsbV@bxM4U*tck0b6wiO-XJh_r zw&j?j-5eySnYeXbGXUA=H+3=z(g`rRlvr;{x2n5nMM@hUYQgh-tD-|BaZT3GV>^8B~3^T;c?AlxgM(p-&y`QkX+ zlyLN+3F)QUekbAD(S;kPKFlZAM>UfcBnE@uEAPb(klVU@De0cPUl=6bnv!ZsI((j} z}CyXhR; ze`3y#*2o~QWsa#Bh%FFwjd}G~P@JWztYd}nb27=!@vZ9ekNLjXd$mvEwy?KDyi8Qn zSS2>CS(&0~YYi!2K6AV$LVG>muX_^P3KNW?$s=^aIl2o2O`o>I+07UqowJlS-K{k9 zxK{U3XSs9!=aF0X2K|C&CiZYWtX1&wbF-JDPCzkT2W%@_EeFjm9|O+$zj{>xFc#Cm zg;odbn$W}rntRW-_VsXz%6;+Kb=-SL-jV7gr#O~-{ndw%z54>rGXz8H>c0i2772Qr zZo%uUN1xbb>a23&ts4HallyQn9JRf#((9ECwDsF$5rE%tTv+~oz4CP_tn{X*;mdr5 z9p8p^Q`V*D0*Ak9{dqB zrhm*(6zQTNW*|}BKH~gcg2Lpk7Hj&RUzFL1D(%!QlO+|`atFGG*=1A?du1k0>r1<`}TKE2%)Z~;p#>!|EqWC7K<31aD7`A6@y(c+h48gnoiw>k|{nh>!x zEp(Fy$=YIUf0;&NYR{eUqSY&p^ebiqeGVxXk=c8<=(d#bnW+R}{7feutA zmy6WsV^+cfrMrLre3Y|*2T-$ipg2^1#6DI@^q+w zW0(4S5T|a4Jn@&Z-<+5@Ii=2<3Np@UI_Q;@Ito>ue2A1@K^zJlUa=(`qwTcKGhL2e z7HwR%N*JE)W3cj+Is7i@8$?juP5-E_kPz@Ly5}T8$u`)JdKoVykGrZ<#~suo&?9F3-45Xn$3`HZ6r`+6GX{oG;t*bldrcC5l|}+ zjVk_KpM4U8u-jwRe~kqGh&O&GElp!hsJ*F?C+j|j-zw0Fz11vNQ+jRo7S5s6p*pn} zTw7AEo~B!t6M_=eZ`zZbZ#M3A${`6%tr}9YTTf*-Wv<5W?(^BJG7 z^IogcUbe#Ki?GRr)yhe8GgXIHuM^o<{g&|oH9KYKxbp+Ga>^y!^JnYju^1gxnSbxg z^S0dVrjtrLp#vKT!OG;0|3}+-e>Is!?;b>8lxC#{&{0GI=`EpIMi{9|i*%IULQCjX zMp2|F9qBT30Rib%ksw`a3>^Xq5PE2#-t*4A-@EQVaDQ+umV$)vo^$rz=XpL)r|f+0 zme+no^6MqT$zKvwDc6Ep7RJ4^;U{A47ahmbb=(h@4m$Qecg1WL@!K77m9fH(wS&_Y zeI{ncuLj*-?aEKptnJ1#s>lFJ)Q+uhy8#*}Y8Zy~z%#r(s%g?QJ$5|^e`j3ZZnH>Ie_<&~0G z9wLCz7B*1v`P|Cy`Mv&PR$b-+!cLB}Yz&hx z+#ApW^n?oPGy7soCq4lt=ZsUyckS;pnJ3J^N)R`jGR*YodT2c+kc5>nd4%b`IIe@p zYUYXGxypUng%oSS40@|*3(J+9*PD2HT!4<;&=uD^n|h5!9H^;n|66LSgqPS$K^%YC zi)W{f8$BRc7w*XnAR9FmkQa(!SMxQ#rkC2QwC576DcMKxk7<$e`__%6y2vF_fol@c z{$}xAroL{W#akqzsZCnv?QO>2$5xyFz0W|vi1zZD1K#Hj=(6p(tAQOJqx>jx}p4i}88af@73({g0Zh?8=f` zG@Fmi*yMdmmKY54!k3dwF?m~`w$2&HD`VTMdrN}NihE)d+!p#bZ}|7UZt!)J-_95$ zZcok5oS^7*HYudo82t&yFy5F5m7M8zMuC&GOb3N9+l7~B$# z{>2X;oy&UvaR2Rlwa5il@(XQDlr1Ck+O@H$GEY7UEmv1DFue}d(}vT#`n2(2e|`ir z0Pl8xB$9(>228$JTtU zDs{lob(9C$Te9UvDNPs>ag9zzqkQfB<&X{^(_NYbx_cQ=!d#8HV= zIh_KTLZ^{I45;q=kuNoNli8CN7n2c5U6l&IfBKL@GJ>B7Go45_ir&Nhdo3=N;R|bv z#x1V0E~HI|qFbtSR6&ogB8Q^wZuS*e(dP-$?Cf(W-XO`;;~cch0_6onngbVfU_{L4 zDW5eWP+wT;xggtCasC?1j7+jEOysh*IVQ^C{mLcbgqAacXF_iXm1B6FVzak?t!py5 z{!lphsQ_ zmq*QKNGFXbc_Uoazm1D_J9a56Dc;Sbv6zlig>n4nOq2ZOa5IsduO6vAxWogS6I;aq z8_Dh!PojTa)H2&C@-UNXlPgtul`F7lU5G=jM!;kiJLEgMlWX;lQm^d1x*{TF$@n>6 zyalfyCH1)ud}_wmO0h4~+6lk(R|x9smPO$oAq%CFy#1;Msx9M|`a$~9er}&ueMLBU ztSRjk0O|9+9z%8mW0*NM0E*z@A+e5)kE=~)0yPU?%NbjsPJdSAcoo9GLNhvmErmg& z1>=%YpImlI?m_O+EA7n~Hw8Cxwl(Di%zJ|$y@j>g_6`S+Ba$YUQP+t1!uAr|dk+=w zf_B9_nL^=!Xk#+*X;t#H%=2GrDU+lmx4~2quCH{ds>hsS>`p19BvK!{w4ocK zyye!{f`}?~mS|FulzOz*0{NvT>3x+Fh3kI&;P?9lOnonr zHE$6a=cSVVw!b%9q-6GsSL^*`;jBnEsDXZo7Q^@)!R?Cw(>0H$DDbso=HJ+Qz0bu?QqxgEPp? z*eA*piZU8}$%gIZq9GrVW_}6?gu7K={?XvNWGQEd%hnG?YXh9A&5uA+-5+J5162O9 z=sUdXF&c_=$!yw&U%HvTQIdV1v!kt8&fPKxtXagX;akf-xz>36VUO&xj9e)t+tKqQ)hO|U z;hrW~U zON7M~puMW~ahN7^{u^>6!7Ix<2+++y)4;jUm3`kq3YSt|uTPe7$)}nc4sf$Defty! zR0tsk#fHzpWi%8hB^HM{@W9gF_yNofxzT{C?#2Rkzp)xu*ENAJS%TJaixN}pL&zxp$3R(XO#12DO)0!}!f?@LW|X$+2I=MPgqB;H z0b)aX3wZiQBMT1e#g8)*70Wt&I>EL1SC~6Ux-*0W2{8mth>hhl{Ffaf`L*s2Gh?md zYr~z|-cS)YA{-aSP&#M}QppE%BxlGVPlkIWMs7ZtU(W918ws}S{K%$U&o-<22>w!^ z82^Bc?5`Dl_Ji3@N*hvIo67DraPG37=Zp<(1*r7AAGQ(c1`StM=kDEBNb7Y*{YqKN zMHLCRC{_;%TCND&qtlpc&XBX>9{yCr>F(OsQ68i2BFxZUGWK20JcM@-x%pBtH!5il zQpyTNi;vx9GZsGasG{y#XUXF6Jh=R?DQnJE2j64O5vM;-N2U|^F`fmubWOA1T^3YN z567LD(wTcU?dbYmeL=w;yyiO;w+%ULytrrLe(lziSO+W*`SKpFDyPEDvydEPv-aYl zI!_^g&PmO*0&{D`?vG5Mt^Z}XW z`5*Nh&0kAg_HLbkP*V3!futFp>3xR!h6X(@yI*)b2tCV>$u0*EE6_{JLv(BqzCi;F zhK@&1?u>g)=?~*pZ*PP)m+IAwp3$$_@zzDJei6~|db`R}V|BXfCdD?OJgUM^G!#m} z9@9*wu};1?3b@Tr;q$?SrOCaoE1DQs1J38T!Ca@1h4%Wnc|sO`Y#8%o3)7cDQEh2{ zP&Qv9<^TDsZL_|EyC2cH1-r%_4o{<9zIuvn<^rtgbOv zIKy+%XGHgO=Luq#iALnZFm#@g+~dj!4`Ncw`s4S@v1fDDR^v4+rLXm`WHQ~7qDn>8 zV-0pEv{%Iib5mF!`6KZQtU+MDDCf%lLpT!6iU|ve``hk@ysz!Akc`W3d!iBWx_=*2 zhr(Ert~q{MbawZ8lGGbVDXf1>AR2VoDd<*QMVU#q^jKAYC`6Md9x1G@AH6aO>xyZc zMQixlHkcr4tq#nXXIYi>Mc3{%;7>(lpZHDqGzJ;m()N~uFMo6+Z0toQGV6!)vh=tH zc#*%)Vt6v@t2LS*F5MYenO_R9KEeszuTomOXRzK-l^9hL2(#!>yXBvU!&lPOG*4b< z-|O8@V{7*vGGP-}FTX;$$TLb9pl@bxez2q$R2OBqTmh4uCT<(Juy#i|j3ht3o~mOm z49XQBaBB{#_*`&WLO`ahLmQMj%+bG#f(3f6n6e6Wf+oPp}sAGMUGjeU5>-ZCH>C-O&xQ*Kmz zq=jJIC8Y_`!_v$!SuN>gS_1sIQ(d)CSNR!5T z#yh3eCcb*+wdpy6CPO{pW9Ga_xiP8fPmRlp@^v=bb^d;f|N3>v8?r+T7DqlOcnxCz^uuKa(;Cpru;3iYty2pknL;*RUv z{2s)9kI;E@GC4BB$$P)QIyEp7%ifrseAT}eV;;-6H$+$8!|stUV)?#S z#<0#fdZY{DR1U0<6f!UF`-Wv6&jKf+JD?~LbWY}V+yIay<^#b8Qs6+oGhitZRowpd z5R%s%93JxMRJMn{eL3`M@IY6kt5LQRNIS1v1-*!H7~p)g^Ms(0!J#DXd4O$>ApPTD z(4?En<3%sKIM+5BI1u34E`Lgu8Hm0cb3TLzHQ52~OZ=L^V#PgHUP5hgSR7c|Mul~{) zr+ikkC4-}A2GaWklI|~d7t{A^_8zpF8*_`gN2OZq(gKI*;1%%YzV z+*HaFs9821KQbdWWFg2SSd**~m{~p8ow^YDPR@6~e8!$&-E%H~5KH+)Yr9>7Bj;G> zD>}IqIbCBqi?K4H66&nea<574M|-6OAkwYeXa)Pv5pZ3Ga?`mo1uiMok=p5YHPp3h zaV5L6@S%T|(BFAW-3EV;j@rsydXTiAAezFurG!i=?L6Bpe(MndS;ma zEKB)jPQvrm)fQi7W4U!grGm)JX&+XB|J#Uzh|1L8mhkc;18;q=Mq+}Y7Gi{0Sz`HX z9kf3+J(VXkmCLHOuF{W(cKQRqvsN-2B&FDuJhSt)^}H%=54&ttTw*;YrO;0KzFHOh z^?Al*cEeVebcMP2B;H3PJkoH)J6!l(ChTOzlOe^-Yi8SQwKTenoHSl=jFG($Livn1 zTN>CRqwOTkF&Q~6<8KU_o*%zuc|_t*oAf$*WMR%xFB{L7$U{JnR87dmY5i3>RQs15`&W-!GC?5`*zmGfP6-H%ilS7E14rr);a+FS+K zdrm4v|C;!=t8-jeDVU-)BGbP9j3nEm6UkBEL;a)Un!Cl0==PtiKhpw6@;hXR0%Oa< z2NQlI_b{f!_Y}*q=*eKDD2?$-Lh26BTOJx~dGCHri`{SC^i=_>T zf=%x|^|!9C1>+vSHP15`x2E-7s?@kdHBMBlZ`JJ>J$tup(z$Qq8BEjR{k;9~E?2q$ z_qOMqJHsL3u~NBhz5Zt#HB%Y>j?|C~{wVM{&Gd}b^z)_IzvS%dm-4L`QImg-I%y~E zWVJR~vF> zMqk__2nLyMWmAe}hw;K{4`=iON6PgX6#4s96vjUctUKSU{_yj7^0gt+1kEchT6MSg zNQW_K&1VcS1$m2NFRj(|14iO28{!f2 z_umWsy;lzzltplD(j&;c`?xcE-Y4o*FS3Ns2#ZJhL#0-hM#sGg82S0@<>*~cui?&{ z%`uUYmf+#4UCK)ZB4NRqFKw(3p%DTky?+4+XOM*{X!D(gCE$B3uC6|+GUmN{Ls(2b zA7xt6f?j`SSBI!`J8ZoeNWJ%%P4Jl@r&`a4cW_Qq=R%)kFWw}%O$_hrHHEaIHvCbC zu_t+iYLC43ZB^MA~{!!*$yg%#A05S)5_!9B1n+ zku6DS@{INB?+ESm7fMT*Vk>TbADBOrJy?q>RX<3im*x`J);g;ZP-MCt{Fp;J^Y^dzvzIqIJir>4>?km?KBpnyqKaYBHlsCjPPu`4V&P(B{9HQiu8# zQKDIWm-ySW4~X`CA%~0Dmt)T6f|}t&lZ*W^4Go7qCSPO7# zlwc1u!a$@<%t z9<@PcW~`1J3Ud6Y20Tmii$1?(mYvfoSqM7|eR&OaUb0ecQW;(o)$_tYQE06kTV}J% z%E|Mt9^Q-YT%tS0!QJFxO%W;-hm_N9pSPHt@H6UmOZ8m|m@(d?cBLw0m)HhRDmL{) zq>c;xFeWwtqy0NbKDg-Xmb^CqGg(JF1KX5dPp3R<6<*f#{Fx8MIDi{53|O(^f5;%# zy#FWg9A(Y|V#GHvGl&FASw2wz6^uAWMeT6vSw+Q`cI>T$n~u09j=pXy_A9IKU=&w0 zbckAd=GQc@;>&tPf3K?c74@kfZ2Gf>W_Vl`ndyjF<0a`UM|mWgVNWcp*tzijs#8J0 z1b2_m&ub=Oiiu8Tvh7q>GqGHWNuS>BKTTBB=`6&0%N16-kGeCyyXJZvgByv7;vn!S zwYysFLo=7VU$R2Y60_jp;#1e8+6t#-eC&QQ`|on5cse7@3lC^EI)l%lVRCt%{~)~B z|4qDfMlJl-#L@SmuP@*{!O&ElxoqIPqH!W;_D#{e! zd{MWQ%*|=5xJ4`)YG=-$vclJ^3+I7`5|tF2TU+WRJ6}pk6JXd>5u&%EQ#knRm5Qsl z)ZLU`VzplkTPAE;NNvQ$+YG0IENzzwn!Mca9%879J+#uOM#Pm+e3w;5Q0;r1Nelm` zo(P##7k*}>R?65hf3IVxkYRBpW(SwLD z`#tW$Wk%j#*dhZ5br!mhoJ4+X4J>;TP0HxYBublg)g0U?-(<~JO*e8S8kfHu^!w}` z0Ml!@o{rL0HD1i{ZDYuZ1Qe!>DhC5G(AoO}>>`|;oc4{jH{FWXinNQHES0>r?CKgE zDKtAqqU=^5;DY*H-P`?tW>Gw)@+!m`iH4;QyKZ&0#o0#(E5Sd zLU)C?tT}0rTJ<@zt;DM6=u>(rlH@PhQY`uWFnjmSx>RlXJ}@op-Z5Ud?_wnD>Mkby zcSKd0&ik{x+(}aDed`T7E5sbGujWic|ND}Uo2EnN8rv8?G>W69t^Yk-8)KcuN!dr` zXz^-ROO(7#LU;xCl+M35%UU^86f5GR$)YG3G%24e0b|1l;w*&ueLef=o4EKmuEfu; zTvA`-_@*MrgVIxz)06)rdfgPByIy034@cRg2BA(2IINsmV=H?(u^rz^87%y0E(U7c zk00XAYZK6#h_Oi%xXX+`s>O6SO1VZL!&+9pFmg6XEXp2G-KT7Mtb4bW+-&a`-`dyK zsgP-_&pVgcR`|72S;6>4z{%(12d_(Css-D}U)E1hAcrld8A^M6UqZ+3yz({ReKCG< zTj(^U3B4*=x5?SZ?tTa@1P@Qf?~R2Y28vP(MHu(`jPoA3WL7o=-1X^-)txNxJm%d9 zSVpkcE!&OyR<-om-Z6`Qy<+Y_2z8hxI|`jS(_J>1gw9~Vq>Kc0U?s)mRb z#n7qZ?vC^3(>cdTds(LDGln1F@oM?gin8OF6IRQ}=_ljwscyS(g)G+keMV4~EM9)f zii(QMlM{_^d$TAVUkh67RA4xuUWUNXkh{R*U@!^jX@B8x;c9%oXCY~6&C-1%@YFSHzG(yV zlog}IdeNP8KV#S5DkrGhTwx^z*RfIlm5n7?tk!O&;(64{%!f`zr=RelS!~h5nTmZG z_nbVN=B3P&5L z7;Utl)BieTse<)<`}Edj;hw!)AG+1 zj-Mk-KbOqC;MTV@*rU_&+Rq`>RuL8>{84%)Dh-&~q9XkkgG8>oMcxNS?h^5_{kGpS z7}7sBN~}7P(nRa5Lk@3GkB!pLMb~Iz`$QWsFiPIK3sGWXHhC*nphSpcwYa`yH+dn; z=}Fv0R2yQ+$Ll2YvZh>F?tI!(*XaALwBC{fc#?HP74JdkNjnuW`r*A=VTHI`E#2Q4 z8c9Fxf^JoMgZ(+mx_PM69QQz~NuRH>PB*YOV8Q3;fkV0ze?q8&<*c%zYV|;7Cw>;a z3ggGaY#IyAH@Ru?K2RJM|snvmDn8jD<_hYadx{m=?DX1 z&Vpj*I`~kF_*7z9kmlB+|^o$=M18*F$It=(ZTjb%Aut5U>-vnvi1G;TC0xPqMlg$pfd)JXv)%A?#!F=`ZTdrWRR$O=O47dCWwJe|6a= zX<68X=||V&iyFV2+-6ZMJ^bvM4NqUTlmd4Yd3RF%vBlMYU9Y?^!Iq-A<8U@yjMC}I z_>s!5)_@H=V)fa1=g2r2)bBHUI!ru(WYU@-ND*LGq=APm2seLZ-UeL^LU-T*VbXp* z9JbYPE1&)@C!K)Z2d*WN8QisNV;=m?#8!HzzCs1Hg0Gw2TIR#g&rXWo?zSIp?ShM8 zen#6SaLovZOByZ15R7R87fW9}T=-Ys?B4vDSzVe-igpPX6|1+3{IU?)2PC(%nc8_1 zqT?%Q&t%@dNVPrRAempIhun(^vF8G%b$6~=&lJTb8}epa@DGaA;(#nO{qOa!+;U5ZeU~wz=G#&ajWg!lva zWaQ=qmPIgGU~;red?D3EGi1y%p>R27>qml3m2q!hLt=$ z(c6hW-EP1J9Te}QdziH?5#{IhWQ(OMbuMb%k;jw=OB&6KDF6IX<7*~14H=xuyT^f-!nWt@vH8Mk(`2jw3qSYwNas=%Ud2k!>0wJ z<%;TzoJG^Xa>Ww-T_SpSHf%uz^=22C4}Jrq;R&Gmu<-Ko0`wvy10y5Px}JA<0kdZQ z@@Kw3Yaj9^syVd9br9;@!WTaW7Y#+&DN<;%+-nH|nS;}svMFXm{rDl4&w42qFPiKE zjLKh9QiRx$HWpi*?&-xVgfF2~PlHqE;$(h7K-tHst}7hodd$@=$lqfNe#RG}VUz8G zj+@*hy!be%Cx$Srj#kH2_!q4^9!`$&ip5X+e~I}9d>{WAl>! z-ZuE3t7SfE6H<&MSS`am_h$!x-nb>g=2u5Ock3BGIke)Esx_8z=zD-e#gp@rUtO?t zLxoorKCHm&mI7?Q6;vaeF(@=|UF+-d4qI-A4>mhpPpJfefO%V!f|;|R7cPwG;p=y2^}=g5TYP4@ zrf=Aoi=l!Uruxl7-sYK8+w+I|W@?CFgwBC6KQVMikHBOn=*#M3Mqh$(E&Z5c_4!%N z(YSoTwf08fLFZwFDMWVYIQIPf`g+Ce^bN11uR?0RM0J-A;X`ax-_eW64v**DXVhlA z%Eil)G*Nwg@w*(uhINOZdDP?j1Ws{>^(}KpEd6nP4V9gQ&{MsH{}eUGUj%2;v;suw zD@r}`uKW;Y#Yoexh-^!z9153gX3|wVhyCU2evUchX+p5*J&*f=MEf)=pp=oK%(&Ta z6yjhdDHGBgqn1-}2i6eNC)knRu1bdUuoW!B4aP5}!4t@-G|eV_RI`?&|e;q-3b^Zm@u)1>Hd+*Y8)f5viqT*B!Gk?> zW`5>=@KN-pdlf5zR$S=m_>g;oZ4)2CQ8F2S`*_XSu-dEY%v+axzrI%sYn=5djVJE& zRYbEmRWoKg)qnd~!pMijd6<$;oP&MLpRtQv7QBJwIaWX*R9)=hD$6Uil-_!jG~R(& z{4AR5$Fb&XO*Nub`rRiy{~mR4+j7z7@EeU%F{w{JtI-OnEVTT1_kif{(no9OPFBoug zAvUu`*^}3eO_7-$L6Sa9O-~T%z1Cw~6+iW-cP*%ES-U^NQt$oNBf$UupghyfkfP_H+Bk(sSa&Ve^h7iVRMbBt~)7 zMoRG_4}k0^aOa|c1;=rk4(3S&2WRH4yO)FF7af<<7J#t$&)@>x`+;p7IJAD;$xnL; zPHh6nx>C=XtiqYUgSsnVF8ohDnavjX2S|Z?2xNi5$GG5GNTUjPQ3E3*ufVC!yB>Uc z=-x`pI5Xx{_6WG?l=r`}%^i@-APwQkLD?xcAcnUCpV0^X{o#D&SFV9% zll^%?6^Pto39x4SD|RaH0EX@&IB04CN_!K)q4>obH_kw2EXcbDrPcG4RT$NI2$a?@ z3jx^?17tr+o!Y(yJn^)Ui*RGBTg<9G;%eYp0o~0C)tXH#NNFc)X<@e90d)5d1(~Qt~B` z)dwak`O5;q`Z@@$VfpXn^#`tb?*CL%ekllG?eEy{exIoGgt(;8n*#YAA;UlLFhg!+ zz}mtBvm12z3;n)=Pe{ShVXTNhX#RtN0FCUkFP5~>d(p5~&jf*az}pc6J~PlX;H%~I zD-rylY-zewthgv{-h1{?ILGiO|3jh=``Bkja&(V8L<~nj>lH*22<}4}VN~^1@Ri);BHfmjut2Ko%T26VJyOS?1-m5Jt&=4QGwK5tJ zjq3>_|IU4=nXa<%c)hUM_DJ41Eyz~Un*3<<$6gPy{*ZQMJf1bz#HD;l%*@VhfO2aJMiP+QV4sX{Lhu}N;&~psoAL55b2UNdIKhxGxSZls_q2eAH*KcA0#i@ zy#E3iq?nnRp-0^Qrf2KgUa1&>SWNF@-_T(Q8ya{RGeFhx#&xgh6@_3-( zO-(5iuZV{MYUh7%(eg;KI}}<75bU)e@8^qk=cNE@w*^+B0~Q8xKmdW4{lD+*x0nqn ziy`12_|4GJh_)PgK#|bU&Q|S=e+g|#Kfnc6gk#lt8j!o*;7;k413LP?R*=9Q0qkl= zL_=q)O`n(0Rx+H5 z{>EHo`}lq-SxAk=-Zy|R^)gJ0UE``EE%%BILQzukMRAeomqfFnkfbmxVv@T&*CwW_ zEp#^X4pbc-lDM{-sXPGA?=@uxy$9H<+bb1bTRE$^-SI4@dkNj)U#MV zKKoBS0ZsF$k1cn}5thVc8kM!1L7zrjJ^$i8!8yIYH`Cpx=q{V)8Mp;9x zLS-1@7Wv(nKoxISPS@?VrNdqWlzL97fcLYR(X4~(9458p6*~*t7FP5euA8@tx)L+* zxsfxHtTkX?x_?g880 zjq2s`N{rc7<^3>|;(!bN+u;Agu8Mf(-QSVNVq{YmW=0(tB5LLZpW*bUjYw#zXNRi( z;nP=*Yh~V-AQRv6WsvXRv-M016zTlc`P2dFpRa6mxcKpD>OjvleF0x(z;NGf{(~%OUJ_ocyo00(!n0FepKc<67b6p|I#5CA{H z^(cf4R9v()0Ivmzw@l(-#X^%6aOO*%EXJJt0eFx69BgK0W>6IeK67&~_;fE>!ioV% zW5J#n1}Xq(R{``(dEm|jqe^kRK3KqZ4u3l+hF;ob272j#ngnMkcp+Jpm6Z;UbXuW= zsm!B!!F>RNivsusXgl!%#GQyCZ3Py&3Acw<8NvzYGXi&wKsjX5I^P)wI1^BA!FD%9uF5)HvZyD$73GYGhF3hTVR&@xk)1yE!Af5GyYQIXP1D!Sa9+0 zGkEXW65Fq+DSJ{82Z4{#{^GpDg}FtM&KuS^O+!&PL;PYM)1GH-$N-N_`8Vkd%XD|i zZT>P2;QPtZ*6@a z(aDDEGGACsg*fuUmTb7>Pq7s<-VZ7?^)rs9m+t?{_go@Ar86Ur8(gi3UR25x#-0o2 zRCafByKsDb3@}ZwT+bq;sIN5~$dALv8|Ht|?>pNGB}A~CV9ZT-V!Jx%*P_|6S9h;( zCz2AWgdYzqdUL!Y7SdfzHz#U~1k7VllteupgFp@Vx`v1epVfM*`H-_kdwSRaI5oWlS0kC<$x)fFw|0SPYHHSmE;*pzR41 zA*~?(svH103Bcvo0mxMyO?9kUPZyLi%fqS$fuO|#9Gy47ND1L7;xDJG1S>XIP!)Yohc&!o|L1or8`gVa5_zeo!YbVRwtd$QS4!zY)Y;bj8BNx+ zywSGjxWaZl3G(LOqibi{d&`(!PX?+v6<%tiU)N^PMsYv8tzDB%6rz=1^fWMXk1AHL z5E9gW;xnX3z-<=b0L$>_cC0VS`tF#m^^ z9m4cL8vU+B#<)m{VR26E2ld>+S`L*f#QmSKj}o75v^i-Br-ziMa&d#J5`-v!&)LAD z%AzpPM0i!EVvxRFLS6c7G8-|?#=Sq})0%AImD=@TJ%KRpqM2f;ZuwqYmYlwjx74qxd z#=l5l3M=J65sn_QE8J$m2Q>5x$yJFRr7t9PhRM;x`cZUpaWPx@jYU0pEZnq9XIpHu zhfp5uw%xGbv4qYeoky8TXlbw4HU)VF5*knk3_ol+T&LjUOS0M2hRUTrHc#01)vI!+ z%^yCC7cu`HSGM0CFBGc;g{ILkfw53ScU<-=xw^pXn1gV4MpBZIFe4SpE__MWu_DM3vKSZ7R-Uko~U z=~(4wt`4by1#t4gvN6_yN=#F@7-tt$=B=0gnDTAhp3h zRpX_%+$(ll12|0d1TgNdOw?TlBa`tPeioFExX5!o&FR@3)fv{%C^*`_maI92! z{C|Dt*|@uZOkMppH!m;s+-RuRE*a3Io_wL=8=#QN*a9ZbJv{h^8%@fm0rANi0 zly4bbPZr{rQoHo;<36P7tts&NFA$@BbrtgJEsV?XKBcamvhq!6E9rMK`sSZKd-s33 zNr`D9y)JyNc*4!=+J}@L(&5$UK=0L+DLira@Q{3NlGM%^sX*bazrS*nZ_e8)nJnNzDqypD0++Y=iB3BILcMydq;7xB?apaeoH_CU zvoa%NJrm(jt3>9tz~y&;#M`#_jtm)9q1mOR*kEEpy#nKU6_Wxgn!&lc-yl90fW*t1yGQ{; zOj+Qn(|>g&FlG~=ni=Fh0BPFMr_GFVXaER?b~Ii*Z2&6r0vpLi6T-qHJJYAI{sT-J zc?ggn4#*WBHZ?bVS^)=d8|Za66Kfh5YQDDtU>-YERG(5*PN9Mq#Kz1P6_-K-F$f_~ z(;(dJ@9)1ktf!L=8hK#YX&=nh=#asJgV-JNjE@7@S~Y6&JPp)uyMq@TJ?H6~4T^k- zQM(C1__MR&{HVq6;HyA&3!RrpMOCKVz$c8PSXP((RH>9oTg8Ex7N>h@JH2T)PsQl3 zrVP#8i|p{^iPbD)>fvSi`1MW`xBMM>^WOt@q4jNqv~s4rx)_4QTAd>c@$sqY-0T@^ zttY;G6*RF+o!dW`WC&1U?VvTCv@COkTY}Q7AGTy%Wu4mVez!|hUu0VJ}n;M_EZ75 zZBU0upMWYGLT`ii1%Fc{F3coYTiNj)-9Dm>N&9c<4Wvo_;|GgPCN-_7z&AdI=?X`KTxWn2QlLu z*Y`G61zX}|6c{}&Z*A1TdEez3@e~uCrj1DbM9HU+i6%A$LD%C9Y!xIAlKIyNZb|mf z&Cs$>4=LWwr9s2g77^4_#j#th28%_LhUS>hwiI51JWN7OJ9t7~h>jFvBsk(_w{5$d zwyOG>DKCMkhLfXa)+cPW&nMvTyck3W?FylacicU})t1dCN9kZwSS&5d(6`uZ;o(AU zN9sB^?o0ZN7Gm_RZqHSDU(pnHVsEFGuP)v}F{fD`+b?@Jo!1%kV2TDExM!@{!4uO| zvqZ*2hu)O0!80?xc+PHW!y*~2_zq4zCyD)5uG7O+_DysB*{xQTS(HkK#YsZJ6t1}d^;*12f;YiYkoIF9O3-;T&eeA=3!x;6jq)LDhq*o?s@H5rE% zmB}#M7Vj$_)=i`Giep>XBdd{t*3^1muOJm-_PkoU=0sqAn^EI1^KMGl&Xav;I1UOF zXh;l6Q-CB7mPzfg!@eQ_j~WE*1mx!@C594U8A1?P$k7i4CRA5XmU(~{j}_`sX&Nl> zk|2A@->>rj3vO@7M^NEQ!=HyBbK-{#&NNIt_a!J+=KxR$Mo~{-?vp1lJOBPdJK}g1 zlF|GZCk|pqS-3!_2;bkWX^8@(!UA`i%{;lLbNt7PYCKm@z*J2fRJm^;T3PK@m#_pN zQa7F+uk+*f!QtEHOG*zf3)(6686Tf|4Gp}(*dH2Axr59XIvQch9YU7SPdP4q#8#8?1;|3x^wT1oICUp8fI-eeTj8Qjr#RZIMA;%5Da$he*HgZGg(n zdO)X?gpPlye$w}?2_cnebEnnoDDhH%WJcua%t$EHJxQa6te>+(K`>^A3x$ov6IGu+ zF7?X(*0`TE#4qOxW2W!Dc;sf|%)WBlETVfLy@X}*_bgS2eqM-4>+fVSm+r@ml$n<@y0WpMI(5DX5Kra2-!0WA9Ez zssN71SZ!7Ah>d1gbcfF~hJ*85DE_i*=X^Up!RqD?DTbow8iQyY6 zd8-*dktbYsnWW>pLNh6j-ZfsmR5K*=lalvVrCad8R>eM$J2^dJq?I7;^*G-bFw&7|f*lsfC}J zM)FDWU9D&|z`)}SK68=E)X6Dqsp`AZ*A)Kh-p8CoZAvz+c(w_)WAb!dcw5#q*ti~w z_BffCn6&LOMsHj_(zdHgT5d@WN>Jz*rf@VaPB`p{yM{2b)(r5kZr|&6d0&?-HJ|VK z{e8Pw-)s1>8(iaYGq;#EIdf?s$gjVoyXW*a|Ev?*oEn11%gHsjt+Iwy@M}h?lvWT0 zPaf7_q$UU6Zf$2nMVnfr>+sd2G%rtB zAD-*YS`8jO_HHsP&X!e-oHb?vPcm3NBjAJ664N3>r)Q@xz?AEMbWC1sE z-;=$Q7{L_Y5}d^l!2+Z!b^Q7b)NkO-jq+ zfgP6@>;El~&d8ahzs?lbIg#`N3YbS7tk+@+ws5i z_k3&8LUv~&!+UM7kF|@*MS{@PQS2`fE_X=}r)~j>fJ~eDmtD>$+uY<(ruyHawKw%} zLBBrmy1}Uu)_(6hC5MhR*L^i>uIKKm;rIkC4-S(4=z=fJ70rUd9~iYqQfCVW1D3Ij z6s*%z8^iM-bILRVd|`PlhQ(2XPNiS<)8F_T!?BXcu>{6a(PCW3tr>(^y`juSVZ1_> zU=h#9p4xdM(l0YM1oh*=d8IFNWTP|mkxD&oWNo>QkJJYvY-Yg|{hdR2{zR4lRKJ>xi5=l9i2&03}CS=<=1az>b(P zWL`H_)=Ugv&$a$>?$9W+hYtZ;^CyycOH!u2_I;bBcY#@zK!fG;Yxs>_x)jWIyWP({ zU3dYnQ{IGfI_%ApJY=d4rros4IU*5$(h$Hy1CQSQDBB{l;GW*-ZVTj;@V7{3){RReCH(6@VMXUGoWPBY~+l) zs@d7m16*uEpElZK^J(tOu2Z6ROG4KU;Ax)9{*tx?gHd_lIoqoT#V($VYlMOGiru0y z&ql}oHy{lS9fGIlQ5v|R7BYNVQ&W@A$QB*GyXyry&fLD5FiOVwVHjyp zialQ*F3c&_`d>_abzIYH{4W-$)G_F?Q9x>R>QUjSgi1FE1El8|A*G^lB!-H_Xhj+} zy1Qd+(vBK1VT>Lf1MahP@9*C0zaD(O&X?!;JfF|IKJk*@DcqRT+x9D_YYPmB&c@#Z zuhRJE;eTbHuq^*{;n?Ej{MQTK+E<@06#u!#hxubX@q5&2Oo5y=^c8#E$nCZo;&;Lo zJH8O!LV5U~g(ZtN6NraD{KcR489bpDB$T~>K9>l+i}=S?yu#Z{A0aLhkt{A9gUCkKJl?E#*E5ygi_WQY|kjjyQ!WHQNaU>}aJ*vF>tA(8`{DWO6Omf1> zR(8eKKUV^2Uv}!IS=>cisy=X`AKymy+ofW4tI2_?;Og{qN-k^IYr;=7;O#q zA^mo5IP5<-ILUr+k`+J=jI285&&Uz>_HV0%h@vO>%-r+X^)s5{BFG~@fZ>4fzwO9;Lw_!|Bvv{GXCzWG z!>Odts(}m!t`>$FB$sRWXvR_0U48R}N|?bl{7v_%%I-TA)B;kqW}JaTj7EW%XDyYV zY7>magxa|Uh_H_0C|}Sq{Rs{!KEV@|^8Tqmb8`QFb1w+|b3nMC)j#c`6qTbiJE!Sd zQWCUp(b2Q}Y_v489I=5e`V?*;ZS`$WNLV!EDNIrAhxTwsmsCs3lqa4No!-=?a3ybW zXzw;bcw7DrcSe10*L&AUx3>xni@W+s)kV!mkohjToN-g{&0O_i*1wil?OLQXI)O>i zVmXO&dLTosyI?vkQM7p?#HUk(_!#XU^HSeoM4!t5&2k|qd$J9YlJ(X_dokW=;OUNe zN?Y|$0NqLNMEd3OA%nQC=USe*tE5wIcsVKH8SjHRl_+e*!q@edP070|Ap=Z60(TT6 zoMnbi-oIbp5h{aLUA(~snXg6^&&qO+?0ptBD;XC?J1^n<^9r1uo%s+`7|%jgJwMV* zHG$}$PL!>=1F=NWCPjd~8kW2#6(y@V?lJl?2%6gVea1xk`h&rt(;_Xy)x5EfrGf8(fM&=83XB-z zuAPY(|9bt7qM!GK;(gZlGL^IU{-q2zwo~(v-#R>N*N^j~n32WSsw)mmXWarV7zUR- z?sv@DX;846L z-cn)dWhjYH$8MyDq*&~&#f0wR;(m-*Yk@OJ^)rQ-p{36sI{2#~OZXO?lMb=8vqH5U zs+>Iko5PpgWQ%FuIl zC@)WTgO7n|J$&4L!dF$E)lt&!mHDXmAGEd!@jCbif+~11_hfbCqw#m_1D&?e*D!d` z(O}zYw}`jDYy-J!aYg+tOtvUjJ--~Ukb{l;{^yt~Mx1#twSn9+DF*&x>M_h?nz1zp zD>Em`dYrfhB^0ezhRep>`>2-__O`wri}illNbjXVFj8ArdtaVm`kz#uH=SQo?E^f6 zTh8!1RSr>3?O{whWL57YVxHb~oNH_+Iqsz}Ug4R@(6;gJJ+qr}J~Kim#0BZ2rTz9v zXPTPwO^D| zjzkh83|X%U98(FdOK0pJpQ=E-?nR4gcViY;k7|D27U?HhEPx)^Q9sxDwH%q)bPP}-!ApDM}h1=fxtd8}}@6*x0A74-| z;^{t@xuk#LqEUv3{%llhD;o#jrQ5=2*h@*=)bA#R#v4bh94*3JcEKtN2Uixh)PDM&@ZL?&uOEYin2 zy38|*56*J5wcJF#tx-o)?EV>170yJDTgCc6SG4AVxz8w=7P3^awiNq90x-ot ztHYuN*fi!c+}0}RHW^wLhV>vqS*W|Lzs>My^k?03m5|Eno#pm)SN%a!J zgr>}f2aM8V@m(KgMzOg1c&VzYlgydg<~?ghbqNHXHsN3iGj~%(e0`K3G8%V2I64X| z)K7+({pDU>Wv7nsN{n)HPqOg#5S2)Fsl1UF4Ik>Q-OKZ|{r$}_*Lx;`Ak&fNo3l|QYJfnr0F>)AY#{Q&$1Lm~>8BJa z3kh~u8mNb5MW5-AXX5IKX!)2*a=H>?LE#+{K#zJ$Y}y)oTCQYClRf?=Vx19;>1Cy* zOS$F)jd@!36US^`^_k8O<$1<8OlB_%5AE&7(T&|pb91*q;1WombSmRz6H zq(6Bp;#STB%Xlso@t)_WeG*O&mhpVDVLOk~@Sk&QG&C&ZSeqwe6I}{&4qwUe*5q#g z&~1!4qeR$89+|e`@vqJZlm6QOG<#(?t?9MNSDjNB?(4`u{q=9k3kG~65(kFH@dSmq zDUa$RG2>w=f!bQmq`S{kuMA9|cd&oj;{n^Za?RP$`&O?KyN!74BP`@*`+3C0J}=1< z?=!WZH~G5!{YYTDZmfD1d-9~gn+@45u6P|R)6w!pvm}|*^*Qo`a(O9UO33Mdix9R? z5vdCg+w>4}$8NVAbTUilZ++cqbW6O*M+6v0j=*bx!~h>oz`8!Jlsq7Hem2vN{x>_1U(r{c&Y#7AYz zX2w(nzd12EDL$!VXZ3Ecpk9wrd7zVH<95K{3PcT6A0}l$6!m{2kr+xz>WU({nh&rZ zx!77wPx*CgmVHFA>J$1|MTN(-28!FA!))zBbY1_pcPODI2R^rqBeXfXZG<{Bslxp654H%Up?BT{a~KBYQUWhni;FC1`oO$4BsFwkdjH~xdE=a#24z2n zD#1MJsa3JkBT{3&c53{b%k@u|1%`BGi&NQ~IEY~3@FK#+)%AN>83z*^f8%sZsFak{ zJD{VrwYE%tx(e0AA zZU`k1v;}of0e;P%Hevts=@n<8%#TPRTSDj z^+g|Sj4u%LXd3|)S9|f4(E)9~_92R(pxy|Buq}cmFhm}aKscZIJmWQaOgS+z(R(_T zV9;)1<4_wz?&c!z6bcw7%-i2<J5XT2{M6`X-88gzzMLMxRWfFlA|me|8%G#k#S&r`n=ME0Z*aVU=h ztZ(=tLAAXMyQ|z0O7^1JbZ90!%6rWX%A|*O$1vAd<&@;CJsbd7Q+kX%Y9n{klS7mi z(cfG47L_*|j~9XSK2-K6t=dbI_Z8}XIww=wgErz}v2T*T2sUhKZ6*IlQmiT+tb+xu z+#rqwfa)GIt>^faJkJ7M*zfW2*6!}}A~DL3H%T2)B(OHEtxq!MNrr;jEj5?!N=4O} zGf#L2l^uu_i(|RUea@vUJzl^pDp1xlgoyy#BIE-$&Cg&q#tN^poQHa+T@s`9X5pKpYmpI_34eLLZXGH45O%9gfc*h^gNS2# z9$?n4JM^*FQ%3lEk|lCZZL{;x0_qlf7McRFL^co-?0tK`B2me3IfXyhC&y1c^XF=( zFt!m07-{9HVI~q<&Vm|#KuBQc@hZL)>6&ABxS_)0Y^e2_`XIW9YVJR1N$%X8bNnVN zd`wXCQVH|RW%3O8fK>=+v5g^U#smlw3o5W7w=GR*({k13MIVEE2`&}X?Cn;HW(?Fq z4`=kND!EoEVRZ=Ys7DhJ@X2>cvUgRlswZxb1^SuDvDQnIRrjkGVZDksdcRd}hZ9j3 ziOgy&QM`C;T1N@)-{qlSN-eR|KRsc{4}Rhzw`4r}$w{{Po+8ZSmiYrecZwZ+0zVS^ zA`%UeHCH~o`my%vb(5l$7JJBp>5;{SXVClid^)wVcsevj~7ZX zj#@Yl#kPPIRljUc#wuqeK#7sxW1gCG2%OtOqtP?&Y@P4D$HvAUrTI=Zo&Y>z8dx$S zteevM=g$pb1bkj#SOio+U^CN8UtgZ5PoMrK5SqZM6nYrq!nNy!GBj? zZvU!0?uKJT+|AxyU!$QGow{|COFOiDQU;nwJFWVIIxz}SaE?n*8CQ!>nBh1seUsb~ zNi7}Ky`&`qd_DP0=s$M{pe%gCW!L7tWF$&>sNS_Rt4n568Ry=9mS>&$0h7JaGP7BN zMr4_d^BVdmAN7SvWjxBv^Bi|^6EK2#mOnofly|Vt>-PU)uVgU&LizLFl{eaCvEZ(z z%r$5&tWY5yQiXRZ3vQdHq`Xc)G>w@UrEyZ#U zUiNJFW*G@m^sNQ`3j0M34D4@xO6wYQC}=ra3G?~BLpI(PlsaAW*LdNtm+o(VBhBd z*D?|k6nhr5zTNpHoh1zkLFqMj1Ca~9rtwyaLGTNE>x8D?EDo}NJGqpMJS=I{3T9%c z`Kn8e@M9gAZYzar#AB$7t~zqX40^BPw_up!7{#;VyZukJlB1{XEGr>R0=@h~Nwv^- zu`N-_l(QGjp_ik&z;2?f*RPSmjcHF^+CRWo-}`2u&_y19O3HpN77=a<^xW6jkq&)s zV^nwf{!c~{u&M$Dg4ofJQ`rxR)ZpI7TmOk|K+dKC-82BS3fz2r4}dudnD==j8QsP! zpC=WlK_J1*T;kSH=oz{d3AQ=^JV^m|l1sv}b#Bi7e){mRA$?n|i_18N3UtU(B#7Ty zYJ#McO3GE4r6#8@zdv2j*q=$d!!Ne8&rj+tZmX<*=$M)A$-0pFDH@iQ$1SKM*-_QN z&(g*_kY+h;8%Q<%g=jf6W>Qd2->{SE-EBMPIb?yn#p`IlC^tZ@olFv|V%2Da3|tlA zW6P2bAg91K5l5f9Bl}HkUVDg`<0SgFRy2r2uW{>? zQmivn?MzScr1wy#3KE_C>l{=CA>Fo7EwAL`pAtn4m)g61cW8tymOF}q10glGLf7^+ z-oMy7(O~oQO&j(1-nIN=1L0zjNX)3_;;mmVUDbQh(Md1f0d)lD`{Qphn~l|&ch9(V zj47RMPd+U>$(c|`cQ^WU<{*9oU-p!dyqp>5NZPN zAI*XX2}A$4lN<}be)3P(<*cbaL3y%Rm2Xn;AO61(qn=4vA7y@sZF*%~Ul-3ozOFfZ zL!R#`3@?)K(myUcED&cxc7W821a+_d3dDWs%;iF`ko|AFs8krbQDg<;q9{{EC1Js0 zf87rLWOF-@8-W*fTRF0nOWmIN3@v3PKg)9;XM8;OtLhIA9K@E~Zhc)kHZBe}+s$EK z>vI7DfmDJ-c$gR#IOX2aT__!34KC1~78V!3*C65crWwN6vtFMuD4#65Q@6LLVY{Qb zYHTR2B;q~}x$qg{4mren#8KtwaV>mN(_x}+h)?&vo?1eU zavs&Vz;m$3%FONO9Ukjw4sTQ>G(l;fL2b`yPIO+j{p#YPbq|e2GgVr>vk%wBur{Nv zkl2LrScD`4<2!f?}pd1}@*y|(R@pguf$ zp*ooo-i^??HsT};K0c@Wu$0)F;qn;}@Eb5*-7UvlRoL1$(RDJa17_{Au%IEql{;^o zq(1~HBL!Jr(h@Ex9${UvFHc3J$r+(=N?P);q?Msa?FyX!aDuDHZGQhq1Unuh;}JRg z_n}aha1xtGU~po`RKuGEEGqrR2%XC{W;jTbSm!>`W{~LM`wr5a^ zPgYR*R;W|00o`8dB@Vlj;W-Z_;0(#{Jc3FFe%RXKtKPPqF+uh9BjG@^>5ZZ5pChEay}Sy`%02=~Rb(VN$Gpgj=Yt$ZC>L=SfworytFCF zl+(iD(EV(!hM2v3)WnV{5rj^z=DT;d-im_ud>4Go$jC?wat06-cFX8~slrJ-r`MPzDs-7i3i0Pd3u3WS)S-7An9BWqAz-F~$AHKnw zq@!oi-u7@mDQ{-3Juqs38CR~Lf{N;<4{3Y1b%qU&Wi~G8-|EioDRByDgQN%JnhKdP zn<$sw>c}4VjAh}GoiP9wN%YLIxIlzasY8CKXs~h^E)e8EewFv7|Lt{V!*PWr9}2EM zc#LOMdi0T=LVBve8_LXe~tSIyC#M^PV_PA$YoR3 z1BMJERl#R=Z=d&K@v+p@jr~%mAi&~>3g)h?*=oW=EVj7MqfegjO7-JDOrpW=ed{U> zPNWWx;HxMJ_9+Vq2RGoDs&dZG4;`99KG&Y2FYhKyScqcAl65$JPh9 zR3yO^4@M?ie}8`Zl3%X?Zdshgh*P0fmNeSUb=`fq$X{2Th1a%Pma~`(A7`*bHHSsz zDLGs=G9-Pz0cI=qc}`dK0QyJ!Ey$`USUC8If2YyjnYmDDUL>5gE_ zd}=6w!N*d>h8DkbP22*>hwb;v89SZu2=f>lum-XN;+N3WJz{R<>LxbitK&7!-D_62oYk^!-RvgXCj)$xbC}-=lFNF%73yDA6s+C=lbegjZBNmm(!J z&g;N0Ah2mN8(f3mSTmMNDOnZ?UkIiAj?fH=GYd+3wmLt5TV&|^cbuf;GH?a~qz=Ht z%)2Hy)Cx~QyinuBV+-x~c`PAX*}e9b%BpGGSKGtbhgO&TH?rf_+D@_^+MnAn3$SYc zIFh*je#8kY(2#t5;qDm!pkntXvcw%F{&G?ZXU@`$hX^DIW$vJKbeJH=-Lwl^K}qU! z!;Cu;PYV}Sp2&Ypg=S#opQ(PwD+{DKUmLg-ritnuK{Qv_W38sE1o(N(q03`BX!Y&i zw#4-k`r>D`17OXpxw1qb@wXFQp+m&pliIGh`FSFN&4tq(rq24!Q_!e4k3`w<`#2Vv zgX2H$)k)`tvu1NkWP~4>bFUw{>I1NMc?hHJPlH*cn-C*HTc7MXB{VY5B zYZnxo(^NF`qY$1d7H{7XPkk||Sbs;i`Kl*d+}PXcdZN#&U{zq~y#)}t_TgbpIeGbTk_pJWh5hNg zprxfX1thNufi#~BZ_xz>HejRxE;3PMkYdo03MVHgXb_6?URc1uMwm*E>67AC_5Z=C z+S)eu_KW~dJ#z@q!#)C`%9(#B=yVH8k8hJ4_B~%h_^JMIRhV`%W$HWQ7%HXP?&gXV z64@dCm&a>PPtWpejx8N2-ze8u>lOYPOcNRS=vO2~t3dB)*m_^#3mD%J|7TeHzI;^w zJ>T})PLSPMw9qznVNrg_MyGQ0jbX#N zu(`5ijb5_=>0iDXYj$#dUHLNrb*gl~f%aTxG>588Y1<1!a7gH8#GcGv`_531-tJ}l zS@o!*k={Lfcss%k3-^v9PdV#g9umcxa%B)6d9HBj)lG(Dy!IB-jRgv4a;xs*8hNl2 zOSv3#ea>JzX(s>US*L@|>lrW>Oa8;=%G1abOb1VavI^*{=z!B+E>9f_Sq)=`|3U~?*b&c=VZ!FZe=lqWr!0a2NPCK{5&;f45b~io*#`0IsS z#3eK|z`Oxlemg1b*z!D2_iG^(Cd(_OW0<(WycVDtTvw_d*S%Fyx9m#nhl3;DncA`W zAE0^|TW){fbneE=%}Tv9$y?st1jR9EyGin0^5vMw=rhqK3^_6$93eca`~v2GbvIPK zOh-w7rF^a)n?U_$ojEt@qdvJjPc8>tuiKYdH z{z-X#m2jLdjk&`gRBFvA!MhiUz&Zn>B!NK2*uw7+w6a~^x^P@q3!uJoi_1cAFD zWo5FU?I7GU8)*a-0Nsrk5fw%1{BoUJK%lKRQQrH^g$ujwOuES>c}*4RX5}FTwAPPTabO z?UGI}RG65X=O1}#`zd-C{r>Z`4X?s}wOX%#aK7RJ`gOOD@}y$jkKQxssN~lwGmB8? zU(>@_{8U4kRXY)DXlH9zTr4C%VL2`Z{5=N=E6L1Xf&Qv_64!uwst)684j z+nnbd=JfQzGl(IU*%u>z9OoTRE%~FwU;95hG|zOHskrrlBp;O?_@Q|z>~qq}bmm7k zta4~#J*818j0$rX%vLwm&<*LJIE98c|3T*oHQg=IgO-oU3X7s#U;{q??ByNyxV&FC znC&H)I2aj}dp^*mH19&Cv)`DcA{N^?#=jAsC1>&A&BxR^?E%_CsA9H$eeSU(#+1E?vn1 z_sW5m96dE3t0=4zX!7wYe);`5Hte@sJa>0_jUe9?w@m&{jG}tHd)xBV#>V##IbNbK z>ezu7YM`{Ba>lh%`qQNqs)}+b>H!|_Pdg~U)qiu*HkS@uFlR6 zz}_QJe*x}aw79jK{enm!+y_kG{{FrPZ5NiL?9C>ulSB{k01qGo9a9*=SV@Qs0nZ@D z78F=!W@ck6E6qAfiHoJZBJThQF+4ItEyDz`((}uaf~sL4Dr9PXw#V4qTx?(Cqe`f|QI#jL4X*xai5mQl+`$k z(!7TJ6E?B!ohy`(yzbOs-Q^@wRC;2$7TOc7<%VEMmLPrK*4qunDT!lbKSHcwy?b1_ zPfHv6m6pm#amZ9^!hz`cl9_^9Ynhm0ZYg$tns#nEj=~!Yn|x?nmsMD~Fw@vV@sp49 zv)sCg&r{N+i?UU1+epzI z4qfyM&|~~Y(4M+@77BcdD%X5b2UZ1xpq2-~X9?~;;pIldi>eZ;5Evy6vv%*SKm#~} zxQ;6kz1jg+R894veK*A{z9ytjH&i+PBO1;T`&M}F_tPz@0R{h?AzgdwPn-peM$qZZ z2g2h~2MT=XL=~rC$dRIY@UmP>#&KT3(B3!01!YBU-vX$ozR9zRInPox(&nwGEZdDY z%w~G_4G^==-KwpOFZQ3u+r56$5XLpGl0W#LLcir_ij#JcJ~{Q8I_ zjyP=5YsQqwGkjbBFetX;$=8l}WX#h-cf1QMVztC9D>z>Ozrmwa(Uq@lVh9jRkDB!pk^ z8IQ8@mRuP1it&D8#wIN*=?P!-K{`me|B|8lO>#^XvgFqP`XIq{i57uG zopG+6taAEtKpDjk%P%4<0iMOo{ljYQh0TD-{r2P$hhM^$JBB91BNJ7xu5}i`+eMkp z=D zsoQ(fvci`euV_}_qqx`Ue<~DHZtqox5;Qv2G~+om=#bLNCHWROsM$fr%DB{{5QY0P zZ><{g`I3X;3F9sW&dr}kR0crq98N%+I#{;q8LGxbT2M$Dd~FckxFUZOQg`vVMq6*o z-7~pk+~0+Zw35&tXJb=4&h#TjEjOxU?^~crxRga%P^KA&I7o8nozlE9NScpBB9Su@ zTioHP6M(Y;#J8!bsRzK>`PKZn!L!)b+IsqyurQr=jE&`_F9vOc6co@^*y6b(9G1cj zy_>PO`~+A{gy!u(51^j#W!6}d$feeAJ8X={N5T4snpD+AAE6^xly38DUeD(ObAL=+ z<3un2yQt%p+-o#JTKY0W`4fzIY2RXC?^)oG$d%vHLWCbZ$~>-2ZJ*Q$NnZ9Yy3n$; z6g`8s%{`o{nyDXcDn1_KblBJ!-#15DVn>e+y0(Z1b;Jk22yMC7ZS*5AZ&8^QcRa8R zSSKIg%#>7A{6wWvSI@FE93M19sqaOrpI}g-t+jwXXGh4!BBEtN@0mO3sDlY0+R{ma z{AgF?3-9>kj4J9}gSUU`uzQfu_cOv0sfJGFT@ZTK;o9&&fT8TO@*GmT8>cljp5Z(bcOzOmF)a~3NU*V|@yG>+ zoGSW!ip_e0--N@J^EQ>c+wbGRnR=7(z=XddtFHeW@$=2;FGEgSXa+T$KDz^r&a;7K zWB{uJ(G9^=DvV#jBQ5)~mAQHA%*-`=2L~9X|E77h=Q#k?8CzPmx3_CZ#jX!d_mo=G zT2SBy5P1 zfNoT`*4%n4tMF^eaQ4Zp!R*shS`6NGUoHfc-1`hwbDViEH&?@`9+Abkib6vxIT$m; zaf>Gf+8<4iR0%Ber|{M)#!qaZF(s=jzMyN{kK2=|mK)-IPKcJ^;4^xz3HidI&zF z$NuIkdY3oV6#OxQ{@~JgI>LZ?(Lyt{jj-qxT-o^E_ls;6lZl2e>+RlB$=1GSi1T9# zanFW(Ik>K8n@fVh;qsf)k>;-<*0US)zB*a*#@;#kag;lmk25Xi}Um7B-UZV>oVD-M1;IGmDSnY-LC zwLN--d4g64SCh`ef;~$+(Tl`sIRJJ^1W=v=eu9R)InvSIURYfn78SUePWL61rkP+Rj~5v1nu3w!sXLIf;%TDr_mJNfsdbHwg?76NKAZJ3Ukp-Z)4wd{ z-G2z7L4J>`wh1%;J$PH0l+UIC;U>9rY30~1{m~J4jPRWB_b=v>lE@wmZ14yWX_bwpXZ(_JDZ12!v2 zQae3MK_#(GUpOS@%e0~@$xA5uAk4e)8|kwdz4B1Zz9Q4NjoSlRlw^EW+7< zT%0_Ib8IbrerT@IqGfdAw?S2o$G0-+x>dW6#LPZVG;cycM$F98lB2WpqPY6M%q-V(aMel|7w+D@3r@#F&|o6@72gAmQ<7Q$ zFR1zSG`+X(h9JYP!q&xwr6WqHV`k=MQw#Y0H1G8HI!&Yz^2DH?{mv+VX^WxB++}3D zX1k=Aj)Mq`j(xW$Kx(Ejj9VxmWTT{xrg?x*dFyMmniklP3%+Ga0m z&meT&)OKIWDmk@jw-P2@1)vu@hTB0v5;R1$&`bD632-%ecPgr-^b-;N_F7<^>v&C( z`GFxV;W+OrU9kg81g8VEzG~Y=Q2|-^3GNbo!`Lf@w)n%nJ*_5XO_}||5^TVBapFpn zi)^k_L}Fcg8(t}R*>N@r;jlRo&~|6O>BQ%LmG)mE&!$##hp~OV9{Nhz=~-*v6u&+( zBWF{HEb>ePyp^Yyo*%a264uocp1QTgKRI^vUvbwE{%A#+`4bH_kJk4;9fIqyT?_E) zm-#%T$nEBRmvmvLcesG0EN{Wgf4Tkmi(}MVagh>wJWl^>ay}xH1a`dx9Hq}u1{fsi zkvYJRpQP%?NyiMqN^Y1x7Cgmt^rW!xZJrTkhPJmsf66?z77X$W3cg!nxP(G`bAOgJ zW|>$Q1GJpJj9LMRHK`)obIg-HjYr!upH{cQVgWg!tqbTVKQm#GyYLQtqIY zv?xFKr3OUb!A+((3#%eoGg0ZGEjOod@2x(9KzbEs>yZvra=DhIi-0{$s|3T2Yu@3v~+J#Fc5o`O_DU0r9%rpxoO`%~`kyGO{ z^|u@ly~WEO?k^Sg@31OVp{4VSzfxqjN_I`xI{V^AoW|irVK^?&UkI+pTYv`xuO|cG z`)cg2)3Vbn_&+i+0ND!IP7cgoT%h5h^9EC3t_Sp($mCZu@W=v7It*kh&5Uo+Ln`s= z$0}~b`bZ$XE-1JQ_*%M`&DE9Th;u`-#KQmX)0G@8QHyw_cu^;qb9+?6sS~66HQ%LI zmt6Cs--e401JG-kMicl~;ppS+Ejwa?(2!AI>Akm<1rg+)8ph8J6*<%$C}@OHNLbMZxhK6gy74;nI z>(|xagH@3-ysZAfC*PVLr55Ip;>!qtDB?~4F_a#oNe4UVKbW7NKNT9Z8%m{z*#RZ~ zE>-9l=067#MgV#eI3pZ*4e{Z}VOhiW$l8GV;lM8Y@wEDs&|!Me2Yk@c#x6M# z?Vv{|gU;Q5e;~Epo!0I?wZF9p_Qtf)cYFx#z7x8gyL?QKol4zp6{hFirPtK((S7|= zN=jkg4F?loc5S6w0R30ssV!g)a9@A_dwOclZjsP|6#Z5)tbs($zW|D+05C~90=c@6 zUTr2G_yu7qiTQ_9>_=DJCTl-69F2hJJ}?s#X}!c&@Vu-Y5|0mexsGS7()t{yHd2pO z{>$nEd?+|9yWfTOuhM?8AN~bYC{*Cm?b$7}I*`o=l9h^}g9_k$Uu!(YK9#)cFAO@i z0na0PQkT&Fuh2EP`VL&de^>IYvXI$9GgtjvdgkA*(eZ-S_ZK-+>c`~c2zo54v8ieE z)YO$pknA-BV)2~1(+|sur8(cdaW3}y$?L;&Ng`y=+;=a?8V7bH2fT9{$vSLN{1YW2 z?~^mzq<2+WTi81TA#lv3N90)$?K!sVGMJNl`+y(NU|nh zmgSAK7`ltT_Tp8%Vr=&%rtowNP6mbQD!-K>^|tT%MS9pZg;2|pdNtCp_i1iwRPYxC ziBdq#fu!-kZ=ybzI~o|g-**Nxv2(gFX=`gwuT8hK@%#X>--xDqmb~-*OlePpXEwwfxwPo3!-53W&6spn*Aa1pk*$@S zh|=uBVy*6hF5ue)$jFfBav+M0S^2%y^jT5KWt&}4!`2-(*R74 z)HnrhLgkw+5jvs?Oz0#q3IKBdJYe(JjE=gkn!wCQpD{q(+v~WMRl2`?VZlOkMDh6H zNOix#R{e%HDg|p+_G;Wn-bwmkQp?*Zh^c1GT+iYHK8M%{haPt*^r@@;&9{*qlI52^Tslnx}4csU}f$ARJ1sXF(uWGm1XJkU^v@Jp>Mbvb1gYW4YWRr#|vd z;OfrWR51Gt@vtT+bZE$+b~RwN1*E`*f|w{FtKDX*O;sVb(;8WWED_!rH1RH~BQO6hln>AAps#0492QP#1j7l$obZr_4{_vtvQjhL{ zTGDs2JtN~LD9$t%AhtL$o^w(e_#BQ1>IV)A0sAsQF!au9FUG3L{czZwzTT3Z-l@^W zLx9q5*nHaXfnGN0RWDSXX7gVy{r%fmk3VojKIl@zwsS*>`fjj#BWR!l_u_(hKw1E} zL<|i7m1t6wIx>~kmD=iTbzq9c<4IOWJwczqzeg)**s56DIX)tG01Rf0o)qkJxM&px zzF$Lj_t?|L)m2S!-~|1aq-eWQ#|jK|6&Zc2>*QL9d>Xxg9cCSW09zO?)7dV1Ii=4b zyIrZY$Mg^vRlAOonwS*h+`ep+yvg4{3ZO^YfVK%c^)+3)OnbH?4D*=h*q=$7o(DHj+TYR=#<1l)##nC2yp=p#*ea@72Od z*_g$A-Y2ip0*teiCc5xW(5&>k!m*b%Dv$>3Yqcs|E%}~3^Z9GepO@^k2YMG$=`=)-b8Y?`+2A^sW0#3mI7{#b&rC{lw;VQrh0t|=F)Kba03&@s z+CUx4wHp1`t(FMU0vO2 z_O@DT(KgU}fUnO52l`HHFmyQJlA5Tb4j90=flr_FOgLyS=+Ata^N0tKBx&jDl0Yy{ zW#FL__;2HIXs9?#=K0SOci?MDt;? zV2|83qzbIss$2DB#IIhAMAf$Xh~Kg{jiETiyfW&tvab+O8TYi@QcP0&*V&C^VdDi? zP@P#aqT%Ecdi<|0uUfxWkizu%Gl9@%c2`vLa3n*Frl$ADrfJe5F}-^u%TcItBnT z&Pfg+E&T+;e+>KPclPP|zH~t4?XIjIxzSp6X{YH!;(rR06f;OV-$-}Tb%XT(ZxS!l6U7sg*MnFKf zd$*;-R6$sMu0Y=_H93%uv4R-{gkONPMq>+$wgR(?UjXAsQWQKEiFpEBdYY6q2^v`t z;XoJFM@L7uY5tvF%*;R^JHVqMCNBOG5IkJs=8d4`g^}7Le>_Qs-eT^5tIW42_SF2$ zAD{V?HI?N+8@;#Z3o@mMjo_=(kr0q32b$ECCnxFdC4T+6#Pw%;+56AP-c1qfgJ+%* zjCJY(gXONQMA66`kcyCCYDPK`Ougkq_SY9%#Q-ES+j}kK?$~cq+G7e%DPlGU%PF}$ zo^W@dPbW0@Nbe1mSpB_gB-x)a>4Ys|?o10>kcPj0CCB~7x_p`4r?UCs#XNtb!(-#kkv zxjD~rOGHas`#TspKojaH!~1_|2s!}REL076VZccMVY#7y=^=>Wq2FW}@IlaJ5le)U z-Dvf_OWE za_zwZ99vfUxXZ#7jQWCzXr^gjc)(bp$%x|ioPzNI~GYo>1vOD zX{+Dr!P`ks%`e*h@6DStB#{(Sn#*HJ=o12gH?01sQm&@vY zeq9vWZDd+|$L`PI?%QKlnAjK_@;_PtaBPffXE^?gPV=r?w0I;5U#;8Wd<>n^;n)OB zH*9hEE&veH8X6kTK0GnCOCeCU?zab&vtBZ^DC2zo? zD{fg)RtD%YykUha07e4>1OToHKC8t0PI`MxSDy*pYfB|~`aeQnHqn=^Nq=Owwzghk zvuC0jZ#g4_+%`T!CD9w9S%XyeqcyYZ-9jme#~;;Z-iq73f7J}9mauqZ3x?LKbrK5# zGPzos-#k8L9+x(_#nZ5L9ZKDf+-7~#+IKcm!*(Q5iRF^K;Po|+>R+z6ZWn;{Z&?SB z#1_0mQ%Viz;x}l*Y`3eMhpnRRxcRl~M_#X6NR(CVoK#)Bk^jWjv_nt(j2f0nn1tNH zK8>UGdcd}O37l>O)rt_Fz}TDZmqfkowv2Mr7y=dGvfn5AhVUDn;RP(4hIVg>fZr=Q%p?kvO`HpJ!se) zjq2AqYWIgQ?ZEMZOI8jAdr#}L^+8(!5M4U!1%7_@N9cyO1-u%&cU2@bS3=+Z$Gv+9 zHd40S7{#+bwt%Q5UoGWR_dzWCu7l$2L#csV=T%Pz#$^vVJ6(@ypN_gMj!ON@mO9EZ zZeA4ataB`F$;QQ``%6b&@f#y5XeO*>kjZfDYnzsq{H*USGZoB&&V+)PGqnC)i~PX< zV(Pu)sqVx7@g&@L$lbC>rI4Auk0y#JBb&-z*((Pjsf1)@Cn3A+J#st8I`&@2mhBjE zj`h3V_viEdeZL<47d>>|@7MLZuIIW|JL*D~D~}RG_n(ZY@K*TlZ9GHnc(N0QRqnLv z3Ws98Qw+XjfOmOzdQXs_s5+_k0xrFvPZOZgJ=vO`o_@Opc2uWAqt@HoTMik;PQSY@ zAHcmWh%^%*p7b5v*xlV_C3R`$_?DQ<8HO{JIjM1Y^L>m z#jr8v85)gNccFvD5dscg)QD8?xtZB1Kj_?E)A{_qb7JkUZ8!^rB8B}TPqkA(Qr}F{#8KXU)?dMd;V6_a1Fo56y<9t1M~L)4bT#_4!`E^gNiXCKIKagx6&C zZGs-erF|81acw>s>u499NvQ5=yY|`eW+cVg%F@CL#$DwzpfQJ}r757Q5a80Ym1F$9 zr7nA#Mh%4J09FJ4?Ixw0Gvwost^21mS3Xjy zk&}}nXeiW6AX0u57r&mHn={g0YfUSBP*Ye^T~wr*SaW2A-!YPMp8X5dtUuwa%`1G# zO+I!Y&mr3X_ws;x{Xb-e>6(x39U~ZcUd2b z?60Azqji!r2j4`dT6Ki?R=D|QWX>eDO5)olCyCJ#+3T(X(Rt6<23x+i1{ws$N6jxU zt=|Y0lkRlfz#k|^2Fe>4jA0u_ti(<$yqbFcIr@zL>ux)?CH)y+{f~`4qBRSyNgX*7 z_aya+0yQ9MV3qUy(OmVflV_-6+FpJ;i6jH!n-IDXc3F3tw6ruSug$A!DX36T`>vC$ z_5u2WRwAURPsph9HJ?uY(`V0+Q*$r9a^%sZn%bg@3F#crkvCxWgbp6+!^#LctKa6H zFQ(=73$b!HT??T->3%A~ik9lubE^lc8x0K+_F?x-N~V??u|5;Or+yBd*(@pCnHi`# z3aeF9&ob(sE!qq@UVQVQX`T0T&kZ zTR?h~N~e(I@H=$!uT2j7O_~&ru*ZzZG9`%CL&k)Irn)@_ghWBsm+Xx#pn|)*A6J6{ zN(qW9>X_I`exi2QyN&^_$KT7#e7wb$78V=$<9$CYbk0bgE5!-N84N8n5bShv8z+G0 z`fpv6$0Kj4{%7$e?#} zOq!1OIF88ybn@O6gS(dw!kK*!U>}vtQJWu82;nnlXU&|B*AJ5F0{ylej%blr0N73h zVa6Yg`h_6*%bxHL9oo-S;E(XO=Kfr}kAqJ(M>|Sb(AWQVpnYw)F+<}j%Gpg*V22hT z>3H{UdC4q`{1@(;c~Wmdc~068P3-TSa%u8>e>J_rjQ0CxG6eag1ncx$xsC7GoM9`- zXiM?0ujS@ve*Q|vr8!TLWGrLOTjKOfpA@-eoJmY8pq%W8I2|m3`qdAu6_5dl=@NNi z$>jrN^0lZ(UI5c^Q3FEC00wXJT0#_PFsz42t}%zoVjJ>ua}h{LC*SaTb{_)+L&!84 z7Hh@I50ET^3L};{7%qWua0CTBdezpX5!OY$cWd9K@p4_5UDnrD@^EoEkK7zwTwKVK zTM#?&3kj`1==+zLb3pj9XL8>8MUhfYR&*wRUD!HV$kKI&`VH~%_Qw^icK6y_JU5u( zy{YODvDE(!0oJqG4^3I~!an%Mi@9uj$PLo62Iu5kXX<#Vu4!h}=?Z!p_X`Qf)?SQ| z=Wr1<>Oabn6COh+x!u=$nh|ZNr>R?FtufRz?>b*@&Ts$zlhoZ+MmeexsN+I$`SDG7mHNO;3Jqj}eh0UL#jS ztX~OvZi<_H*1<9!RwLJ>r_Tx2G|b2_Sq!?G5t)mdZ!++yF z$lSha$UiNBLUZ;Mw~;8xyfFPJqV=M}%z*6v+>)l^RN4y>X`@ezk})B6_ELJzd&@(D zPT4O_BqO&gdxG|VSKHv@-ehME4gMYXq?%Ys|E1i^sCOr8OBCm7B`t3U$+at^abYhUj`p*Qh!{cjN8H0oGR>Du{=McDfZ<0#k zEe`jPRn|RM`GLaTWFT--D1TTw#Rxs3l;_4J08O0!tPDR7i;lkdAESjZXpkxb1mS<{ z+G=(us<;{Pq=7PIe22{~$E$URlIYFI6aW`>Zv}ePZYAvvVNq|8{cBB>|G~2ded>o= zkEax%^sf_>*Bh{?Kf(t~1xLIf14Y0S(@s~&GehJ-fpn<1cw!R1LFnL@&`Ra;nnxWA zjJSI$ev3j=usi_?FM+lNV`SNSyzh6s{vUORkeL%Z`5seB(C82lmTpXxX5YRp>p9h$ zZ%OEW{6*Pa{#gD57{QV9k*;wIDyvP2 zzLUkvjkv{s?(gjJ=s>LpObo$?;Ce(@Kd4yHU<=G6*95%xHxv}Yhlll$Di6~pjH>hb z4;;87)!e~whWyyA)nwSG4=E;-vg*zX+L2`k+ z*-z22`(j>)NA&}T1HUxs#)KVTAC-GTZT5bmv1#3#^`;16e~!k+qc0?x$~CPHBW+=Y zW%QLMe=POT5a!=wCw}AqU##p80QlFx0EeXK;2Vb#1`5-_z`&1+3caiN;5Tnz;qm=3 z@AVp_#e^sMKlW(25#De0EzHl~fZ7Cz9>YCKg2hc%;RQ4QIjLIeEre+tSdP@e`LJcs*=buqaqhuQ^K-i=cLAf8X1OJ!ef-`QXKwf-#6RM*JJd+3S|aCJmUlM83Sc+*6s%*wXB zgY=}`6BD(|2kunJy}VYlYb*zK&HK$WZ*LZuNC8AB#gc(uetrbm%`#|k!KQrZonuEO zWtiaSx0YiLgG&1r?+wXc*|Cc|c6=9ev2rzbn=C%vz@)CD_svBHos`D>Lzc=PYbmv3 z_|Pr8HSw{;w12^`i>6LNS<|Tvwu;Alc^6fgc?hEUU;DbR&B!0Gp0sTW3_L~qh+HY- zr;LJ3rhy45HJLGT@#}J@v}>h=(am!|L<^X(R+Xv!pr_GZ0PY3>>EM%xDF>tqAZ_xf zc~cD_7JzwLci^@}uvTapkwz1;{vG!=rlz$QR#)v2$_HR-0Hi+0#Wg_2YRDFVA|#{x z#t#EFDcKs&ZHH}5&ENr;jmQnB4cNmSOxm^vei*E0^Rot?0>RCYWNrk2ZZkP@CXhT1 zs5yeM{oyUnnnX)B+-6hZ?{gc3#N=?c(D2hdIb*J&<{?vNBzm`i-4fzMy8DSw$D_rtx}fPJ7I2x!?0& z17mlj8Z#2!v@4aBns&fUtd+c7_A6%RSvfpXvM-*tm|H}M}xbb z_1d<7$IR0wx)s(ZzuP6+9j(YHtfOhTHHR^YBMlbs&aN#Cgs|X;-Ie&TI#|p8drXO{ z-byT($9_c<8q$y17A4*kH`n8GUcScmZskXFoX&}){d1@7TwrDCcI^^t30+(P&gCaq zcW0EdZJ*0av=hI7-U$BHfepqhDJml89x2UGJmJMfAVBbw!3-}9YDGjJ00=7b7~0!u z=ouJbqI~8P{YsDe)NO{MV-$SKb^9L2f(SJo!XPwV=DS=5dZ_;C#!a|I%N+2S&CN|C zhjrnCR^ll8o6JZntg{6!ze^DYk3)?Q)*Tm(S3LKGfcg zUG&Mc9Fw96oR|rPrrN0Bv9}T83_K8yfn|w%+8cT$Gnb3w_+; zAq?O>!fBPcD@41QhN&*#1YkglzKQk-(P?ed_l6}C{+}#vfCdRh{~8{~=bBH!-QrM^ zRTu`64}yGsN*(4*wy4O63D%>7R+9GP_;JTu7nhDAm)15K;qWxI;KqImI+?JvB5w)N z1G!{hH1Bf3n<%WKfAOgDBdYEe4aKsRcxIQiSc>PQYDy<24$)zcjwR#3`d4^u4{4Hc zXfzjVwJ`sZR^g1!8@{ccmhx%r8F|@iLZyp`hX;Xd6AV|0Y^~b91RLk-wf^GBsDe6v3l ze&T($h>z$c&#a3>=F6YFeijuWjVxkzL4x)HjQ}|gyiZlsh_pSxf}iTenSQ@v49`}) zd3}p}%%n5veTs`x`CSf6Q4!YZva0-qll-=7LhJW}b5cw2EeencJnOs{R*4a1U@V%@wYYgi=y)#dxD zhYy?Y3v`M43pFZ}KOPd`?8a;E<9F5>>+cqDfs0Pf)9iwKZ}dC zK8%Cv0-Vo)7mZz`ViM}-c2aU86xj{Nt*H%eaETX43!HpsIsI4itNVkmmjZw1)CS}$ z8L7w_izXxvU*b+Pm%tD$SJI@aUD@9l)HzIUUn;YZcolM0S5g|UvS>_Sz*nm#Y5Vhu zMZ$QzjzVW>f%6P$GrkQoWy|#8bk4kyCu`Z+x%n2m%*LOp3hO04qb>hqK6IWVsr;<@ z+`6`|m5`YDFQECo`$80~#;0$rlpU8D#A)!0KGplkd{}tuJ@xOtX6ZXwYPB*KW%8L# zYu6HAi^!PW$_l*ZBE=}d#z{?T1$8_7nfhr-9VN59yE9L*(te4Cv0`VC~lb5farsIa7s~0se5oxhgG!j=TC%h zg#j43r=W91q|boh16H*DAiL^|ic>iKEeG_7fWWjy_u3QT}GE^qo%0_sUe##{c|a>lV3`STEZlsx5Qx zW(MhsN-M$e=N}^NMIRN;`A4vCVrqfhLee8cy?9BB7^kgyokmqXwpo+?JFTPKWBEk; zPtvmAU7GM=lIU>43=S0|`=;|+hE|=$mJG|3YeJE<4VCCb`A=4p3xY}5meR0g7;$;G zZnZvjD^1+Fl|iQ+qxWa8cJorB(lf`c-$mv#D?xNNqT`2O!h7GD*SYZzIOTt=&pX>B z>uPXy_p6h6*5<3lDc2tpI(u!~QN6Yg{PI4JhX`mSTcy-TuNsziM2E+Vb=u`dddxjM z$WtQx5D1~aKjbNR6!z`q9({>^p41)rgCI}Au!hmGG5#=L0Mn2W3P5&a!h0Qr(gN|+ zO=xLf$!1>o*J}y+>|x|Y6du5ZL`O#(C6w9i_xl#%7YFVdhD%bU!0=GLq+Rd}I*c3Q z;z0|^-e(XL1oO_+_G|oj3qx<@Gbf+og5Hoyj91MMwpmNh!|XGU@V^#$)9vNXyI8(c z>F*^Z@NFd7_lrX|));HDoWq}Srn#UZKDjf?sC3%h?vjFKoOUDM+Ixd}1sOI?i)A)} zB=$aUy}Ekow9JveBx8OxcCH5uoj9Fg>;39(eT3|L@PZ6 zk(}4?iJG}@RF4I7l3ms8xA{c5x`VMTiB}mszdsvSnGQ@4eYHZ^Kc1end zeN60fGSlb>i4mc&-mViJHD@1Lutp~fbIC@bQ^-ZqgL3|8jr9>ca4pcVjJZFIyw&bP z%be86)>(da*qD{=i0y~fIiaVIGm{pyEIXuK<>-2iO>939_oQhz4fNNlTUn#^K%j;^ z8Sf%!dZps?02(fkRtoZh%M)=0z{NKO+aD0*6of_kiMD6Pq~}**e>tL+1Z@Z+y#a1~ ztlWv5kB<)qzfm`LtM<7>#Tt5lN66)N3M2iG#pyJn-Zf$+J1f@B%Mc?=TO4Rv2{Fy5 z#`IK>ga*)lIwHv-Q1^h800*TIreJXS-beN`g-@(()6cd&n4c|L*`V}qrPp~)(Dxu2 zhTA>Xw|?5RA%jw!Rvrv)E$R);w~6rjSEl~jYbNy)TGim(m&wQTKgB;jtcJdes|dqG(R<;Bb&Qp3HL zqGO^j&46ds*xS*=^d{x3{r)ENE`-k2DBAwVb=Xuk;Sxq z?4O^SdWIC5g^r{~hzNpZ+K71!E~BwpA7q?B@>&iK9a0v^w0xs5ye?r3=DUf8vTRu4zv{Z1OUD*9jo0-E!TI+rMZY#V*|oF$(KbB$ zIM-+1_Q0ZAj4Ai%V-JtY3(*=+eqUoBk)4v(m4GdQ!hK$H-cDf;`Z`{_4p+BAdSRGpzTL@LYEw$CmL;>jTQl*MoOP0P--kO~47@BdnKGJ! zHy_L7*j=v~V@2by;V)Q7hHv^GyI;h{CEl&iNw}s;?S>(y8KQlyKp;aRNY8<;6Zk@& zb7aAE92ijJV6a#S1$~TWl@F7v0HGryat1MoVTCgV6tkwXCtpwI78Pyf7ez?-aNHN^j8vDC%rm>*i`;0MTN8zhi=HI*b=J|TEIdr+UhY~*v8GF#_ioIj0lO}6J zcm12#>Qxjj7(;QAMxpmpAZq+-zi^__GuG$r^|AZW6hHE%$A4q~+S68&PMZA$t9G?a zawg14QVAInZ|0J%$J;4yu*ac*a}k1)HLljQkYboxO;#XuM+raeag@Btq2{Q2_;0RT@1u&Z0WK|vHi<4ghq z@Hr`|35Fh!i6W%jo;F!oh-K8#hbjXFCLE$11kw8pAOJ}320%Mu%%$_9(tOZ5te!kw z*Fw0xlQlw3RToKR8C$XF)=x$t^nb+GYx2y`|xcgC7r+K%-&MV-wu`qev_==MNF2%ESe#MqOq-dN_>5#+(5`C zoHdk@%V#1q&&f@~-J&;sm}Pa{_30l~%Bsj3hTi`heCF~%I$nk-sH>^OTD~91lUto+ zI{maIKsZU3MaacbBu#66HdgwIw=kw7&W8T`Y7o~0owf64JSio^Q~i@=D8sPt?+g#g zWrUrrEBX4XMSa^ezDjyJ-eo&c^zpps31z%imu2BjL$y=?=`ll!uwNYaZJTtw*zZ4{ z)7v)J=QA1|839KPbVgfB3UQX87D3QI@IppNt*@_Rkz7a=Dhz-SL{+#8f**wVL3%5| ze31k`h~`1~PIzcA@dFUZ;BSj|J^Zse3W=utj?auMmM*6IX_4+;^4b2~{oEAfu1_s2 z=JU6374e_FzW+@lf2VKp)Dat5BV0!RZKR&?UT=bIR76t(j~f&-7Yfiipt~afq1Tn+ zvMJA<;7=}Tw9dS8;{aH~SL)>SwEBj<`?!I0$~&jqjJKugy3<;GF!;r>Nro+7p$2U^ zgP3n^u5NOj{yc3Q3d_F@p8TC&s+prf^n0j}ame3j-%E8~G7Ea9fo7z~j1Hf*6lFa! zcc17EP6&KhVBYW@Rm3n_;Hw)a;NXty=I*796o%QmtZX79mB&V31)p|* zJ@rOZ#dT4ni-xC993L-L?QJw+}P%)XzmsvlR!gsWVC@4R(KR-;;3BB{EZy#eX(c z!ZBsFTMya(NH3m4;Z91qRS)0SWUg4UW_TrSc)>kLK_#0E@0vK1;@hsBq>YItp7q)J zPVQzybig!fS1y*v6@9I?{0xKP`@v6q7mxKT5+aG;wknrKziX`jXB=41&(8IHGxc64 zAT7HZ9uIPJfU+u#Lm>>j9H4lo2GIZl)Bv4=r~_zX^X7~iS!JtPUnODBu4ZO3yB(t&*wocNRQWWaZ@l&|wddas+#6*Cl(8+zK$ z=X^bdc54ybC~~ki4AH$K6TG;%b{9DRYbMR1i^~Ub%hOa-KEI^uAHJtwR`N1Wy!x9_ zYrlGq&tLe-)yS>HPH^T*b(mx({?OLXP@_| z^^OuJrjY{EF)!n5f$kDtI}nbh-m%xRFuHiTF;hxr#8Kfz7@j6)It7=oC}zC;UZ)Gw z?J9IcsSw#6JvTP>wG&&!->H9}*}ajV>lQU#pdDXHU^m_P=@9m2iRF8>*=DmTPbXu{ zXLW_J@5L_5_ZF926MZv-tr;E?F^5-D*;$C7-2V--dw^5A70!*JLk|O_POrms9#pdi z>MUrp)RN`iLH0MpjJvDr7vq8%s91I3pe$=ICiITw-@LL;$>t7q~@lVYS<j%s(E`GHc%Z=R+owS*4r>om_y4=1N=FG^vl$MQX zSatR4YMLr$P}vmgf@c+Rs9~MTj09ASnof1-&*xC4nj(u#;QRCWArc@oFv1^Z!@A3)2PM{o^~g z1ka$$N=qI0|Ex~yGUl0S995P4+M@`E%Ri(RV16*_{tK#0q$6f9_Ix&2uKzQ$ka=UH z1eSeG>oPIGRx#o(QYqoNRnLnT{Fld#=-_d2VNyj?=+Su1c zuNr?zZoH}B?m+N#ehVs->hqa{ajIxCA2s{9%@+kSVf&6IZ!Vi%7&^?Bo+&8SW_dz? z1Ivm&P^D*V!mlxRVrPC^yeeWD-pe)Njc&~k$8BOLxA+1zR}-n_m?SLASl2%v(-cfI z9Pa7O#oF?!KTyI3TbN##zo52rOU&!5D>MTxn`oP==W=tj;d2;|y~>@ePTOM|wf^G{ zH7O#_YUP~rLE=(>mw$JkfNq zF_BHjpa-4{iWKfw`M}o}A~Eog6nbu_yW}_5mZhf)m%*-{YV$+$7_9Sw7MeAgclV_N z#vO0lExqmaCr9+~d*!A4oPvzP#%)JA3v?3N(dFH4`|-1?If=cb+{K7TiMsQ+$2%%f zba5XDlk{0W+U9a3VN({^@+ zn0IWFPxL0SH_XWBcH7*IjCyV+h(0wBlMRoiI5nJzP6|vF;au8yGGal-)|quE!hFh@ zxl39qG4k83r}K`M4dz@zD>o}1oNWpw4|#Q;&BD#**X5p{jP!1*;+HeR7^tKV5}&9a z9IyCzeVo;fIL=(l&d)~Wc#}|Xk|WQav?Mck*FK{cbMM#1JN^`elLdb@b{UO7^5~A< z2p(KIm%8$tQPK0m8~@5H(?ae+j)OP4?y&|jSuk2KR$7v3!(}S7E0=ba5;|8B(f#tT zL^j*h?<(o|Ec@WW>}Fz7izfP*gbEefudQshvphVi5LJ!S-?kF<3CGTSFDOvrjn&|#&ef& z1Fr9BC658@ zU1wOOZ`7v2ZSwZydY0B{B+>wC9n@No0(1`z{WgB2&vOCzB$J@ zEx{igXM!V?uOhLAFGMqAa34vwocOyvxP_nJOk!r-n%%7uOJ0hZG)fANQ8t%e4X;qY z-e&KL4t1#E@(~s+>%o3;9>Y!+w|Ex|XEmK~p$aul5yF_q4yLw*Sh$o3?}p|TUq814c8qo>l22~8 za|N{j)5B`D*ltxlb(~(U%zb+z^Og*~+$7F=rXx9AV$sm1dZ%0cm^d9K^bKt)IF~zs z31t=a9bfqI;Alfy@r-ciKdB^7iyWHGUZ&J2;$3Qm${6LV|AaJ+IdRW9GgTO#A)+Uw zr(4Xp*WWEic1II9Bm(%5g}5p4|VH_v>=#G~pW%BMiuT;bT8bL)qQecj|=T z2?a=eQocGZ@)hC}U_4$SeZpCctNa4Fz}U=?$f%0Nw6k6|cxWKC4?35wp`o{cad>1% z$6jZD+ci(map#0!xghpl*yY$78#ntcM9>RSf8~<_)Ls4kL2yf7I345`l4m7W`C`j| zP{3Tdho``WIH_l+rD$MA_`=n%Vt#FX_BOnQ4#B8>dWw;+A7lGZ+C{yaFVZY5NFb|A z*}F9NaEaFb*#kf4^KXP+SEw!QT2ouu`|~j*jZ8OZvWV+-+kKeDSu9O`JlN>ZS$v9n zVY7RG1dSJ${XX0sYKGnQ7C64YwdzkZ=`d@lY?N(Y{=lGNba0*xuR2I-A+Bzv%$BRL;g++_ zcg5JSi?f$%^!Tj(mvx8Vs1ICq*mHYP^cHpcul0!<7U(7}BUs$=;Vx$aE}uGAlWjYo z$53$L9L=w(8_X;$n~d4W#h;0DmT>RWVXo1szMxTDQZ_(_DZgH2-ytqHUs z;DPzx71xQ8MD&rESLEjRMGc%W>Gy)z77>e$Mv6i{hbAA67N=iK{V(aDr_hsy3k})$*KV?tXTH*B=gw zXz7b3`XXNlw<9@I{4#DWCuFdQbNo_r5lAKwueA}))>NN0xCJ(Bd=0V?Gy8Jafc0$g zmj`+7-+HG<-wmQv((}8OKFap6#y^gvX0E-lY3{FLrIwbfvV4A=lTB=q(dtcAj1%V( zNu)sx`;N-X%s{Kdqo9DT#X+FRfABJc&!-7}YV9R*BkG{r9W8x{s62(9>tA2ad2R}S z>Fi5(h-mY{nkpg%-*nFK>sq$la$gP zi%CjyUN{XWpn}1_JFV~T{`R&QTx%d;n+c0+nR7u2s0 zzZCyJeVXbO?ZTDnt%dEB8D6*jtxxA_X4J@i4Q`8xs)GL4P9g*e-GP?2*-QlV=+2e} zpH%-*uzK8fIq+`UVX~5wR;q6Cv2Dfg*@GUDo5aNQKVG8; z%FLjI>UKbz>W(lHBD^)Twrt1&Zo(R{IO z@bnO>5V3084Hr^CliR$o^;R)0bJ0G3LEN}iS^&$WD{E{4*b4|}hALdRN&EXqKo}ae zj*)=(B2KlE`-D$}mcS)GYy`?h;Yq8E5Z^*L{e`GM!4CRX3C_$WW(sCi)e7@h9Ug3En-m-l(hZyLwC-&!(!*l8u^%>355k;8+8hK7L%ck&WwPALEA{ztkR~Ai<#Jh3bh$QLJa%J;I9YCgr9ThKmFGN72{2> zo3L|TX0yS2TJ0)VT2Co``Epgjorg0iU@=Rpm5qYaTF=PnUh1QpsgE2jJpf7knx0Mp zlbRr3PHJj{`J>ne*BIW?of-((>Xh4}Irr|=*KQs_On`U)`-JE8JMNEanZm%n!#N2N zs%1o+KRX3}p;lt=b@|`iyz~m_bujxP!z00SY{$~g?IN7nx7e9w33d0iv3Kx&2;^>V zZa)5bi{j#fTZz6K%OxcG4X9;?=1a}@*y|K$_(Y$1IvN>#yH8w@nF8)#%6)~=c=J>2 ze;ahv5*_uN?^5+cO&y3q1z3D-fMWiQ_ z2`0H%08Qh?B#oW*`NWP>wB2c)j4Ex8lAFYf{>-6#EcAJyIrK$IKt%Z8O?RzGbU^Hif6ZzsDX43AH^iNex zVb>!E_bPhyM@14eiWEL^U60+aQWcvbyEE~oI6YCZLkXuoEjMqPLDY0jvg$cm*@wEu z*rn;d=*mn>OUrZNv?mxB9%bd$L|%o2Xka3ift@B9J@Un?d?iu1G}33fJ#osN2h{rRi+}cM&PLiY zo|AhyzvN>Nz3bT2++6V`T#^6$(|sCg$;$Y&e8R6XzRorx>5H`Gh|f8cv2x|C?q;Vm z*`*{EUcT^>E_$Z}7Xj}0-i|<0Nut(7jBA*uJTr$m{zY8eEeS?Fh;ADV?#{198Ev`r>AlQqmOCM;KX0KWiciy2X_K z^$lN4OWmSktk!e2=utY2lkY~ZU%sj553QVFzk-sX9(r%o1fi3~yt<{5S zmuAOec49i>FU{&oNX4jbzc};tqIZP_h3q&%`&0HSi$!B{J$pQb@ z$>^-+_tT+V@E1Cfx5&!=DwY&=5DgWrvQmaYm)nmsLiy4^e|>qx1H?&rY^0!&kZgj= zdg^7r?=>~!HD99UkXqZoOPkbt`EN4tQq@v zLH)y7A>w-cIQ~NzPiz|^n?d3T5+R^#sM3uu*_X8Fh9#V>YfgzGy&dK7wHMubn3EP0 zHoLQla!FAfxt@o5A>@@H@``VHm!kde`1O1Exz8=N`WZ%Jbm=*z6nRXDIWNFU7tRUel{XZOwzDNII{S@QbmkY zWLRhn?XOTFidHcyoj;9(+=6sHk8|c6yVgY>T~DIzU}2_?%i`sz*lsCWNpt;Gf)}4? zwj(=AaGm#jVCL=BPU2x7{B+;tjGaMNmonUxWchkCi>B#`Tf-<&-Ry_gt4s4ih z0Yl7a!|*!@e4B1GrO6XZF;4F+1W_KuD#DV>~*G+(Q#M&(iRAmP4y#UDZif%~aC z0%!xiA%Eu1Pu;twrktmPPM-9~r%>a2dZtmD88YS*3tL{$$HIBO5~2KEPYInnJ5Sxh zNvFT>O4f4f@bQ4c@k7)q43%o$6|w3Pd%Cf0=J0Y%gGNVcy?P5#;6g|lCW%UYhVe}B zctBDo)lyN6bwSHjqnY6pjk--|!!WaB^J5!(xmF6^&cY1ubkoko%p*2Q3kmE%aZrZ zn2gH|d7PPgt@`NEi58*0_D)$lN=JgkhJEh+4C1*>kL!Mg4xii?k2gAJ!R7)4AU$;ps7F!=g>{##G6u17FeHNl@*z+}2x~)MxoxGOKQZQAxP)?(SHxBLE=p?*6J#e{=Bn z8hO{g@t)TdjNNgnlt8H=QYMJoQqhO@uX)ZHna=)4L^dwH1V%e}(909FoI52^!nijY zU+?lpJ0Iq24H%Qu5>7UK=1+h5f3yJ4yD7#hRIOS#ofC`yCC`eSV}wJD_>hnj2l*X8 z>_;U4bk3vRIDbrh6QI6!O>AG)7gd+C`!Gkdmsri=yk#;&wvg0!O{30fICiU^VJMUM zMZW*CPpiJW{=iJa`X@!{fo*R4yw{y)&K0{syEC<|a;&r@*FrVSG0a7jE=(!ej_XTD zC2{YRvx?#tBI*b)XQle%Sw_mOePTuKAB!9Cjz-Lt6rvJV5;|F?yjl#8`&Y{pa`xAl zSiDj3l8iKzLg)|$qDhrHvk+0X0K}PPLp_Ni6}rP8QopV1Q|9E}5#_CBx92u=Y5kr% z|NU&z$n*4pfLoh+1J7G6w|z``iwwoMLo5d#>kUg*&Qnh}`}WAox#-S>U|gI#u9~0| zct)o6_XU#}P3H3t1Q`MfQ))|RYn<~5G?yxa>G9j;qUPq^XKz4nkW|+a*x2;EJBg3^ zuTzFZRjxpn4r#1;cJIk3`ebM_c<4g}$$dfB36K|bDppojj<;qF1%u&ILxw(Zfk9%n z7B38N$Rb$4Ti|I=IWodklTQa|)n7rkksq-P1|wKG9)fU;z9e;s+S}O~VmYTdP2`-Z zo-Cbt*&fd!e8=2s?45%ld+}BWQMcz9iomX?gixk{74b8}X$m>wY$Wo4;a&v%{Dw|pz_NMp>#dQ~(`D)m=V|qQP~-LHLA{vejE7VyF9ri{0K!3^r&u>n*Nkee z59rG(p+^_W=O>iV(h8ht#oihy*fIE{vUO3)Ue0Q=$jDi>0u{mXoVm_+_~vRQrTtVc zE=9jKc_lDW)UdX=QhZdX;Jz$&|G{9oS~uyM`Q3qv2v*xd!G(}NvgQr8WW2+4p%Pw3 zlkhH*1}|-rl{E|6;SMTy3g)V1PE>9>T?9wZkCD45@c5 z+$sM~)Odr8;S91f(6lZ@6X`^7fRR4`SuRNSDqKD`TwiW#?svQdl^0v0!7tCnpFp#u*aZpQNLy1K;)tm*LHg48bcPeG_FB?#AqFQ9q)vtOPsU)YvQfcoRk+^?`8VMZFE2g+&n(bqiM(M;|Mdb3t3S-I8fGQpc3_~*(43ssPU#98Ud z@$Kx+PH1m#cV@|4TVl+?;8Mh3Nj?4gc_ASNy?FA=qW?(F&^)MZ{@_e{XmF$Lo{0ce zpk?5GVe!?JV&TY;3ll<%uasqqU#3T50!z@h8i|*%Z-wYj`oA)`i!l^+7o{;g?vnVE5`TNS%$onva zRju66KY;iK=v>N0mB}vAhonB@DbL-5i;qNl3D*`pTh7RqFZuZ$-HA90VMrY5=;&~( z{!*k~W;Z--{P`jcCD7SHpeXTBlk2>YDcWDL()C=ucJ@QKmq6U?45nyx){`pmR&0&h ztpgnYh3x*4rbYNI5K?!%$|DVWM*u9rE9GGyLG#G(Tl?N6^Us4yZp!0LNp^AKc{rb1 zsp*g#4>?*Zt}JAhUivhXzN14KEGZi9^%S3}ZeIURsC;&8{4Zw$S0Im;$EAN96X@}jv`44KY?F1LFJrw-TKJlg?@lV1^AghwGVsBi@+Cs7Y-N0%k zzJ)Dw&%+W419b6&_;fpmVyA1zTOUmFtM(GFc2!?By0g>fON0f`k9s)`C5k;Fn%!UR zti!+=y-e{ya8iBcTIBt!=l(7udw9sn@zYSSDzo*i5(G?I+1cF%C>gGtk1b|heSNP1 zB9>^bP!I!s4~PaKfafXbrPDS3hUuV&N1TzS(saFWI9KK4hJ4eP7G|Rvrpbn<{{ZBi zFBJWtiLD}&ctb;hFv}pQE;6}PMA5$#FXRp*fZb>*EigbsCAJKpxK47oZ{OqXWwUsm zXhfpA8a&2j^HMFrQscO-(o^F^ih8`sW%3W7xW~BeOZN{5XgD-iWD@ReszhFt9xOkM z-HJ(`=t48xXIW72qYEo$8`-n@6SI4(Xgtx^I6Ufnhc^f9nBVsBi4?ZX{qzE%MR0^y z7lnr*Lpt;Uz`Woa9`(3r`i$oag|Q)AK!A9pDl?Cm8|4l6jH5Tm*~!95xkmh~+- zHqx~Pdn_fdVT=}gB>#y$uR4lual>gr$>nQFu1|;TVpL1e^>OZS?kTb6ON<2}B42p+ z9%5@B(Q8VvqU;Gb7mRzTh10ru;u8`O#V5#qARiCTMLGW#oD>+j5Ih4)Ac)|Q(HQ_M zX!IRnM_<(+DoRR62>k#6^FqiyAZVU-Cd&58oUT!e*QcQa$vzp zocWuR)f&mfpK=F`S9vq-9b4)zrR*0s+}wTSm}KeLaw&oi%wyp46!flv+5om`Am`m! zDB%UM|6=F*@5h6Ott>tR^tZP4+KQ)lUD&=Xx(awJ8TZl$MhSE>{Br(amN0^jn#ozD zRf{ZDPQ{!5i8p*}O|6W>IMv$ziS^6i_I^uwCdDXfr}ZIOvJdxueags}$~`|dB?0Lf zF{?iToqERM7IikmW%{+j-yVc$wp_^hlKNgBnB;Vd z1P}~L?QQ`H3i}}ppC+H9`kkJN)XV?z(;=Z0ki$OfEbU=vkgnn6o;)EiF}Zsbxqhh3I>Oq!O-A=clVwD1&aLHUs)a(j`pv;vMTK25 z+hNA*Th$L=@`m}vzPv|$Q&VXRas<<#T2AO)*(@$_RR4rpYa>^NFo}tGij9 zx$I`;x-o}9JiqeZ{Efrd&0mLdf|{Rpdnla_ukAOQ8~0q@H&W@aHHxhpWRAp<$j|v{ zH0&TDbO0YAz`&IV&(s#LfxRXn-~XK8@UD4|FB=E1j+Ui7u>iE_7;=O|;cZnBs=3f@ zwN3G*@2MxDe&I9mLgAkTe(pA_j&}#`qr2lOii!rsdsd%9cyT}W=jtyjoowy7wclDZ}CHCGy{&U>$+kq_ND?F(M6Rpx|gw8@Y#WIcMv! z%0i&kESWOVK%io_da`<64ls%30KWrCHHKKGN-j2j+;CcuDWFawad+X5kx`O&UmX5U zNHd(&vbT`(r<~afnM6poY^nX|8*s2Q+T4HT zoLN={Usgb>k+esU#6pk~EG}50uY@qR+wi*xmQS99wl|hZvGCeLZj_V#*_#QB{x_c* z4ala1UwHaaPt7nExRBi;iO?i;DpN`4@{|~2vjx`x(s+R`3JD4U(yvT6z2df;EsJA( zZtr@DNLR%~YP&*yLiw3b4NR4aTcK_8_|;lPBBjk9rn zVM8sEPxsB}Ba2;6elx|zK^Nfg*}5@rm;VuTslAkV@Gx1a)eBRklm2jmr|m%i=JVET zt8T04?dFP0*qa^Z9dy#Dks9ZT&7j<Th<+@lu|YiClF0Y!K!@h^6wXQ@uJV zH|1u%>LlIed1*c3h$Y2Cb;Wkt>*w0K>wNW|55jrQB}2F+wcYilr%v?5Gg@I0YO4GqLKoNNS8`?hi*z#P`ag+ zR6$Tex)wajj%+EI zujtaopA(J5-gzXKw=yhcX(}2b@;s{Laj7%gh6aQKOJSqjhN-r7z#l&oP}6fsfpM7g zu4EM-AKyn1N<+wJ!1piEbdaohEe@#$K4Qtixk9Uw(^RA(a`<<4cI*}EtY0)t@_>`g z-qDLMnD1N_OddFUFd+;Acvm7HT#1#3p_T(X+BVHAoB73ov@5!Kn8?gfR%7gR9}v}$ z84qC25#<+T+-qE%1pLI_L)b<@!ssD!@WL%MK7EF$>+J9Olrb+*vhD+?{YKeL2JH zGF(e9^mtzyzlYv=;*6c0oi5b2+}bNPnw#b4p_Zxx(`T$e4CZUa1{@-hjn2nFl=Gtx;GoL zU>jA?@jF(O)P^#;hrv(C(cOtkKDxz9b~pF_`9ap5T7Aj!A1APhBI0+2O8fqp$bX#h z`RTnZcp>Yk`1bHy+@qEN^oacTiPZ3lb0=dCKl7r|p;@_3gE=VRHE>;xkxvD3gg0cH zkViVM6JKIg{HCm>+zpf`5T?Bjvg$}>7dk3;Fs_4)B?Hn)qJZE4O&U+t?F1lrh=LrX zf&;jr{%M~i)81`LF}+e^e-S4J91xnwn6p5_gY4u}GIB@q^iOIuE4@mFsQ!qpLjd2$2#!r^ZiE z1SEvqX^v-Mr+2Oo*N;198vxO2{b(Ks{beuiUlT4d!=316ORCRU+cy!(LKvUhz2s3H ziuA1nm*@owjK=M)4;X76cRXie#T>2*wk$>LM$O^X5jShV&fz{8>|j3159Pfs@} zAimnPj*#kMibL-GFPa~AaR2lTv{Gaj(_=t1_NKP9OABRjrybvNu{x2v45Hf)=5^c1LPd8c?e>ukHpE!Eq! z^PB#xtRYlO<#!N`=G?nF*KO2O-PfZ)e>=J&Udig93K37` zj0pE@&TUUm9=W)r>7UT2&mBBaKNz3HWF-w2Jvy3poVmRE!lk*;664ZbV3(fcnH98F z>#4b3MABVXPH!2_lWK%hhc^qTK^XA~T&@rDHJ?yo;CY2&!4DE5Or?&Faf;9%s%C>! zv7pRw%YODeoI|8p9)S&>KD~4M*K6T|u=>977AWy?NzoI%fpdYcYc2|<1sv6vHw>YE z0eqO#Bm{#6FG7ge2faD2RjDztkcn)f%4)9wT3^@0siJ?C6L<1g*sw-J z-17YoKfixY?sqOKeV}Z9r)j5Qhj~Y~2ebR8htV^kFG0HRv@v-u{?}?tdP}DG&*r_X zI_?8CmU5{!)cPO&BPQ+Y_;0$J+HX7k+F_XKsFvwY?P7H1=$~kv3Y7>^9uk#zdV;+mh2&=2H15^W`>| z^D!V(N7gHv_XzgfQjo~hLU$BaNuH(H*ui~|YJW@DYT*xMoTk`P7(Lf~qR@u{MNjm4>`k%BMdi9Toj@St;)GrK|(W4J$6oQ%ztT(z;#^2Id zh{65^5g6CQwfOPq;e8fF<{nDiX&Hq?AQw-AIDvybgrGFGJC|7l5=uT8(SW?tjc?m9 z*ux#@UIPyO<~ON8XaJFB7hWnp7a+QORs7TGv6Wleut4L;6b=A&7EAXmkZvDP?jR(m zyLTn%SjJ!T#Z0ny)wAfSD)YR-x4_mNz^papAMVce95{e1HFP0dLOu@ZbAzJefYZ1i zOq18fK>?1w4Kq{TEMc(10H6c8t+HtNz+%2XZ;3?mx9)aFl>{+mMzKq^5;4Yxk%`pZ zOr@PM*6CY%=bflKms!PlFXzrCh#FH(l;WSajHox3|44B)&?nfBLN10ZAzPXMBY#HL zaJyhy*c+C;=2(UymLoZh;&wOAkUQPncs*I%B7dfBF)ln`H)Ms_*CiJ^#61XAk{P*o z7%oYupH~bQicOA_Ngg0BV9K2SL#eLRh8s#}D~gS=Z3R^~aM!xmr*TW(h~pq>9Q2e! zLJk!(V?><~s0Kh3nWK2ocg5F9^IJyAWqT;YK`j9w=#vDVkQP)!ovwb82W;11V#SIR zEnv;?szZP#&>kR?2kBq%*flH2j0)g_!Que9Bz648ZGu54`B3z&ORa;yxTq0%6ZZV1d(zM}+`Rdsq+I9C}lI8@D)RpY;+?{(1Mv=>k=-T_-@#C8Olj4CN zIbVI|S|~Ep;Y!(dqr25^=WnpZpLJKnR9(E3L@6<13ye_qpIU9J!__s%9ZbZo&g=`( z>b_g6I}F)-Gp?fAHW)oCF^f>6HLYw*jHZ*I@pw|BQDmXIuxRw-G?#d}5Ql>BbeYbq zJ%C3A792BJCvMZMD2_*@OYU(A3?yj>+3#T3MUV1}>m4RVCPlEe(z6^?#pAYKE$68I zw8xzsHJ83!G5N0g75_}Ke<%dEmt_maTI14#ipLhLN|<-bml9V+3fzxai=;(K-2~Z6 z(zRxF`sPzf_f7 zpaAfh_)o_QFEGgvgoE$V*?XW{3s~Afh!<$HAXG|cY^;~=b#L)c$nkQF^>^vWx|f^e z3)B=SKY(NE0#4#OcOI{gQ2Jg28MFa`M*LJJJIy?GH4TON(EZLSDW z5Pb)o!PvWPAC|LwOxu|CLybD^B0KTcbxMCnbjWR-G0##EEz|0Fyq`^RFJjB2m1l5A z=;6z!x0j+PBIgrZ-ZmU%`GyN}*EFZj?N~-BB=?$$rik`eHFRdV<<1whSaigvwA?JZ zx)40!6F}eYxVGXk%&5Qmpg&Y(lIM#4M+)@K7cN`o6oyZ%4l3ynuY(6$fkEsPkYDUz z=!QX}z9&}T5HzQs4wt&*?=2PuHB2s-Zk3R~+*+)vqSWyvq{o~_?~jtNMD-LCAVU3! zDr(VUA@SbUQVprVfIG~Bf;&XQBIM42MTb~1U>q}@eMd^AcJ=%+C`aNJIV}8wQ9)&w z&l4e|(m`+1J<%G3P#{3to|Z(v2f6_A2}^EAdq9z0hV}uQj^ge0RJ0#dwQKZCtVLjw z{ISY7RFlUL5NnAf8<^pPhr6AVGo6x?vr&6Byp<`td=-rVF>%-P^R$Iv|5ulLEZh1#^>GLyMa`Z#fR$pIgN_!m6@`54W9J0 zrD72VpY_m8Xuec`(GGgId-Ar+dVB3(KHn6j4#1F|$7VLhwb2@kY+*fYSOeBtv3lEC z=J}pyPo|TPhkVD{GUjgLMwzckt4pb^3FF_cmK;VXr2T3F?1W6W8C5RcC>aZ@X*z2@piI5*4 zu_?3xLZkzsP%CtzLsnAhMa~#2Uo>t4k9*L0u~QpLG5{$6d3CbcG<9us=Kg0pGWOUd z`Str(&LC$5o(Y&lsJ2x-Tj8Ucmc(~(u*e*X5 z$8xP$RM+KnjNS*G!~*es0(m#PCw(MT`(1W^B;QSOxW>MvkbB4T9rh(C6SM;n7U#BT zMvMYa;FXz(;_#myYq5FE8yCZR)`f?~f_{4EHR<2=7qC=_hU%(nM?sd0ynvVTPvs-# z!QhBe=g%8Du05EGessMV#X8wXQL(FGJ=G7ge`I9_53B3A*mtwD&J9iTF7XZ*ci2Uc zQ19t^O@*}N1>02H*Gcd&2qa=K?M7qvk2LzK(?ZSL)kJPxHK$6|=-8n>pA@khv3>WB z(3k#voym~4CSM!{)W;KeM6YYctqsuy^2z8!vWr3lnE=2-4-(Qw@%V9waCGd@qmULX zB0&kUC=^h@W2|p(Ca7{C{sK%C01M5m4U;y2@&5)$7l3zU&JWOSKqvJU`dWO;`2Jdp zW6fNfy^KG?Xsj6rJ}eZ@fOCWV453)qF%yMy)?CAiDj^DIeX2m;Z)u;6O;&UBR$21F zRAE_nk;X*KNDma@kVA?TS)gji?OZ1d!(s~-Z_&IEOn0~!ndH|HmO@`}8ymfVSx7d& zXS=g9^K4jMEW~^!ak(YfKvXo!b#(5oJUUgOpEijTkm%%pv|#87+E-P&zuH38)P^^tnq>B@z4@%}>?hQy%A%s`siK#?HO;6V=g* zk`F%!+K?6;uHCdG0DD!U{_RRc!&At|5eycB7CC{zoQww?6qQd@wB7)A1}xt31Rt(n zqm^FPZTBfhVSWcvCbaI=k0_w@9I$EN++K|+^M%#B3|1SWcrUU`Hj#!%2n14!hKAS_ zBcMt0WFY)RSZF&TKSc3%u3po1XA*I^aHJ3nFt6-j;l>X;>VIAnQ?^ZvDqkEdvIZe=#8~|SzAB6zr5|k;Ub+W59w=Qfu;78NLilE>W;M8c zM2e};?M@J<#@~HVwnL)H={a-l8fiv&a?*wujggMVei5I^{)=37ElS!5m#N}bT6~?O z+)cfb0m1ed4nLM&`r+n0gR7IbwqwH8_d9&KEG22&O3Op#FMU$pjMOACC9})j-D8wY z@@zEj++~{?$*MJOH^RE4ynOcKB6K1Q?tD6Lgf+Bpw`K+40zVgqO12IR%+uKp!JPxj zp_wB5-GO2kEDK_T02}%7;|2st?Lb$W4Ke)MAebT8eg0yKu0X7Y4E9q9ZIU9}?{Vuq zHZ(Y1J)U=vI-HpS>=zalP{*zIG}y*4N*OTB2lDb)!enqzu)VD-@F`(@&9B>v2yq5L z8AQb!Aj_*^GIP759kQ4^S2E9Szv{xO+6X2)7{!G(=;w(g)Fj|}prDA{pxvV<+d&UB zHOR-2m4(qVNJR`j2edOX`@g@JNc1Nx-Kp@5iy^e}lp+YwzhuL;+;W~HNMtgyO^Fcy z`_41f_HVh&ya(I+J-Z*<67k1owA&5UPit|hCdai>ytNV8QLPl}e&wg^XIk?t8 z;c>p{ZHJpH0Xj3Wdn&PWd|!AtbacFep(b#STF%Q9Gga|KN7o(wCZX*b_NT;nq*!*U zJDTPpjp?_eRXXu+a)z#DQz5mx%nCVkr4yd&E6?2$!x>lWK-fq@2!- z?f{x1e{+`Gx*D;KR9~*2YrO07j!u^LP`D*#J7!|zoScoV=N9+rlj+2bYnyBzWofXh z)0FD{YeF-BD92PdC~Rv=5%M!=&I5<(J`h{5F^~K0_K8bA^8uZc!sjW}q@d3@!+cWXWk&zQct9i}Ncw5k`wGGH;giG*G$nu>Ux1DC0f=fO z(lBnN`O+*Sd2#z=pY zH?G@tk_~?kf1%PrnQNCEF37QvhtZ)}ipY_}46PmR&ZmYtYe!7cn;cATtyzb!4doeM zIpF3(4{!yyRLmsqVoX_gXfhv*cd$a|P`uMY76}%esStvrrcHBAr(dz!37yl#$$m{= z(KNMtX0_V>#dDZI4)TCx1>4d1G|L|n_&)-8240-9Vodt><&2`>Xa zmtkhU8uvVA;|Py8eza&EbdtwZ*%>{S{1&m@7{XnyVUtXJYd+TCyA6F~{^3)#M$LJf zk+cu}++qaQi@3L|%4AuUg&25FHt$sQx68IKG1hp^vA>E zta$T8*S_s2NU}39{Gucd8;XzmKA@{$YT&J!E?u*I4W&j5cc}Cs@8U{~rt2kpBaZNf zfpR_^5grb0h;2|Fg^C&!$f0;b`LS#L!W}Nfi4P_|XXW#LerJzpnB(!^ewD2Lt&kU{ zShJlAm<}_yEvejl#6hvr$lIa|ke;yP;yq|KL~_4~Tm_f+_pYSk3-j%aFVu>0cO?t< zYZ^F-#mt7#$o7c@uSw6|c8%{8jPeilQT;MJ@xhc&TB~JlO6YY*VlVDOc1nX_tfqo3 zwexKo5|?P-(s`lYjMokdoM^G`v^J?SX^mgTow&Be^u=`Yc*DO#>|}+@H)3B07#tQU zOQcCAszkf-8BXL|Md{xb6-tijUUlQU#L}=g+p4Eg#De{~*(+da;+L06Ub@HZ66H2F zm(3z6I>@}#h2e~+zv4W4?Hcy-%;hMJfkorUaq3LLORH>>f_c-T@p0h?ZS%}M)_}m7 z-|Faa44sg~u_y8+#Kpm?1fuULclTFnNN(e!w#Blm$-^(j0h*V7~E}l;}(D z#Xe)`HKTxp36Yu_7>JP-LL!fl=jqnf-$^xql<}v}AGBK%=892HY7R|Tg;-G6*is?EZ-)p4T z0hCI&R|4F8UG_E$BAhyr-XtjOLCu#N^n#y3#{)7m>~LZDkQDfAh`?&+9yDUN4Gip? z_1aKRbMOsY!k+zIgFdw0?~Om`UF%M%SWYF#Fv@KaX;8F%H6edh=e$v~fPe!ufn52W zI{k&CMQC{;V~?a=!bj{IH|EF3m89-x5nGR_<<^1aU0TGy!RWEwv8c1gWi2Ly+_%#uF zP)~-f$2|qrT7cm}IrWZcyyK+N4Z^XR5GpFHm9E{u?n-Mo*|;vh z*miXG>rk+J$nvwr-oyD)@oo>6hZ#cf8d^+xMGWB6s&HC=}1ZqmP6dle8S;gjU$7BM~_ zz0^*(mSq?7KIfETiiy6_S-n>AjtEgYslnzA@6OxmWjPLlO;OF*gP_RV0iChoNz9cp z&%O|zhV0-OI->M;7GC|&khVm8Y7TJuw9DqL$rYh>T?ES60P6xx2=q4`6-x1}xLvp@ zd=L>cK)?(P46Z|SD&*{DgM}A>*aCv#se-`U{iJl&5&_Y^`bvYNs zOBI;TRsflLu+0n%JAh-5Nh0hnnrY}P!e4`t34_FaY>U5iuGH7~xJ8I^4YJnUnWY|M z@Zjf|cH~l6myD)gO)k-NO`dJ`}Id z?&OT2V8ddDWRB#*$FrK9?;K4Qk6^-|SN4CN)Cr8Q-|+0jwi~vZ1sm`>mAU++S*EY7 z+q+lX=ES-bwkf|`p=mLBtKD$n-L)@8+lGEMxfs$q#$7r8A1sy_t@=;7i7QXqzt+id zYH-Z8b~6vew|9#cbMF^+`|~UCX-p+<^p2$yWeme~o^2SCEDMqCComvT;ooixaD5Gh zW6~wkH{ySa9JvvI6$(qmU@ux z1`ZiW*$Y@zT~PT5I{lDgA_=2{>*_g>)ylVl^yW8`Ac0MX&3!zZ0~zcr!a8(p$C2;` z8S||>*ZmDaG{NhZf-3KLuq;;vgmin7pDJ~oJ~4!4DB$eHoIfnm%rWZOc2g@$l5Q_h zi*h0Gr4cl4%q?^-<14i`6z9EHich^FM{tS{?^|2q$_LjF`NRMnp2UZVk$IVS<}AOV z+$RJh7`|PKoMhE$t)wK5;$_;oNA^CPS!Q9yRQ)G~3rk^+9CFSmXc7sg?HU@NLLNsi@0A*b$F+qbxrTIEQw@{*h6^C&j z`OmEYz=F;s$OosKsL8w#R^!{Z1QTmJ9WiEXdp1u~{K72HR5o;}>n-!P;N;Keg8Q1B z)CcZGL~>0F)8xkP1Q?)En6?0oP~t~RukayQvhYyAe44i}jT{Tnawb(h!j&%ll4|Z+ z@9y9Dxs#`HVk$bEjd^Bl!_?=U`gl`+`}~DLR?0+Cs-QI~izFH0%l6(1@;g@^X5-m3 zui_^(x_9zx&S*!uDfxFa_J>s{vGLx!hD~HC3l@k;4OXF6n8@|3U%ioVXgpqcW-xa? zuA5svp7w5(PrG)H`iQB6b_Z#&a+5&oRK$GzRJ8F{*D5~7HP%dWtuAM7ReQ*v`_D)= z&VWFW{chIjTv2KIJFAkj=Vyj%59`Z?hxvf76&bmDi@WZ5LC|I6iT%k!_q?Wt<(*~$ znwy7@s`+CRd4_c1uvP-_Pi+4k%Q1^ zd<>nHc5Pwu?Fn0zK634N{+4Y+oz=G!xtT50T3Mp50hT3|bFCQ8Z*onGGJr!0#*E@snXNsf(u9ovKpHlemn+G~3+FPBkwb0v<}ed+=@&BF0}yd!vb&|roQCy~ zGuB+{Ip9wkL#q_~b7hCu5Gh$?1PfIAR5Y#M^nc;Mc<6TL+x?&xG2{2~JvFhyO@GWf z`Hz-tF**2YEp35Yralxl1UZG6{h)P|YT2JlwggNjoU3|NJ6Z%kCvI)i-fQwU6(N+T z?^iz<(bsb>C{KEc$uY%XEBFhx6Yr;x(3$cXZOG z>_B%M;@bgZMP{i16a-ci5nb5dFMe6kJwKn`pqrt@KIbp><$eeYZy&Cf(9_>oz$=i- zrHM(szAVTTGf?}D!4z7XNJZenLtYIbFepuB(Tqc*7bJp^^c0Y60n7o&6c8|BfP4DO z0@Eu&Ry4pTp#%E^K{Px|t|F~XIiYGr1tWRkqeZ-U4I7Wz9i^-10al;jnKAN^cDdrb zj_=~+#vYcN-GeB}A+&~DA|)Tf#cCF6g(hE#t-6;sL^!P$=DdmN)F~xZDg8K6p*4mF z9Ub%0cQJ>?hhO-IckKJVC+y}pn9LYE%QXv{Thx`BOAObxWMvk|w{ObC&i1P&?=hQ~ zx+j>a7?jDpyf(MIQf>H>FIv69!a6d9_V!4dR$p@4Be~kQPqWIYv z_tes2I=6yFwc}ew|G1C|ceaoFjTGeLDZEo=wl z^C$Xji(t*`4<8GPHfM3wor_DZ-;<3VvKzRBz8g!w_e;Pqt!ucfh8bzef0xo>jPy8y zzeJEf=$wK{?5E$|i}4LQx_8(LT?7D0{WY9TA0b&$_!NlUNKJ%BWY}&{)&pR4@#F`< zF#yEKc**(zz;E_2BKRI8>3-(m&|Q)r`f3W;RuIovEo5Y5Bmjqf#eKH~7&b#h8{jY;SkowXHm0?%f$5I1pd`i&j_C^8+`Ja8c}%={5Dqfo-lt!!=Y z>f_rNHH8TR&*JJ`Dt49A&Mjy$4mkw$DJpK#URLY3y=OR8<6I~Wr6@Y2`ayT1d5(-r zt?}y2_4vh5{+Nyg{NbB@PLY0Q5!@ejOw$WmzSePJ=Om=5qFh#cyPE!dRhKr!G}k4a zAPweR@5B-%@7_a-W4crw#z=0$k>wZ`VqSz5~1lMab788_Cmg<-wz3flH=?Ip58c{{6d zdH)|tsT63v&7l2EecihIKkP0}6f|aOe=|3KBx}C5_U&fs+chul!zAsV-Kx2eEJn(& zB6DvIck4NnXXZ^0wAIw^@JHVliggH(gti2vRW>33Dzb<=5kT{c`croE#GK8yw5S7| zbxiPia|_CyWwsP`qbVxS&y$_#_TPmi2D<5@2qJNcfJL-qoP{%vM5T|*o%HqbVYwja zg$ze3SrND{q5T+y>LbFMP!uxn|M_%laS-%+l0xtjd|CvX&lP+gwUumUY`(^>KxJ3FR6LBS z;O?JVuPaq_L3Nv}8&fH)roSlo5N3W(i>ats?oe%(q)uR#lCX!e6hCR6H#36!Hzv^I ztSkC}+^ceKozhZ;YnR#5>1f-fkG_XDDz?jx{vd^OpHJJ`>VU&Ib#vnFmrU)*H<>ff zrEPQ7t60%H(#RaDhcg`$D(y1M8+T2k_w=GT!-@3;b)4N?c4HdKSX68h->u0vD0OGm zx&(^)@f)b`^%1;VZ{aJd*-PEAi6Uo1o7zToq^zi9v+frukU1ZS9@PsNCT9eewUuaE zO2={>Tpgl}vnMIXH{21NUFTVI5?S!c zxCN3^%cuWDK$iq~JEW{opxJzh9EOuK5w0LoAY1uXvGURB>%mIw(LmAFZ=gV#a=%Yy zf(qwYvw3PNd1^`uG*>Uh<;bRX00aWV@P5O%$-hKx zoI0h5H5K&@_bsmxvnbzL&!MG}_uA}L(GCy8gl_sfvD9eRQ@BjIMWvgJv)Eg5?#%&8#!IOGuG}1Y0MoOvWOh}`^OxA=<=0nHCv8GAAEsf%o?%WtN;2b z|NfbW<$tz0FrncHLvAw_L;_SlpxAs z83j{OSegIf_DS57M6e@5sQuZ^{`fAJEnmOe^i4GXd2{fzB;Q;je*Pa%>VJFNaS_j- z9;!M`fARvUj~|9Dbif0kjG~3186)u6egPiDRkm+ayg$i3-06bUt^pxHD#xI1i@qNA z&xLm?U11F?IILw1K!)Ez{h6DO4TZ?gA?*@~Rv8ee^Jn%T8(4<-=sGxTl1s(@56}DI zb_h{Myg2|y+rSdAg=DX|HR<2G;lFNtG{8H1RuwQMDj0VeU(OgHf+)~HNgYA$k@1$m zGSMmkR@Qhb`hX3j7cxqBO$MwgNsUZQ#K8o%xEW zpv;TZBi(b;*E3x=(vCYW0H=laM`ZM;6Vh}6ovWDn=k%3$BHs*!iX8@ihuqIcaJW2~kgcr0`b_gfS{<&=YUfJyVhoj_f7a?5Q zo;O7Mz~O{+11VL2C(CF=rjvqKABE|O5?m3LdqZ2I^Mgf{lscFj$Ql>d@y8O%gJUIXx(NOf=M z=y0ou2SVuxO`B7q%O2#H!(@;u19B-KFLPX0p+A_Gv<52r7?MQ7=BJ+j^8*i}b@+vP z$Q6O~K)CJKxc!EH2xPD~x7$v`cC%xtr(^N>B`$Bvf9&(Olw^ioKdwV}6hxMgt|EM2 z4YJ`Iwo;Q6hWNA3W6VCUdqA*J&}^*7M_IQKiy2j|o^G(Zdvkv^5>D)=4N z3o=DWb_Q_;L?)krT965JJVdSoWhz+*2`}_0+)I1}^$_?sX! z2@C!tAtfCh^WjFyov!=i^v|JS5Bgnwfu)e^Lel^Q4nWuVs^26;SMqNzfG9Ad#@}Dd zC_makAJv%SBBL+0DVHI7f{p}Jpf!my`G*l>u}-1u}`;_)ehbR9=km3|w!%fRIVTnH>IL|fwQJ6)JA0q==?U{J|FjsFFqalvr_Sy*KM!1FD$)(8I%_45J2 z6+$xF@&MO$MqtaUqyWAMY+Xc93nCq42B(PjmtBG0wKI-G z&WJRlmcbz$nC09|7t*`|8)8HTkea%6Xb1s^;!X*Z{=+pb6W$w{8L#;Ysr_Wvll1Tg zs0M)%yBY@nkSW{Ku5MkvjyT{BcElsEr1e|6DfJJ$%9CE=re(M3{RVmYH!(`%h%(CI;h~|6+b!Cm&Kum+IoX|+qu+&7-atNXQhLHZ zyQZ;q<;K}MJ)1!vjeo9@)#ivGVb4tZG9@t*v{6PO;xGTP+hZngrD+?P{KuF~0^1(-T7lWe_#i>)yL5!8vcZh?t+ z|9oNxPHp%-3b8_O5E?$r_IS~450Dok)$pT+?rwpm==dHvlt__L;_%TeQU7@j@QE=c zPTJZ=yU*?dY-r!3Q?)H-LLSj>B49H+eN}>X?xZdcKjVqK9{B(#cN`|(kHbXfkuDV-^9@Z02mT_* zB?FjWY4+#42e4|^U~NM|vi4bCzgo$Qo7`plJW#WmsHU-Gx^d%7NZspR4sJLbLk(~; z8bIwIL|7CM3+fD`=&f(j-f<=kQ@t^&D@IWIc__?tO6Y-U*4sGd@+~dU{L-*;Jktrypuu zxpKwZ+k1H@rb72J7ngry#{NDgUHKXw0g2J(Hk5{X^DK3u=k)dT9;&MT z8Ei7u}Dtc~maxy3|uywnrPVd*G&8STQ>dSbk+tK02Tu8M~)6)+x@=*9Bt3^_J zRU-Ys(VXWlT^clSC|3Mx=tq6?{f+00d0$)#srwDp`k9_gozKzj zbHA&qZdi}qOGr%g%qoF#JOZ1tDRR*iq2_d%ii(OKZdpJ39Nl(p#yNd&+ByB@v~#1| z8ny)s&TIYUj&6L7(z)9K_VoYyO%8v@kFSVO@K@Mp_cjg`*sA?BQ+uvk`1R|1{f6)# zx)ragCm|`3*4Jl7!HuPB6@?=|QWR}B{g8-=sJ5=IV$^CGz?1B!m2c?|G$j0}s~}jt zZ*0uQ72yLO-79bCMVe&)$A9k<Zu}c?(A0 z(ojbT!kO;Te#r?VSSPSpTSz2qfT73-Oq#f6(2-QjHXyyGoPL>s!Q;LU1%4+4%lWX+ zx7}A)ZMaI-6~j5yeu3Kkf%XyXJN;^3DkRmrckdo7ehXk8<|(Q|E(? zo`R*)y$?5@6Hxdtf8=NX`>r91{Z5ooQ(c{f*|CApq^_ZXQBaU7q^{E}l8V>hy6x11 z7pArfKN?Yl}804%Zj?^b#d$6%W&y;3;Z-Z zR>W|Y4M#+_mfnfaxz;$ZU$UmVdpJk4b`Xi=8(1x@c06Gz@Bx?1qw!ska7Wc+=j zvZr_AX5z{QrLUd*Nc(32yURa9p^NkV+?O5;R0b*qm-56XKWa^tzu*1^;H^}*!I&E=z4e1*gp(=xtf_ zMgLmPFW;?AKGPiAjV_wsxGjv4#F>TkJ`%4MJe-L0DK6qPqC^Qw$>q=Ga`^tsFyl+( z!!*yo{?q=WZ*pTzX+OTTbDVK&D=lzjU;ZP<)o&fH@&A7JU6$YyrSr3Ik2lB$L09>b zdxX2+$Tyh&iV5!Mz*HP__A{rmSPCMQ=G z@`j)BM;AbQp&&>XdcS)&+9pXq2@OBOU0q%2I%RZeUG=~}X#ncVeRcIH9doDkHc4Y6 zqmjL(GFFH@Lga1vfwd6EHN1&$J%5^XV7yw;5OF)8Ua&eTyAf6an54+aNKIH7l8e{fXJ<`@T(-0TQLceJ z7Cbo#y=V+RF~xQL`tw&989k4FT}xIX7s7Euu|;nhd-o^6qT_eq=$_U^Wr+_^96y8c z_)`~&HF4H$j}}ijpjsI5cZ8Og?U$GNwzx^%FG&$7*%aY}^@=TM9GTWeO48jAzjv`>(Dh~{-g>eh{Yt6zxR5==B1VfM)UH6>;La7En zLnZ9M!4h&Rq;A5I2Hpozz;*CW<+|6GVfxz2bYj42IUf0Sr)AwZ7|>dJxNEBIx}$&g z+&LI$OrAIFDh!SioXK}^F)$To2a0tvii&4p{%G;RWM6A&Y4?R2->*J_yyYEC~a`#JHVM?~mt%Vq$JyiZXA~9(y#nQ;Hw&O!nFg$$F=# zz_yy>jrR4Lrqrj6GMspZ`>GOnEjaOvw=?~Jqb%``Y%DEBub!)G(h0-|i*lo$~z9p&9;|U51sz|u+v%P%RnW4#m_sp3y7yTqS zD2U9K7OZoiyWNL@BlG1tDC``=EILNx*a9-7G7Tq%gXM6F+vlGM= z97tb>U*=sctxF(F4g3Eoe{|&ar?}@>9+aDrrM-j`*2PATn;p~<1qR?k1_d7F1qy;< z?bmyIuRs2jI5vIUHaK2EBpcG@R8rkL3?oeFJnQn3;xo5~OJXAebzOSi$mQ^((e!Xa z+;Q-tZi@m0QeB?S4bdzdoYMY2{akgbTUM805HA%zKK{2pBc8~MyapuDp+~4Y)1HjT z7;o{Od z2pg2Q`IaZZ-@d2Lv7E3=6k|*N)uuEeKcT&naXRll+<-~Lf*6Qhx>57hF4?yS1;?RJ zxDLxL9NW8D;l}a@O!v8QuUexWaF^f3_d5}P$3^3Ep|tTzPmFoI`j~T_?*RNCVM8GbOXn51W+)*kND-U$Ja;O9dcVz&QBO@#O zqkrL#89(y)n5%*4tQLMtJ$=dmaM>iZDu5=32a=Y;kF+RW zk$@SxJs&tm`I=nv!V5X_2bbX4aj~FMFH?Es zdF6A$ZdTGDz>9yW6|w#N98dZ7sS$zlmO!zhziyi3+F3!T(|^1h%|b{-=*s!8cw~D# zfVqo!j6scC8IaYP`5!J^Qx1%bJXH=r8B%oy+iKJ(gq}$XfrTd+na^&Sf`K!7kk3Iw zAfyj}@~s)8`OR^4;T5yKoOi*&XMv@B3&^sOx2&%~h}_xPX}54+S?0_2?;M?^4`E66 zM^4P*(cX;m)?8H!oQ+E*C{sH=_AcJ%ZoOJhuV!S{YL?{bIk-u%jsNhiUTOTveN^p9 z8RAM7+e;$=Rbf2{>2&Ku*}zr@hK1cXFkpeS`tCRnOy`^GGtFd%Qw*6DSMjnqG=09R z#sVWSQpld&v^)K2)%y!fOibU6+OCxKKh)A{f<(2_G_ynkPA^NyI~t3852%`t*%agh z&Y=3!j0(0qmnQ+~6#;<=SdUN$iV0FXPDvSm08cRQAPn6q%#a)q(mA2r0r`%H@ERE> zaJc1mL>bXg1^cgHGF$^y_u6gTPXPHm7&v>2mdsazk(iQ8@7IZM1D`{M4#Qp-;vfq^ zPlo$gMwUTzXvsc>5nG`5ky^E%lk+k1rP*sHfzMv5T)EAOr+C-pX5cuMUjnzPTx`oh zEUPzZ<889xnVc3lnzEpbi0 zRJ_y;c~0Dr2YmA)RsE*SA|F$mBpq_`x-JTg)ksc#l||&{G8rV1fJPl5c` zTr@LOu_jGTieCqp=esOi29YGQSaFeNGCIMX(qkBBF0lTi&K0~5$EbpmO1^u-LxEqZ zT!cN?#>mPTLEBet;bh6l$xpL;)%CLp$ABnnytU)&O9HM`xWolq|DiMC#WS-KNMvTN z+V{?$J#e2rkocQ*d20Dgg~{p2t@;Y)?UWijXcoP z4hjf7qn_vZEpSL`Kv24#H{>*}fBFx;}95(r<5Xh z&d?VuJxEY3{;6GWjBsNk36D^y zz%R&^i_$ZO5y>`%hL{*9a{$oc=6PF)Q?UuS$`9u?1L$c!JDUQ>(1r$YpJ2PNYCHlJ z^0E|64_eSY6UF)sT_&?(Fz)fv-RrU9w)D}VE56@ZkFiDbaK$?}$ehdAFL3lQFi#+# zJ8NID5fejOx;;h=aFh7pdAM_nNA9Gmr1Nm&=O2=4o_;U!ra*55`^n<_~sd1CRUV znI0M*{qDoN>I&eV+E^TZF3=VJT zb@r8%4PAe@^jD3Qa zj;~E*e^)8<2EiYN5f8p(r6m|59&IeJ>^M>;b~cb=#G&*=mOHQ;TCiGTbl<5y&uKm` zl2h%{bQFp$28*Ark>~&QEBo2AXY+Taq9X-uSx{-p-x5B5_AV|KDLvTK0GJe^5+Wcs zI75-$>BRkmCAU;?HZY(Q=GY5DwW9#)dw?@ftuY1esk&o zk=2u#WrsrYsUh#*6N&CG--YM)fk&SR@y9UC5{21Y$SVf#g@NP?z;}p|>Y>mr4}dKS zCde8tk5oK}6$*oJir->D3cL=`n@HEDniwJVoNS0#gMb+V`*(hRlfZ*M)1&2h>Bo=5 z2dQAVE5eBN@K*Tfd3I0p)EO&XrM@ubTW+K`y}9?v{QYd=Sr4`HVRuRQf?A`H7V+Mz z$uDX<7Bj8IiaUBQnk|vg@KAqY^m6x@7JOu%d6mii(|x5U-$jUH@H8m^A(#yEwbOHa zQ^??Q7tORBi%09=7QnphzV@^aEf7mcLMRi|wlvC={%Q`AF+O^?{TtBKQE8E93!DN9 zZf)O&$!Cxz1Ao!CefLo-%~E0plkPTR-0EEcCj0o|1A620igQ%&Q_K3CPtDBo+e9=kSQ29wUGN zy*W9@f<^W9_1mCWQa;<2rk1653Zej!z4`27sM-Py|Ay^x%JNjSCDa_OZqbH@hA#hk z9$-EDC3O{w1@PikcJ?uVTx*{Fu^yVJPatgGMOxWuZYvZm<3-(f7|m^Ij6zyRFc+vtCD0bY3Zcsy@Sjt-Q;@3IV}W|aP9A+?o_gFYdD!UTtyM_q)5 zDp{$$VwWK4#Du1vYqExi8}5Z#!A)qYpa{zGpcOK3y;FZnU?9iidnW8>xik!MJ8@NdHdiB8bx(;TLHZ_9QU2- z-O~R*#gGw4WJ+X3FteTpLSw}@3z3ZMvK)O2xq&uZ+KuSPLO6f+ryK^W3DG3o! zx*HT>04eECL8QCk?D^e$);edc``7(XS)(w_cklh~=Y5{ftMdInin2T$4-T%rr4<#H z;AR5X1Hi@jtpEkNs4Elvwg?}PjX)BInmQow!yZaFvaXivz56P``4uY!blrP1*8_wf@hr7!AP~q;D{bsyewvk}0n#I_g)W z;C>DZx9s^F%tm}rxM-SJ%kz*X&nDvpY1kaKC|!1-<}UP&k*CWYOI!SXnT7e`3-r_U zh^Daox#JAO_#!RxHe=aDfHWtdy_4(5{Ca;u?1J<==`b408|?}!wRCjLx zk$zOOuvkBp#!p$qd-^uDB`-fe30&X0gAs>mXo1E9Jk$1W9iZR@+Z}DaCwSO-fVkeb z0zAp^wgti!xH-LP7`Nc#wfaSNak#SLAP&R_Iw7HHYqOxUzvE2L1eavvl9E_hSirzT zxaa{cw+{Zxe_Y=J-GKL<{D!%*vhu7$qpra<1_lP4DF*J1Iq(i0_+Y^g09qDFS;EdH z(gt^+?%{|_PQ7?#h)({16u*B=64As9ak+Qy?imwOC{q* zimb(kD$XkKg7_88pM-_}&q}CA$VxH`0t>;U9-F=peMr5$*ht#z@;CAfWy5mN0xMg3 zN42E)bTXUD5TQoG>j^?=jN<*P2$bznMP}v)D({&N#~=ZON100EK7=ob6HB8Vdk-ez z78NsXU5)h5G&N8pPu!$NaOU0dFy?1|yHC6=zHONZeo|cj%iy3NjUnrz2M@HJ+LqK6 z6i|WoI9%KQzk6t70vg}`M-MF!bcQ2wX%F?jhKR_v)}|fH>9L+gtCu2tFp)O^9x#QOu7u zIv{WW7x(dZEN%e&?gkC(@hzcrt#WY#C`Z``g8-$FN8|^@_W6kfO!HT;+#o2u4=CAq zA)W*2u#^nqS@?H*gjTL)o< zQO1*VqagGxVG6z&4#tN7iutY5&hpuN3EVR6dirq39T^rnOI>4WL;@Y4*rlOpmG`ba z#JW};`l-BH8Ii4>zNAada#E^u20 z1RB9Wn*nT#q-o2#~qT%FEY5>OgN}<$BIK9~2kPE@w9V>0az?Z2F*k2Q5yM#F#)e#d&)4;hiyG*{-N7oQVpi=f|H-a{&8r6&=Z=w#xxk&T40 zy^&jXib6bypYA{cwxy6g;03`@?b3=Vij(5M;4?(>Zp~Fei{dMGh*tdL&l=0Qxa8k# zxC}7@+bGo!0>wBtPncjvQAR6%Ge$|DcW!#(7o%TF-$?Xm#VuMKS)!ki_@I|PJ`nM} zt1h~BzatjP+C}((b~h=9Y7wX;{WF0e@&QPEC#R?IJA4Zm1xt~yp`l^@Z?f#0L0u$V zAOhk&kW}xSe%xK3`drLe!(Rlpe~^$#1myzXyWS_DjSi2&4}IX=Sach;1SdOq_+58C zXSfav&LFseKh%01nt-mQ4~U<@8vwvMaM4CJ1X{^uU%zeuI+WE^`D?Hk%$gQ}JIbD7 zXdD2KEp>Et!MS|}j&JXy9`u;FIAo^OPEcL4SG5y>R{gto3_dj%WDAf;N|lm zPFWQ>l$$_ZHr5wEyyIa%EosT^e28}5{E}rBN|1M2z8Q*4``ShE9QD+hDS69eb88<{ zs`0JN2q!7>HN^7@@-gY#ze6W;G_5>KGOa$#wi&)W*K1pKmO3n~GOw1|we!0qX!4TK zD)S~<-R0@N52b!^+O2rB#R#s;W5>#MOTtC?YZnP1eStDm+tgIU#DoT%sTHBW|EB7pf_I9w_4N9IbAwF8#jI}I zG@#+W5DnDu0bl#!y69EixQzwqp5*v!Wr2UU;o1_Nl;o`2c0Zx9Kx0EpO4`pIc#H*y zSHjH*K>G1)Te8L=2X{_VH`%3N9*<`qUzhlr@DXe-sGs5-T6Yr^Z&aM?ymt0NC1BOS zGRsxntlMC3?j#x@ayqQjM&4trE|~py^`|8{P&|Z1Uy)w!h)~S18oLZOJn`m80;5VR zq?z=&@Yx19n9HJ|iF=UZU~k$?6f;uS7gG3TEhaH2@n4@f98`8O1_VG;ik~BXYa_?V zT!7NG;3UC@X<^wf%WHArgbS>xLJ|;mThsCIn6;0o;u2t4*@aAfPl%5%qoT6#r~-^2-$s1j3|(Qi-`)iLB_n37975nS`f&K0NROlgFSkKruwOj)!FyfcD$hfSNnfx)z?CZfL8G(+? zkT#^t+E;w&OrcG731MoR3A8(;x?=sgoV^}R!qTeRNy@q&_yxq(&P@bS0^RD0?5`3P z8Kw}F?)25qalV2|<`p*elK(MDQrgZ(6*J*rtLCmC+{F-!ZhIGFk92Ew4EB#ig|dHD zH-klzN(v-&eFI#U+=@K0Qe;e&P7&OcVnbFMyd6A(9gos{>yD*oLzp{7jwP@PezPrJDxY~+!HQ(`QvnhyaMgA3NWyodL%dc&1 zZGjZu_43;la6bK~L0{(5K-EGxZz8Q1kz@^jC{klAp59@QC(bA-3YOzhhM^1%!)_1h z4biXBT4;k(OoA#3b-Hyo#H-JqowV3GUlbd3I|obQEe>?(T!|5imN+T$!H_XjOmHwa7#5#>FNYUyYFV&qekg1Q9YTL1sbyc0*B$zAsVBnX z*R57~&UU$9rKn^Jbnn3o>uW6!b(U06U}^TJG%@v@_;{3wRbTJfkVSf$@xD`9`Z;Zt z*~OI^#sJyRzTeRyg&H(`N9;D5isw$t!XG*ZN499h4z%mf?+}X} zWc~UO2!prp?DPJieqbO}u%?q4kiNqq{~jck(s5AL0OR!+CitYsmWfut=$!VLl6egRJL%AuFgKb~# zz>42&+|TxDU3%)Q@SsB8f;%n3XrlDkW z)3GT;SO8-@`q2nckKoCg0xQX&O7Z<{Mzcxeacc zH`sFA6x3N~EFL+hV)C2K|CFd@%!^%?Ad+74YwoK}z|#cT<@^B@k|&svs%Ok4|3o== zzp&iajF8vgw}=ovRvz~^Hx>DI88OXPV-1+#GWneDtv6hr6440#|gNFmEF3{LNTOR?9=m(9AL z%q|#gF@79nUe4h7eEuX(o(ZZQk%qIkLs#<8??9Hhc_Ab%@VWfWw|+woJ>)&N$Hj?& zc`2lzgS7xQ)M{R_)|Yd-=unI{VXt~Rg6O|xopG2IZxBWuz*rI9hm*ytYjM8yzqE)4 z;+Q`92FOMlWf$L+w%WA@8FL$zSn{_Y4n~LVyEc)KgCAwADp4}Sab|Wf%#%4X88#0N z1DR$Yejqf}A&a0TPEb2?Zy?S4i0S;FHzbKjqx7%&JlqfZO~83h8r5+6$6kt0xB0w* z6$u|oS5*t?z>%#e?`8)KZ!ihkxmHW#l=06`D}|ZU9gJREN9z$(1F- z&!6ftDn9=56KcI5`dYg3iQ=gfWVre! z7Q6D1Ht7U${n+TnG7@C@+$0e@6(WltiLbc2_xD0Q#f@ws7dN!QwZU)ZDiXh9sHJNS zn)U}j@#SK)Cg&p<7QelDNmm(lK|9i@sECweFqLfS{$l5iGr`(Jp7Lp}NDL&afMRtd z&k5k{6p?USg47jneh^>LEa%273hWKEmXEewW<{dVkD@-zh282s+&&}tE56LKbw{Qg zdfFVCIFykKxkWs?cp*Pwt$8ky4oi3$WXZrAZ49Zt(=yE9JFyf~W8`#3@QZC_5;jFbHCZ5Zk#8KolhssJK}K|M8lJ__2*3rRJ_%TF^g=j+vp=R zE|8_5bQ-Zq+k4&D2m8w*C?w3|I;Q7J-E%Nymzp+eLj z1i>s-U>`wf>+nc-0h$LeP{5s=U-JCOVjUX>0YScgbyAVIi}P>O4LyI>)89@*4kZwl<=zEX!-ZC^Fus4badnRO6>Z?ZM9KTnBi%H%*bIL{s%v( zy?@Xhu_%tS`(q$w3e!~_&h(q`UZxj>TMv}E6AGwF%;e8aKX@LsV=3qTJyHA9l#Ep_ zdaz;-P2A}5oGxQJnqT7neM~zwQ4UqDuwi=Q%BEFROhfjs|Axy#t7xZNnyEXG&2?r2 zTWUcw%6-HcT~eCMB1rl4dk_V(5FjXLrKN2($peQ6P>%k< z(`&%~Q9#FxcKUZb$Njgm$nch~!A#yw*|H^ZA04Tj1aH+KyL?AUozZA~xSaGwAS{thQ^i9VUCYNjJ89cVDJ4E^ou0|eaP3?l zO^wh|alCcImn<5U1g$#X=6lt_E}ogBtMIMwDj!pr9~ocH7_E46>fmRH^?}$b>Rpw+ z8eg_w%I1u%W(inyX;QCt`JvB>AfCWK>s+gO<<##4*ejnTFo{gax{ znxigWN}y^d`vqY`p2OU1*rGmte~IKuJ)>Lpbq@B(yOQMij4?*3$+M6;2F6=dWd72x z^NTIt4pm*&c)c;(z{X{Lz=SQ5R%$b+Fe4#ip!{KZhY4cB09N_HTMM0e>B~df@rTAe|tiJ}FX3Eg(ZOo?4aFcc-M25a^5tqobS;ZAu@ zopdNUg#oFy<=1ixq}5z9uh^yR8%xtnkw1O>VO5Os@=a_qe$kQyt`478>nB>ixv3?X z&FHdwQJL@@y6WfsSFl$wYsu8mjg%qr_=)E{2jF%G62@Q%kpnn3@Suk4kK3!6p}U zy~InJ>XzRXe+>EZO?SwVb?WsqcmHqN0dd$X=>~yV9MX2RN^Kdt1R9nHAZFv1Skik=2?kPDaAsKsvnVC^fA!WA&t{?Ot3tJoCu40^z{HH**kj+@7HwH z{_H0dq>OVLicDeK@=Tezaqff6^em!S1WdNl>Si=We}>Zk7W(Q4R=&_XZLRr{j0I)A zY{VH4d>iC^Nax&Y0Mm^1y%g${V-DIc1otLH(C?Z!mX-YWe?6#Wx?0-WQTNJPfX{bTI)?-c0SslDBqrfw=1Z9jNy$F@5sS&nu?bWgqdnIeF7BkcfdPwb zRgSWXKb7-_k%9s)=8q4O3-iD4VlhwDm>(R0A?xCYT$IS1+3G|oE63Cn6LMEf!k@h2 zJPhZ4OUvVeDV2Z0h(O}sQ)DEz;xCh%m;9met>RD3oxh8is1FRUc34JKBBG;gYHF5^ zO+?pJFCjdzrs~bAJA8kv-f#F84TbHg726o0hS@UW%^Ok%-?| z%V!c7&m_qAd%Lv_3v1xpw@tUA@rEv<|YE67GVA48DCn(!Y`chmIP}+o#o}eXJg~B$;GqZf7Zv68L3oMdu;>=C@F^q zue?DCd!p`MKkBibs}39Kb81SZSn!QMRrc_hq#6{4z^A`| zZGKs~ZEWARgd)`rThY`CMikkdoRF=$r+my=-16b*Y$h8Vq-Y{MbWd4zzsQo*<3aJI z*~MZo=6cZ7`d*nyrp}w4WoSIyRiWGEq~eQ}ajNgUDVh|q-VjjTYFKG&m=l(Yh4s9& zax0=)L?uBH*iMztPbt1<45p{+jC||8C{2i-EID-`G3ZT7>?hwTt}RFjufbp{W=7ED z?FyB}q(>#Fd`WlQ}2E+)~zx?uMxd z^LFHZcXWAaM|sW>Ef(ZH-0pWZE*uABIoOdC*k&l&l`)w?y=I95+HOABB@Bd9+q&Aq zjW{`)B5ly(R;FJiC2l&`-(Brkrq*GuW)JCEf3e5)n;=xh?WI(8KU8&8h$1O`xL@n) zBH^V{AkS%@u28UT>#Tp=LL$v{`_;P_Z+nrq!y%E%_SyFtSm2L#18xa%aX+R<6q3em zHhVu(prxhZ;gc$PSTF$(7;pChJ|$(`#7>&y<)KDwkMvoA+@z9{c77&o`pWwo2F7e* zA*8D8t+fNkEjv4Jwrauxxjr|)iz+Y0Tv{e<6u9|FD2Mje-*J5{rK@Np`8qMs9ggx( z>~ET3jylc2;QB%)S)(7S6_Bp1j4Yp-Q&NbK5i6)Ta+*^oS_Qpq8XPR_dDmlA2lCip zd?r~!pXcRDRbgm&ky49L|&tE65uiNG8jE0mDm?jfS<0RvZ1ML2BQI z{#@4lBvd`MzNYu^P_0bm_R*Qh-3t?D~H0W6hr={Zynjz#jj(-q|Lawa?v&t^!mea+( zY8UMOT)3~8kGk2}vF;DJdEk1#uhJjYL?%Nhz95D}x=Fg&&%CC=p0(^dYf3^vC zT#x%hkj0I>=GT6tWvNci?a#(5cB(?m20zK@WU5vye+A8^%=Vjo9y z2Sq}SRX=?=%3DAF5EM)pTFl5Du1_Ht5&e^<-iZ{TLAPDgxk-LGe83MnCCRzN-^YvI zP-}}5sBhOS_qox;*=%e%dCk+(a?c2GR@$R~NL%HhXz3^pUznJPQHOkDe`~wY<;XXQ z|Ixz)ONyOo4TALg{%a}EYcmylu@75|sbPPjBU*brnwj0l@;Sp|i-`5BHStYDo{h>b zp?Vy}=JXG8bA4HDMCwa8yrL*&Pkh*9^^qF*@lc+drnEG`iNhMp#;_)Z(d&@Zqi^4< zY5hs4<3nr=aWCmlb2jI$uDw{75JCzDiqaM1(NBly4XsaD#lJq?bz;ZwH|$Dscy#A> zKv0TD4x8w{)bQ7^RD2e>gXW;*FiA8GJ(59sh0e4yu5XD#y7|DCarg7uEcmS#F5`}q zXddVmQQ;`ndCm&W7FXKT<+gQo>^$_SY&fi8(6VTXHKaw;D&XB3aQI{Gp**r!ll`|B zK z7;kF={7wax;>lzT4B(zp|C%7FHz%hCuD_LMjk##pI4#YUF)|nl%N}T+@8It{0oKXT zZg4oG5}DiPlP(37rX1XO_rndf)jDeN`TJWFB}D~tL_bT*jSIqLK3r_+_8&dlko$#~ zU(09fIy&?U>J|4smfk8#<_3No)Ollr) z%QY}ds%mMp=N1MTx%hxl^1j=`!nI9W%J~(bSVvUIeQ+-#sCJZ}fXCm@u<5pl#H5(hd4*sH^aL6B;9so~jJq+q=u-=TcJn``4Z9 zeSRlPwRLrKc}u>rjW4>#Mp};0MseS|s~(mcUS4jNv#obNeB?A4jo9_!z{~3#`d6eh z7kI|{8Fp*s=hTmC;n*GKzPN%+CgCdp)+u-#a#=U8Zk0U*7m@^sCnXk60W88XufOub z5Y6HtKkjdfo4N=^Sk7Y!-LtF_r=a8D5%YlLFa2&dqj|xjqie1-y9s?QqvoKuCDEv% zG4M^RSn3jGn8i_uF5p(C+XEfvh?hDeZZ~bBAQaPfjG6U?5oGN`)@K9}2k=BcId~Y{ z=I@4eJ8A~KlgRw!WJ~SQRq@02eagMDP(Kb$*t=PiHe;^YcJb*X1QvS2ct=^2%#38I zhee@_OAM`(&3_~dwFrtLo@=~`OP;D+RGso-n=1_Ge_k{q)Ig0tEpplXuyv&5ov~_%cJ^=gqB|&|rZO?=7V;~q<1`nk$Dj}6E z)0%+K#|Pjx{*$vE0-ePZFdF0tpgnHBVN-K~pbfBh|M{F@vJNumU<9hE^SQr|k0_GEt{(hSXLyxzJ;)%Nd@JqxWk=8Qt~= z`J9q@RbGcpWLZzg@@GB)8+eM{K=;PMy>IN>#kWmf-VX~AX9lVeAx90hG%~vk#&g}E zq_e6QePcwW%JNPn?Lck)6A{-G()8&EhQlN7bBs*foRG;)$1;?%hE7s%k}?fH^)W+= zJUeLXy2Kyq&5rHS@E@GRvNyAi!{n310}v=O6UGkDa8gm;&BDh8l0YscyK258q5U#Daq$;Tu+f=cb}*G!hug2X z9m9%8Q+nZog<6aj840wV)bQKmWm*=xfUo*uUOC4Xe&3xLHjujyZ9e9|d!{9|WNK+5 z#ln!EpU8ZWD7&1&*>BFJxGV)8?0kXFB7nan6eTrDOk>5_m& z7jBSUuwC(1k`BrDSeh4(DO|rx)Fn7_%RM;%gnX%~5OV)CgE|8YD!{tP&C1I9#6w$* z6YNA4Z<OtYllFiOD$c(|{B$zcmT&yz~>Pyvf4#4$0& zG-AEpo6V*>CX(bBPa2gIVXmgo-r5WHsSfuj-J;zI76e`4~KSq z@djykAf`8gV#4J4*10c3r|7tsg+HP(-1{89Xv9s%s&N`{(K3D~SNZ-xp%Po;)YnPC zh4Ccsnw>95=go+$Q?)liBQxq)BrB8t*@xRpqfNu{CwFu9E!)8vP@jRjED1XrwVBD> znyibJx*eEkHH+k<#All8?1Q3R;p=UBVXK8!A*bimvyh|E$W9J4r=qe^L5v+Q4<<|> zQ{T&k-^r3PN{GxFQdP}AH_VR$xEx0p>eYo_(9A(Q55m>I`JssRdrM}AEY=55iY8Kx z?!k^vuIZdklOVq|&KKZ9 zr1}%dZOhiHx9>!AOHxNb=(Zi4{Z4eqI4ka%DQeHu5G|2;ChRHSKSAVvQ`-R<*1yOyJoVNMWjGx0(YqPU`S>1m>5g?i~; zXob+kU~n?S@VKIP1%flP;I70k`GI0`z6(t1Y{i98w@j&idE^w{K;N!F5Ut7s zK4M_+8gVo4cf}K3CLtz12KG3pea+G8=D^+Mw>q9gil5!>FH~x4XCtYyyS$wFQ>JCU zKFW<$c(n#S;8+YnBjAlF|{B&-S!cU)qLkSlHkrFY*;$h9fMK~f(tC)#m z2ca8iMYYkC|3ucC5xAbR7QQkHjg`OngrqjTLhEc?-r8E;d1QX(A_i4jHm1oYH7{>gb0Bwdq67AD*#$Xm&j*P`m zOH&Is3Z)CG-Ts7_=|e;NF2ADg$y0#`Iyr_?X^V9Pc`jjr9^FV3kz1t&p6}b-H5bVa zPkVKHN3E6Sda0k#{r*-{rmu}BR@l&lRS=T0G2U_a#PYdEZ%~d#?Q+}b{6jcdR~z?7 zy-_8UNAEq=D0f-@te468{yY@@8%2A5lF3tkg2_I1`Yn!AmrJ`mbgN)GV?=2&ge!TOGritEIUe)iYJe6^z ze)ToJk}LQd0RPk4WBd|}kO>4J#{ z;fqQiGH5NSUTrhHyLTwo{VE%&X}wDpWw3BA9e%w5ag=)cnRhApN$~OXZBTWkocO9} zv6(n>^11z3Sl9f`fD+cATQrq0*1i|4ri+?$3zwmY1FNhZx4zT9p+QaiQwiZ&8^Mhf zPLnC>?T7Aab9ZCaf6L=GydSaJBXxXc=!*8RSM!U^lEi1116e6GmLW$CpDyyFNam!) zr~;oD@nQtpF;DeM@1E)z_Df-^L2{u5GnAZAzoKZ7=?AXHgPyus%y{zYZ4x@INBnn+ zMdd9fZ{7^Sj~w9rhR@Le(Q6A}J3TwB8XK**oq*>EK|*hBLPP2qKYuDP_PGK|%kO$y zZKt+QFxviSbhhFhyMUilJ(Wm8W9OepZil_X5Rpj%{35M1?bgCaJg^=%e@vv z;=y%@#D?^y^pi!y|_v>RIivs|)<0suLw@L?I2(Q z_v5*Zh(-ZCNvqf42pF{49f?huDPT)L>wko}v$JDiX*u5J$EnjSy%yhj?PwSa`>o*g%sHv~EJEf>rozBnr=CP4% zMyh0c$MjgeO%jn1*ztKKkSa#iBi@jLb@r6}(R}>og9dAeX^8RYfrI_Z*8K|t?b5!` zyuZHON`v76&{yYDtK$v!1}`mKnSv|0ZX4=Zs1jknQ;(Q`KE_6ue1<*D#pa%G>!jp5 z-P0&Ld?xZFj!n+pj6jmF|D_ZXu5RPM7~A*Lb$8pW-+B<*y{3Qm^x?1f;fy{`F`2}S z;NOo_PmIDHt}W1CBf&0$qI$LGhsN%yWKa4nu`x$J(+j5F-i1wH3QzifkX%-eW? z(R!o^-ZDxZ%5FlGd=r}(O^At|9K&n&7$Hu3c6L8X~HJo6Lkf9tib7`PI#MH`}oLxKQ**_}oOD6Zx zwmY-tgdts`)0?p6?N-ywu}oCl-?8r~%^WpT=k_0t@w@qM4l^>WUO9qU;7pifat{;* z3Vo>w6Hq>{CkY4dC{3@BnULO~w?}MA5Qewl&UIukAR5Tp%OfcKzLbglu@GKT8WMd_ z0vqr}dS2AVz*vN!pp?Pzv+ukVAFJEv@5AS!-8%|4`*mr>s;B=*W?n56>Jsi~Pb-7^ zeO+7A;KSN9I$B%eJtk2|^WuC-L&N=j;{HP{(WDPdlc%9yUH)H~oaQ{c&HLGKuD>%j z<3@J-8#oT#CI)6oQvAv9$EL*+?==-e-ZPsR;ZS3hsvm0fach@hOu{m=odQ<& z-1R%qUrb_Eb`WwspgPGaTJi7R7)SP@z!3Z?Ie%{#%pV8IDE{@`HO#kP3hS@7U!sYj zN>-w}jSW>)_z!Ft&WZwvgt1l+dtlfeh{k7xuWDe-2eJD+;Fje9IToB3N7C^46PyDJ zuAMs|tprjupMhbS1Hg6&)kQ)8A~g+kR{36tP29paowW3H_z*H^cJ>eeTJ!*7D?HB* zys<^VD-FtaK7bhbJuz{8HlaZdM1qKj2rBn68F)Gd9(;kPkpZg-{;d@gsRnkdx@h=Y zBmt%Z3}K*d_1ssfGU7>^(?BX&V{+ z0^5uT2ytWy+LOTJI+-tg_yDg1o;^E8L2!b=brBG}-+*V)zlUR3SXsFOu$L>C>G>WI>goU} z!}s!FcrA+dz=vA<>f9WohJ0|BpU-BSt!5GzRV%2684=9wl*&jyevaAh+3VE09pMIz z^&Tt;o`15|{I%4X*%I#iwgbOiBC462@szRzsJNK+gUYGAe=V z*p0*B5;ac!w+c%IKE<|!CTWll80Za?W^%Bl!so~ zesM~?JowRRI%>GkA^q0~(f44xV3oqAl2y@Q_>z!XsZi9M{3PmRT%-dN^;Z;Kgb`;W z-HyZLM9<`naIZ9Kv*t6vE>jO`qhc8mbTp?|kKmQuUHTgq?H~oU*niFo)te-1x zlyR<+KL$4AEFH!r@4Fjp4iomx{O#P2nchhnyE?(D4GzV&CXnnpXFlc?z_P^dgCQcc zR&I<_b&6Z7WUk)!iAd>1=QTWae`F@iU%%02O1qC;DpEDT7wbPREkuPhn8x|8x+{&^ zw*L{xJ$=Ty%7gAFdEUDp{Ywmi_nYOFQiP{)T9J(tUUG9XbJ)$Qj)3T8!FUN~z3i@i zkidatg9&Xy?sfCvjWT4J|6vKPnTw>yW12j# zqZ)g4-rfmV1zPZC|mhhC6i|G&znK7QOdRp3c_Y#Mu;Y>$aBSc;6xb;C z=`sP$7;r8aK%)lewyv(OuwTEJI5`bdauNW5jTflXh7EQKAb9~_ivSwHi1!2v+#+wI zs1*V4MET{*4REO{RLd4R`!^N$?ByQMG+2`A00@SGf&_}cFhHv9pE45^7taP;AE46! zV%yw%^#jK{oh=Z;pz@e}MMO+IUaU-*C~=_=iXvJ74HQR!qX+=;PYLik0NliVe?A?b zQE`v1x#%s}f%X6o@F|rDRGLm2Bu_;^7!bT`tQH)ge1csfB`;4Mz%l0L<}9q{kEyor z2jSnbOWNQme3SWs_BwTBc-V5b`Yj4ltnEk^e^lLwSlkaB@pyQJ<-YU1`t1+>YO|ii zfb2sd^PXL?lA~QEVOi?$dEV^(BV26n2nrG%o@qfU`fx-pW#5HgLU|92!h+~0d1jH5 z<4ZWyL|vQn6jbP~6K3cWAM2nuqb*f-yO->V`;7(hpAn~dN$88bUlgeC`ERBz%m0|> ztCE%ZqhNE-7jk}jInQ41@}sOdUv)Ebs|{lu z$_M(r>|J?Ax#dqI8+b(@ozMF0q3~?G;sT;L?lrG7 z3GaD3k*E<}?Tr121PcDlz9vxzLEG^*!|tgf^1|S8i#n{uF_fe*t_HTGxp~i$^x;cW zebNT~=9Oik9|>o(E87vT@0D&r3b#74Nc7}+hW@QP0VRJmLqBH-|7r*6>f-3?oyM9* z5+n26_Z}F18=70sv%7~G4WANpo&xoOGZyJ%e*Da;O0lIX7+QjQp*SOAVSM@U;$@JAsnB(lZGoNC-? z_W47OzZ? z8YXF@#uuAHIZn}nJ;$v6SslIj9q$578075bxP=d$XTa$P7{ujW=earTtdSLaWD<)e zBtG7LT+53UlT9jgn(FjyF<7NQG`~b#(`8;jE&%%t{_M}2C8T6DCA?*r2LS^cO|Qvq zY66@5r%ifPO|0GXjG>{Hn7;|DPeW{w{ev=3(x18M;N0|Fy%IN3GSL>`sSWO;2lff

    F~T@W7Z-_ z{mWb8+|-4p?Rn>}^JmhFtcty+{7f9m;divbNLnlf9OD{eg5nqp*BT^>46ZjjHk69N z1HHU|gi~Vt1u_)oo#h0y)CvM&a-+KzvM;fSKKXnjS;(rCw*RhMkAwR&?~+zN#HDC8 z;EAQ}&-Hqa_x=as0!^8s0?~`@?BjQ7iN@%60`g<`6Yu?ZlK z@obg+FXV&@F2C{DhOG~{lgElQPr=ZJWXzdKe#v|u)Wz>A6eYRN?sB!el)@&q1Tbtl{$*xQGx%oe@VTKFX z+=w(r%ooNibWv=DC#kPz-lGYL`ZImBn4v>%cMKohN6O5Dc8pWdNQd8`?D1M(?PCgT zt+QcG5RemD&L*$;czY@2hEk>Oj(@MFP@rc)2&!#-E|=<4u;KPazY2YtbA=-86y_ zYpv`}@!!(siQU592t~QdCa`Qx1Fs`MHZ?ihzNr$F0>mKheR{w6QP5uY$y9uNJT((v zv;Y@7dy)2++4+qIoAFS<)eFblLxZ2TKtzG}bhR}kh&5xP!Mub4H`8O*tz57W={PwP z<_#N8fnu`}MH>kITCt2RHSznm%|at57!`*K8o@ZPQu;%g)jmQ2cJ%}28-S-;KE4K2 z2lxg7cm^Gbqh?hd7wZRYpF8y1JUR1&9z@|p1CZtYPbc|eJ`P+;cwJVdR}S6FSBDSN z+4X+cm@AF$YhQW1V=J(5)UL-lla6bhsM(1e%p@zULgBp1DEL)6IzErKtXA|(z%)Gm zKtSNLhLZY&WpsGXyZbIFzMMzeg2=z_4&z}l>njmy->~ps@kShNnTbY^8LO}!dyAC+ z!NJbB5XUGZaFRz6`*C{r-(G;-Jl0^Bu@9W8gQMHS3FF2KVix@EAt)$qZY}8A8q_*c zH!qVMD||IB)hc*@$Bd~BVLJhOGMTSC$i50KDG&!G3vd4|c98=e=@HYSKs7$|zc zY$t(VU=lL&o=D8unsN_8t0`^VW%I_w!^23wvh6)V&1cA^d=|YFy`Kb)>#s9e9=o61 znx-XwnjeN#Qg-=Kp(@9g7K6;OuA9P{0nBk`Qpne;73Q;z*w}IhU+|<9i$1v^NNm3x z%NZN;tzc(x%E9h?30;_a>c>H>|LE1noHjUqLy1+hZ}ixRH)6dQ{)AbZcF9cWq=S+m zHQLC~5<^HvIFT$ZKY{A!tju~D#D%m!z*&%?%W;1XRvBJnD3u)7YV-QZTzm}3G~nWLD3{V>rB)Wex-T& zJ0tf1^vU=5t`u=D7dn)s9y<)SN5>mgIRg})K|FV7Qfl>AH za43B^c?eJ5&6|z43fZ@b=y;;w#&C5+pWH>)s#yp9eD1Y5wTQ%#%D2}`d^F@&?L%3M zm!~9rDpL513`Yn5SkVFJyZI}=~AI=^C!PFdtdV_T)0T1Piy`K0;7r=Z}J1vRnRv0P( zA|NfO(YOJ7?N@&dz}KGwz+|ms_OBj*OexXG9{~rmIykpMUwp5t>-%f47~#l4pVO3= zi2H!+3HLbwKFdddSChQmX`J`2WF!Z&SBXPXUVKFwj!r*o3mOvbCVcTUvmv@YhP@j#xt97?X7> zT#HMdz#)M6TixIHpYL9yi9Y5gpNyncW=1)Dds&U4!A&{zjeF!*-$KpIft>|w(hshz z8oczR_hNE-^ski>KHGoL@4v=2{L)5fhkv1q*Gfn-<%wbY?!W7@tWnQOyPp6DTMw#=Ks zX5abAxi*Y~_{d^dUOWkOT~j#T-Hzf@*Ic_P2(T!?nWcRZ_8!m3#m0qDfNP7U@fX_} zxuzt4PR*oJ5BBPeW1^}Dn!HyXN|%W%Z0|P~`-NeZbMe#CcwGY6=~O3moS0C}0(94< z9>3wM?s+AnKTkNGc00iwLwC5Z{F5kKAapyOB|oCoJ==EQ%#eD7#|e7sxhw2yePfj~ z-{EoBNTj>?N8!wf`ACcaQIvHWc@*e`L_x%hqUg z;_wlJqL{a;!*w{Dn!7j?M1W!lFO$^Ay@H?F*Q&+}{$RftNQ zY?vvkGw7p^rDnrQlGm&(hQjW04rZGc=N3+p_FM~j*OZElgzcK1v3kI8vo%rvdf9}) z=Hi5qnW&@gc02>?Z!U z0iD8H!{V-LENkUeO*n1#%C$!{1*$MKA_HYP`kY z{>7@aX_)EZ<#nKmpw!6kMitq!ZF2jyQdeD!<_&}zi92pqZ;2S2Eq>^(hF15XL3Fw z3cy|scIRJ|oN&_#eXk@5)uP~2Uka-=S)eam7KiBaZ9dDH=ZZrh1Li4w%u=JOJlZuo z-XpP19}k;IMyw?1I{3){)%ed4kyE=R(426@io%u9WaNK6WZGJA@4WUc%HyBDdp{;K z))`y8OT-+sgn}HCbxU1g21N=x(!g8nNc~w&Fv6cjRpro+Bc)@4s+1Mr&WB$}mq;+e zkshMj&Pf{{9wdrRL-$aSdYjZ%2VLf;5np_XpPP{lh12JhGTZmx!pRBgpVxmJkP#;L z{k77eBfN_U6*Y`FELE>o8qn4F;@^lcvTAAH9(yP+xqUxk9eXnrMINPi^98@%lZ8Cm zX!DR1Bv_IiTbyWZaqpq?6WYZrKwvlC_Yjl#Y()tmwH{#;44I4WMmu;p3*)HuPw2^suk@vA z(Htq4fGLwlXWNcrkULo)Tl2AHg}#0U$L`;SqPCKaU_l`V#Cs@=7cwtl zN17s<5v18HiYT=lk*h3xtgdZ9yK%{7fC_*i*8m*1*SrQG_-p^ICBEuP)HGRM6D*15PHOb`$mp!7#Y52w&^ zez7qYh+s?55|&a-)De`pT|`v9s6P2(ytyFM2HKmocu0F3Mla2u}^hXCT|^)^1C>;f}}Sc?&aK<;A3?g7xD zjiD6&{)({yn!Er;Tjli!RDK0`b3GBbRsinowTA?3gx|BWs64QMXppsDLiI~ZOqNFh zE;8Xqvzoz0nS(Y7Sm$z`K6`=ysKo-kw$O)`JE-RCN{>;fu~b~X^cz;x8Z^VOjB zs|y&271J&$wUXX`*_2PQu;T6Dxfi4e?o1w(Y|X-OGk%ZtY_TC)q$PuhZ-~cYq3p%L z+n9qEp6BL=#M0tRS9HPx_CtdDJjreOk<)CLf{MzjGW(71GxZ4cI?H#+R#wR>n^EaJl#)BYoG-h(QhW%9qBE|n&3J*Xy#`| z1N}3u50H@GJXM|w-TE3ob`8Gn{m=T@DCCxHSA3OX#Q5tRS-^w_#4vtAiCJW}R1<8( zYb3upV&~7sbkEP)({ZzjY`x^guZb$|6kAdMxppG#v{Q~QAF^bTPYoXPNB_q`t$N5T zvw5o0i@RIUX+q_JE++Y2!R?pMj1Dz<1}|{-%wveCwu$TI59}W$aF-M{rhEG=2fJ1x zI<5`O_ChC%{Xs_$yBq&3eV!h~7=j7yx#rN4wxC-XKk0HUKq{n3-=PnbOH?P$8w!Tw zIgX$wZWhl&^ptSrk`A>X^FTUP@L1Z?j z?Ks);w+js+QEYKYO^UW-cvM4$LW&>NcRZ1_*v7qXPHDs&uLIGI=7+1!1Lj?iZ&#jg zJwm_zIB2{1nQ#Eq0m}W39<%_F@%rd#x$yAtusD{juC7izQoBljA80E8m51rT3!o+f zM51u~h0&YkSRJ!I0NgBHh&s4sk7H}1cn~fFEJ0-Cbv7LUZY_4uC+M)icX(05CtZP? z&SxX@!P=k5I`4KADZP=+OI~`^Ta= zY_yl)6t-O~>nVX%I>de_Z=c|B`q{R0%xoO7Pll=wLql9eGq`~YIGwT+0`|SP&uX8qPY{oo}Rjz|NEZRpkX5=CtzdJVbPQ^lv-v-pJI!N zm|%s-p5G@R{&zql?W8N_`FxCwKiv77%HPkNOy1Z2EFiM)+;JG=ckdall_R0!Sg}w{ zNF{+0q;fcl!Oscf872Sjso5h?D2c;*&XDl#3Yb&Az1fUb#DiMBU$dhXFJi5Ot>YbNpRvgXXg~G?b7I_~o;ZN) zI02sSy{D0}!&?rG*^`$+>If>WdM~#*A5-vSqVCJB^W?`GbaKwbNcu19wwER^B<$@Z z^m3n7@^P0W6xq3kuYBN}nSOb97I7bzO{@j(NvB6+d~%Tc(@q1vPrwY6<=tzGn@z_z zE?VD)U9{j}!{VWyPU9FAO*;8_o67E8S;+h}DEFElCcnR7ThRF6#+G;3p9S-=k8mAz zjG($g&0qKC8*&8WYKqiSCVrSITiLp2Da!0-DLTwVdIlQ*z?;8k>hR12hR2Cvz1yWn zTv)RKpgWhRBNAjVlzQ;z)Xu*^%6X$=>!4qjxp@;+uID3=jRV^X7#80$AK&BDerV3K z7`kjAiy}HZsE*yj;xo*Mn z`?dmY9yegrP>i|XkxMvY+^4or>LQ)o$nIa*c}0y9>q7p;3p4saW0^A^$Xf!;D2ML) z{hD@49@7L>K4h-FSNnk1C{LxJS=sMRIn6oryn=YX>LX;&*|QD}g#4e^7JX*SV^R;^ z;Eu(^YE-`^H7nD4(Q^Rt{FITJjXypd>%V_qWgpo>B%gX^wlL*-yxapuG}3R$V7U59 z*8fFn!u}%-{R@jv2(iLC-&U(`d>|R}s*svB=NTeZ?B}%$@g0;BCQqE$R~!g|6X`I6 zN|Ixa_8NDk$+&6+?VS4tsX?4sx<=Oo?G^-jB}x6K9<2Q`w-@4lS6}+5Z%nMbUg9)d zpQ!laujxMfV_*cFgzkLiwD5h`gzo$PfsVlG>;>{Zgk6rIisS`fO1kvF8IOx`eg`>I zZ1Tj&LFR`OdeDz*=X`{DjnN$=rd#`i2zYD%`Iyfxp^~7y-uS({8v@ppT&W`T_cBeO zM=5h(@d(H@$!U%{;3@cPoZyT=B($$AgiGp>ErDtw>;tXZ26N8884TyO3#S=ECo!p~ zcjYqi40~80_uZhC8N8A-`2iCixu>#|@{hW5qY{7*z$<-R7sRax`|&6e9lY5RIJlsJ zj&M;gPkQCh2nx`qAMx`kq-Sf5UbPTK25lHlj!=F7T*_sbq)vW84Y}gU-WIaj>W3h{iC?+d)u#E0W3EzQ4}sd!9H>E{MBDYwfbq_TohzV@hv zW8p0@)F4)Kk`sn&1P(4#GF^YoilJg=lO0v6g~dx)m%mjh5&E|G_Oq$9`WDUCPL39G zbpMJ~s4ZcUMj%mM%`He-Kms1>;!A(C7qF&jmvI9PN4xZsfb=_(d8FY1??j)Mq4JYd z`CEVN{LUMMcrz?oxzB|4{r%nkO`2b*?0&|?LBm*2mbuI;Y2b~+5gd&gvM}+4Eg%!Y z5QTaA?wg}`skyMc-j!A_;SG-c$p;5IR>2)c(N+1(sXpuX-W5LxHBYe*NaYEX^-(o~ zJUH~7&Lcl_`l4+hX5#TN_x-mUVihCiVv3@G|&FiIUl{0&lN;K<)!pIgmy$x zlXQQh$RZ;!O?)sXAt&)3x7#5zaop!ophnR1E4`^+nNjhlZI(ULchWI0Pu0&+SN7sQ zWw0GXJ=sUgdRjg?{0(*J2SQ92!*G-?(u0>f<|8YPC^h4F$ofIW%?$0jgJArb!~@2w7=)S=6$S`+M`dbP8Fx&HdubCdLp zv<Ur9Z*5v}GwZlrrwCqJ|4uB+HlR@{_b+DoCnA z)1)}|Ew^Y!N1vvIErouRy7F2RIp%XHSTGqj7(j-f@MkWVSYwc=zzZ`!CJJO{Ah|0f zb+{!j+bN`Sp{cb}u-6J$6g_ax@f!~tX@*%~Z9JB_+M7hv|z_OffnNz$12+m;EYKAXC%-7Y&M!KG4mEN|@}>fB}{!hgm6 z`B%S*ocMoc_&vb|)@%@Zjm1Xjb(lFY?nR)_4d^Nh4GO2+CtGpBpX=_NQrb^!R))L8 z&JsM_yAiGjClGAd$%qqWu$^O|RLXDujfQ219)M%YpRfH!{@iJ#QWld1~PCmRvWh zU~jy&Cayu=2<^o;Ke6&R5xDO8V`!{9oflR9QLmZhp|`n*VUzMuUI=AzV#8f%BDM&@ zoiMAUq)da469QtgQLG7|yoU3cTUcR6MSv7Kh9(&~f$vt-(Q|SUt!eM%9>~#9Hw>Tc zqpw=ne2D*{Gtrw7_;2U+P5sO|j7K1TO7IdTAA&A8#ta;+=4($)Pjyu4VNlaAc2{oe1*0Js+_K0rly+ep zX7f5?NrUaYGEDLaT7rdVPLLrGD#hY^GxF>2^=SAM;gH3+f0|F@=!S^0;7j^|kP5i@ zZ|oX21RvT9sn${MTcp$ssYsqKKm2_#j!L>?x6zJ0@t>et#1Vi=-|%8CPPhs3iNAq< zR5P_ftF59h{HFfX1&t+~{<|GG=}1Dh_kI_4#=|f4M5MY}VCBmE99L9FZ3YSsH`<&3 z`atfFR>kVYIZ<_Eu@~^$^^g~Pe!IidL6o9|c)2MDR>=H4lBU9}I6i+W@(xB8RrINX zWN0E&OUZt~(yvrL0sg71e+44-h%(}^oM3n9*^7NC9o(odqtxPBuSWj%hRBr7&YAex zUv?)qH!9Ld;Fnoq#|7G0w#%$pJW1hbRH>6T$keqgJjTy}u-jCD zxk9eiwci104P%^&iSaX%9Ss%OKGaVL36m2(-#5>U@G-7iW+kj5o0svC=eB3x8^d{e zEg{urc~K-=D%F28bdtF-rxK01E*d`RopgaoD^XPwACtq z@KF{t>*&@!Rq2+G0KFEr)_Tu(o+5+vm}u4p647Fxqe5WrdZA?C33yb*~Oq$=U8j zA9$#eFZ0ihX}$BJ1n>Y?7hJU$ZICT|*x6x_AiP60g1B!ERCkr}!^5&avLGGPLxSZ< zY7SHU=+snfII2eVmzJv+8^!HE^9@<(;eXCZp@UZ(y+yY%;mHyMP&D~`Z!_n5?1Ih& ztis-3pLyJ-Xl}pqZ`#?XMpT|Cf?2bNh6IcMHwzGd{4ub;(LpA7k-U}APT{*);b9Lm zWINjpHJ1SMirv9Q#PyIO%9_uvb@us3K7UVn0mTGw0~>EL7HhQ%oZvtU4TJ(Zl<@{X zBjH@(=V_MI*4@zZ-2o{dV;1&ON4LZ=Z?%dy*;eja%<5+z+-2NJR43l_n^v@5=*%^= z7bk#gWaMdxK`i7R!*A!J-Nw?#OVx|@nY&XnjPRrk-NE>G%R1#@ObX|?$Y+(kwnxm` zyDTyj7ItvU*L-_?ZF|q(PxrAInIg3~n>S>q6^5I487^8KdHtku$wbAD0DsW-G#+ahXBa<(D`_fd&c$WZ z$yVSeFt`_2y1XQ}wM)n`<@e=Kr74Ue7spy7h4NfvC8;EAd}4=Faai zJ`pUBI|-oK4?wlBiqvfK13HJwPtD6bGMM+X7!sdwkrd~n*fP5}2rKa>OOE8eR$&J$ z(CZFFL?F?@c(Df}vL!XEeQxc|Yhv?MKeM)#H*!zXqX)!WTdJO|I}x-XQR!XX=w;o( zP6%^A=i=a!`BBju%&%*~ODQBRm*&)31;P6qC+{bs=-O4Yo>;(4 zclV&h)p@QXhM!xWiSQ)!sM|^hPrPVUW_6K99A}b>4uW}&0z)a-p{#2#p~jAQjRso^ z_c$XnJK=No(&`70*Sh$@4L8HDcB9CBvF6FU0a}I2MB{)j@vIphEY6Q!>ja0pCu~#A zOoS)o?ZBxpt~b?&WrMHtbKLOaytBD3 z7jzg{?U0>vOY0}L&X$=wDhRU=#$t^c(L zIvQV$tUuqz@?Q9;#KS#Gz#82IW8!sbdSm^8RKj6)K1jLR?B)@H6gyOLpQwmv9=oa=*;J|UGN^{**I+eGf5KB z0wvuoBcxX25sV>^BBV6Eh^!?0k@{apE;N}K8O^q*T&G44hqYBZV`8MYG z1i9s}ORP;E-i z`c8yg7@OFNY+TnwrvnUbtgf+4_PR&r;6=t>lq)^t!W*m@5DAOBiW@^p$p1AZ!o(?B zNrXRy2-PrQgQ6$C`Sa&7iF#G*L)<@8UdjP368snJ$Ql^6z_xGmhN1fOn!NiHO%F~0 zmekE;S;`Y1(fBPcYso25p4ne!kAXE~w`JzM8zh{S+CHnY@E*^ps!W&*Oyb(rC?h}I zn{2KPr`4I1{I>DIACbihZc*&zVPDNj9?tgz0Rbahu%vNGoFMdpGW;yScvGHUU=Xj`FP!% z62=y9PGS%*1mSPM&xO%m)fshT24eS78ih3n#3X#j*{xjuQ?RyhUh}W;FThNk|Fsv9 zy?E64N`TQVFS*X>xuFAkNB_mRKDI#4*XYeBJG?+Qgq22h_}VVk>fwC;KAdY27jpfK zR@ZA*ygw&J`~1PE9aj4u`IuHur|h zDT2Pp8e2bpx%aP!`M^=IVB{Vjm~HM0CW2Ol2)2V6Y9?fPY6|lL8oQ0vWQ?;Eg|o9~51zKb zOwyQIW*R$hd@R*?OaePgm)av` zt1~)@dim;4Bdl)InGzF2I?DQIF9K}~tQjoH%|(+n8#~uP(ss(UwYUYFA3U}<_h*C- zTz-WVr7GFS+7_&v^*RY%? zmQu5adPEwO#MhA;OEG9xJ#6rP3qR3mj|b+2+k!(i?$$614ll@vyzDo;9GE>OH4!Iy z@sgf?Cyy(mOA}!|MLM5t1~c<^p9)Zo>(^vEU%ge-&K`=fOLoo6MdT~dinhGy+D$PgNH-;M)(uCr6~%yufLz$>W83?& z)(5BFs|NXxirbs*M?x)crZVZ6t~W5}n+%wGe+Rt_ck>=J{p=DP2WB8u7_xgItf88M zTEmNH&S}s8$W=PjvS)ICGfrZgK8+_PFt;|Mia0mYk>lQWBcyM}ror_$R?E-vMsTh~ z>ew!jrrG#dQ3r$N5aIuw?<$$255eYGI`j<@i!T18EKzOtsY-Lo+Jr8F=myxX@OeXD zf78+6#z`|Axk04#qXPGTdHZ8bOdiLwKISmjotY$Y&*31y5dqbjBWqnXt31YbuI{{N ze71iY9cTmCNL)wjc8oAi2%xe2V)jPwIKK6 zH*TRe+>G#xE24xp-Vn@tXX9R~s;^4JoxE$JIOZpE?BW<%i{Jr|-tq^;h8Ik@S->PF zxA?Gc=b$z&D6Ry@U~|>%t4Tzb!{yBy$`Q^glcFA;Wv9`|q15I9 zbN9j1EUNUD6w`OPHL!7a^7Dkry>)M?yE>i66dnHwaxvDz4{#ty+c*Nt-1mV(%mnoKXV_*b%_^ClRM%GS2&O^flW!ORUGollA?@=&=D*N}&Jjna|cOuLhd!z4w; zgyZplu0OE^>{c1-aXv?(*$ECovA5rr?x~m?jV7&>scTq>aKQ>@M?TDLYi2V4dcN>9 z3qoh|`xZjck0XkMjEaeleY%ZbnH@XT+lpoYx3pC7tF7w=?f3e5LT-13geN9C5B~b` z=Sc}!`0`=#_5=2dq7va*P04fizHf(}_O^D2@6HCiPp0I{80r+!w-kntft_ zS2wSrVCEe)HP&~Ow`qMO$m3WrNmj@4ocUD zUdSCH#LHu8`Gx?)n0qU_j|#moy8KKvXR zDPi@EZF(pf@@Ec=@2TgUA2b?6MYkW}_&fv{y!;$nW5H?@l~1%uc^70LmnAM%anH!| zdsAM}FA!9I;uOI)g@Uv4mrLy6G8z2VUO@2Uh3P@VlLqZI<4gSg28*^<3E?3A-?kXP zJ#oq^Y=-)JnS3-_tv1q;u0i7WpK`q!34X6d2NHz^ri>3E z@-sW1^fMAQmB?LB-Iu?+F0Ux0+E+OzZa$8utFiooH6R!~E_EOg7A>PvZMR3UGVCDg zApf%^@n%?-a@KIJ@Pk0!*OyPN1Bzt&6s=(;V|lfL0mapEcHv_WZjjN~WVi>POABrb zhb7Y3%BN!tvqbX6CtY*d47ep7YwSQg-x1Wa_#aKz+q1ool$VsP_D_K~I>z5lebp#~ zXJiF`nI^8GxK(F(ht|4ECcDJv?d+|wU`B_Z}{oldOlK$TsADA)Yko&joHp64qAA;`Wd}CbFtD`%ZWeIpR+-0vy791)Z{tPiecS=n5bMI~RjlE~? z5ot%h6%0dMF7m9V8mHyiSW+EZx}_HWVwfT?2gOs@}GPwfd)$JYH z>KR#cfKk|>!i?`nFh_+h{9iSd&0f_B3@%0z|A~tlw~lEV&cxK*|A>+rJ4nbk`xKAb zB-ev$ippnsCj2=S_RroWJ(&_29;3M2-xW_`nhM{iC|~Mjh&0ZLAYD=lX(KHR#h5k;NfOP%v?=4*%fi*&>nlcW7P3qhYL`o{{Z$#lOcR zjVK=Eyx&bV)+5OJ19OsHfs0|z$mvK+%B7}6PfbWC$4e+GHFg*%8e2Ou=AC2GC47;9 zolCKzh7*J9wvbLw8=p8 zSRj^Z+llmJ?b4hG!<*KYt3^Dt$l^z=p@ehBv~7x|)Oa2ml7bi!!82|gGNCs7yLLfW ztN{B?GoB`t3~i?<$`wt>IJMH276mVK(5kL1E6XOf1%hN%MQJ9s` zlI=4duhW7|L5=bDd(waT4Yo)0DNZ-yVkjQI&$kpi|JtUV&jMC}8%g_Weat;n^Pr&| zh!3*9R&{=v9RGYzmdBvw&qW1Q&aLre(|1bLq~1f~`>ifF7MEDhDSM!9mWJplz^aij z=KbtR&%uhCK_rHU+(dIRrvPVx2LISz8E5>dYNr$k?0vkmTIn1mxF@MWrCX7@{>xy_ zsf|Ax%ig`S$DvT_BdD}YJtt$W_ZxwaI&cMgNWII+5yZVE@*-@;^v+UPa{v7irX?+OD5=%#O@tM`w9U zS%T0XWUUiixlPH5wH*a!XX3F|onXin7@<~`Sg=N&Z~i}7WSE9tB-ZWr9ByseX~EYl z%l&Ay+1$Dsfy1Ab}2FuR` z8EwiC#k!(#(?D@8Gi^NON`>x$x&Qw5OS34brF;y9$atXO?;+>9@ElaDMib6jk%fa99}G(K>j76h3+ zD|X!Ru}|J8nc;p!oo}6Oxz-F15r8Tir1pO?!f~Y58pW;-012-e9_$O0v@W(LZm&h{S_OX3n_Oa}QLPniV0ji1J#;zWjWtFyA~tuW)fh3Xp2ZRR(F_Jml^2 z{c92$_6bBfEdFw+y=oK&dj^wt^@q4`uq~UP5`knvSs63}_-(}Y7|&d>lveqjZt6e( z^0Pb-YGkO>{n=KvG_}%tlgr;Ek!Gp}%-e9~I8WDS*n67sZSWBcZV4X5Os0?q%@i7D z9X<1iFn!qXWf{u+HuFtH`-d1Va(8@R%e%juiqek~`Z@8>|1o8kmM&=8i4fv%o}md8 zeIX3Am(7siZK`$Q8uGM_q@@f>nd?a-`CelaR75Hd-Pru$GFFZD$Lq)k7PY#6ko zrzdJVM?s{wdJ;hFoBP$)^X;r^tWQ-o6?}cTdUv~%;lvY_)NP#)=@3V1Xm;Buq}(yy zry7pvlMdlh^RyshIVvmf-00bY09c?IeZOtI?nQ^Me<9bZHx@nYhb~zV64kM=4^AzK zPj1kx*#0Wpu7#as0Com0NQ`-Vk-p!~^((EXO(oSGc@U07wqoL{6slp;Ff=cao9Fvq zTINm<5NO@ZoqGqq2b!oEj8)bsu}XoPtq_$vtN3nYoH7H`yJ{DI3D11;MyO#&x#inbk&PkWD8jE z617E3yJDKQ@mB-tb-ifhV$J*(HFFReD1!%LpK>-gi)x;E5}COqrk(GM5?NM4@QseG zRui4#lu1TfFYF=#;Ys{ZB>C7Awiw@LF{6e=qQkT-^Fx#}NE&+y*5Vrh%o8X^liE4mG4quLhHp%|r4^9e+z1CxsU z-pE?Q98%_5JT*imsmm6h2>KYe%yvQ4Zxzpx;;1G*ci^>5DV8_=*n1n*zqy=YLcW2O zc_2$8lib*XfmprUib1r*r5m-Argce4(N{{NpJ%c?2)PyY8YYe_uKYzm^j(y6WaR8r z%-9Tdr6r$#NgOqq_JLiCcY(GRGx6j7F$yr}OOkg0jOj%4rR?^d0ti#y(j}@8B8~Q0 zvj;f_&N6c=`k_%5@YD`mE>5(n!u>*&*|)f8}L0~yobr3_e8M!a8c?T7L14-shB(t82?(l(k`|J`QF zU|>W3*UHie*3LQsxON!(kjfPY*g29qNK>{5W$uP7thBG6ZhQJcacd$BA`bZ;CH7O` zo>M^63vkG!c@>aCNpST8J3G*glO(u{l zK_sp@K4{K+$#iEo#~+qrP|6uo+Kv{v@Ligk?7h6-C|5W70354RqGAxd>TRy!5?G5puVLK^N7ti7E;DVnMYmjkFo=Mv07mi3gS0)c4CT^xANS zah{#U2o*o%yN;Pm<{${0RzgOi5vSzGxd&&68w{LR;zPGwVKDeq_%PH;#|9%z!h%O! zgAoGk9*ATih`rk?PJ!g!XN^?`wUf_X+DuR5SN@u zoar(hrq+1Co&W@l&^D;$NhI^;b#_ z{q0gr+xgTWoHgnW?nZ$=St1E+;+?sQJa64&?a#hD_tE~xn662VB;hy{<5|~AkVk>y zM4MAwLmM>I+#4mfCQS4h9V9n>r^rIaCTwT>pPZfIEFSak01&!|g!HolKS*VHwkS26 zC653MU$p~yjMNSp#H7OG{s#&^$(GqFPa?7>g7?f7w&w%cU4t)te?B|JVh@+E-dVSv zr1km-MkJL0emfe(J+g(g0~50#Ufwl~sX1pVR{U8kd8Ix-qH1fa zo0HO?>O;Bu1I8hWh#x&oy_oa`Ra4blfb)@>|1Uq-KB2b`Z&jfS&CDQ)AY;>?e?^ZF znfdhOEuQnnyS1w1WWK5rbnoSOH~Z+rie*i#1>y?9)dD*Q6Wg>O^xyqhJmynX#{IL@ znkx9oTl8x6c2zW;3SAkp#odO9jUKlWAp;+ScJM>p&YYZ$qOuF#5&4}pMg&x)O7zx1ufV(oN#2rkt*e z;-9WY1x@Oh6+IqDfFfeOf)y9Di6!>v<(3ILt=$(*yZG|U318@@gt*Ngw$Er@bwaGi zec08>d45c#hSKO!3+UQKAPelxL~B{u+KeZ1eJME7kO zWf)2>LO@=c%{@0NExVU&KzlwP2?sJOo%nNd_?_#h+HOIIc9$#YpBe7O+=_eJ3%(G= zqS5Cdv@0Cr&t~iPg$`D;AXGnBshH5tO?4A{`)qzm{xK8$ZZ{wK}=p~ z>BS;adsXVo*h*T2!pCfjCAYAewZ~w0wpBBu1aP`Z=EMNb3;Ef7IH(&?a4PZ6z`!P7ZEz%fQ0?Q z-aVZ{)1-hu&taKKQckmV^6aK0aRQ0anm}x!?a;A`$wmKlLz)U0+rha^KjL{DaN zc0rEr9gLzM;{3K82S55EGQo*_*Il3Ds;6ysXp_^;C_8GO%}AIYwO?KRk)OuV5<-n4 zOFX{U`<2NWU~B?#yKR8gRA8aPM5tF6(Ss|Q`D(Uq6;rTXAjeV-UkUq-@wjrMPi^Th z+pA1CDhE9(AxcIp={n*3Lv_~{njbHa2S3V?@x&n$x;Gy2sGr2zhWvz^C%!sx+t+!g zXi_D=TA17|8F^Tm=QcN*m1(|Nmd?t<{f8j3qX5R!azRUwcV^iJl_J5^$qg!c<3c@& zo|4~nC;Vl`7{w1F@nf~%g_m#mmta?WeaRXvQS0>EIR8r74Li`&Fj_b6eTGQl876-r zvuYq}02IA@mfZP!1FV0LWu%KhNr5(&@l!;wZZ*ooiKg*O3Elb2c>G=;N6(wJirfHW z55W?4TWZV?LD6TDv*j0U*RnDuxv_F@|H*tJ%s4t#HgOA(SZ(^O^oPJp!~6t|p>g2~ zb!OKnB&^%{CKfj#^-AD^|f{L8aXq3~f z!owN-nEC-E*JE7M*0pqLGG+7q%Zdkw-`YcY=8PZP;I7D=v|fNfqIM_Q#HoQblJ&qi z1PUL=RW%_oMa0bLmzD+P+rwO)vzwk^X}UanI^B0Ua$D%bH9|T}R^02nLSnZ}TnKjv zsv*zJ&UqC6w{50kr~J2l&e27Y$0Ki!L1|%uCTO{%vVKKt|Oz8jHcxrXl1cp+ptXBa5 z69Gmkuzl6K?W*bjb{u&Pq?Yg#f&(Z6R)7n)+^{9()urFsD#i#v1QY0FtyfxwU#ZQ& zr=S*(qYc1(n_pZEfk#AfUjIh&4H6>8Xz#PUHJf}<~^6sz*S6FTD@Oy z64-#x&(DQ!*Fwo81H_&lZi=d_699rhw)YMh04<1~Jtzdi175wzFuDlmA(o=kR}3v+ z-K#bqBzWZ%t+tB;6@V}RV2!@x_1cUTOyxF10qCs!BN>8L0NgdxrJoF-;xg{saFM37 z3R*S8<7mZ#{s4uHH(< zZLQY{$PNE-SYzjm+j`9pXWxlcQ+qk0{YXsF9M=N=9;X03Xz=tcxu9fnw^>*%zTv>U zyT4_+S&(P~=kqAQPAvVM}N`#L7xX`buoturn|G&s{u1l8v;MS$kkyQ#ok}=gz#56GBXS6 zzZ{`dF4sle0Hm6iwl@WXjfGQ^>OTm4{RizWD7wbJS|F*b=@Obb75wd^&_MD>nB zEkn%pfJUq$))|P2DcrdoLIuShm(O*x;jX>Mu`1h@&VN#2#vDFg!6sN~yX|$+>-ZrnW(oEiLk#V2|< zyDW$KVOqx+-WhPp@&-J5{Zh^72k3pHyklZL=uDZN&0i0!r%T^_h5u$QU_Tc$OJQ(y zcXzRS0RS`Hra$UTR2fSGK#ki&-ajh(F9VVQWKh6ip%=gis0Rc{RJERC08%{Q-u?38 zGAefQ{`qlN67dv>SG{<>gHRk1NDnS9yOZT=_$yPn3z=jb_&&hD-*nWt2v7po^P@r2 zx`L$X0x6s}tjL&b8(fAK@5DRD`KZ{Ex|q)!W7ZC1 zYx4_2$qrtfklLE|`Ezp8$+unz9?Yv^!Vc~VFJqZWo6g4T$O_j(a zeae)K;m#ghtKo&MjxHK{>|f&R(WC0ptBX3|xbi^4$o;zUmm9S(2YSuuO3{NlXTl7M za0{F7%+za4zBm6~0IiJmw+mCrYH02IeuAZ{kLw+l2qzDo^e*D47H47E-ZLJk1xl%U zumbUfXdIy+94e8{f%UTScSr#dFZwU(u-V?hy*qZT_D8nclU0BYdbNt*==nWDV<+2? zam4cSZc&bH4CFzzoWe6jW&ovPD!_X_(6qV?8IkDQ3#N7VD8({N_~d?{p-A?BXnTvO zyn-!k6L)ua5AN<7JP-nb;1CGz?(PsgI0Qln5CXy73GVLh?%Kt@|LvaipeMZ+0~Q?4 z$Ej1YYwx$7_c&ZIW~ys>O#kG;GJLQ{3|a?OIP@JkfNnPB+_&FXjnY_iavMZ?V@PoA zrX=wZxQqVd<0E({KfUPCtj~rndQ0(2Sg={>PX-6SZC@!84<|PUH9s;PkpPN@KGkQ0-+K?N&GcF53YhP`(3ZU1#Da_4Pt=%?F4XNf#bRjaP1~Q-0U=6 z3~x-Rnz$755PZYK&((P-WGG=to+gZ8wBaNAoNq1D__?|240(xGK3EJ!hH?SXlgyOx zLUH9Jz(cyWAfR-~fi6E_;jWD&i7bZ&2e24iB_IbzbDL9Un>(>7!w!+~80GROsyS@M z5MpwODs3jTX-Z$v&A9xcVFJhG*^y8X>+p2m!#=la86>~8g}TnoE!X}@;n2EbH%6mN z*VSun4ud3LRr!%s=2|X2&Hr}(X5aL9BcfQ#5Cb9vHDV`Yc%aV#f5 z8!{z59|kcoB3AMk?F|e#SrA?UT%lsJTRmK>S5jtFG zZt*q~7JlTg+_m1tn20B2WN54`53dZx*prVb%7d3ba%AMK;^&u1r-rRa%%++71HI=rGyO$03ZvqCmzi-}C+ zcA3P@ko*XjUz-8LIl`n^;Q;SG^`*}2m5+(KAK~$wP;rU|E)hdF(Y$bkA>% z1NWNW!?aD|GjkDfp_2~Tv5oi16(UxKSNwDOj#34Lj0sKwa^Wv0yCd0~&E?_dLKV+9 zmCRO2ib3t!r4f1twYH>yq5RiwMbyG$BwGZ)-0eD!XPUj-^gZ_qD-JXy067F4R>r}{ z*HFt9PL@yDBZ~{`=;%mW_5$#FcVRM+gf{{pSHbxjn}G=W?7q3rIm&?Q3?@gT-dNIC z#?iyg-hB0&RD<%g0bo<~O2T&nKPXV{%LJ!&G%m}?U`J&=sqRHozrGY;yek0T^r91DO(f|G$ACE`A zInMXxrMk7Thok#)0)Z~a$Gw-sU4?F3Z3l-!qEIKZ2t6nYO8#M{GAc? z;%Vu8ystIg$qxm6{txPqIzg0C|A-u#0k`j!xAh6cwKq)g+JN4dB^cty58_;wGTn!b z0^oq9|J$u~_S1(Ca_@lyXh$XXE0Ysk4?EWZ;NQ%2LU>j$4jVljwu}6(hqLYd$#1}7 zjRw|r5QMxEd%=Okp8KnVy~TQ8&PNbG)Ll*M)<2#P2ps*LfG7r3t>Z=$C+(qs|MI|1 zUqL&W9^2^>Ic4pJ6`!%%v%mi=!t*jXE9x3iv+sAkRPsi`!lo7()!`+q8gsgXNTO_j zbr%~HJ;~3FpiT%+XX)TK^D3=g8v{R69rlQn_sE= z_Z137kaZ>HM2LXaRWrQ}=!;Cio|2=Ifr& zl0{SIuxK4+1+otve(t}p*hx0w6xJ{HzF3|tr{SF^i2LNjvNOq_=+x@uJ@~Msv&t36 z@Rx!(Jx&l=ZoO#*f5*yVH>A}0^6!VSQgabakr$L21b@Mh9>_h-MYsr9$nVOU<gs>| zd{S9IX}9`{fQ(OmO-%|YlgEP<_s7vo#o-6n<0R_yH@}-YKz}m6)-wS3CP0i61Vp*l z&Pg519|&AICh}#Fg~_g53kwSeGX=1jkzh-hqXpxdWWGH8YTg?OE`OjyF+QikfeQZDRTS}5yF|& zPClGXH^mH_o%bAkY6R`sGZ;8YYJ5Pwk>z&w)IlI_o>!+cy`#G0h68ty zC77+TA^x1@g7?Z94TA4YNt^qjO8yD}aso{BG0?LB@=W<;x!Iw2mvQ&X^KM7%<+VG% zCM2q>s{vHR5v-x(ASQ$Wkn&!T`WghWo#oV9r*?oo%LkAl;9D679AQ%5l-C7)+7aoi3pQtYvybeorju3(VK)%l7A($GRA^s^AiYuu3u~q z>Fl|3Sv|Nei~rma8KoFzRTdOh{9JyK7bCX&K6=Wg{S}H@{l>&3@d9zB#o&1v~ zC&63?4#pGN9Ig!fimG?MJA;^PB8Gs4Bi}Sia5FPvkcxUmB ze(_@X&25y)h}1{j3xc?0#-_H!;GD}=EP^mmz9`~=h0*4Y;fgD0=jKnLbn#z*syp(P zOid8^w5Xh-RjyjZI(6rnn89GFN##J7Jr5o?Rc1q${*x<-IFb6azpxxh$IvFWVRY9H z8(Fb(=PO$vnH6BkL>=FjZ7ulLq>YoCV8^Q&)+N%RNFILeWV3!Ha%1_5ifK)*TND zz`hd%B)jg7vsKr|pc=$W%vuH}rhK=P<;%SZ`a@p4fs~(J&LF3uU8h!i0f@I?`vC2~ zaAdwe`SW!_2h?k@V+lkm0sQ*jX{i=K>Q~C-cW5PO1;Hlp_KTi5Ks|Sb-yJJ}e+A;c zrnSJ(NlHpOe93&BsR1&dP{@@T7+rn`h%P|O$zMJzuiqvrukUH$&KlTS&vY7IE3Fzf z-sp(|zlEw@Aayg+4r*T&&QkkZGqG+dWhRJ)?-#(VZtTPQH@o&k(lsi9AWeH>ToyO7 zvT|QYB(|B&oHG+yF9a&Qa<9pYIHuaOyW;4#qJ1`sKX~kz-a>E^w-qk7{Yk452TL9;Z0kJ&O8CsWtk^rl>%noP4ym8TG+<(7}oC zx@t82yoQUwxC_(aDVl58e%*2%B=H@7{b@6=A0lm<(+h_v--1&@&QQ)NR zEd$^zW%cm+3fg6x7X1$i@bf3 zx9%M?$?TImaQny^coTm{GJgY1(V)GL8tQe&4h#*Jxv_Bt6l{dPl>I`s_>8;MrdUgk zMH2O|pX7O7UpSv8-X)3PsFr0GsK?vnF3m`^xOT4>pCvYX-L$(=~%Ul{sAR2+SL{1S>6 zhfuP%Epr|Ywy5Gz5ERt4pIoBazWCn`c)Y@0qYkDLO`Hl_<}0>A#@)OE+;cu866P$0 z>zv8Gd=h1C5+uDCTm43`;E}91BrjD%n#tOBuLT%Aj8Sx)?#Vd z83Z>p{o=<)G$`=Tl)Iw;ko2!8*=6f979xH^SCHdZ#j|0&bwVd@crBucV&mBwYNFgBdWW?a)jqO5)2r|hhJn3zG=0tSbKBhf9f(W05Um`OGog#}@p0G8 zrx5#5##|Yibnk?DWHP^_L_BC9J_}cJd|S3Gf|gRdbgX>(2jM*2r8~)IANYf(Vdg1q z_NYX6YI=P6zzh~?S0v{Y)&pH;enT~Z)dThFsI)4Ehzg&i8A4{tm!NVnDBFyRutqeh zl8T;gti||o#MnnoIneZHkKN3LD*Q4V+1rE~(t8w6Vl(&P4Mixb<+4~#{kNmmGd8;e zza%IxQn3~ZSHhE?8xfC-nd03uWAnLC1K`y?(RPvdL&wVngBS8dP1O7#zoA$M?c>q} z5ieaF6F@62ccYY}qQ;goS`Z=cWICaN96T~Ht}QzOO1dHC-bKDIt8%ZU{9^RG;*GVB z+>PES=ihC2VY25vmT)hFAu##DU~!j}p77y#k2>lHqwZ>ny~dJz>hw_kNhBC)yC>y&Uihb4l| zB6r>Mp=)g0*~CmWcwz-lPKVrbeDgH;BTn>{k62jM$nlaI@Av{*%V%a`e<&8odQzRe zU=u3H^rZJ)^!6X};79RCVcAJv;Du68m-)MIkxd~`q_{L!dK?aW29=B5dq^Ik!`HgD z|Lkrk;EG>`!jZ< zmheY%^TTr5E&4g-OIQ0%W<)-IRl>>|xoIf2<3qu^0bL-Uk8oty@kN1kEl$kEG>t>) zm!uG5j3@QWJ#SO$6kE(94z8U0?9QLxi9Dn~2M$TcqSy`&%BHjD$S$zUI7=nuqUS*c zc#VlLPm2$ad}7VETFEYVaq+)jqo%g@Bd>sx@!SEbUNKi#n<`ko1o}aifi~$tgW5d* zWmEd^aS*J%b5_MfxcbU`?`LPCb`iWujav6^TcCeY?ZY~dxpUl8(P1zT$}v%mB8Q0U zhM+CWNuKBP$1Q262aYe8!!y63E#D0m#QA>7^2{-t5ew{u@ab0u4du~g_4o+DBpO8j z?Y9%d8};u)z2DgmD6$^mA0*VM^dKJ-ZZ+m7WO&9j)X~LtkoKY%ZTCxMpnqrh3sG5r zh@rFn`tSK_6`ze0cPoP>set2rT8Zy_0v4+_=eL)t?xk5P#WiV3bYJ3dXD<9bHf43a z5$+KR2~rwQH*rGrGgE^n;IDyauzAnWfqx3)Gee($j|;y(Gh2C=ZJCv`mKH!~gZ*>h zf@xSf10FBZW*4QW<-{|-ZzPN_-zn-v>b-hFVO7XFWX%FId9cctUl*u{!DY@FWGyp| z>T+MKWxFOUC~ye=@Id;Aah$6r5eg7k>^z8!(Ab{_;>u5Fo+W6KTQw{CtV7C zThyi8mW+6KB)~ zgGeUWbL`1V=oI>Fsnh%w^?$si$bmE;vw2|<9q6g(KcL2aE;{+c{EgY{LX!5NxS%aF zthJP7)FCvgufBM-j8uID!~#CC`PzWeLb$nYOZY`w9CRFIyYT4g64ofoO9@dD(k!i)%qh-s(=%!B?ebw#B{+pKRO_yX50;(XJEVg*UVNel; zPo~7KRLl&XIUW-kC+;qOg?EhIr_~6XLZnHGlgujb7-5`Uq8$ffuBC(%&DEGvq@m3x z&ii9(wfG0&N9>A`H6@6F_d6X?I~_a9W%6J1)D62_g4zw)35W=%gX}675%r>Bt_#tc z44Bd&G9&X3j^O5PS1m}c1G&4pm~o_QNFD~moczTge+$@`uH=v4xi9dN$#h3& zc*6LVAfTrFP21ANJ95hLrxQ0egDycGr;GK;T<3LW<1h`?VKBVm#)&6pdvJ6*+uW=m z)ZvxR@GqBbm}j0e@KbPIAOo?e(>n<}uv_4xLzCJ0SAwtrgKKuI^vIQnJNtuy8K!6b zgEO@9?UFnL+ND`eOuI36$vkmMs4CPk?U$*eC5GZcVAbtD^V1c#v;63^k8O3${U`_| zH`>BqCqF}WZqBy}3|~t}XYo<{$$JDc2!Es_KjOs99l~{PwP6HSMWF6&yftk#{XlQU zSSf11-l&5h9M?5aB;V-sa67R-bqJ+0>}*2B5vA@RFLbc1U2y%jc!duiTeNZ(apAjk zS~xQ~N_qkOIAS9-^!nn>KQz)hYPL8>Q!^apUnMiU)d{WDoxfmQjd*9)|qD0^*+aj zyCD2q1#vhNK>=339+xjw>Lb3HhV9!jHC{@XHQl=en?Y z1IHEPL@(<;e3oBir4^MK?=bxH-nEUU%Hy()Ssz3z4^ndNY3|?boLu;5D9z>;zrL1F z2^LmNTyi^>IAhNnry0)hXp(dJxdKrWS%NJm5`R{WLlC&x9)U}b2d*Sr1e(`j|9*g(Bi{n6&WWC2^+sPd41!`Of#F6#Zb2 zEXgP_t>@M=*JCOGaf?#NGt|p7`ML3gXWX=&l=$M}j)E_hS{?6WQxYV!g2CCcJA*8? zs&ccxi=Ym|Ac~Hb$|Yi&ers_4(XDES`_Lh@&jxRBsSs=(4hYyX43JlT!QTqK`y7X& zZ5KWWPP%sdK90+-*Z4Zt02k|r9Q%xcCVi7T^^-rgJ)Y_-E7bG(02_VNNkN=w|KVIw zL-6aIgrYJL*EdE3TC@W-vn>3?UbJm45Z>$$lyKPitR15E3aK)N@M>4PEzCW{XTdXb z<*+ZSG`TLHK8>F5p^<-Pz?!k6ZLDH>*Nz_&ayUE`qI{M#z|G%HvC5jiaIZxjAfl;< z{=uznJa63QiYxUV8zFSi9+&Aklia2ggLiXhqWz$dtAZwAgH;^%=gDO?Wd?)P%!0Af zrDsE$%u{|Ht#sT++h({$FN&Ktvkp)ZK1RuHZ&%0Sx8A7t&odjMpC8>*8Tv4O%MwK2 zF+U>~syb6un>93xrYVPz%_WM|Y7c|PxxHX&=_`V0=r zBy#T@&$d@V4$v0_)N4>Z1Qpxr@XCHH`u6_rj@fE@F#N!BRW?ZikBPgxgCa>~C2BU` zb|>FSaLKh@OTxN9j>o#;zA{9MuELIMvY`R{aHItE>KPC2^uGvd zu1P#+h1Q+sa-2pqy1}!EjofVDBt-t;buB9YG=NJi>9mdd(~$G348yp3q>?k>EtT!o z528=hv8Kyi5~zP_$KsnOH#Z@^F~p@Z;dCL*xv?hYwFMOMCwyb< zPZnIeL{UcVr&$aeXLb!PZN=2Er`N~Ba@cl*`DUtsYZYJf5`{z7X(*5T-?%X-5A$7+ zx6@9TjvwYZCHiN-IpjN1Ugw_Nvt(*#ndG%^`JNdxy8dPL?QvOuz9;o|N*dz!&s%(1 z94jYHrk$e;;88gY-mxssb>uE3@>;VtJS-Mp?%6Ztv^V}1XK9}e9Tk~|{P?E*X{pbW zdMO=ytin1?DK1r%w_vBEt%V^4@w}P7W1KqS#iI^>+?044T3h8wXSg81M8kftXHaO@ z9FNoL9h?$G(fTS^HR?nF@9poSc^t9WJQKg8YW&Y&8$L(EB6^YY zF)AXs#d61<>*&4T~dQznJ`2!!;6SQCOc#?C8KEanM!V}gNaLJunEwZ@Ky@C zXxee)z`tc`e=?ApGnkWQ{27zYGx>w)$}3v%MmI9^~%KjQl$Vq!%!@2uUqNi^9C=SaP;VX}s>{syTw=~8yLL48|;$;SnC z&qziEZ9~2^myzMi6G_L6?LQnvb@9KHKJID`TWt~DKZ~_2q=$n}d|_aJmQ+94CEZVC z1I8=vsmR%#Jz=hYF7Z4(!^0Le&g8OKcbHuWo$avPjUrg-;#2qFU|x-ZfIo0?X{jkl zYQ8!PDkRczc-NT*>`nZr0*X2S*?;vElF-*D!=_g;1yaJ-y3womF!*T#s6(EOE3&C; zYIXrzz`D~8P;Z=ZoOES@Tow-}gl#_}*%#9Fmn)W^4+yb3pHxR!nxVZ4Zlh{MhXE|fh($eaIGCxSbh2rbG z2h14wWyKKlea*=k+53?*e0#RR$nu_ffYfcV9ayny1H0r`CwgEd5KS(Y&HAZ<|2h42 zN0H|+friWX)aq|0}vzbBuiFrd%uK;Wz7N6E)o1L2U3_Rq(8=$DH##kVgx@Vvg zHTdF2vJfW`!Kq^IA>9!ZeAUlQIuhT^EhW*asNQ~RJ;u;WaW?eND~!_D`2NwWJ>})= zrj#~}c>#Pg$@l9pN43bD|Wj(^ieC~u+q(eVDdta{#K@Jo0K*ABMw#Yg}S0&Bl+y| z2j%z}R&v*fOdEG)5i=P(KXhLX4V568v2$}*_TT}{$oXmzx+9R!j@Q`eLI6Er&*V>y z`WIh6g=!5Ife>I>j*&Vb14>)v1&Pw5Jf#fmTZ8H+8Hhw|7b8(iElp)6R%a!}8(`vfu%B29# zpB4mnjJpv6^pUzW2MR>B0Q{b)#EKeIBnd=uNAychEx5GCCy@b@RW4_g;}36)b~Wu-8hmi zSfj&RbLslof|$s-2x&;~j`eS<+Ud|NH|aCKAz@_|(g&`7!#>$cI!7Pygupa;Dr)d} zu8Mxe`$Bp4sln}J7|7B#wT1LpXMELPD?;Fbp|M_Oej6D4jseOzFhXAK=^rp)gZqR* z_vzAHKAv*gsrxvOYO!6ni$q;s#lP>woEH@NaNEk-L}0vpe$YV8V{eoXH(I-Z z7!ml|JuJ)uH_6uqYw@{uNh0^$r9?tTzB@2@d7UWIfKKLvz6UL-P-xBwXyZ4)$@Z`H z9OohLe?klC^=tnXIm$D_O)neV@17*6#zFNUIi_j1vt{ z1`?<8tteX}#N^i%-iXfSWrgl5qJW*+9m6kXaSt~~pvnK(l3qlAYLN7l9jEe7WjAR7 zr4($(H_V4PXWHn74UO^1S13f=AL(+H7g^qBW;0m*{G-cEn1As`v&xJx9djlQUKVNu zi=_P?qB4}@d+HF3*asHrn{x~Az^~6JsKJ~`Ust_~SR^_;M>NT6u`HnLA<;w6w95%m z(&?VtL7|f-=r&L%-<|!l;hX1ucfK{4!56phuek?w`dYvBV`dIOh4pk=*Y1za z0&lGFxxCyn`hRjcqm^Z~4JVw?1$zY;BtBcLXtEheXBIt)gO3sX24|GcZ>)0}6^) z3wZEPMFU-~(7E61<}Gh;RRZ&OieCfnlNsX9OfLLqbgTkmLG)bX(jU+Z{z3ANUsv5% zE%%A3RAo!HopXtq>^*5q?#+wC;BP;uV`7*5nu~e#YJJ=8zzZtG-Q0u!^2GITn(^|i z+?m)>eNy5mUKWg#iVXf(r3zee%F|-a5<^@0r*bVJNEH;Km<@=aJ|^|eDc0tFTn}lR zYVqk;Z^c*a`rEFfFMc!iCIGFC++Pf{d$|mUj%6zNZL22V=qgHgoAA?pRBPKh62mtF zhq$CuyVZ_M@@Yf)wEvG)|KPyDK+h8=AV}eI-c=JOL$|FJvdHi{uK%%o4K$*c$4eQa zKKG}O7bDQ@AYgq8ye(EQAmI6eL-FtpTonfN`@jF~q_|S2kfKO*DIYW%b6Ti`@ zcCc7cq1x79{7&Czp+x;*V3MrI(4IuD>xyfbzcZqC?)6Xt7%FIuExEZAeV;`Zd0jgm zB;ZLk?R1QcD9b)}^HH%fFof^Io;cP6TP~^DtFd|TEd#4-7t8c(T1h$ch#~Mnt_@=q z{xO9_%kxTd)y@JV18Iyas|n(-jQXHL73N%9uoe@uRKZ|q>1t8>K~z+|=Yy-t&tDq^ zs}ndRo%h31HbO*1LTc?ZoH+G50d(C^Rf-K1?N8+5GcE^dA3uKE*5Xyh3w>-RG{fzh zx5FziO%=zZI9n{I_#*H&NkMD&ZzQ^`)9(g~eov{10-UTM&9kQ#EF5urrwgL}?ZglZ2r(5ZXt7rLPO5*|Y-@Xavsom&Cpl|Rb$Hgnh`!5_ zmepp}7O;!#BDhpd-~y-Ul2iHH(1P8RO(E(4h>}b}FKDU=}G^x;Z zJ6>UE`KQKlu+%B>b-uPwOmIjW6ON$|P6fW-Wg2dX4%B78{K31iP zIN2NQF@NaqfkYke=9&ar=j#&*zsqXFBXY~|8!+%Jk;EaTkU>VyxDaX!hp0K1M^nMp%Nz|OJg)RpdI2{(odNPy?>GO zg$zN*SgZ1yiuouH|9&2*(S5{y29|F)IEGzUmm9KAYCNYb*Kx8E&hTH>el>GgTlFz% zodi6Jj5<)0jAJeO!K-36s0k&0V_M+L3;RZ*4A&T7ko%y{JHyC9z+73BYsm~0G6E>X zywSi5&a{D%(QL8K!TD&OXJY6z{U$}-9`sm-?C-r==I?^rwldb{K@{_YZpWCUPj4xD zP=<}R&i|(gyoIOtbSa^YhIe!*YbmsFSZnC9S)c4?FXh4`86t^pKy!~MyG;^h!hAkX z#L?Mi2HZynnFTw<`|MWgx^l-RrFL>yzYl3P$8Bu6geZ7ZZIs2@&Xr0~WKhpR%)gN; z#8wu?KdjQMM*442dyB>7<=9ya!nB+|EvFE)1fjOEtt|<7CUJ6;#Lgp%=!f`_-7eWw z6tYzy62L#A;1W8FYn;ohes~t^&3)KMFunTB&J9D9^xpzO5T(Nx^~>Jx{$}KqV}(?v z^^g%e6AA4Hi}5bWw=71?F3g(#e3KhJ$4f!)22ih~+r-AI@o42UaVuls362(QL;qkY z5p($yLp_UPMyUKj8c+1^g?=ulbfh`{aElyGhUdj~z=4$YVJo<{LSX9VOTH3n9zW07 zGUh3iNI*ftbHj{z<2&cF%&16n-#uNeXsHyt(7JlWy1ttSXXCz(J=ml@uLtaH!YWFK z8*TS9>)i?z*M|0txcn(}adc`GubRaU-?%*EN!3Sq{-N3ij;T;iZvFoiKd@KbEX0LE zRs;4NHH#04a1u-d|45xujc23$@v%@ga+awiZB`K&|a@k zzvJe(E>q5;l={L?fNP{Qxwc%%ibS(`V`XD-{Lt*X#ZdO9R)_4Zl_5qYoY1^^Gx5|$ z9kZk^iZcG2NNye9uxy^lc(EhM$=2q;{4JnWUfEv?&9yQtgg#>L8bL7C*p?+^$Id@u z$JQ=>Dwpwz$}_SjX_)a5MVf`uE`$-;9U$L)aENU5=en{&JimE?d5GW(qSWPBZ}?B9 zPT3!;4VFZz0!}Z8$^>0@8afoBU!B{NG2tQy-^3tdG#*p9jeQlAqiG~S%D>|)D9LiD z$38lVsy>&Q=b5JL!`!rn8agxsxBHvw6%zk|mJf}_I)2b((Q9=fEi);_t>}d~Szhox zr~08qy{0Rwm72L1{P6DGwahv9I)t=syxa*cBHucnN#+u)9dk)TZ#`gPE$Y;9JSYF9 zAp7f-+?;+0)DuI|86GIExJU8788ckN!g(u-d5iokiJ)Q+fpu1U3++Fh=WE17r`tWs z&i;QtSf_f|x(Dw;tQ`8ERz<5QA_y&gPq_@2#4+p_>@@Ew<^t+dxb|vTA}pr>$hOEq z-U5d+lU&$$XYa&${zM)5Bv2e*KP_R_)7Nz#uhmA^Pn$38?0O4`_B*^BdR6C-OT~c9 zuAMAVWP3bP3e-uyQe;9KqQyGBrrt`3ZM&_r4XW(LY;(JIlv%iKA5jrH(=N%FTr-X~ z1j@Ku3*=HNDryk&sK^@q>J6V@sDuW>^krT&Kf9=5wZ!}^SnYrOCD)ja`s^;WJF>&RBZRtt1N7BtL-Reyt@5z=# z4f_dnRDM%x-k!QYOu6YVAW@VkXcy93oIMWf{*LT-wz{XjDCj z-ApgCWZvqdp>P4I{z}P~45Oyth#mZ>vu3d`F&$MId*GG&1MMkypX%5vedk3aT=e6CwV7jP^&!U0U^rs92Fd#lcHiwjE6 zq6*gT*`=U!v1H0dq$D2(_`Nz$bB&Q$u6B$Vh^;d1u2vLu*3;Wp3BY2=*81pp8S@%I z$pCd1=Y%q-f1~`)N0667sSD^;*Dn6Fc~9}UOnQ?)w&A=fW7)^>H0EzD6S|PV;FEx6 zZI7YY{*1P(a%i;8>#inlo_`fp7FeAuugxqocjZ*TZG|+>d;JS@?0;GSCaIJi%El0j zqk4?lh~S}+mKA75=$>5L!AW!8U{2B@F1DMeYy{h+-7Q3SbaX5mJ8JjJ9sSMUwhpxR ztb%f>CVenG#pYd9+&}qnyUAzY_4>xafPm@|#icv+kj{F1o4zGP6{=cXH4J?b%>(Uj z9>d)m8`IhXf!{G(U;pEN*8%}&cd>f9Z9scGMjS|{6lH)qIKy*5lM3qC8J<_6y9iRI zO;tOx{Lwwad-%hYmKs7T4cNuFX4rQ%8?pgLBW4YhF)_%ah#YixwI#CmO)?xWDx8cWwkzW6!-Nie|WF?NBSjq*C z?Eh2l$22$6Q#39-t`M|e`;aa9Q-X0MXRY+)dpl;iTy_?!ayVfeRkU9pC<0R}suveR z7hJr19P`0ellCap?x?PArDc-EDeVJ~>c0!xZ{LFuT(xX9)rE60 zqzUag+Og?E4?APNL|)Pi(i~(JH-PFRuOs>}jsydoz9eq!n3I~7bK|g7y4G0sPUP65 zN2LoTN~rYzmH{{^1eYIEKLd4XO4Pr{P#(BPhJFyX;jDZ+8&N8UidKo37NH58u!*#& z)k$go_68LyXjil98@BQ|XnI2b@@^%M={hTKX+44oF~&K&skdwFZrKon@s8PV`l#(Y zO~*NE80I4MNELCTji4v_#2lC1$J^DAqE9tzN4j!ColxPWk7dJ7BPX}2HW}AMYD>-6 ze=juH+E;?;;JE+I+#UkGpCmmt6aBz}U>~MGz>L9hDT0cFc9(9m5%ap!Ak2t*pZM^r zJhTAf%hRM`AI$$LtF;>|&sGi*S6pOO77B&32QXd0g7Irk|_=BhyA)127Y!1#K1tC-NHNU<<)(Y8=UW~!i zp$5gvDDnHf7_Z83=Tt#)Nm%!h{67yzc{8E+-Y=%elSQVWdx}6TgxQ$u{>!v!10}~Q zoNr9iG=1(jBe<}7EL@`pOnZKI?z>tgXNVKH=TI2vQ?DAi0+vxGL-JqzR|Km&@+%0{ zNe1CfB{!Iv;TkbiAqKr-^!&&^N^n7>=u`(Oru}#%G6d~tQ|KpAp@j zLh?`4ezMxna)pzc|KEBIdf;-b{#GhlY~>n3(vM~G0wps{0LU$;oP|$&7d>NsZwh=;neMOcsh{tKLro1wA-_RRK*%*5nT(q}@6!WJBr+9(%oT0wM^*P(My z?53m_+}|F5B2;Cy$A2Ngp84EzM@Q~+q1^G%+GtJq+wY!{xYow0L;>+^`FyMCaV_j{ zvAJ=%p|HnCCZyZMAhju>BHh)&k<{K>x|;-^B> z4EH7*G3r3riziKBoQ$y)E)v;d*l=MR!!4qG6+;i(ux?UbTsIa~5#)#N6>ll*bu2@~ zKe&Fcdd0ksiB&Xnkv`o`=`r^5JVYOo23J1a)rc1G{gzL zb~P7JOk}QZK$SzV7gd^7TA@A4Ec>+u3p=4Mi@_?PIbQgnSz_ozRfH^`eVm%TRY^^{0>qYrlA*s^x`0PanGP^UP z@AGGK!9nUh%O4KXsjLtrE>rKF8CbWYH)1=h+}QkHPW;Y1oArG6f9i2~yHD1jx89kj zlru}t$$d;mpBX+-j%^d5M64IrJr6F}ah2N{ zEVn+`w&*l}li*wGD&B}K@Hv<+U8oFsY-*wqN<`JIh4aYxJ=c`3@rH^2CP@RFYv0=b zoSk=GR$F&J$aS~w_p!H?TXMkM74Q?lowq)gU4L~T)>QD|LSTwn<+%<+i5?qS6tt`=17=Q@^{lvc{b^P1b_ z4eWqMd8YTdv{)~16Z-Tao#RYi(r;=E&ob z360TALakf1=2<#YF%jJo<0O+YXy^wFSGUOLE+BhHx7vA;@k1zM%qg#5%DAE>&puQV z6JaE`kQ0yd%`FYyY{+s9d5vBU-!at8VT2P;ZS97ZpQKUGe$HF{+WPe!j~9pIkRP5q zkLePA%gh#oVIKT93*Pkx$|e3U$QqhzZM0IM@fnGodGKU?s|9h}2IPJu7thc@n8BsW zA29wEOOV_i0w0Ay{K{NJmh~RgIavuggV(o*_9lx^H}0s7+|cRYH(4&BA0 z?U@2OaAW^BeE4n>5=y;ngCq28eE1)1Swrsb>X4BFgI)YV9|_gc94+(l60EkAS~+*r zvYEyB>w7Sq^?%WHmQhs(TLY%MyBh(eq`O;*11JsB-QC?SDAJ8|cXxMp_o0!l@8#b6 z{a`H@95~3#JG1x9-p@ngyQrV$-i-*%iqp3TmocJtt(p+MSTgyQ-%RE!)wI-4|FTUR zY(`&2W?Jf;ovk+NBBNL8A`>;>O-@WNR(vB7jpyx*7S;z~M8&f>!yWlpm)I;vr1y&t)#c?OdEgKdQ>=&ytIQ z5(UOa!=YS~IMn%!#00THH_{Kjx8ni=#mBEb=Zvx;LB{H|^fD50epCnnei43I+nTki zQ;&}M%#BoKc$3A2&PAFfIS6Odn(_7YwT((@g$9x(0fnUz`q)rL$uu?3ulK8|$u#Uk zqedT))9&1_zMAYao1QtG@n)XmwPz+lbI;k~XGd+ed4vB>c3DdlyG`r{KE3sid9o8wQbh%O~^<>MxwZp?4&S}qndAxtd>=-l48 zxG>^XU~lrpc0r+%N;7@?&n&IiXpuq>c~?(L^g(p&3D7GI70;uo3E~I!)|O%0MLD(& zHcn=w<0gwA_*0`-8q_ojJpU^EJ6t9Fn`H0_7^2`22Cc!1XD>D?AHC4|vZX3hMLwVMuF1`> z$!x*ciURRKX%plHz-YPzE_g10;xv1JCd%mmMuF>j?OcAESN;xyqZ?@Ij+N0q*Ioz+ z3EBO+$&omIjhUir@#kSMmU(@objj|M9kjjTpPAvyL#QyPgIlVJ8`#+rwj&9epHK03 zZd6fXVx1yb*X7rgRafkr6@?@26OT4RSb|y-jJ||*#5O__8jc@wA7NNNOyc#t4v8P) z370M(tiUPl`25PY5Ge|&@>1hLiY3-(vZ3Bk%E;rd zy9PQatC1eoJ1bU(;BBVKMg|)P5bf03p?~5byYR$g$&Q8qN=4=g(=1Jn%KAe;?N|C$M zG^D$d0VNc%%{D#@<)c8<0M$hy3?K}A=S#PSd|!}#DU^~^+vQ!jVl2Abx+*Iwe~8Zc zj{`7_cb?CC?JafP;1AXlTNq7P1mj+=*M%Q&4nxDmmZIX~SKOOwBDOzZQd&51(J#TE zmJExNki0-2nMoTY_?5_yY1YyAqxhFPKi!l-1GHC=8v8tf?ynOYScB1Pft_3LjzMk7K&GtFKhMq@Ma z>&=b7Psb$}YS8olv2hrZNs>-=7L&jEheT1O`e!`j=SpakYh;>gRYxt zxZhSP{kyjf#Ii9eyq`bAwzzz|)YfY;M%F?`Mhq6idGLC+esEY;?^Aqo0f)>S8FgLl zoiP0xbL?x_xZ37Fue4vOPpqo}o~zRPTP+t{Tuh|k`<1J`=bJ!u3keKeCUg@{V{<$Bg74>_0jcdWs{fdOsmy;)T9~N1vFBEwF>gk{r&IEwyY=MG`H>W zZ?DS@wiCdWHqZVaL!uUQxIlej%E^y@hOSUGK~O}~q$3z~TJadWq729>0rQsFA~Cw* z9s=CRTv>!3z=dXNWuz1Hks{?atwU;^M#wSsY)?r$gz;|;sOQjL(#?fzC&tj6&ZK3S zi{nyh%5&=+uLUAWaleT4jA$#;x+)@ff{kAy#3(me$(9}?h<|CSGk?0vaGXkwJ>o57 z3kA?rs=RO@kc4nw9HrAdL}MC3K$k$7dL@GkZjh*~f?blLmllvnWRk3u;) z!39f0nF`(3b^}<`4M%idGW0;t+ucGkL9;n3lGaA!1?KW}!Bmun)VBP5l!=LhoT*$$ zo?>bA;g261@8;B!+l&yct7|UzcUg~i6L<%&e1u>3QYx%u!Cznn;dGLbgm&qJacw>m z6xWU`Bx!9&)buvpRc3sAfX*oB;K*?Guvle^{&&@fpO6{v>(m0(eH#DXN6YMW7KsQ&;WQU@V0*k*KeA$q{z=%@ZT# zuB_Di5^hHZeB&==ElF+9%sThzOT~w9gf!TSqM=3=>_d+ArYD{8OIBUSE2xcCnD!Fm z--Hr<%YcOeRYo&1s6JH|)b1HxiEt^1RM3R@M``5N1WH&M%1qFrm1tWZp?J`hVfcIo zg+b)#*9d~NcBzEeJjZSq*^oyT^;J+Alb9h{b0!xR`u$uTqorAf6=j+zOLptJtRt@e zHRWJ6GMl&!>~~I?Pbtt$lQo7Ia+ir1LWwndL^$Kyk_JzogP`G*C5VlP%ppg^?^hKh zbi!c9yMiV>PSWt<#4Ti#8(+Jlx##asUL#q`pEnYchhFgYMy(IhLsvc$5G5}gP0P}K zKFUkDfQLE(Fawg`@pv^fevR;uqJ;oOak1tziz=FO6d0W=)yBVC_rV7e>js=nJ1o9M zm&rX_o1M3(O}o9=pM+b0rFEy+e&^y>lG@UM^WRKe!xv=f=;Eu_r@w|tG!8r@|BjY_ z;oCI&10xA1vtYq&>6M})FPkW4AXv12EWQLbCbvg?}v zLHxZ>{EdbVTt1@AvlqKR7s1awc)mqyv-)km&h*Y6`n8e#LzhR0HRL2ojaMh5d)}Xm zIqqa~6|*UcV0&P9B|nsqW=Jr`zf|zWNk%t*I`_lEvaS?rs3C2QEKZNgSqlA`7sfD8 zE}~p+RgdY3!8a<5IZpYFxQV`!Vw#O4c)@=I%9VO&{hYe}$-C~`xwyCT7aRtCRt_B0 z{U#d~H6f>l5y=6rDJat5o~^>KxC!*3PURZrqmZ?+^hy>9>AxghzI*)q%SVFdAdn#! zduz4h)x&(oY9 z)RNrk#b<6teTC}xDZAW)NbZxgBTF(16E$SMN`@ll+k(ns{x`&Sl4JeiofPwXo5K}x+CapE~p72Sk8U& z$EWpP^oRMYk-|BwRs87G`RwOo$bXEh2&+-YA&aBpQtdH=8H6lk9N*brVktFZ{7Tn{gHlL$zS3LiOeiarfzO4@K^qhTytVF*g zkVF3Mq}ml)czmb?e)I4BtGu$a&sRE9G8NaFd$VqQ`Vl5kO{*S4a9xc`Wf+=XP*Z2s zKZF#`a&4XdC8`U91@-&n?0;uNc9Dv`9BiL=B!eeqm+XS_S0{UH6VfZ)*zbm5x6QAK zWxMx04R@bZ6C9y0gzWe~=G@5F?d?;FZW+r2&5=td3`&^(8#xds{q%2_`!nH@jB8daIGhcF0J@gW*&K_D3h_vsg80E^ zzHdhcM_zT4n?{ED7-L-w7uphi-{wjn3WhO`;D&lQKmCMh51NaT-&y6OkhM%4Z0Fuo zM>Xx4#Pko^P@Q>qOtuo~mZcc@$K2H)`9av`rhZE2}?aqEC=DdYnv+ zlWr!?pSwrBfE&I%qCE+6MjamT#&noumhOIJv{3xAUdjtKW}-)RVju|7bTU!B?poEZ z7i02IXgAGrcc4AtP)!)d9%-?f8=X?`vqdEnMosT*4l1XGtdd$Z8{f=QaSIk(?pY$s0{|s zGN%9TC@ z%wqK41!ockfrOX>{KTl8)Iu*y&k~i*pyD^}FZKQAD7JPTj~?e+%kbY~cA2d>%}9%r~x>Jzt5GFv>Bb ztmMb+&c5i?-#8bjj|`dFKFqlN-IA)mBvHrWN|Y8yEBtFLd~_mE5{l05iVZx=h5fhP zaxNLzqT9p7%J}-#Z8io1l>_Hi3hPicoPDtes&zNLaGHK=3{>Mqg0wOvk`~Crbn%;+ z*zUa}(1 z)xOYuuRwp#(us1Z?nhU%D`z%`0)VaVD?sGNB2G5U)kp8`4=q0;4IvG!n46Y0qx2ga z-C>Xq8Fk$jE<+Uh<|Srs(6~zQf;?}~x=!c~U%3bwp|C4hXQ6KXuEt~hO0ay7lo#4`D_}NW+Q>yS2K%R z^&E#@5$k)LE2cuV-iktC_-S`&?Nj}r)Eg+#7-{liOU!5{$c{#>RP2h5>e3tULXpGe zlQh|hEd|TNa(P^-Qdrxdk~fn_L3>P8+yDjqi%hFbP=(DCxd{_7SX(_(0x7|LK#Nk`LXL-6Lcp>KNuiuB;w}WUsHkK;C$*kY4l$%A`v2Ac7U# zPO6gmy&S@b^gw5_6#rXk2DURX_AJoh51mM*7No`huLWSlJTl_E;Um=3s92LxpiB3w z-Wio|M+EW0>ujWkO-S7n@;#sDHcvxdFMX-wY_#HwDIJ>8!1?LBlrhL3<;jg9K!P#zYlvt9Xi9)9~mcF8OKp z(dw7g!-5_th~R}_y#g{`Nc}UFCNl<>C*)-+b*;+y5u-mlOl2cwRqY{Jrh9SJKBA@f zH2C!(AP>!vbH0FvQwQQOyMsfl&o!UC$om|6yOIBiSCKE|wpg_|kA9$l?qvRF)rk4P zv#SM06UEFX_V4(%Vq@)^iO*YHDxteyL9yletL|k3qulbJD^7(&{LM>a%bk3d8-#!MN+ti;{_Fg<`lUc|px-KA_$V-5~C0g=UOXQKbrmBa#i z`xQG)eo$cHI8OGCL|fSJxRe_kNEaybT*5=3Ik8zi^H;V-xY|!`F~`(!v+uY}d*!FEwH)E6WazffkQt9m z+OH-KIYF`i2s8_*>|d0((K|ms%oF?7ARK)1EAIbm5`m5=2`5h520E)Dc)3N|#eFu= zba_Rd-O>wyGlm^RcXLWKrpBI$5~2L&E4hF95((|^s$5s42>N?rLNc;X?Rvz4o5dg@ z#A2E?*abCvx}QsOQh)pAd-(ClqOGAVH%SxRsC0UhM*q~vf@83AwzjIJ+N*#Q?LrU{ zVik;qtrH$}PImY}5`H@DST+}OM!&ZC?GUsj0trc;eQ6e4w^~Qfv_M7U)KL9{Eg`w_zEdRTnB7JyuP9{#9np(AQQldd8sbDFrV5!wicImIr$IYsfY;V|OoHfZ6c zx9JTR=$a7i58hEy?bHZ@#y{D3%&40oD3;yyY8T4IBdKaT+eEC3j{#+P^5UfeL z@nPi;R_!t?{yjSz$>Nd!$<9Bb2&2KeTeUEcXyIJ4-ryV!?5?PX_ud~MHah-7iG?O? zeG)=o(G&QA-a0PhDdgtC(rmH=>ZqA%a@|RWuTjH>~I<5L%|uB3ui6 z*S^cuMRDwFrbUKW!r=?si;_ye%bHdUADnBi=~$wndCvADgzAd^o0Ei%_PFS`9>btr z6v>H+e@5#qD6&>bl)`&`68Q7hR&RR~@vYn+n93}U)1qKT5(Nho;B6%3jI9^HA4RC1 zHhxgVVtz3A+m4v6NzFwa|F;Q0e1Jcm6oK3WJ6MW=u7hbLHM+ zk3vSLEX0WOw?)>`{R8#hOE$So#r$OpnDe&lD68MT_s{70jwSm;45&W|z_{m|YMwf% zcWe+=3IDy(dJXBnC)Zec`84cnyV7(DZllfA`bPezq+v`*KiHN>R!(X813X&=?AZkclMaMvYWW51ypDffO$4ik5#+epG$@$YwRbx3m+# zjOdV{fE`)(p_WRUzYYSi5?rdY;=a_7i^ZxYUHXQHWo2FEP9*ox0PDQ<=E%b%fRVMj zwHdBd$hNX7qH6Hrsu4{}ZIzAYwLLVa|4j0sJu(jA74Hf~7%lt^pStS~HqoRn#)BVG zPz=H+SmMf3=`=!r5c!p&WUW4Z>J~?MXgPLFz;Xj0%2&eNG$UHwG{%|agXX{$|8AVY z3J~rZ?k1HPdJ;c_+Yk<~#5||&*1d7I#~+fu&Zl7-1)LztRfNDZDia3aV7XnefrDBDJgXa%M&bW7iA3cU%i_(dA2_cTha>`@sdlSuBKMyrX893^r>u&g z5RWY5h!;N4q^JoWI)bRyvx7|i(&Hs_Gu)>v^Mx`l-7$`lZ3{SLt&h!yUBX|m&^@HQ z0?OZ*2U})hyA4o^`pOSYu{ODQUn8e&SH+IO@`wFUvVVeSUoZYdVQC8lJlmc_D^v+p zFy%4eN8{kdF~2>9?Ecu@c{BdVZShx=I2z{G%v_HzyOlWWvltO!L~H+PErm|pfD3am zyS1m=9aZz)s|8H~c}R+;9~MTFl2Ps_90S1HQM#HB*#-Es1pJDH%lr=2c6;cpWk1n0 z;%Aji`B(`Uy?i^6PjoOr!pb;h>Mr2C9-t>{nsqAI#aXnOdN~Ce}PzHS0dgfs7MbY^yIr+J+ zHI3^~0XF}$W-wV%eI**!88Pxty#cCyt2K3Z37n zLay0SrDQpZIY?z4$%TtYJDtLDGe^<$Y`!v{pYAa6vU;<0XMNkkwY#qhQ_ftSDjyZcg9d`}8l5Tz#b4C3(=nl6R%LrRKMDtIYa{$b+qJnW7i@aVU1x{e>KN`0zz_)Dc6@_{uU7EgxzL(f}0~;85M+>^o3 zmF4i|9_>~%2L!F+SFt33Q{(c-jxOz7>3id>WnvAtzVD)ax3GQ_#YwVSJm)>k3OodQ+Q(R~;xSGB+`KaG z@@b^r;)~kbe+IgsomtER86V z)0Cdmo=`v2I~0|V!yk6J@aS*M_TR>r3CA}KbSSr7Hh?nP#0|Xkur7U5#37R?;~yLn zvD+YczX$}B58TeCuUp_%zvuQb8@7K`a_r?zI127l< zvn87~lSFQVkF{neFv!X1TS}sGd?dpwQbP^C*eW>ZqM*uCUf8Ni6tiyERMDq3KEMb3 zO>R+wnm7)YAcxhZV`QE0li&!H$0I-HH*9j27yng-)fH&6?X9Fd-6S)^i=!eig+WZd zwe5{DF6(VaU2E){4O>ubD_)aSIpc=14}@p`Sc~#8XlLjlZ!r`ONh6c|GbukU)XbZD z`(c+bEs#Dizo9&^R7h|;0v%ceM-RkfO|81x0S@V_qyyEc&nK($bN@(VK@II4eICxa zXP(rPgBifVV#XO?zKCYr?OmER&}Pwr>;JQ{`$9A zs4}Cs&F0qgBoV(!Mu|L-iof;qLgDb&ZbXq8QL-y~1sHORg^lvQ|QtH#pt>qN72SpGLB3JDn)Z}}l%D6WzNp;>1W>}uY6tOpZ3sBx?&Q)@YVA~A%I z8sfAmT4Y9DhPeZ(t8D8%r)q$ZZ%$|=-RUk@{*B;HPu#ghZ;DZvGY_#TIqGd3Htx22 zXklspMF}Zdi>OTUNyx=2q|b@5!b;QJXu$)4L$#yVZ^ zL6I4CS-U&<0>cbPRC)ew2Z9cqHKd}t)DPg-=Z{<6c`g~Z6aeyb(KRP(jYV^VNu-cEP%4@J7z8!14&LM>2r_F5j!1Tfrxj*9ko2Q>aq88cao1ban$|qmeI7F+;^#jU-fiC;{u1TI<3R)9^AxSz$Xd5cV z0?&9#7s@e>RLf@V2ofxm5Wc2xJ82u?G#@Co(l>4j+k4;y;g!y)E;;6^j(kZ8RUWy% zIo^R^4^p{uqTD!{GYH)gnhhmc?srb2?*@hs%|ajSA<{jhitm6D_WSI5|62hHFd`#8 zppniHAbkMX3d*9JH5+cAv$+6Zh8J1?>H1-ofdY*t21*LYOI%5ELu;)0eSQE{GP%i4 zp6_pEw&enW6=MRpmPXnJuWNZP9orgjo3Zp3LQUvY%paw46XIF`E|x-!2-N})4bAUt zr3;<9vROYIiY@_N@?VVLI(|D^ho_pS9crb~`$@if{S8;GvV{zp242o_E&`&^co}u! zu-)DZkSeE{P}o`UjCn@LVZpcrhmCA)K|r=>B{|@zs}uC!WvZ^{_$}Xty zGykL^^XE-q$omxjYu+vI`VxJxH}sBFk?r$jTpmsO#lA#0RP*=?TYQE4n2Uutpe0jZFc&< zH`oH+xC_9~rlhJ0(}~Kx+F7@tI|B5bzw6zkN$g<&1)U*)yM_Q}XduAnPI;f#Ku@mS z{Z=Tu`;}2U&~7{Y((!cG@-A-scRUyQ{>ANZIyTdB5BLC?&*A1_U|RhS!-qgJ7t z=5;m1s6!M(DFBoRGy>lScrQ$Ofd4Bm(3ks%(-IGG4asHzp)N#W#Ix0IykOkRf@2A^ z9E(yqbx{h$WUK(KsnSfF5tUq>oe0q~cc;b1%^)%(=9C+a9mkk7&jkeGCcO)d+T<*} zw%N-@qTs@HoQRRb6w$Oimon&CM)H#Kpu_EwN|b%+X(*EF$q>;>XttpZ`{1@ZerLM_ zR9tQ&!%C{}EgaYUG>BbD(ehqR^gA3PbuEqc)ZwtN; zkQ^jmiAVg0>b&%1a!K0J3jL1YX3L0Cim1Yua<6l%1GJ#I< z0|tWK>%)PHuCBsHyEpIkDErZR8$SRMFns)X^iH5EQu$jAXl?)%-xt7z^8jE<5Q4?t z1*u;5`d-WhdwY8Vz(ja|rSI!?rqjt{JRky$_`=+j=RlY_F%X7H{jMr82h;%Ig^G6< zQ!W5%es6ULhAMWeC-i!VF7x6#^DPYk3~W0z*|j(?0e#k!fW3#zZ4(msC3=A7S2tjC zxC6g>BZRR{`Ux0Y>NAHWH^2efL*fIfI>X{mATY?uqU2&G|w5fbY=9hcZq@k|uVDCYIJ zb1vpzbo1Y!I!Nu%%G}HPd0UZV=$I~qW*p3c`5ZHwI$|rX`&*B4V!X(V3x`FA`t@%5 zpW{djbiL?&o5qlPIX8E?7;gIanSWT)`;^c#42PPw?T!mC*iX6*p>hjaKqc1t`sL5i z$JQyDBz|7>{0sH3CwvIlWee_~+bhN~=UpnK`yzc67K6)ZvHnpJhGdw}OgVdTUIC@5 zZF+u~S1Ek;^gc*-Ob+VuiNZ?k_&3T%QRWse=j{?X40PYAsgo(~9YBxWJpJcF%1i(| ztEv4t2+3RkC|O&!QFyUp2Mz$t^S+~He{{n6>!JsgjDU=eXuFQ3cG_Ti zG9W+1?RWGhr@=wG1f~xg@O-}G9RS!1KzG`!U$HS9`blfG*8D3FUFc7h;lNLztXftU zQA0xmg_I8`QxQEM0RJQ^(f7WSWPnw~901ZtlRD!79zAt!YkB|%bhg?gaM1}(V%G`D zldj-#donZ_PyH$BXr+P0G|e8aOta1apx)G4ulxpn{QE?NU}Iw&931RCbxBB04j(yT#V=o*YIDmp^r2<%PA8uG$Mi#DDY}oLTn&(E%6>u*ff08)U`WuxL!h!lEojH zWhjzl84K7%*(~Q7@tCz`=yAGtE-L|KNC>*xb_qZy!bS=n9Fw>C4iLGPYR$19 z9;y=7tQRZ&3E5354f>D(Dn|6k-n%Q|otI&MY6xJ--bp0y+%Etg<>273*yKp}?q~#@ zx%s|tukSBgb=~kD{qs2xu!FDxNQiOaH!lUj8`X~=Ki&hFFiRJ# zPFAylaohjOd3E+l+F&{IgnYeN8j==Bv+cJy|E(xeoqz=J-Fh{JAWr<1-Y_6EkgE%M zD#WD10lg)I)ru+&fuR339XU(=wk6F$Q^X7)$Hjx)A@t8NA9?x*%k4zmB>L>=jV(2;7ERX&S2%1YKEssgmoKxn|2NbdU_ z-`d(*IPx_^Ao-n(1xPifs*S%uyk`s5)zu%9>|54=s7H(vQMT(x93V4F0fGls-&e2q zphiVeP!b4gAk=});k@Hb2m-LcP320nd;BvS9v)t7w5R^^n{f+J8_{AQu)1CRKofqp zdpE-YV%c;GW?-4=*w9-F5uxae!2R@I=!PZ49O51KC7#|YBEE0JgCol!%f1Ld+{@5U znTGFcjt`Zoqdu*J6EAcyi)UQtJvNqETPO0Nx`4mLodDQYFfmgVtxqOPw(jncE0JZ2 z?0H=!h`A$;oQ;?wIos`BIHdYBmqD_CcBWMGBrm?9wuct!c2Vz~7HW}RqJiO>3<=;C0BUhWp84WoZ2 zEFwo0C$sFqg}0Jrqa7O$*Yv7POEAtHr7j#;$#iHvdH8&3Z={r=O^`7eMR#?s1z*bYgpK} zZq}v|C2{keUhXP5?0h_T>ew0=!^a4SMtbvtm*9bMN^_c)eUBra0Y_ty7$pF-alhz- zCj=y_01&I^{4OCiHFBY3ss}KisW;l`8;i~Wkt*=mx}DZ7AizMKtTrV8xVb1G@#&ol z86EvP&Ie{ZYrR$gUV;D@SgKhE4AXa2=J&|v-Q_o$2)Ja(y?X)Qm9oYp&SsoAnm!PU zzP~#R6eOS{BGvVIFot;c5eDA=T?7yDP9>C##Jk)}(t{eV5VBntsJB`Y19pWrkDKlL zome_n-0K1o$U10&Efiqr zUJrkoyXGOd)q11`jbjMwa$LG2geSKk9DF+q>+iSa&;%1@CPQjcj?@m3n z)~zjuK=zVm*NrFuqz*8FU5(4X zfBotMTvQis0wg~7TO@!W`(3H`ZNB5EAhmHPh94+LrU51t$Ghj6S}LmWp81P03m8Z z;2Py!vIPfCL5Z5<+2p2VR&?oCG%R`87$p|4tedFlMSNwF+4Tz2?+R)${Yk zx;=(>_rI%oov6}HQg#-3^tTO1V*<6E{Pu#MtwGg-+2&m3mmBP7c!^A(I-QM{oRT z7jp=$M6M3C>ZeRD;Q%ie55k{8jEq%3^+40%p1Z~&PT_(E!C-ZoA1*`SPRdKU-Y42k zO-X3PDmPda87D&`TKVE1(`D4Hue@9!Y{JjFCTV28z=dCQ)GjNv^{<)b^_@t?OZUrc zI1Nco;g2Y#)T_kXv-w4&_8Tr{DEu>MKhFuvBvzSH5~tmX7o}b^&qtAEhvQ*3)&hs~ zZNjV6_uad#c{pd+vd*M1TS@$XEda6G+mK3Fh>m%>4Q`gH9vPoRd@Dk&j^qp>D^P7b zkQZ#;zv}z;^8Nwp7y(Smt{qRL@9FK+?I|$9VoFO(hYhlz;n8-1@HY$4nu}0~03N=N zf`gEN5E3|zFad}^KxQ2JgH;9?)=vxY@AJyygqxZ=w_3?OmCM=<(B{4)Gl9_g-9q|{ z!2+T`hI9nL;Vl7XwdCYvfXdoDe8+W==_~XuU;#{6My94}^)-Ou>iII(H?Ob|A#*|+ z=ySbvEAGb^1m+yD*a7f71_p*~fDHNmVjm#y^CSb9dS`8Sx&U}j0f?&Xn~LvVS-l^f z-jC_LfHI1mABz*_`fX%i<&nLFuyCXeM|a{E8~!j&o{4OCizV{?;QUC&h2f4_me(Yy z*)Prf7`=jk9C@HoK|Ez2QEMs`oMxm8J?lv zeZ|kwI6>HK3o}*_rOL8aJw$H}A0NU{Jv}0q;d#aZfB=wZlHSXBG+b-`t!xM1ECUk` z&4UC~Z)}Kz%S#mFv&*9FHkRr8leBNg6#n{G&OD~YQrS6}r*#{Hi?qNzAnj z)nZ%i!{eka$T~ITxw~BlxveJykleXYg}#y<-U4h!f-x2wb@i|HkQ=!>s?x+L(GsSK zSk@o6s#edZ*dJv&^ z9dw*$b^%)c26&x=pN}Nrb(dsUP<9Y+p^OzBRPC%2{rU21k$E9>ldETc!zR)uddBav z^F9@%)adJVyOp2s7#SH&=6}H#AX8Ko1=PyZKt}zs+k-~oFLuSk7r;$sQR+KL89IAE zGBT12M9ANMkBpAy0Sh50*wGIN)VFRt41LhAg6=%pKr6rz;uoL+PDxz7!5(O`v;~|n zIxXKZ=SvzcJE75|K9&OI#-`GOXmHROhm%!-5_hIb@r$bZ_?u4+H$Ko8 z&Une;L!3*Z5k|RF$OCIF|x585NH-TKF$KUWN24H9{v;Pb2qLt69IgS z8HuQyfId70zq3ENBq>SghZdc)|0y&4nY#0w&t9rfm*=8XFAXbS*L~gq*CY6f8cvX5bSJ`4^{nzdRug zGQG?T5MMJnJ_$e1_TRfrwEpZK)e5S>CUubvi+>Z*PIix8ohtoQNs+ zAwoQAnJT>0+H`YjyAfH~$4LB0$%fBA@2~;&27Q(7rNj$F#qgGKe=Ek+!8aee7kn5} zSXe~hQsKU&#z$V&zp4VATE}jPe<4$XEX+y1HVU&u)GL#sNC!AI|50dEkPyJZ@cHej z^n_Nqt|*yteEago0(Pdp`dY7IvX|5DOg5zw3@F3Fpbb^O@=Nron$wNKiW}vpduH@+ zw$D7nu3Adu%WT80bA&Nf4}Cq3s-$W(IWCJK>rS`4PguUsc! z5#L^I4-N zySZ@>PRJKUUw_`g6RoS9Y0_NO(P&H5Vx)H%(;sh6(9g-`Z55-l<)DZp?27xT#ZkO{ zY%ag03Jg1y)%~gt!6F4h0>@KUH6zc8&wEIlX?5X=%Av7LwVl>3AJ?^az#|^H_?&RZ zV|GTCCnL+YR~mPdh|UpDVc<`31h)^y+p-VkPy7iH0L}D09Hx}?I0`KG4^Qn;rmcTO ze<_$KyMxbqI#qS*Ahq&-#bLu)qVh2{V$_svG;_+U8k(#n2#u18f0;0*j{uv4y{+Mh zTK4DxvbRJQ!k}Z@F6!c^iq=Tu0*Vc`#E%^1jw&|H-p7aFaD& zbMW-@k{ho7!*diF%Sn%O`!1;FAm-L}NBL~a z{k4tM$M;huB->qQOH-wjd?TvPWMKtKIQiILDW&I9DXLo%8V{e~-lDzvyP3E{!T91L zP8+BJCbZ?&g^)GVli%=F&`17RRY0*D`3AaF&g27qz@~-ehKdr>&=cZ>)`_JX{T5CV zJQd3hLr_~iwPd}qOd*qm!Gl}khb>_l)rh|6!N6CaWBakbAwpHAWli#OsgNLlhGks= z62G%wYi2eNd=XGX5&_OaauW%`65}&doHr21JWj`qsm}ZzQ<$RhAPtG4?I#=sr|1lV zDs8-o!s*(~8prE#)-tKl!zI8n#D=A-&WK%)Alp&I5YS6R%`(g&w#N{kpA-g5I zFxD{WxrR4zI(eN;kJI*Op9bBf2e*{gq;bxj)0%Uho3`a$q*+_dye%Lw(MPitJ|!U=|DGVI|Zxm6vQ-YJ7jT&!EwlHWD^ z`Uw^betKhf5CCd#`5Am6N2y)!%?HL+`opaL%h2?x>iw7CuAFK7x*y(1I z;UGHU)Rk~Y#%I-k>c7K_VGC6_-BX=|`ku3K!}YDtS*gmLzw;0m>`XH4Z<1rk-faPf zJ`{3qy>%hL+7#mODLQ9rLQN-sTCM|&ulfrt9AL&Y$|l10vh0$DXZ%HnV4;E!>Y&VR zysXEAEi4EHeD~vub}tNOUWUCl%|ns{%Upa+A}=~=;~2rJOdyc(GF9x)6(IH49h5c+ zoTY7*h0mSLE$ljuLci`(3!XG*f`JnO`Tn`5AJqzt(P+gDMGYy4mPIxM+5zxv8dAvw zJy;!fWu#(AhU^DO2LO)hdpU{)QzNpBOl1?Ed@Ws0?MHm*yPrr4C>$yBIuypZa1iWq zi=MC_&6==YLMoKZtc}$F{W7C+!1`#%OMqz75+{8uK3Bit&Cc`X$B^vB8bhJSfek`E z++A<6Sf01QT}~|@dgb|NlrhF}@d0ESHz^MuDMN@j#BnTe3Zn#>H2_k)gbsJV+s`3V zs=ssRx)RWdgaLMT;&tYIZj5_DzKzH^yx~%7i7zWvL^@9slpycqn};4VEIe?-a>fST z&vls%0jE}G*{NHgIp*AP6Q5z(#5o4OU25AA+36ewfMPSSeRYqg7ev!Bg>+&urpzX_ z6oi*EWDmJ$;(=P*h(ufvpcm0iInTLng-m}!2bJIWYWc=DP3eg*Ony)e>_+wf?QaK~ zJ33sB6}UYuJH3+tA-iUI_C}YF6(N$91QGgOA<__eT;SuxRFSLrWq51Q6Xmc+_yA%d z-JB!BV{x)e_uKv4r`(u4%wAyy0u<@C zSp}ugm6BdO65TXrVMQHb=;NZRQsSbv1^&fAu1~d4|2!ku8UA?XTnh7tY4$<1XszVk zOeR8X(}L1n)r8~@Il9L@N2tt9|GudiBbIrm48^b=gU9f^uZ2-&>9;!OIaU;LGD!I+ zs9|c4vWMEwIO^^=tIo6n-oj3+Xg%L^5w9Xqmwxi`K%xe9Nb48QJtpbxgRNup(3=9@AQ3cLF%~_9Sd>Zt;iHnRc@Sgl4x! z(iDrZ*T1vqgOUd!>fuOth|A7TFCIE1md?M-ze2Q21Wc(roz=wAzcKPnbcikNfBgYv zCumeYN>f9jGVp9>$q!waEJy#-vh371L>Yq=&#)=63R}KX4y?|Mh2D(WJT*%We! z!NcKtFpBB|Wi}VKcrm@mM9J2Bx}#gHE6$Sb=q(_ZUB|I3hgmA!Q?K5=L+?~ED+M8G zHzol$r*oLxhIteImIrC6%%Oi3|M^wGY5fs`x=8C^dRQ6{U(V-Bh9(fVHOOd%dA0(T zI$MC6%;>M&7`Ef*i;YC9A|EgFHZJQ(HOON*BF4>p9{jTuxN+^pIoNU!7>9a_NN4=* zPkd7trJ~T|(D4W1(SlWkVWn~fHJlOy{}K5?@Q}pFq2K)PgtpT2&IY)1!5SvUI8aAdZ zcVCIFyw^0s_Z0BPg1itggjkA7E&iE0Agle8-Z!@xyFG)>md+JGtXGiCyR>B}i#eWp zsQJ=Yds=Sx2^>c&CnSEs9Farvjk89qri0dJSpE3bY-s1HA>8Z=?)?sea_?82pjv0c zgqqnkZfI~VrcCRkMwUyRep|i^y;r<4pc?I(kTQ1JwO_VkV*lgm7c(cx9V!1?jufJZ zg}(7ECrTW#{M4@IjvHJL^*dRwOz?h*(8QO&KbTy7Is+<;egs#&cVQ5xEwkITxffv0wCkA>5&>;#y(Bug+DPBz} z)%vp4<50~RNX=a6ZUnWf#sUU`*%4a&=H$7Q@z3`vxVN$E8@@EUtDh7ob(A=FYgqB( z`2D$*IOVVGlIv!Ji04^2-2WntK@PSyY=i(4`!`{K|Bbkf^I!S-fe2kBei9+K>k|VC z8S-{OFw-QXI}oPTa@6SPk4Y#3C(+Iugys@R0Yw&ei;#xr8;YtleU7R@EECE%M5fm@ zxKbMqx%}R@XPc$@_PAwvM>yMfs^OI}XHa%3rhXBB`^~=K$t%Nf?rwz#63wN*<@Bg3 z;NY~%*9ODN?{>%fykKD8?fKMpB?BRZ8?Uwl>cke7bhotSRP(fIhw#@fE>(S8X%&i; zzY^_8jm+M|0uR^Rvcc>16JdeoJ`WaD7^WzhgSfl9ntnk;=FW)ia#ycsjO%ORHQ^xd zoASNUyP_A#U1Mp^&c);526xn#bv40gR?Noh^LqxBnYUzJsksT;2HzpU!I~#BFP%%> z0@qvg+asx@_PCwHux~cjB!^+fwry90zw%yxtjKS%M$VyrB`*8668lshF%>s(MDcMM zg3MGtdYP|EbuE%6r@e1!t~X+H=R1}@y1Xj}9*RMP?%gQ5ib5F(t+V`tj<;fS6E*Xo z+lTuh2iS+_Y4oovIg$Iq?e`)G&v`%h`LSP>$}JQSs+6T9L3xp*i-SYdc@_#Lt0uQg zQVqT(SAr!4B&EJKM{{qyl>sg{VwbTV8S+BuqwchxLiOkT))=Q@+qlG`ZH^YE@mp?52?+r!rvv}ocHCNSh;DZQ6;stYHPBm= z(V0(VkNpWjEbzry^fa973827ws~yM%&jd*XN9w5Pu3`+1E4uvEk@}k(WiNF8ybLS~@NAjEBByuwZRHKWGl@J!=FxgLKbRU~Gp{$*~ z^*5hOLA$fl4cKQg=U4?H)2F;yTQBEJ_dg&V>tE}DU;h8K`hzc(&wqS*_Jf|gmVyJ# zcrvwsf0a{hH}W8}M;Y5~b!Lif!!zf-tmf#$Z28=FPOFn3TX$8Jl@+TxyMEU)g|Q=U z>#F1~RquOQ}yu&>JoZ&6MVQqV(-X%Ze9B%mfQcw3gL>w8Mk)j?W`=MtXIpObVb zt6kr>4>CoThWkxzZk48%!`LTcywWkl3Z}W^u4A|=`uNXLeCu`2_pZ&x;o|=MrfS=ocuC2sdmmJS6 z9(Amv*4Vo>{^$D~@oJv@2nqw0iTx+MCd-w8@uFroceo#^n9YLXOL;}j8ZE;=vjW%; zB0S4SsDHnLrSb7YEj$fBY5cutDMIoDa@Og?(3!mlKP71$^jtc@-D@n-2@Uqt5kV3D zGiA1vq1BWO<;#dATB&wDc7qV{`}2IU{{yWZO4rY2b9pMzE^OC`=Ce@Av#IBvpXT$x zk)@wyGUf*G1-#N^T(zs{X0ctQrX&f>$PF2UQm`i}d3gM=g=&L_C&uj)8u>ENh8GN{ z>}v-#4wqTi(;?^`3n>7RyrvZT49Oj^4z6ph z_Yn3loSm6935vbXO6TB=M1#|aWewO4!AvjyR!Pjour(pGjV%Qr z6$X`|XNeATuq{CQeya;4?a-D}ZlNu)roPXtr**%=X^LfW*ttGU{_Pp^5uDyvS)^L5 z`ilKo+m)xT1ovxnL0puuBXq1jvpYK+4Uc0xHu+9RCX8Qpk@L#sN$-|J!b%IK&})5C z?bU9R-fPFZyAbv-b$>|FC9+x?3!1sN+y$vaq9UFVLY_w6i&YKIcgdwWGoDDIhv!Gf z6UTV;(QW^hQ^&8S2|wzJMtsm;ez#w>Ml@ClhpC9Bk?9IGm!9mF9m1mw#Of7QEci&(M1$v|g#h7K&Yzf86@_W5MXqrwI65 zhcmbB^YbvU=1vFn1Crc+1MRH`(#gWg0`aEPbM3%71DLm3Ha3mDO?y3A2aK<0E0)i2 zyU?^5Dxr1VGM~An2UhS*UzjM41hwmja$}l^pfkAp?Y^UOQ*ob=J-^LYPmutjTz#C{ zzKZB?1+VUQmuj&~Djle8Yj0b=BNGgR%15NLqR#%K&}nE;`}8#9w&TI~mu=gk>!U-P zkWG7%HQ6S4@fn5}(yMr7@X&JfP3Um?U(%{*Kuo{XAKO_gm7jgImNBlFBT z^XP8n8ptmCzH^^C+p)#b;CDZM+NVP#K=ohnJqIUO=3PY3TU^r}TbtOO+Y>~BKy0V*|=&c~~rbcTCzx_1Pn>?I+c99OXx0=`_1_ADhY z^*k5b3gxH94CUC9X2<-@PA~swOf6O}KbUcdw^)RPY^w%V*wFAo4; zj!&?Z&1+}lCJ$91JP_X@Kq)z&oHUa5$XE+X0-EpOOMk4MuAYd7h7wNSSEzZIHu_C% zum$XLLy>M-@xDn8TBnnfsa7gokEd zq{irylqS9+N^$WguC4i+3?2|UTr*tE7$g`TxX*Izc~Z{4ea29I%X!@@2yl~rs}z`4 zu0T$V{LzCaO>=AFQn5$gF}E{S)Qqbm_Np~|aE(>i^i+BKL@E8|%+@b}xR_R-l-~t| z3!PSyrXkqVAV~u;kxLyE70@89;fL)2{Y@UPB*q&Fze|H6K;D@ob3%jtxZ|*U!Kkta zyPKJ^;X$w({uYH^%*2Xn8gW8$j176b=B|rvw9`bS`{%dW67<_?-s-Jigm-5#<3Ax? z6bSLJkf&|7_7z$->dfafYKVUI97|i=Q@B(SKv+mTM1!P$*}5}K%Vfc?p7NOEIGZc& zQV?w)Cj{?_9uMZiO{2&Z+};he!q`&?yn888%%4f8K09-Sy&)cIG>HimhZcY~DN8Mh zFUYsHrxwXa2J>LB5+-33V*dtMm54~d@TMJ!sDz;aQ7+ZgG{2TR>maU_{lc64Ga}*| zue~`mB>0%6@>(oewEzCuBB&n^eu#xRlsQ>#PSZ<0NgQyn3xAE4a`q0reMdN{Ne{ti ze-Fk-_o^`AhZTS%zFBRSi!CL($OloX)D59Y%gE#<{Nl^tuJ|}Az62Gs2MCr}$dO&p zeLH*MpSqtL61`TS(=G!9vk&UAuE{y;^9WUKu-dGIB)*}Rk_*oT_!`^SrYA>ug-+W3(rG)nK65BB>pIio>#@+ zIxAN+e~~#mQMPiWbtjZmNjE=tA?UT?b!!}GGd2m5OfD2FWN;OxJpHNqCzb1^MKTt$ zfO+kV@rkOWsSovQy&p}b=!80N?PYqN^$X`w%eKgZK%~dJXra>Em*e-z%Xu78G$4iAkld@iGI^WCIwwl z!&Al!(@H)%{Z9)3;fj`nmc5B649Hton(S$)s6zhy5d|hC;+~$ow#)V4;U^DiluyNK zHnQ`qo9|xLOvB7)amp8DWkTN6`f5B_=>K5J2=WDL5s$+b1tD)ewSv}!t+~Fb@XYzm z>~5PLI|wK>_C6&Z(l)N3YVB_18;Vf8qw3T?){84_h@#`Wf@=*W3VZ@t%O$LFqCLXk zXsyHy+7;fC;?poFU$X`AOSdvdh>?JjpW%1-4eG?kLcz9m0o3VT|DsmQT6` zS%PW3c>_2(vEZ_jvTCc?c;PCNBLE216+Bv1xgM1HGP>fI+Oe@BeZ+7>H3 z5U1bpuH)SjasFa^CHHGai>7FWSx2`r#NAo!| zdcLS)-Vs^MZ2+5g(mA(#6whNQ#fd<3Sj5!bS)AOW|KT+!ulquJ)4Q}%%MpdQ%PQQj zQnp-728|@Y`ytPgP#_?XoqF*TwB$Ay$*j0EF^4TYkjwZJvj?c$4}>#SuoGmSD#wQj(hJu=bM2b_pCN_`^d z9dnCH(8HiKp?Ym|!M&m0B@W9L1m ziVZWPMk|}9)HV(kjezQfpG5HsTbwYfxlU- zXBJ!+-^EdUaC5|V7{r@x;osbj2K)nM*bQ*=(Zz!U2D%Bt9c;dJH2w^q5I-4$V(xW| zT_5x#4HbiYQ5B4;CJBW^^Ak1sjH#F1Vo7Wz`GVOXNxJ=6n^AaT5DaJKlVMy9TFJel zfIHcU2@lrej3H_ngv%KJqR9N3@>vsCci4P_VWG3a78zCni--)^-qfkTK$UoqytunT zSl~cFGYNFMxd|+o7xdC#kmVUdNKpyzV9km*rz~(qS3rr5T z+)vp9li+*(<^H~})E`pcowN}AC?$!D4!NF!WJOol_7hnWvqj%}BTS$DB7*roGla*s zGaxe?76{8EZlLOl-VT*75~%xyGyn=kK2v=5P95-}lxb8I=jMU|Diujd7y@p)T_AfB zPA_&>!cAG=WHd%q>G6Ce_VlWnUH%t^69f=EHCo$QLS+o?mp@GxXi}~hIRB{HYeRsr z6ii8b%u<3%G9d-C-&Vp^O>{wgH7a<;)4kCCn~?+5En`9 zP!kmE0z*G3yJ*6+moPaOvK+dRPizdS9=_qK%m zlJgvod;H2xDGZ(yi%g~FB5sOubOq{3xG<%sA}V7m!_#j%iCiqu zn}Sz?NzL5^@JwR#H^?TuPNM1Ua~LPB3`_oQ=zkDehq;bNzQ=E*!wg@dEg`bYzRTMk z>LP>SN2S6h3=4$NAkWx>6%YPZaP74H6-&tgxjy8T=4>$Om~3YrX{^qq;{NX>`z>^0 z@QMx5`$oXuUP2SS093v@-eoU+)G<7Yc=3rZeRgr25+ddl4Vb7A<%aHHWBpzwp1xN; zYTm72G0G;W*)ikJu*$GUG=_sDy*n-(;IQknMruZV0+PGr1~jX|g5ZZtpOmMneN!Tr zrZ0QNcLTm!cdGnFzt}0NW0Z%6)J2Pp{mMh#_{Ti4$MMdy zX^^~m1t?^BE!n~l@Pt1f&_L8dH8IP|(pTFRlO%vTj{ta4%zdk@^YaT14Ly!$uSce0 z@vM%KquKYV-Z>A0XU^C}I9$}vy!^9jsvg?YGi0c*aH16!%7Y?f?$U4W5R*J?+Q%F8 zEfMje?7a(qDaSUvYuwG191~idE6@M0#bTqW$??4u?cd8j9v=%I4t}@( z{f=EQbM%Q?{X=5DeKM9vZ{glCK9+7fLo;u4RT1b} zJF~#%m;OSX%tWt%s)Uafj3B;L`Wbri<5PI}_k6@!WQvL?5UtLuCzh!YN&mqfjQ1TK zOnv13$}(b{Jh#B@dZcRvk7a6 zR+6UtTiTR;CtULV@45SJrG=>*Jt-`a77omqWBWKp8hY|l)Siael7a{?-mt(5&YV~ zRN93DsHEJP+}t!=ds|3PBs9$N&N6>`i~EwuYH3NSsNPRDJNh-+`(c9&%!d45@i`gb zLO6#W<)jLIRZmKueUH7U$sr#lcHdL;PaeRBK=k6gxfE06+c5e!@e9Q#nUIhXqqn?) zAC5U4yOt0@l-}|tuc(NEh{J5UGZ6oq>&KtB*XIw@8}L8T?T!%eYTU6RORj_3?@bWI zO}@H@?{BXO5w6u{B-z4gghVSwRE<{n6vNqJBfs|t?i{-VB*yup^kcG>2QG??%RgPjn`1yBVG@f|*mWUfa(vUYIOU?opmh2`2flM((jA0zL&xUVkH9p9c862Uul#BKu0cZ=7jTkp$$ zoJyfO-&fBRX1$TBE|_CQ4UgpHOW888#ABz zc^YOQl{Ia3yy2f^VT3z)V#`AsE=O91@vm-y@ci|l3dj<1NFr1O>Aq5dtg!iGt~{<0Gxtw^jX;`y)g~oM*C>zZr8+4W%=+(jUH52}n z9W)Em{N0Lxuhr-2e;{rS?t$Oq#33nyR}jY2s24eKYH*R-AB`x#&qpIje&zpH820Q0 zAtQ?T0y18gdr15(2j`M_peM6LUZ zOG|`(IQ&MhB(~=ED6-_Ps!I)NlWcBw>^ZQxEvMY#Hg`0hcx&k03Y#rGVo7lsi&Yu2 zvAP_eR`Teo1Z#!Nwf2=H*RmTWH>=o<=`G3Eo@=B#`#*R5wv-j38`wFB!cdqHk0}32 z7PdO^^on-Hy)Clor6gQ}mUftvTXRi`FaV|Vy-tagRkE2OlmC-MB?L*auNsZQ3Cdn{ ztkgdNzoPu9JBvcE2P`&E644@Xn*1;a_tm(gyBxp0e7!a>?5lPn-)o+2(&vfYukkPS zJH>o78KuLssIdbFq$pC#1te3ZxC+Br_$7sf_0*uHWJZA)wp3Obj&XU&0(&&6&*%x4d2_EH>S{vw|n?@mi%M4v0aV+-uC5#K*XT;sf)&BI^LZ(Iu^H6dB){ZM}KF>@t%ul$|t*2kD!-N1gwDPM@NNt0Auw zR}K_!g;=@H928O+6ll?OhLE!7iq)xg^zg2?(mWi;=x2~kbxwRtcH}k&^nw0H5Kj+= zDUC#FYsoh(^1zM7;FU|3DucKI3!3efXDim)!|fPv7r{$%y3x!zsHM8g#MKg}3-bJV zo~x!jR>Bj0zu%=npR=g5G$WZkc>)2nKo^LJuIg5mB^y?gFFvMt%b=RQW@d_wgXqyi zrjNzB12+AA4QfuZKp6N=)BaZ2^QCNtz?4E4KlJZ9qV^px} zZ%r*T8}X*TBboWTV>Ao!%Zy`ROx&OWtuF_ZMaWhZ>uj+MVFAUX+lpB?XwMI`u9}|k;(<*(M(Vh;JBWu zF_BUP{ln^fU(b2{IFJ9JM;uP(K@Ji+BYhwy_7z>Hh`H?u7XV5LwL}bndKmn_6 zE4D8W1x$=>fc4w1^U=K3^;ojWZtVjEpw%!!tl9PU#DFUF@)>Xs{{pNGfZRP9i0`>t zwypx7EYn~i_Bvq&29F;<^1*~i6Y%1i0uTm*fIgl%*Li>ZL+yW zoe_qrLg1qbU1ybn{Oy!XLa%LLs7eq7i)ucSOeg>Ia{!>dn{4}TpY3%90z2z^_tp10 z3lXnOauhD=ic7YK&!-lL%a8Q)O0(n*yRuw0I!y-F z;IMAX%*znPXij%S4?q()#BMPie>QgA<)?Kv3w-~Z!L=si=!mn4^a8yE>AJ-aWu|~S zFiyB^4EOXC`nZf_qrjJ)REE56oFt5p2a>(QHsboe>d!o$4|WWn#d)p@2etKbS|=P8 z2d+UrZ0!`W6xWimOQz85(3C`6+E62tI5zu_{^xL9?Lgw9*3}?V+)-~2Tv?~9JjMe< z{FdSx!_^ES&&%USumjQe;J}Q$3n7jkKK3K7g4zD&UkeNTY&9PK`j&@j5j?@lwEmi^ zPSMwMt%=3si9=5sNy3?7^I)gUAYn10(}t*>ei4N>7bWy%$6q7j2SNT$=k!9@ zPLsdh8*v)#nCkc<$@*_5{`WexfJT3x0Q!zNWwsNLazCgIyYKz;slZa$_NdgxaD+Jq za%Z-Q59`qZM9XeP?q-q}q>N{camfrwNM*KCv4A9dW?e!9#)0hI9I|~1v*O?Wp1OC$(*@wchg(7;-jboKNR;T}tjmLyT{%3~|OXuN9L<$|09sz^XAFR%$@bX8`zV|yAd0YVLhx@i z9{b0`0o=}M{x&nEz_I-oZc9|oc%XZ|$&g=L7Y=F;Y zGX#hvG~3kkZ2{g9zcr911HA3u^@Py=A4Hbj9~$~(LIx)*iBxjUTcHHFoZqlM>U<|o z$o#?K-b|hZNV)j1?E%GBu2~c4alHqmoSApNT>ZUzodD1Q!1L?!@K?^&y4U$syN7eO z=h5#g((b=3UGi>jT<4w7%m8ZSi{NAM2X3SX8V9V}d<_3XZ~{Gon<=TK zMumiF90TtJi)@e3!e^V zNLWWO`^{(c6!#Jl$(z;@pJYCggkyB9cSU0A9x@$1EP5y(MmBYpH6+Jj{HvI?1Tp48 z_(puZFJh?EVTMuw_X)yYB_NlUegwd8TtjmCvJIiwNen1}IZZV{N-u}moly5-Er4@K z9zXb@OIakIol9s%N*?|VJCkVV?Ejv-&SSXpq?j303T_Q4-(P^~HFa^HS32YzZV!DS zpcaGFI~5KUhqFwUUxZ#OckHy}OX(dc9i!xq@|bg(NJKYSqXy*HC@o!piSo7X#Dkv& z)9JjbhEyE$XChOGys0AE{8?19>9dahw5e~jkFcBLDl8*apyxX%OHU7hmkF~nz7)Do z@dei-4orp%RXf|huTmG{YexwAqhxN2XKI^RrQ>e?4)TH_=ns$dlVHSMQxna}1IL{(&Vr|q&Qd{EKyFY(nnX5@h<;IoGd-D=&HQTImu;DT80+(eyO zW>@wt5Zd*Y zBEV)7C_7XD7eaP>M8|P<=`O9HKt)9b9XF`@)}_<__H_K=0RI3JxbqXEfOgR&qj5zR zD)qoMTV3dYs2dZ&ughUMnfr21t&o1P6;_+i&c;RyB)tH_XZXSt&^phAG5O!w6%sv{ZF*Qo56?CIR3U;4s%LB zd13CjCGoAYYWhd5LD`bQmO?M=dnx%1&kTds3=w`yp2Xz0eq`<`h9cPB7L2%&rI;k} z?mm>;d^Gu`9ZYJ9^K@umi$b2LJTrrC4r1Vojr3W!Jy6AY8qP`jQ4pZXXO_7t1x8WC z{?*wAwJ$&@9E6Yw^5L50gSNz`R*zIUE4a$LQ3&xctZ7?mB%OV@F8?-jDuhuaMC;#- zp4Pny5#ImZG8V1!NjW?{COHdc^N-8*?Hr49SLXU%XZY7aq=zRd+p?rz#J7Fkkf~>e zVgn2z?`BR#c4mhZ9@5RNmfd|z?CqNUKzUVMVuph7>Y~eUiX8Q;Sqs(Bd(dbBjgnzI z-=*HUs1aVRvVHYioF=vlxOVc6zF;u%G8<(PI%GPU7g#6UQZ=1)SsxZ-zf(E`I$a0C z5-tg;ekofbr{YU+AlYff`!gwyA$d(4Ueam}3N-b5L^8P~*-|-bkY735PxDulf{_qK zJ4Wp=7U%XiPS56r{`c+{1_fSL|z<3~2+B#!ga1IX>$jGqb!3qwZ2cbU-5QOaAAT)r#X0u!$ zkzwDN#&_0S@Nx^FdeXUEEx@s`ur9WvSlIkJvuZWe)zuZ9AZ<1}v&tD)AT0q-6!(U= zGvhBzEDsNlkMd}fY!ljFHKhK`q7)idOlh*<|O^;qvU}?YqVR_e$$Tn#ALbN z4x*#OW;XyxQ3n7$@$nsSySsPjf6zOC79Z&4cOn@oNkL1o>_3u|C-Wr`yIx(+*RudZ zPzo#!(l}_JFfuCY16P--=Y|LHiuQJszDRY=ZT?RSuvhz+Sq|-l6B!jjUOxaL!65(E zkooAG6>2P}#}rmH57Eh6RS8>#v;~E{L{-Uo;E@)z#bqjmw?5#&p`ksP%ms1RfOJ{p zqdcrm7D>!Kz+A;HIYcmI$ga)FtQBKElmLueKlLM^s#q^YQ0;OPA4pkQ`CMI}OHFM} z4S5QMIK6f_MGHrH2;V)8ry42xxbtB)a*HX)Fw(n`RfSySHoVffRCGM7kYJW%UmZ)( zCe;-e8T>H<;YS5%W!&f1fY8lkJ*U`pv3Ugy1G>h0`I5lf6-Gz{r)qc6|C}Qci^%ls$Mxo9jtV zUSIn=ol$4!Idq1e`)9ECZ5N<=(J(1XQqq(+p=Mtt!vxsKif zk+YO}VK%gH$deirG`Ex|QLAz8Qyb&D+m-$OoRbZutdTY_4BVLk)b=E$il6mT%P`U` z}CTXHfMKp3HA`l>E%Wkpw}QRX87K(jyq zY)1=7RD9eAcBN9CuXig>5NpS`iK#fAe`I83$$@NZg0Jrn? zv21@B0+`>wf1j*(WB|~JA6@E7O2R-TDWr4I`7r@M7K$8X@j^{Q1EgFA41O>MKKPH- z-{wlMjxPX`$t6H^dbVAuHtNmQdW<39-UD{nrT}1|+@LEPAUGu?B=poxNUDBM7ygk4 zW(8NAw`51mh8ri==T`r<;#ldzM_^>n;i@-Gvnx(YT(h#F0dB1Zp3-l*Km4rd=2wh+;L$^ltY3cxtiL3 zdf3;6jeQ5dS;8CCUXc$OwCCa3HfZ zerfS_Z_N;bUi`%Tb%SN(JQg-(i~QQF_}0sCvBJh3t<2l25IG^H3GZE{n07KQvVwhN zaxpv@i6iB%AUNF3vLhm;?bO642hVw6K{IYm;))dOXLN&;9e<*9=hTxB4jqeob=}h1 zpP)nu5|KxKtNAy4&2xjuZSt?lYTgV9SDBs#Luq*-V*#Uef_gfaC|4nF#;KGs;*h;o z*79Nr(ZbIZf&x18hHd$Ao*iV+(q$;r6y%HE%Kk7q#0cVQQoSh)lRD}jA` z5AXsn(K-ZlI3CZZO>_(lCIEm1NK%O3@O_Q}THXO~+pOl@M7f{*9&7|$Ho5in$-p1| z0bT`8L$;5uKX_8-KzuHMaOD6*kL`KiUY~xTAIXt2JHT|l2R-axD{ULWk0cW*xJX`O z(_WkMJE3HaZO9RJW#kq1e?d2bla*~AeR`HXA!fecoMc71fr|_fsO}Q{OjuK+!HcpC z*G3@M3Pc0bGt;2@J=PmGukz}vilj)L1ph!qzxlV|!|#BPjPETYIiS+l`7`Pg?Hm7g z-{6qyLF~_v-bn>dBuiK`=iFv)UA9ju*%DLH+O+&xA%vzoCktY!`8e2v%SiMZPQIjM zag$F&9<(A>j84QmOSm@lTf^1M{``edx1aIl8aQRjYMbF!?w6$=u16_&uQu= zqJL}Dm^DMNlDuDO1sNoGYXp&=&naidnzH>ewt%yjbPRUCkNW(%)1LB2`1*l5F4_|-t#H9FTSon-D($}HGdgI=;e};oLHm+&u2!H58(m|)fq0+GX<0BH# z!*GyYCHa*YWXbqKAfSpk`JyjzJuTdK7$%93o>NR-Az||TMO;zMwx8z&>4w8)CPn95 z4}Yr;IYPq(ufV0A8cTI00}tm$F^i zcJ{HWaRG4Cz|pev2;DCw730)GeWzinOy8%&4{$KRDvBM?;;RFgvday1);RAMVL}d1 zhra*<*Tl!{^@Ar=TgPd2d$N=i#oQVWj7L7Ot{=oMqVKCB-@eg*=q3vX_0`nG0Ycls zMwd`;D6$Elv-tP?A!r2vjvw1Gm(%4Rn2J0BKtGt2Vb==JjSC>+KG>i;gK_)78R9Rg zIAUPRT&HXCRzIU?0ukG1g5SIKu4D>*YN=g{z&^?_1MqS^?m&JLC9X! zQ2#HUxH|yy5Fm~M8^jOtn>Rp^1unekg?Gb!C*}ihi-gY+9)gII0?R)#LRk(n89)M% z$x=Yw9xm0;<*|>g@1vx=qiKmbUxxgiJ1%lt^y{U;$ zE}*rnr%o>QK88~sL|6V}{N@wrQxOImb4WbYg)i4n9yfB*R$2<{nfti;Q<|W4F%BMV z7W#L%CM)vF7nFID?ucxl!6Jac>{LBrqYOb~EP5~uWd93o85>*1<2|-LA+5e+ZIk~G zF*!ub{I&1d#fKKsQz!V8SOR%)kkpATeed62WrGUC!elCn#3yH3s4lVj;ikb+W-ZF7IKoHCUCcTcFB*p z@*-N=e3KHWVSJzG2(*T>!sm7_Nf+1~fZcncrmQ=C6zlxCB6{O9a&vs?{i$aGtvT)3 zITS`X5&Rf18U+R!A8QJLYI*>MdX_7V6*myq63B&KmD{M zjWM3LM^nIw#+5TLcd-EYbRVdBB0jhHjO=z?m6t1fvjXkG{u(;0XE#v^$mY$qUBu|bTL zA}08NxeY{3vFHXi8=KT~!&0v!*v|zS>>KN>r;2>jXnunSgddnIItGTC9yFuQTwv1~ z!fo6?X5ZAi&56ZTT%@=Z5!{CBhH)!!Oz)L&)%rQ|?&#+;pSJkrJk3k9AgV zB|`t1@7_lHKP&p%3K%UgbW066SGj$HI1@FY*9_HwRXg(Hc2fEFCstt6kTOg-@w-{y zd26iHgtzUy!-VJM@WhYq z0q#HC7I@eaZsd5$GfAX&kD%&N6q_2$5Xh-vZw^L<7< zyPQjOmH=bE%BuWsNG&IIR2!@l*$R3F{v$t!!uioMwwvV46i6R8CeS*8`p?9a*iVVM zM>pbKolXOZ=P#T0u~04ge-lzt28_a>G1;(yW^Q;C$v(i$)HFHiC;%AFUCpqd-uVL0 z`reVukNYoI1QMU)g2l%UxF08B$^!5YfFh{3!7EKGfPhz=?xc@TOjOCPAwdN0Qi}C3 zsBdVX#p4@`p{+-Bkk^c%byJ0G=t0y;{T;2&4&2M|Z7SO1POsgx8S#X~;&f}zx4=fe zb!Yq&YyZFdf9Cavv{-o%BV&X8u)DKU!Z|HNx_qn1=1`jqMnpvd5Q#E8;(Ko>M%JHb zYA^8(<#OI_USlgCD4-IRUAEN_5MZWq16cR|fMn#9VM|OBGDYF9B$*|-jSxAsVEjH0 zEDa6`SAefZ4c&ICQQAc#1)zR~v7sb8#QCBdUaPvMULYlkSn7)_faj4^{aMk^jHkWT zUvwALnt&7G1=Dr7`Uxc{A>*hWJvATvk+LVNM{p5h#FdcPX4)Jx!AyHQf;%E}xDA}D z(~NAoi)j01HU8M+U>+s|@hW#_Qc)yHLfn^Url57;?~zIeF}M z&qV!K&mlQXWXFmxa5qt4Rt-b>+ZQ}G_6Sp7ZRvA-t3>5SB;{VEYt5*1f5i*fV8YMGaHdAQ@5>Y^q*XL=I zHF+Me7T?a0mN-D=hM~={TeuP62UAp|l&RP`WyvHdvyh9#8=v3t!k+bVo6CtRp(x9;s7u@ppv5cgPb#pOm(%s&fPgM)yp3;q&J z2^QmXiJb@=9W`#jy{lE(b39h8-(j)XaBL7f(Q*NFC8@5H6==iys2(c>o6IEb_aLMb z_$V4O>Nc2kX!G1>oahsNVl&39NW~)NujTXDrkHK1=;4xma`S8))8zITpP*^y>q*Qk z72&%)vie0=F_keB3g^Yd6@y)398j$TZhc9gJ>k+hHc&5Hx^_Ab4Vc2n=DEp5ogva2 z?Io;SyK-Hr^#fRFR-sgV#oHyEUCOO!@m7$%Ei2;G%bLB%-tgMWK=^~jvP`?R3ve|v z4S90TsD(`p;906r=HCTWpqE076{)56WeS(t5tj%Q$^H!-ppQUgPs$b5brnn*<ARv&L&6 zSe)88uB+Q;?};9Z)p6!?5uN8|#y0)rPB844Sixmgp*s*zX$gNV-*>CfFR;LkKD?;+ z>Efwrh$A~nenA&2_*lke_sLznd?T{!)R<0;4dD^rj>m#RqYg^oKRlgdc-(EU#$(&I z?KC#pq;b;NYS`G;#%^phO=H{GB#qtJw$+?}-*cVwVZW`ey`GtQW_Ir1-JG`VKM_Ms z_3K_y8sClyNm5DXv$god7lYm}Ef=e=7_#kiwj$6v0}IaJ0ipKc%jHL7p-&)h+CKLu z24+T$faFn%u|E$d3?ZUPEXq)b1L2|j-cX1%moI%9DNnUTi5l!u?K>-5I(vyu-t=`_ zXoZDE?p$0^7j7L*>(6I{=jvv5BJ^MCu?SyF-6Wx<<$uGh>!GYFdwtTPo7$WdceFNy zitq=0E*9F7qUpHW1T0B5!aK>9QN>J<3E9MHQbzI#!vl&+7r+$g3sbB%BrzT7wpUMR zw7hQA=PYkH=C=)!^c=7T$!Yn+8>vt3+30mzPytdI=e!iHmlzo3jnastnRbD`{ne6o zY2v3~YSCrQ3~TM79Q{c+!(e--a!aC^-0|Tuf712i0Z-}lNm^HB=#YI-g%GWwk?7nY zU+W_>pHD@e@pdyDG$ye&au)k=ln6tMCsk7llYG@C0@G;u0JJPE%MvwjpJ1si=7={B z6{w58?Q}zDsoYKpr|-d~+iIoQxDWOTM3NUXGgrhI!nwxQuA19;E}@`Xp*zXh4}%!K zd0hBe?qj&X(!ev(i3igqP8*F9Y_L`tQwjX`2lt~rOVo8*kvn^WIgM1ff~2hX=+n9$ zmfeYkhgGRv3Pp738ZoOJsg@IAIBKs`GO|th6m-s!Kks>kt8$+U*x7ahCt|RgZ~mZy z>3k;#n-(FP^NDdvJU!`pkrSRb&sT*(*?c0nu?8gLY7SUdP_(NP!&MBVfu&KM((e`V zvSywziQ?YB%(`+rsUkZAX$&FMh|A8rGrYn<8<5*ct^T*u)3`T) z@C^!a4haPoEqwfjf7aX|+ZR@}vQvz@@Bqmi8HO%;Q3}xzpPF%f!nzX8>S;B^Gh?1X ziUxl~j|LNv6#pueE_5bAN3iW?sn9?(A4Fek0FZ zoCIs1E9^LJo==k)%qBi6Xy3}f^sMvb?qQGiRl+ZOsh8OFxF0siv*9;SXzQQ-gHW=)w zqFbwmm;=)<--`=p*Fq5v>I0jWPnVp8f6_9Wm=&Bae`atX198g73DuBGNojn2?24Wx z0f81QfZv|~VR-a{B;py`JpWS^zv-&7TM=iQC^}Zb!QiJ`jyMWuoViU_oU3R4Q9;Bn zgXva&5%FaqNuoUKuQNXN#_FOCPPJ2FkzltIrx-*t#2n8TT%rK{f&-fG_xj6ahb7p( z>?KD5SE!kpeOt~c6RV`PE1f@y47s5ewv2YwFeixrpe+BjVA%UBK0h`l#lO-Y{n#Q9 zE@DoJ&4`Q|y|=|*E%{qAuAbPe9bZ%Z`USO(2o-@$2H53&%%9nP&alcI$*^iWLrVru z8;wfzrP!va^`oKGHQnCN?*~lg@6B>u7b>SIQHV=ARYsH_@oTc)J%Rn~8cT8Y#9mQk z0rxbWYIgYjs?b!j6Xc<>)Qc&ajbjBzRpNqJA)Y9GSyzo+p6-*}&!FP`G6BWG)dq>Lq z`^}YdAIEsHsI(a!;t0&3h8F?B^v51_ox@xWt)wdyY2Eh3?ii#6sm7nkG5V}%+c7od z2=N>0Lg+44i62s{6J0G=nfeYeTQ|Kq+z(dFREW-CXuL3NI4p}o{4#7Vu<#upFX?^p zjqzy+CHGagwLfD7+TB{iD#bpP9Ukd6lwQb5Q%X0(pf)z4tC^?PGKS2El%%Ajg8ApL+FZEjXAQpWoQsr zc#uxXIH_38jPvfw4*vd3T`xb{ooVE5B&BvumVQm_>a7{CRYO}tKT3n<>&MoH>R^|l zT(PlO6dY6{ac^}=QG4WoU*M`b^?@Ly8_mx?te$u@6+aKV#^_=n=6o;PlOm$~*e070OP1{9U+pf5zPScQytFhCUZ>OzmXw*2(kk7^HplcmToKPR;6a*Kv^XTut<^(Y(<(%{{y16Y8=U((pOu zz+iog2xU?HuXqmbi8Jwd|H6zg^e-dHhh&J|RyW69wX|QsBs?n}c=%?Hfp3Z}0SjhC zv=qak=yxM%DoTxf%s8C}V|U6~fFGd4#y63hzfQ_LHy*LbD@UlWPruXa9as}hb_SW# zDoOj^BBZs)BTYnOj#<$c&fNB^!fb1d+PZRoGY|5@sO=ISx`=`rruzH4c)?SJwhzkA z0t7gJ&n$yNvZN0c$3O%hKkui{k?4EZxRm)Ot4!5AQKG&43_LGu7^G*_{2_-OEiJAr zt@uV}3?7uYf z&3X3m=>1LP!1v97U*Uyry$Rd+m|2eg{JQu#3=m2ABZYJg9c>l~=y%d6^K`}i`?W6| z{?agYHk@2=-l`J_c=_dZI-Dc{CAC;GVFu>Ga7`L&!6k8iJeQ4Eogxebn84RNacBNlT|Qj91Q^0zck5J=*tM zN@~mf#6##)q(7kN9ah2 zUE8o%Dvi8pyyWBLI^dL#dU0PLQRKy;p<;J~zC zt2@gWTxr@;KT_Un0-J$s5$~V81u|FjfmpDnJeM?Zl>{fLL>*<5^AjNLcLjI`5*CU_QtA~4#E~zwv4`u z@3flS_cM)FZig6#1wn7MdU1X41X*)P@8W`)e8vW^24hHW_i7Pzd=j`VmcacL8+beS zXld+!F{NS}ke zSNzT;nIw#fR0CQ2*Q_agi^-6oF*C}h6&pY02HPi%fvt*$u3>P>9B%ri6r#z52)Ul| zJM1fdi}53jL3(w9J;BfSiBB{SSCFbFrRGJoYNB$LFmzJSZ;2Os$r^JvlQJU=Zc?KT z|F;X!yj2y}}onEjNORmaOc0r~E6=_Lo0N8tePNSh?WYJ)WL;PCWQ|Vr=1B4||>4 z8Q6oJQ=dG0qRBvm*0r8IaW6^~K~eGvC;un~P(9y?o8_wp6V?~0q?SI|6{+ms+Gw;B z#0eQ5ZX+*JZxqZv)NCPq@E~w?ETxmriV*i#x2`vY*=+eH)TRcX1xtdydlxGE(9=k^ zj4{;vKJx5Gp!wk@UXG@}f1uRDMEH2CjO3bSH}!x?p^@d=%7Lm?T^B>)l?2Mh5fm*r zl7DeLVzi6BG4AN1?0vycepoa!*Ij~>^r4jz9*Ju@)=Uf!So<0A7g zgcF7JF*;!)JuI??I%+41g(tULe0mol>o4?G?%9;u{BLh|*b&P2V774#bD=l*D2j~^XfrX=dY;B@r$FK+SCSM-uAR4eimyERALhUqLiH2r|iuvT^FBaDZD~RAH-L zL3H{mi?@%xOKu2~4@HrFB#8shj@ksJdGwbvnl;cR#I_CaMRgpR7Eja)&4goe1cQXt zZV!X6L&L>~#ADH|g6An2{5Q2GcCnaj4CpC-i))H(2^F+TlbwG`^q_!i#L*mY`B}nW zg6Amnr{Iaij@-j zZGNF5n-F1=;xo_DQP~;~NBWuBjo=QP%A3-I5((r69#_fYY8|{4N;eSCt#KCiYT z>7?Z*ucSg)vrI20e(%@PqctuB8!R7DK(+*E0$jaF52Ak0*7NfZ%*}h&EaALsxZ%!ddq>P(;fJqP$Z~awuCsd>uv#ZljUD3a>M$k-H7Gi zE<#SIqn6Pc6WnEZPWZe?v<&xFX3g;hoK%}2wL2H=^U^0q7JmCB-;+WA8p1O^%;BOx zE3I#zkq$-%SZXgBW!RTnjNhBls~k)Sos8I9H)(Wp~j0x zWKK{5U!EQt(;Dq)c%y z&B;XpL$W_P5&J_SXOd*L{8V)!{=JVg9bb_~Rd^!59|mf)5Fqe{L@k5rs>h7#at)%g z4L;oQe4%sIliOx9t01uOTgUm@ullsf0GDvWmSx%498v zklDRZ{w1(hl#9bHc6SEnJ7hemv;}L$t!Uro zHM`Ti_h7K(^Z85w&WY2?m!Cg0R!{BhhWYRbdyuDnzU(;Ou4_iJzeb>IBMlls_7~)f z;P8Yf$AuM>QA@$3l7RE!9>gDqkv{wq7k$PQxV#GC5ZPFO;@7FOO{foGsI%0= zEJOQ(Rf?<~{t?v+#cV24Np?VzyHM7} zJRVg%?nP+H{G6p2WqL($&IKca9G~7Brp>8n>f?e&rnQ?H==3r51!ow#QW&sQ({>GUPXh*Dyvcp1wo9mveGLYrqCnVIIbd%7;wYfcf z3j0c_1le>w;TVL8`h>sUq`}h=lQQex?L@-ggFu(AN!6W!0fQzRdHE)rF#$1v-Su6s zXhKByv%OWj0f?Eb7vs43xw`}EqXLRceZ2fqC_z6dTQj){=@$^iY+K;_Lp~=bzNUSr zso&~y`Xkk?wY?Mr!+VC3UJKH5aH>!>Zz9*hjwO@h(_u8Ke zytE%yag2*s87hS1IUs*TC8=6L^*g+A992DI&+Gib2t#va`){us^h@D!5Ai){;;}OL z0j}wjG&)8O#WaN!iw7q0_~NRk3zvJmke_8QB$9P|q?(`y6$4y57EpwO1ZQSi0>Mew zFDh5VWad(TA(u0i)e~RYAmRr7IJ_{UluzrrtQd8@pNsl_=?-w~!b%oHlOiE| zRf9G7U(rV#WZKH$$&dmyUHA3sT8R^P;|mz+U_}TMXBGGe(Dqz zVCcbD#L@B5sQgGs2>S?J^syjj_mENy19Ar%)QIPFsEW>owuNIe`Hxi36* z^6|2fyEnDJGB%_ZYY=Ua8c{J%2ZMy7@yt}Y6=zAS+$=n_BRDX;a;hot_Lioylp6d! z8u(&mW)~vLRkzRU4Fb6;hg7OGw^EqF;>Ak%Y3+KSaGlmNtS`?YCS=i0rC$Am1(a|K zgEsFa--CT(IYKTlnbqL)jv`bssIxZ56@MYaf_$H0Fy-=1I^rG^(iJc#&u+UrLHg)X zI!oh0SxL z5;0OM=%Sl=nY9G;z%1oOA(kIr5)`Xh+w~5=>Bls%6KslCXYy|Dw=vyglqjsu#l>qT zOZSNe6z^(6CRnl)6yUfDS`@-R690=Xqv)Ske7O9(gwYFU%L0OkN>9b_V3A>i8An(? z^{)z#%z{2?1^1t0IKQh!zh5kP`O|KnNggu9p$h)L*_3h+C^ltPhWzwg9#N5DJYwW{ zM^P6IWcc~<<$g!Pr0*K|B6S(=%yA@}AceT5NvTvOKcJcoG`IOH?Iy-$db=cJ< z_G$BN{5b%Mss9byS*uRv=)pauI6!QhvWfzY=8$X`a?SLun*j0rooou)%P$0j($)O% z^Ot;EKiX>|Dn>7u5d6V`Z8BqToZ1BBz@OgXIg`sPhZ*`&bswlrFg52^Yj}xvKdVFz z8GxbRu}7=iXN#-wHqEywG-t344&`-w;0!RCu~2=%yh`!cE{zcHG@}mIem|4^F*87Z zj50L){2-q!N#EU^y6Nmq8oe78OV-U8;ynOdE18 zzRxLJhEQr?=o)NI4TCs1)t1s!b_~N~god7tAktWF&m551Dh0tbDFVAY)_Xi=)3{{m zM4qYxm?TBPnV4wh?$U9|ZVG3);9xV3u@hk}bDUv>4)qDkZ0cvb@Y`k!tij@A(z@mG z_?QoY43vK!SXQdH--qVr{WQnJQ^W0kNbDm8ibw&x3Q80K3@=Wvwu-nG^cd3;o*Qd^ zp)sr*>{$6G6UJaLGZYgO1H8~qKteQBJIdU{DZ&C#qZUh8KE^o z7dMxoiomj^%SChcP3}W>eF%R`g>S|myEkE^@lx>**yH(CsU8_7h5TFmgiwSX+>sr0 zX~ePxpAUWQrZq{NG}yLxz5nTDBgjc6mfz&5I7kBC8z9QkBJ9t#!Ll}$X2HC7Brzzn z_-@<#VKu$bm5WlbQd2L&gsagQ@4TcQM$fF~Q_YgaH~d=A^p+prc%cXv$WAlQp1|Fa z8S;%nZG>r5UMe5zGR46Xyeod+$g#*yC4|06-9$*9vO5!(v!sWnoQ@^HW0uyRNl5-M z!+?C|^8V|Xzi+jZu#+51ay}D*}TMZE6O8f=kT%H_AvA2(B zY*oTP9{5MqwLwu1iEGg=A*u%>x<4q)JA2|tCCUaiFRHuJF*AX%m|}u?e-WW=gS`OK zaQ3;Gq*BfiJ5cARKM2vQ5t>#%f|%4cXy3ZnGnJZ4dx3;i>YdV)H^R9iYWJLTsFQ&# zCD_JyQDPJrhIIurVUrD89RZP*6Gs_ocDZVA2??8)iedf>YpeE)dl%ic!ncZIG?SLk_!xNs4c z?^BbzyZf1jwo)#HS-E+SpdqCzBzP@f#GTe#bR{ukXFg>uMEikQ()SCz^A$Z)bY$1w z2pY}~dDQorbRNAb(^t#4j={5dp9DbJaJ>cN=s7j^+|Fr;kFl!Fb#m-|vNQ}u;vtMg zHh%g3p<0W;Wme*e>$>KvA6Op(a@$fdfZz4VE`P~!(%C_Zg8bzBs+Qq?e^&;nLzgL`7zyLy?! z&XmDhXyy?Q#1YL~90a0-$fTmdjWQBdl&D^Y50cevmpY;yv*el8AyT}Xzqrq&>Vtj- zMJGV5eXJvo_2guy+&f4~EB`1r0a;@*ILcV#X1wKqe4-hwOpCNVilCg!yva*5aX3)NSbckS$! z%pIa#hzE(*M`D$HItVs#!hVPwm#wX14V!+(k}B4uk&LZ2XrZx!_DQ`oQ*1%9luBpl z%n438`T+#}7`#;UMC@yFnt72bE>WKQbS0FOx6VW?b}T+tqJ4XA%uhYP;2mUaS4*TR z#BGmne25zYzvNf_mgg}im(npu#^_cTw}VMxo_cU`5IevQZFv{#Aht&dudXDTpd`Q1 z<+)HaZb54kBkTTK`u8&5nMW^#G!!Ll8Z?58d+Cprl`=tPZl)f{*GS>Ss_5*h$0uyd zd~#qZ&394j&o6OB*VYvp>KiArpufVi>CET=Uvyw&qlRC=d*d^3a3*uIW3eA1vH+-s z9gzIa;LNTL;JGo52tRAhYMf+Wm|1C)eg*eUNM80socx`3Lx z73Ry(cR4gg$9+4kM0rH?D~dbS`9hC`C%wRT45w{w9wEodIc8LN?8plD9c=J4F-FMb z-{w1Z?IuMa58^pFi^P4{ek7OX3OWhy2His99aAU%$ntJLW)rn#T~e>uFP1RDqChrz zIKWEJNkAvhMQ@DWB$R8jCF814NQj@AaUz;sJ(MEh3`%o4)6)1V^AIzv9|E>HkqN4< z$dfq9I-sr|4B2(19KBzSeQo^?su4h2`?YYWMMUKa_lNh#=I8weI$2GOwgQPe#w6kD zo+@<}L<_uf)GA4{16Uq*q5L)oXeUgAgcaVS}^_`JA&Tmi5T4;KTAtt&t9AHhfeZ3-m0sS^0?#i< zI4-=jY29)itslP~$J|@1hlfpoZvEz;*-T6s{?5bCfINj5pfv82mP8%E-8< zFi#KGMJvtXsx{pRme-7zx2*!umBLH8cO2`>m6MxBqnB(cQLnVADSrv&NUA`|C-Wp? zZ@1WhAu@cshul)iWFMeq$l$U-%JY9_gh%(*d-;cOe0$h9Xup7Rw~eBXd#6gjo#V$S zn1l9m=(3JvS@MC5&u%7nVlPOFKsM=|dCvYUZ-@`VF)$|8BSynLVZDngC??3<^U32! zW^BCI>lO;r;ZDF5A(9LCCV%BYR+19g*A6QFn%W2DUBsH?2!qLooRbj4h>~QCiln9= zM>6IQW?G9s1CrOOhkA#7m-(*raAtqC5tkjz5~%?swr#bcZW*NYdS zf`7@&3C0-(p)ecmv}4r1lcneqA$(={W`vCv8;m)qV(Lv}K`|rtI|V^>t%o{=Rb51$X#}!IFx<9WS9^0d|)Ju zo8ihPh~>+xT{;?a8c==u@9YA)8DBv81BijdZhP65njOi3C1q1Ud64qmn}739n;SEr z1OoJQ->%2DK|AuprZjni!~*Z6iFQ08bzD}>Qzl?%k$k}SLPRv5^F)GIK@oFc!kXI= zg@@vsS&t0(!xD@h-qNS$x-VND)9Y~0Ip7v{S-#QuxbDs%`H0pfTJ>~egYJ-lpV>1Y zJiG$-OH|HEv!igJxMLR6G{;Js8&{(HFYT47Y7il5u!xg53N~F>60N)ikIoQv#2wem z&A$Fdmr9gNiP6B1nDPwWWEwmU7nRqUNu279-CsIF(7Uu86$S_0^qS&m=t9wC`kgUQ zsXaJKQQ700_}+5l8G(-9-ia5QZzk5(EJ(Ft_MPBHH~dI=0Y<*x+0fyyZh2aZ>=^NZ zL6?OH2PwKO2kF~AiVHDqHecRe4kitIY2+xqeBK4^;A0DEaRzb+0;PLA>83T(W7Mw< zPy)jT56P;d@!X&*5zJKFrQnpb$)YE0`}%2dh9=Q|bD5HY3v&07jKL`|6Cy58{U|=6 zb>%AV{#8H|n+;OXVu$a*<6gnY6-qCDyVufQ#eN}gFD&o0h%zkak#b*FXa4ubiE43$ z@K&oq0K1;wC#(W=ygYZsm$|tVQc1~7y`B$4l8lHk+WRxtb;ciGk}Dr z2NPQ`$JfEWBY*%wH3FIZF!)nceKdHd+;BhiFs} zJ5-tq={o&WY$>8^*!`yv4V;ub!s8xL0=ln$vxDNK7mX=q)Vv}*-gFdwYbsS;+)=GaoiRqNvIy`-$aKs(BbuBXBBH}{D^%cX$6+@0hGvq_7;rKKlq0y?)mPn@i zT<9GDtSo!oFIy1;l9)!Dd8D^+;I>dbxF^4?5u9E@o&fE|D)!zHRjKFL9G4Yzj3y@Q zsdcyq;^2_!k)y`751{cwlV-D|{NYWvnnfQP)z4z=+@9baWw2Q*hxTFITZApL(Q?JSRg4 zl{MALBVq;UBc&&MB87J`1_w+sB2b2QRJ{8v?cBS)tyTK^nHMGnJmrE{6F?d&A~otU z!-c}uv(vNit)LnAF{YttN^*tEyrchYIjPM*uc28@jf+N8NI*2QeK{8+BCa# z$N3S6{ROw=JF%n-EoLfu9GM68ms2KJGf`=5DniFpQ{I7UYY}0AKiKJ9@EgO&QIf{o za*858Qz~Sk&w6Z#P8H0;APXME_i(S{usU_BiZDSW*5uMqDVF6BQ=AiIAC?R{Qn;H< z4cj7Atx6~i0po>m3$WHBevSUhPX$eW*s3v=(m{z}$Ka5uXWO9%{G}3(RSvXvU{N-h z>z7+Cf(&{B)Jc6lMJU%_!qJtUC5EDgx#c%b;`Cpg4+;$|8!;^zvJ7mRfu_7^o5>7m zVd>W}Cl4IZmF)RMb4oY)=>(R@BA}V|xEeJT$i&!(-0W!ibMZvbi01{R6oSJT&Zggu z-vI#_V@y`^dn-&=^POsBJ!wq(w_zPe?RZH|a@TU2-!n zxgyl?gF+uU8*3_e~zg5yB@J#L2T#v|Yy30t*Wj zkLO=PH*p8w+d1*tHI={ItA$9t9v1DA1-plcQ$KRWf$xv-N_UK^$9h6gk~^){6s29> ztn+qc3uDbVF|C@0Fy&w|=of!+%Eps@{-Km}xLp5ZV*|kH{AbSu;CPhsMEwq@i{Jre zm(|Pt+1_x+(|#7VLf2@d9+0klOW@sMKw1K~zbl;6Z0OrTjt7@<55zxq86b%htmfhejMPm53=i-w zNr{OPSE1Xr|F;VO=)t_+{d^MFy8MLr*Icm)2?_rbupQ4u0_1~`@htnv!_J5G|JY`L zj{2XrZX}uh=H;SXp~h;G%+PZSc0%;U?oYGhWF&nqm^Mwn58wb{+ikk6mHJQo^~}T$I6K% zw*u>Knf%nilSIR0*jjBxK^-k-jBIGe{Z@*S7+`1Mrhy^wO^xzFMom zouH(}%a^jN;vmpC`4W!EL(lc)Mu>Dab%nx7!x*5Fi+>JApOckQlA|uYKfavYitweG z{w*_kih8=Bfmdo!WPxx}qXd@w0B_Ouog%=5>l)Q`x@;QPrIyzIpeRcx@VE@Gz^VzJ zQ~AA*&DChU1{;>Tu*ou7)p+lxwt*@_c0Bc9*>j=DCz}tDYa84u!h*$9-00&*^aAaK zmC)@qwpivAO-!S8Qb!;$L%g*W=)PusUlo=Cc3L~!Z5T-{J=gnW?Xdmrk{*iBB8zmL zr9oe@)JlvbjOivbWX$$mIF26mPcQ0%6OffnkSds<{z$wpZq)@~xaQ==fb7IR@UMjR zbf3b-JTdTf;bdrxV?>x92MLYHq2&u?$7v4=g&1}B8r3G_O4!Xonrfdvec%Za9iVMf z@kO5Ld4|00%|3W;?eiM4PAq zXa~R)>;mj6TK+|`tABPR{}6zop)iI4Z*KpnSi!K!k6ZBV$S;5-3=9Cj4gm^aSlC~< zN9O8|K2-iyaR6*=Ba+!U8E*~LW%z%>9uR&GF`9?!~(Mvs)>@dY1uvJ2h5O;28NRY9^(qCw|9WD_-Q z-^}q3MKFZjPhBJ?7~&YG&vM6EG{y*aC+vG|^#{@Q%hTOg=Y*OYR{=%epO~Ad@DfY} zu|AM?iRi>hlu%`W)a!~QM5);O*eGo~us4Vk;tC0wZx5^Fz8~sJFYQs)8ZmT4df$bq zTXEBj)}*e(EqVBJbWV(y$81sNgvnn-C|cx@tM{4juy&6`*ny~EUS#*#1H5fqa= z(N!L}#4l6~j$n$1($b`@-=LaV@E@S>P=&p zSS)-L_wkO_#jMb!c6n5IAUIwQl|GhLkZ^qYuQg;`jfsos=wqB)V?}}V(hA?k`=Zld zcAtJ6Di0>i*iYIzefWYYvA9M<^65^HQ%~XVYE#boz|2dR86Z9uteDK$2-_y}b7jsyUIHC6hV zctZF_u?r~C*WCbFN&tw;Qg?tD&@rB_G{*yJ17HtX&6Fsl)pSddXomez?eD6tnJ;#PR!+!W&k9G~ zkcF8cPcUmm^H69)JkKeQF`%}X zY%PZ}#k>(iniVY5*CZKN*trXtf!|yw!W)mTeiU2ybIQHB7y0?U+IeO}g^(czk>(<5 zzd8dAbQrS;7DFBeJC}-w^>;h*O|8%?q(fe8P7XBYoGOV-Ikw;NF%mIU!E!Vbnv7YB zsM}21^zjmAEZc$5<)wN78-ol4$1D96h1Q|8+2i3>TK#Ulx$0sai1~I6lcAX{gCOJVgPY8-7lakXFSlBS?k@uq6LRhW$Gbep zROr?Q}m~ z+PcdvE~Ww4opNh!ZXXpDiz`^3pK(!%c=A6c)BU4+*{?LIRvU@{A)@v70SI{jy)~NE zA_^dP|3wbK0LlTFEG|HVaX4*D-=D830QjJP9!0;?IbF|JGXPZBbd`b7dDn}BR@Gde z|G#iN{`uqjvLD?AAZN}NNWuSu|8@a{zA_;6YKKaC-YJKU3GLufXvTa(x3|%7a8P8i zc73Hos|O7Pb>SVkf2Vy|4OGlA0{p8mQX`gP)==5-e@@Xsib;l~a^)r`CND0u;TZh} z*3NjWV+}IfNd$U)8R`q~Q_F+L`@b)IStG(BbC4l>LdaWuM`4L*Q;rt%#c0QIM)Gz| z6y)aY)jbXF^8!m9e@;zs;_TNhMtDKRMeGD$HIoPKkai1=;cq^^f40U7b@mF^eYe4$ zrkLz^{vMHE$MI0qdZuUl$g>I6pcNWyVjc4<8F4k_6BNN~YP$na-BntLgLydOnuu^JO8#!ktUp&I2V3nnr2S zfthFn!i9zayxNq=C&o}ZDb;VY1k7DQBl3y1IUQ-B2|0|kKX}?^eob4FZ*|DOv$@

    D2+**Mbg~VTU*@feX?l5UjBWHf_|67RmJW46CF%aey}CE^pyZcfQ=7P$8nB8LEGoFu@#GKr`TU6^$x1*AcXQM_0!ON&uC zSB2o|(?G|uhoA2N+6lN@wf&0z9o}&-Uhgsmx|TiL=2(|EOBJqE{qXe9amWk2DR=6wGtjz zn)`0`;U1!_?_cwI!$bja1HlDs#d8AoIDwO?=Dmfs_{7A8vz62p*tIP9j9O{^rWWBu z{fo8nkMzWfF(`H;dmofuIpBS6Fo__f&K15|e&#!Sd3NB*s;neMLqk(_v0b~c5~?&! z;RJBuCZaJFa_!J2E8y-7d04pv01mv=>M9-R8G?g@74n8*?^d3(R|+_@u`~0>!sdxyOj735T4?4+}To zk5?&9iqe81mc&&*KZjB=K(_@-tm`N453$ zq{`(y4y#-~&`i~h7~)FBU(T8i?&6|de#$E)6g?vqK7afr%4Yx0=J?*R$#aH+CXFYd z+x5dHt{2Tpfq|Bk3=gy0q_<9o7yPgJ&a}38Y>u?@v6Mt;?k?GJQ6N613|g85HBKua z!%;c_y3uN@u+%8P8#d?ADIB+8Wnp>5mt#LpTwxTs$7*P&?iVC#{NNsDe!<>)YY?%Q zm;yI-I~Pf)JKiX%Ys%mP*52Q3#A5qgX>jn+SrgWFy25@uVYSrR7tsuPF||QFcinO6 zkgfu3duy3(F1w}wHpE^ro-j@YE%05sAi_G_c#eCv zTAjAIUu&CSebJK`TKh?e0#R};6HiSt(S6g@ukiSCs7@LViHEgf9*V2lOk@A-a3N)q z>Fs0SQ1@7U&@7K-@8)&qgA2ire+!TQ*xV;(z%O2Yng65pI`_(7wyFIPy*XMhYn^QJ zh`(VF1c*r14x}39<E(5>+44D@jfq6V~FTo zQT&m&<*_&4s+Q_f>o3x_CPnl=M``1EUgKXh!QI=-%gfxJ=j=euB6kT~SAS53$>Z;O zlCY=i<4|(hrNz4q(3IUa6w9Cq%Am>AkDQdhw)BeaFx0o3wg4faH28%xl>mSP=zgiV zjdTHMbY{RbpAvKzL_tPK2vEfb0}%WG#k4JOn?M7cXNVoyS~zdX?$b+lS&lMU`3mm? zXPdZaOC@vk=r- z9Q8%;Et@^fxNb$zFL_>u!>hvV@-7K$wm@Ev?+D_kbv#ocyG04z4@3Q3HD1B@UoQQd ztMZXioe$}!?mOCdtA=com!6xddVK;h4k+=8+UIAF{hpO;ybP5Ybvs^e>2>g5Z}`y` z#vIsQgQvLKW}uQYc)MzDEQ2=JST$NlE==Byb%tqSknGv_qVgUuR>^JQ-e9--9#B6? z(F2sAFJ3KY)N5RdOcOem7HeHw<&a(GO6;!U^d=0!f&gRsXerw{J#ABN`hIF(|Mz}z zn976c))lE%v@e$ocvac=QZ112E>nVI-bR{zN|DEDGuez&&#@Ea-hw3Jb-9L-n_Gf*t+7G6d7Y{2N;wC1GS&wFWQuluI#&BW6{c&aI-WqNlB{E72B=o2&yygeHI$k zpPMBVB;@Z}%nGrr=?LN!ESHh8MW7kLLFYz6N$9BdD6@&grA_kOXldLE+b1av7W29%heHTG|D3zstTx6i5y zgH~Mkh+n4mwkhR>E+{a@f`edv{1I3NiuPI_*V-h7^_#MT?aNcx-q;v2jN6`Tpn>R)yE`O&F&u4scl{s5b;SzCIC>Ta4t-|s|vm&E^UtZy+ql$>~z zxobv(@pN=_jA2>trDZv8Rt(<#Qh*XEDMnpPvKHmbqsZAvR3@|KARLjY|*_+*Ftb=qcPybp7Secuf zBO*0`dh^#$fERB1Tc$yD-g?c-g8oQv}g=|aDM`_ERX_dK|gxy#FP#9ihJ+1O$ z!k{of6V0K$klH7frMmEV`OSi+~<5reu*D*V_4I}{Md)|OC>@!^A zVMsM1kR+u*)xJdC0462%`Y^}!bnc7mdT!3?^+{td9Fq&}mxfV$Aw8{ix?OaWhNz)C z7n*@oISHrM{}_t}2WVw~ZjNsrCysv^8?{|p#2fGx0RjH(`tOdmDNC|Fya+rKzd^-kvR8)BZ|qyji!6 z!!}*KgR8e3%hi;)i@f!itbii@k-jha^3eE848J3kE!RD@$kFacB9jB=4EO|0mfnk%rCw z==3TH8(TDvEy`t@W><98zh?xo+Kb1|MrdugLbcJm#$z#hb^|O>Q%TZTp~QryZNJ7O zg?MPaE+Qz9!aD$c*qjAnfpaD(C$Bmh^>eu5Q)pFKDV;lOgE3J;ymw_#NaFm+Z>*XC z39I!%$#8x0is-@q6iwOX)h{;Su?OK3pdZK>tWXlZxP$}|`qt%T8ssRiTm3U?AG^C{ zfgA!xiaoL0xI|zvP^r}Gm^e7# z(o-YTsR5f}(GvnBX<|Zy{~a<7mj86tXYT}pvU*pl?Uo)e)gR)JU5vHSMN3r<|6--P zBNSlB{%&AAgIdpFD1D@2G~6=*7jPi7lWAu%WJ3)%_tp!kq&M&?;FD)F>Dfiz*ZZAJ z_Dg@G)!d8}sM5@|sP3N&?^91cI-N8k$1sn~au87x=XUjwlwBl8ue!Ou0BzF7q*t!W z{Po2SOnKWzwz^0N8ubafS(S^>Py$*`g2G zCHWUDG9Yul?+_qO-CZVv&96bDh~>3=x8Y)X#}4x5xXlSG!gw3{UE{-9G-g^Vwz%(# zi(kyh_12!?uwY zG1aTm@x|YtA8KYGx;=02)obMqpVRcwpz=67y05YD2U5Ur8EDWDMy!N@zUOmkL2pMw z5<-HJ@N*PLxK+RMA6ZGZH2Dt*;)s~k6u+CZo!>TVIWt;;&e&wG z-}9>OV2k!yyk@yM9(pC~dCi3-jqdm09v&AbdWJtG8youUz&wTX_IPvjk`ero+wtgm zwic#%=Q4VeP5LXISc5vH^rT+KYIHc?;5@N8D!nUFA6dPl^n99m}OEZ}X}w@r8EP zwRN*qiw+jtl2uE`mvA&*CLHmC=1?s26JpP-BEgoVa%}sQboRH1{p}6Hhg9e-ctqL< zq{h1+V~=czO@ai9le_D+cjHnF5)SY~KH0n63v9Yg#;e)a^>><);CO%_#OKDU3sl~JS0~G=1;ih+Pf{7HLqjoook(@Oy)l|y{ ztOyV&WOK~W2?MAiO;SCbI>{BmJpj%}WClsJ)Mu!k+vtx${K6gD3?~XV$N`aMF;Ynh z)Ank28WMfbu>Q0iZqXbkPY@q&Vy?z}RM~^fy zo+F*o#uH%z$_ofe*bA}t@BvTUzP-?iJ@N%$U|i-7ZwO@4Aq^5s;ICgMg6S2AvmR&o zLZ_6J=R+i%4`xO&Ne6{9Is~?U*2f=9^<#lRq|q%p1YhS}*2>2iss6FbFp{=V%i#)7 ztY(jt4VKrDZ8d2LDHfO-SpEU;MjfH_qyR7Vz-wL&nMPl1pauQDh!Yf!dDv7DaX5cd zoNIQsjAHRxH5ib)J?d!ir5pyS-ExD20vxY!rJP<5@4)>L9v;q}ArRT20LSr)6Uc4; z8@RP#@@eM+^ih50<)E&*1*zpgu@b@zx`R6IeNPJu227>CEhFAFRLL*#y|~j}#_8+u zQ2CV0w8BTWM$7eq)MNr&m7JFX5lUx3h|8j$OP=W;->*pAsZW=h z!_W5mVvI!!1fz(`BBl+g$N4*`kj^pI_~C=rq_|0u8ANpaPv`+EkPuMHnwLNQLCFADn$AKY6r?W&yFYpC6yDzVSJxhFpK z71NX+Sg~76_C!VqI~eOqFy^dq@G4uw=A}!_MoqG+%pK>%X9!9#(j#0+v*g^`?X7qMOnL(01KG;t6^MI3_{;^N}! zYHG7EYy{$+jq@!sBrARN->kp!C`{wd^KSDrup$Cr`V0LPvtB7&TT zB`LU~$GFt?O&T02!NI#NkL7oR8c&1Z6;0ngqIwy907{r$WT4~r6xiUI2ltLR(Vk%W zUOO}zwj6bfP11%t7*Zj+4G6N-t+!1SYRxGYq;=16?=akqn&kv?D%{ex73C z|GDP{uhzi#1|$GL3w!lDo?#Go{ii=<*(*XZc)2>RU9?TAzqx+HOsmhJ{H6$w?kg3EF^r>gJts^-Gog_jL2P*CrLPb z+b6IClT|@>r8muK3e)F&yt^Usf;m~wI5D9$h5a_9^}j9BfmxEDknIcrs0XW=Vf%Af zAL8Kmwv!ZWZ)6Mo_GVpo=@T01Eb?;!WGf?sjagH9g~}}V|&N>kI3D6*J)3Ef6HaC)AS3Q7L!DN$F8v4CJ-L5{2b7&JJre-sAi5^48U9k|1(eqsd+dI(E>0U4CilH}+HeMf9kwC5o)PPV3v?@7F zsAo>5`qeOwxKI59PC-HI-y~qCG^xwx%7XPm8W-J zJSk~zey8r~xJl|Vdpj-h$&D3Ky$dn6;BN!vZxH4FOUN(rY`9!vvIk*(T4IM~#Gy|~ znXFlia0JJMZK}iSMq{_74+~dcYWC*C3W@F4MVV|5j#z!Xm%6qR!$OsV7>x%-KiTf|xhXMW0TP4zSi# z8q697I^&D{N=e@7X%KV}$}%EQs>5gbIVq;t0(6_f86;J1Y-~UVQn8w$om~WIh*!~^#hjVj!Jt+d9gn7fTW?%b?NSODj8@5?aEXXn{ z1~0n*6HS4=FIy>~agXa7mF(uU4ejqT1i$Pdj}oYO?DiKW;ozDd;%Cd&iKL}z;-~x9 zS^@XtpAht|tt5P(uk2H0&-BC;u_A`Y<&MS4G&B2=r)pPE&;HfUhg4*V1ah^#Uw5%= zPIu?jwj~X~+5#+Kq{r-Cve^#W)Zh*e*~LV^VRE0Bt_>aS=CZ#{_u=SMd>*ZDpe$~Y zuo7v35MHd-nXx5CmT_KJqaTtHH&=)itm|2<)0vZow#+a=DR>%iK|nNPgwWNX(9&n9 z20T3l1O=1NGA6YVMc;HPbpGTgesw6pSVueOkKlOR#rbscR{!KcBlU%P$vew^H>!(L zDP9h2OSfre?Z6jg%v|7W6{FVVRojdW` zIXRujZzK@Em57OPpcRSgswCHTnNMlX;hH36Q1{R3QL%E4y#3MNC!lObnoZ!8pp5N2 z5;b>EX@h>~4Y zTK8gNRKKmR2ZvdC)-jQN|wv>hX!%ZBOp#((`ha{o1Oc^5-Y_@%Gs5{~yjkC*VB#l3X;SMj&$~PZw^mm&2Gf8Om z|7tQrFf;1w-0FmRfxu5xUfD`(FEG)V!P5Ys5}bN#Ya36(Vd_ed=q<2n-8vM1vU1>> zK?l=-OF=S!`pN3s(AIcqP8h?`M4vIrr;##5sRw~r5%H$PZUS7^^r$mW<2dUdtmKSJ6wgUf~xfNPz5K#yq z$YXcQVCtZ#gz#NsMd5=gYeWCIEt^bJ??r@Bf@Q&UQXRC}1)g?s|mCbqu{=$HQw$Vn3POn{mY)EmN4N=S1A zV0JKn5t;sn%Jd-+chdkvDL%{e?dI^e2(Nh#ucHiG98-)o?+{BAFlF;Hq0{+LzAPJgLHxO=r>}S{U-zJ zx8NQFU3TlI+o`85wA_&Ag}7Yiy72#?tS=$N)WyJbK$t;7irlFm^a~#7UedsbiC^u# z*pmB~8#Y#W*OzS{&MiC0tJWC4q&|5eb6W}BuvgJ)0z(R&*}{0%FW$kLM!HtzIWj>E zG)GWbY1O+$yVZ{fkiL@WxVktl2IKU!bZm`!6xZ0YQ5f z^hR3+9sG6S&BZl11Wddy+RIdZ_(YUFi)vzd%9`E8gAJwOOpuO_4x`!XPa9EJ?u==w z28AM;8lrP(&M)Kqr6A>EG87Ug_-O!hP+|#|rs|$04W`Y!jVR z6{O4%=+?uxL+r9?ZJb(3K32`B+gS!IYL)v za;bvdZyV45y*>@QiMxPcb^YRYWdCr|c;g9ITq>0G2z-u0Nww(_UW#5STNx#nT9Gs# zL&d{d!a06AH?7pRGzo*Najk8bV1wWY(3eW1D#h%gTZPeDoQcR@Dks$|0a@#U-s}L_ zhf)CQ8YE7qYn>0?Hy*#A`fzh~dA)NZ*eh_NrM2i@pC7JONm#=@t$UUC;YsID(~f)7stF97A&pssw30L%3!{^S zR3QdBcMCR>9QduAJ*_#FsB`nocwIhLk#viM8I#HL-i@#IMu$%jR52?aO zZd$?p@UY!ndCx!qu}dKdk?dxV3@rKc3p0!csL3fri4@ zu383^;hSN>Yq)QvxkeG~A3OB$L@sj(!I@&jJP+L6y5RR{h`^x7(qqRu-le zzuwgLczyOi!$%Z9xu&-Tym=&(u>SsF*-?DF95-ajex9=P%A=dVH|YNE;&oRrS!Ir< zg&3-NE+sjs^pT4hUM^A8lWfS5JdWrkxk?&nOJ8z?Ixt$w=-sz?C$EHXJJ4su#}k6? ze;h{t_M0l~Jb45$o=~B%#oS`0_ILR93OT5J@7gc+6Cc(qmXp%#Tp_`_quLzZ&q-*` zWHr^6bZM?f&m;5l)OJ)B&}}D2X4TO&+QLr8lkc3e#kBfiCk4vS6_~8X+tZ9X^0*z+ zfq%8RgyGvanvSIhb^Ggio2zBqY77H48;nWrJ4@k%IcJR_Vakmz;Wsc?=Jnr(_w01d z!&5sUf>;muOQY{}&d)*5M7BBA5lWjv4n9ufQN|2NM{bLh-)|Ws5c+HU2#^?EZLLMV zn-9m=d{QMF{5zjNtR(%d{!v@Q+ZLaa#C)3#-RBK9N)v-pl!Rj0o1hA6sgf)83Wm<> ztls@-&jRY{7vnLeK`{*K#@M0?@9x}>@NcPnEL;<&*CVEUA>>K7 z-k@f0MmGk?PCf5pY8s@S%fxDuHTB{w4yb&|>G0`??(B?=h8yLS6vgFHmfsb3GcyKT z={sB7M~w*U^T1KfA^+ZojT+=Bcr=6sJMB()z7WOTI zM%3kF#`RmDeoA4t*fHQO0G#Bp!iSh!?axH+V+;(8p|MQp9zSkxTV3xn-9$jedC0pF z9pb<0mTG^dX7rv!ag{S%;$6AM+Ujams7hgP4Db&$xm0K$AcPpw*ElZzF4=vP`nLg( zm4$jJ{r8DN16PTF&+cCAzu!v2$}agk*UG#tih3_i4;k3cwXZeHLfrBmri(mzldxMA z`!dTg)h^!u@iF^RR)gt#Z**MW{HbLSyF=w6BQJjdXoC&N`ih~_0GiUGg6Hhi&>|}% zw=w1Dh+{Er<^9&h2OPas-U1R5TulwSfRz#E-Ga&u5I-cmCqzdvwYF|!#)!0G!V7vs z@#sMPNh*H4g;yg2qp!p1C07j3n$S7a9$H7s{`c zj%2(0#yGQT8>TE6vYNRayp3jv+SxvH)3&`Q&@eAH`GiafUT(bj}W} z(1;ti3Ix}=NT&;iV}oV3hpokj9TV995&c(}Y<$K)p9|yfhI+rXc$8yumPeI}XmJ}c z=H-vSH$`f%oWCoyMEyWur0X_X;n?5H8ImmnZ>Or@VhUU`pTONP zNP^+r?Wb3&ck74Vte_k2iDl)Uvg(UJ7c*_1fxlH4+gcyuBN1<8zo@V8ZOSgi7~8B* z5Y=il`3k-IQNI`Ev*fypsJquiG#k~VKU%#@QaBh{%Ug*}A17A*yIZ3-syfCnT^2y* z%uX=(L^&NPY=@zhwlZLFq0DX^@hV7LbD=pF>Al=;!(j^VTr9rwo-hIFC@6VY> z=b3xX*=w)$sWs-_E>@(%5uu@EsrTz}*veM~$6kDKH~~>JLq~xMb-*N7r?G;JCv|!z zLArWfEH=}@2X4kwwSyvmQ(BgqtFH9qJ8oPcyfiI{N{c$3{-WRr2H}r%F3tVR57wg9Ah5>ukLahd0-6%E#Ff{Dw3Iqd3@CzIA?P z!lTZRPZQ@cxT^x+rHU#ISq$(~8@@ToX^%QF!S@L!xrsl7Zq_q1Ui6vw9(RjkvMrTS z>~DE}A)mmVlQu~l+=w9v>ODSdq82 zMhK4^@B*+FeMVht4#^0?%XU0&Ez3-7Oo0VwCGC&lfxS88_#&D;Y`iYJSpQs70Y)YX z66BJT8_UT?XkkScuNiKS5p8Qh;Gx34yMF~?G@#j!VbxXD=YmHGa*x?je~de1>e53I zHyAr$vTJYKXI2%|e^k{Ml31d4ST5Z!b(Qs$`KlKP#X?^wGkw5zD?oZurI7TJ_x$?8zlysg$ zf&P7QS^x9$D%s3HM`;eyaDQ{F@W}b`UXx$wGucBxaYoGetI&YwPB@{L-Z#K?__xXV z0q`c9Fs&2-XH@w$9qo9M-Dj|O&Z_=}igfO8iDlj4T>BgtPt3SRc_cMt7gyRv4AtAh z2T)Y{L4||>fS(+2!6+uC<9RBfqX3rDopJP}pwXS*66beuqOfuDx!r0-UWz@M^Heu1 zBN3fYs^%FqIE$!G&V8l(>eCLcG87NNO82FG=ol^csoDnL8-1l>gsZdLRzh^u?^cFO zKt~CtKD{K-nn`!N+MhnuC-N%sD6CEG?LvTXwY0LLdJ{2?wONfDUcR3nsGzZr#OhwC zx-}RQ_;XfI0tm8)LY0eV>F!i`A#|wEyZSKfJ%av zska^BE3Mb_tXI+;_@grV>1jFxs_=r~LIg}ZY>!Yb`C~Yciku(0ccgW7i2#zRA557u z4u9yLevIq->aQftXOXl9Fo@8obWTl8d9>;M7a%MbAbPtPeq~grB^TqRiOvXpDMErw zW7Wo>AlDSD+|kP zY-G0LfC}#LFB2aM(fY2~nbylgnON6q^h6}0L0e^SNi27}hO{s;Po#pWLHG9ajMO`X zGiR2B2(^+#Aa1Ghxp!*^gcKN29dt><<^BrvI;$&;ST#spovKCIHkY6C_?`0rOfK2V zQxloBWLsjfAzf~UK0%Vq_~#-k^Em$t2u%9(WwcohZIsj8`k`d8;3F^g7dW zkebZ2ktE}dm+6R!9%Ug+GJkY;B4@r6(yU^=qP)Jm>@xijBz*Kr?_DhQE3U1o&ljgT z$rU|oZ2H}y{lF&c2gw4bEkLzpS>D~9M^I1@2L%D~)hlQ`cN6R~@*H96R`+|+@laJf zIx1OdQCUJxf-aQ%0+YRvAP^v zp}-O~q|x}^jR_BRP&O3*ljHy%ijAeUF*i{k8=BUGFN?g~S7kzS zFCz2a07sM~r=kXNsL0zlYc*MqOfW0ozr8)P74Ck_8#uj+q>uL<&)?qfj2nEnw}C1@ zHwg606-)tX`yVJYCLlnf#^L$#P~ah)98zqs+L|e#{|tVZBY+DX!8}vh*f?;mAT$U@ z2=?)j(bFECBizK@sNW`}yGl4urz>p-w|V+hODmyuDxFq!%Z*oEp2DAmm2e(>Kl*lL z!MK3Q>yE4;FX-p1bqN+$mNPFPx&Rz#93zfm=S5XV+~v6B4z;%!I1u__cNGb@XZ1cOJ`Cmug> z-99dQ8BF71;^n2K22~mkO*-PaO6SjK^>(4*Q2JB>9-dG1I2@?n?bsA}YjSdOfN=t% zMI`wDZXSITz89+VB@LUFsxg8u@$cQH7_H=%Eoxw%-an*dp#{+>I=u5hg1AB3pOT|2 z2d{}1xCY-A++@nG4x@}n!aqgP(i-_y>pQf4Y$-h`r8_W9EWEMtiOp&EFPfKcD{fMx zX9FrTpxc54IeY+)OBjXXcLBt7XD8~vyB#%obRMkFpspXjGguK<)dIjID& zD}z}!tV7Xup}^HR>HIs-7ddSMU6|QAAq<1G0+;;@>lts#(iT>Mux&!wQ?`mIc1g7qqwzX0HPQco(fbiu!lEt z<(Zpfl-5Xwk~~Wt_?9JU7(8-dPMu`Kx-PzUOn~~l51a!DKCsXuTI!+|r_#8n?=pgnp0#>GFUcKLz($$QXOK$`5~FPJmK$( zDHS=J?XEa&+(6}jBNVAN(3f+qYZ3-ELP!)S4#S!PRH)J<1vXRE$6_l51Ih`^klq@W zE6U%TRX&DgbXPPskm`j4*Zy~NBe6TU9BZuMzToO+xWXjmbNRfqOuMooWx7f{-hKKK zOF=ziZPakHOl;y6CP{$g5knrwCS*?K>R22#y@47>qRXzX8YkvUvC90P+0bHow9yd< z0|WolJ_*{SB*K)mjrprX4Ni2G#5xzElD_V)BfD*N^$2qgrt-2iM_x96@2Y|IMIuyd z>x+i^_M;7NYJ(cB54En0Vj!w@wExlfW5?5e$C$a$IiWKty8#+o=ZjYSR{pk!-&xOy zHGX`kdHX(pi6dTY2{$4QWC3ZRQG2*^1@?ZMnw#xXAXp*yt$eKb&iCcOlAXQ%PAVqIX@XxSjx`~xt*s3df#3c8O^5YMBefza^siC97Iw6mPPWz)qo!w~Y>Do*GRM2Ic#w)8q=9b(B;{2*UI<8z^aaX9=XsS7ZiN;$f>((cwFflQDoj=gRax;Zh zduG~Pcwo;;)0G9gBT$x{l$5K18LBR_iTEGf`l*LpmF5R+k#@Ym*u%raEtv5c*f3}# zm~3$C?V)2}nt+)zPu698co(vBKLSa^XX39f#dhNY^dLt0JRYJ$yG zi0tlgv7yMsph>%jUauh5uUws=E;cl~mP78;)Ko>B5O7O}!)9O@sD@1^ZM&wc`b;TT{e}nx#7IdIBy4&YpK|E%h)UV$>k9TtK<`$@N zArd*0^x(JhplNJ5eE{|ppv&toVZge#q7--pU%g!eaoT9;@K!e{2A7_49C|o{?oB$h z{}_K0G%Q8+Z@~Irkr!WOB&O>pd|4hZG?m2%!7aDx%eLAUk#)pQl~9;&sP0 zLJp^0U3g!ai&-o8=9xLDzs_-TCR_SuEM`^T8^vx-@zgj*neb_y-Qz}nH?sBVuqaX# z0*z6f+C>UM`r5YJEDwQ>+i=Qwu}S&8?Y@e}SQMiy9~(~?+Ojykchq2F63^xQ+V;!& z!(xz#r?%Efi_UzR+IEhT4)>C)b9(~{iXuZ&RUt#-CA(7L3i;Q~*Dw^_s7j+8f0_X0 zQSkBMg7o9)&hy^6$wt(B)V(sDy<1cXrSSfZRuBVb!5$R`z0`|Dg_H`o6J0*tpC0^; zIHV0XKEGLc_Pq;u_ITiJ!A5?%oBY(&`Fqm`{R2jAA;a=3Ob(Djbk{d5+Zwz1DaCMF zCNAJmh>wpCIYg8>hZ-ia(OqTZsXj(m?;QdvwH&KP6v~07hnT$}KICJD{*Vav-Gxocqt8QNec++_RQS z<=9*fLqeY(?{8-t+7UXzZ46o?&?1|enSs0jv&d^e7J!NX%L)LkXiCxH@mnM#1uROK zCJa!ifCs1s82Y)^0N#Jy`UK_g8v6oUS9avFkVHr65|*e&^=PrrZoQ+JBW34@gJpa| zC8mbF&W^no<>9>!*fBw11orR&}A%{)}+Xr-rB@;mWmz;LK>->Vv!s?GaxU!Mmu#NF%`*xLb8FX!8R_+gR}P>N{> zsh4PBi9A4F&JH>aAXTqmP{d00E>e7`pF$f8AxH!f5s`q9 zko{1N+LVK57r3T`LDgo1~+i~!;Ouxvt38 zH;|wpv{1Qg0w9KaMaRE6S@Y?#9iE)cX2r!oMm_}eu5nVqCF&J_CMN?xi6V!E!tnEe|K-oj`#H~ZLk6Y z%d{K*EG$IiTY@}WE4i0pJ!m8-ON1$Z@y9cf^diTHLdqmMbuOj?Yw>*|Jn|(v7|IiD zGrR`@bMG`089^1LJ6(o_(6{BQMv~;C!$U}?b}1CY#Y#X{O-dULpl z+kkXinmJUg4nRq^>K!v%I;Y*7b~>R&9|ZaYsh$DH?bmxFYy4VYgM>~$nnIL=gI6)< z=!-w|C+Ft+{d0aYL|P`SBc{&2e0TvczTMC+D=H+b$+d|6%u26#?S&-D&?| zMa*E-_QQ7S9GgeO@)-3gud#YqBU>HB`HQLV*F$KWUrthgLBpTLKcZl2${@|Ct*u>k zYLQ**krUH6Zq&K)yLP|ri$ETGxa(N^SKx;v*-WI#{?XItO7ziHqGU`A<+j_}?xj%_ zNJdeVf5&EB`HLm~ddI@fj(Z0^P38esEz&$pId!DxmP(OwX4%ld{RNbYCRSFF+uLTK zE`hx`fC&aY2bjb;60-w@{XuCcQt94uij&C$Np1Ocb&24ndry@n^%j(Zi;D{|@;18s zi`TsPGF3dOsnpa8{zP3JS95bS$Yucr1F>T6vrrZfu8$%*cX*DSsKm9rXj@D@=s=EF z+S0-LZwKCyAI#e2)TgH8x>YA&sg#+L)&h|@{r;Zn9ft_R^vrrqb+^`mIklgKrl!7q z?#sCWPff!1xbfAf@C;8HnI;`>)Y>7TA(o_lK5`$COk{+dM#;0wcxJ^-YwCeNp2MUf z2Po^@S>tm!L%1dp#l@g!I*oZg{kRPxR$x|7*yL5HJSrQyj zPUopGq+DU2Rlx^|z>IgmI|ADz(i!j)9hEq8@cY0#)}aLb(bg3etwnWNaAUhuOY9&G zq^}!hllgdW{`{@N_p;=n;rR+`bzmW`jkTHVT}Fgkk*K8KSgmw#ap5kw7X+_eZ?gt{ zTJjr)8ESSuKHm~O+ouTNaN`r#eOaKAA*rAkGkK#D>vHy(AlMo*`bq_P84C0y=0Gju z2U`(CN=gb|#0l&3R!6T@-5Frs(nOeU=f!`DUl2Os_0j4HZng{8(?a@;K#&bp91>6v z1Feszmlx1^nwprvgKGe&_Y`sZNX)ghwdG2hgeip8)z#%DjezPDXmCGSTQh>*5e$Dd z69;8#>#lBYf0mbZYZ_bQK9vdJ4L)N(mMRu?q<;IbuwJ59#j5Y68N!lql;an7=nlX6 z?fvUjoLQ4@D_M93gj<$ZSzL1O4|_~Rby+Y_r!}C1m#pG=3T?|e*@_01mV*bF@LfRY zKFUouM*?TXG}e1M98zKGCGg>dWgE+BnLr8u6N$CpKURErXs-g9kkfM=6l(b8crJMG zEALlA-@O2J7M6Rn9>a=uJ;wHP>JzWd9nJAZk1)iSoajf3&%bRx!=;mwmU8nr*NloN z;n)Zx4m=Q;e<$`Ywrtd8kx4{>^<59%5*1iB7#x+R{;2q@Ivs)$4&@C2*mH8iuMk}t z??dpLw3vS0J#L1DPR#AFmX(#w+o;)Hoe}w8#(lb3oy=`jWIC(sZ;tZPjh(DDp`B}Zy{A15c+I1nYgxLP<jz+TPfB6BGFt9`e9`F|F)^rR8?UT9TN^0clY;fY~ahl7s{&meZ6vg zoyJfFlpV>x=0S_=$d>^|iHVh!=p1@jkWjA?d%8Rw;3Pn~SX^9`&4C`eIo}^PfLy0j z4}tWLek*7%TECRKta>_WOmQwQEdfP3%(kjXFYe{#6{X%nkbdaaBFzZ`6cgxU+gAF_ zLp&9+L`5l+$9Lp7lwxbE=NjmJlce6t#%E{#!Y6xNKla?JArUB~E3*%dlG4@8qg3GD zON6Wo;N#<4hZ}*W8#EIJGW3`dUic=E(oP<<4Zi=>+UWu<0<1T~NeralzRCY|)^@$} znT=o*^Z5kxgX`Y3>keJuOCXWWe+(G-QE30ZxcCi5*ax7O1NkYm1ZcA!ZjfI!%W4^>&HngN%k z|9q+c9$0-U9v3SdfoB4g?VFwFhb&+Qgqi8Asj;i8 z=-9v!1}#CT;l%8$Bp~#_&}6gRj0@@&XafPzlGoIf0-OVH&=BQ}YU}D|4ubyt<1A8% z1g{Vf(_-KYiIalwVLQ3?h7al@O8cP=H;G~Y%d>)R+BEz*>i_fyGc$c)T;Wzp=VI`r zH5ZOB&lNiVOqM48h@NtQZyZO`S*m^sG1spDRf4GkkT~u%t_T-)$;cOlQ~yep8isw6 zk)mf`iI^%pie?+ML;w6SiteWhrzm;o)1b1M?`<;UAgobHdJhIR(BJev$dTPktkwfa z0v>MDzZ(XBSyyUx?f90&tj~6C1lqI{{hD8V9HTjfS~LohP4lr{rPcX+7YKhF=IMU_ z`#lJX5nrUz;6!a!N((^y-;Uy6*2LS5P@oZ_A-9Jg1(NSMs14VWT(U@Ll>( z9kl>8z7{48uE%_;*w7rTN{yRkX6<*RM;oT3e-ZF8#QK$r6dn02N6iRJROpv%EVSUg zmbmj}xXaV$W0oE{vh$tAlbA_#H4J|5n=TqjXs1xGkecV!cCRl|=?d!BHZ)9um!qJ- zg9m{m(2>^GTOBOlqlmW~zA!!Ns0hjTBHwi1dB(VWo~ayPoSd|tWp=_6Zy(zdC8Q}> zb>S@{n1i>!oXxx3C()ds3Jy?2AA9>nnk3IkmsFw%j{=W7%w9dc4Q&vO-GhxN~|~M%~Vuu{RvqEJ#@ZcY&dPh6ISfeFNyb861&Px-|r_E%@Op08C^h znvevh6*_sE8=}1Fc$%LpE}o(mvxPZ{wmKe?o<*}2*#=n`Xr-@)%da_;mRx+&zGqQ? z~Xnw>fX!>$tWA24<1`XRQ!p!VKcL<1$lzozh-@{aEVL6s(&7j{~q z#HYqP&$47)#H5#^?Q`u>+955NDt-WZJ4`Y?ag*drq zqAU7knF-B2PWPHq{GdrWasm#ngsLJZIx0in*qhr~fv3;DI%@dE`7*9crK&aHa* z?kfoVO-b1LKA6v5H};A~h&&l6XCI5W|6Fc@+;r6hxf_|-J~FDB3gx2MK@%XJI+kV#8T~-rCwTJlI+L53g07laVz&Cl^hT}_PbwO?Z{5N8;VpB z2EVx5V)RUWyEg;{08+yU_Dz|;hBpi;b>Y($LqvTe2xdi=B(Qp;X-r!_Iui9www@}> zRjwt-ejRPcUkd-3$%xTdruvVu;F@J{-y0xd!yOq4>69E zw;ikln75hJ<|F_B;>+0H983VI7ZY=HpFk-Ame_;EI>_LlG+6o*U=4?y@*Q{KwNW=Q z8X_`c5ZCx6I7Tl3C{cPUk`$v(0{N>JEEnYc6e!T{dC35hyAeD82d7(y`-u=CpGjjF zgpbd3m?(F|<;mwh6;Hb9{qy6wlW#kWqafURj&Re3UTq#g?sje^>%pSzSfAo8rVvR& z&UIhpl4=0^#mdqy0H9%cc^MWD4t&m`p`jD5%NO@QV#MrXBE*fp=rXRYb}jK%`gPoX z6PbyoPa0lxQ%7x%TrUHBz*{~0*?MXCcDr8=uSUjgf7Ny*qEb#?9k|`2KaShG9pFED z33f3r{w&2vN<0C2Eucq$aSQ*SH7y?eCX=VUE%?UAgc>*NMz>xi;hK^>0ZDlHhvZp} z9iSy+pe}rJOnC35olZ+lYcv7y6=kLWD`WWnb-;hGk!D;oR2U=}5;<)9Hx1Hw?UlrN z5@k|00!GbB21nw9aGlsa7k+@@P#0e%?jHHH%|pOW&zh3f0;h7ZmpCj^$&j6VOU5id zZUikM}4ru z)w}s=?5@`(2vP#uqrrg(!qoNdzycksS zQ64LsS2;gqb2wCa{>R-hIFsnREY z{xxO!CIbG{Q93jpW3nM_|00sc^@vxZddb+ zuk0aRlL3ll<1~5S^ET6N`fBsmwyjZ|_hoo#H%#}BhJn#uba-m^`aG^bhf`=9_2 z9~mEa-kr$ak9;}wtCZrQuUiib%ZVtx&u9%myz9#BoVcOv*$Hd990H%q2TphvCQ((BuA{^OPc=K#DSG zhivMsc60dSz-ALg;9d>x=1>0vSC*3IY%9N$%L=~?;17Y_z^B0C#m>go*>Qva4B~mo zpQ(Y&4TeU~>8YvmC`&~egK-zI9WXQPxrd2$u&2F6%FlYOGTMLCco?9kt?=GrG&|`8 zT(z5Q&SM03l6(QMjdCsh*r%8-IoYT4K5HxK=%2$iX@;}=9cZ3gulDh4B19w7n%>K0 zwqp+!9%B7AQ{nVsc1dj-fA-?m+YD~oGsZ`$@)oxJ4;a$^=RO5Wv~;k()POAJk!SjMc{D3V>(r~j-_z{0x3$zxHWfaK!(*~V+UE13| zbL}DDpv~;?0Wm)SbiscjMK(WQv30&fhY9dmAgTo>&go~a&JEVc7J9Gr4SAgp z^}g{=i#6wG1uyI5tB9*srN|a~3$TZX8}-lfe=6Tl5Zc6Bzl-YowdVA}R~h|>>BcvQ z)>=YCk23*s=9n1Y+VY)~Ma7Rt990JN1&Y-etCx9{vb3h6hFSHP7kRd7;GnB69PC5O zZ*H&KxD#83;kbuOo>vq&(y!DjX}`WSAV9Qg8d>>)$2ncc7AobEII|BMi z0{+972T*7Kt(_#zce^7yPVkWuzJ$E>UOYRb&s!6ei>g5}m)EBUTHi#M(+|wHzgG_wJb|oWOO&C_gAN@Q^%|l0 z>vt7j`bg}6#!Zb;z?+Bj6?BjK>wS)L5h7nSd2rhjbT4;LP z0-}qm>OUfq-ks}?t==x$LdxSl#;kFW|A5=v(jxcKaqBKg1O5K7D?K{RJu)A>$ zq(y;qrEh3qF`&}VPZAx9;wM4?EI)wII`#Nlt8e8paycKai0e1}ao^AWVny<>cCx*o zpy0L*dM_A1xao=~TFn(nv9lLbutJuX>77XT&WJd$@`p6B<~xk(!isTVQni2Dwudzr zPe9)qW&>@{fZk?6*I?ODe)kQ2)^}8M*e91=WQ7c26?$zlpFZ`wh6EF7?uT!bsb>rY zV4QxT2ih=qIogm)4=ng3f5iassDPRwKzKEuiEwY}3$^PLqvqMbW~R-O(z92tLHu95 zJ;BC(WbXy?j!apcLz(thmujX?l3|K1Y7Dqw4%I~67)oT!#|`7vZ$f_t(r*KxymaA< zDlUGwvVZ0VGMF-sUpC0O#l`<#vic6qTIL*u4LD#e1sD6oHO@we zch`=-OBy!IAb1@fo3)_BVt$1zUobT?@_O8oA(0BSC!l1Pqbeq#)0TR|Gy(Tm@U6Ul z;CW?+@qRKyNE$U8bp{dtW?5?h#r+yU;J(?6aqGR(O6GKxfTRp@EY)Cg0+>(7zr)iE z#N~;UAr`hoeNk2%ha}+$8bujX(W@8QG8j53oRR(Lq|2*Lfjt2q;{s*z){!HzkzI1b zjku(euuW`Z9W|5P8NTaqJE?W%7^;?OFslWsu^L+Y|C|ZCqK&^B&kS(Ds=scZQGYx{ z-nV|c9&_MX67$fH>DAEw^}d(@F_oYN{pHJvSqUak`GL^AT(2#1e5dEo?L9v~WC?h@ z8LB{i?CkW{)GttBI0c@AsXu?ZK`Ie|yv;z|HppEA8V*390YEzxyfOs^Ou!`pMHmUj zE1(sHHKAi;V-0h6PxI_d_n5J$4Y4WdKLtJvHtJFS2v_==AAD$)S#czb-TG;*i_y-F zMB4ax@%QSOez%k=K{RVz28-f@Rvg_Bu2wxrxC`KS+*zEAw>^MD$D`F4U;14#Kgi<) zZ9STHnZ>JP8l`ZD%ZRrxU)n{J+5W{(C0t}=)Og-`HaZB8nr`{CtN&;4TYk~cjjP+_ z!-HQ&{D{fregswkcG&PVN2 z%$~^;Q_!f==m}$@4sV9>ybbCvwNe3Ievy3Mo+A8phdWMNj92x>{fghMu7JsW^_2eN zK5{n^B{E-Wp#f9qR@$bgXER|?{ji#%*X(SEOOEV{RH$mz5TsWs}NR#zOk( zFKskPX2T;!JB=+CRbLa4CMLMR&Bq5a2(k+bcK9%lJVQcCBk}jFQXX)xO#wU(VD2xc zbW)mdRk0v<`PbAxB7TB}E3uWGD5iLBsRxPfoVCD#t1gc%8TaNeP`sYYHH;|V3Y6ag^fp^DT!YCiV=KCpFEc$|TnPvK&uP{O zmxn3YlU~$oO+4}%=rYp{Sc}-OFfqNDQ`rGHEod#ypKMeTM9CN>0K4-hxW}+YkS;-b zO6+m8T^}?Kl9P0IG9o&t|LF@HQw`9C+l%Z$nBLr`BtRx2&FQknzcArxYHG4qWOyJ- zoN6rWFCV&XxV22WF2BtViPvRf>#G{<8|=IMfosZP$TEGfPEfs2YAH=`PB&P`(%Xh> z{H}ij@|n?XUww)TzGr;%DVrv z+1%vU_qY?eh?(;WN=UOh(;xMH&=wYh^W$k`n)&*59(^frW+>;Z%}u{1zw)0X7rsD3 zUwI+tmeY)?B}Z6Qa-Pwya7byM@QNvAG1L3?8pV_O2oLIu7CwiaYTl2^e-EUS+5Fz~(IwOm&tyk1* zj6#5tuqMd|<|wM*=%FFrnp6e%^*rMCcL~i6@&h^{g zwCc&kB+=`?OJLp7{9I=E3k^I9y^4m^g`>Gjy9xt8x0I36gzhPYgtPlW!84?`g*RK( zk)wz`Jq&A=BF}B3^v8Z5=}{z^ey=|H*eq1T;%w~a5qaJeMaW9sI(Hewf=>}RxIq)V zeffHypFIoPnWc)kYP)jjkV_Mi)_56S&}sOppTFPn4qZZ`LcXF|KQC$-=#9;?v)jc~ zRa4vax_vu7SeP>4aumzt>2TxL0Amb*#FB+-n{jAF}FcSbn zYu7Q9bE{c%8ao|SbS73-XW;%OvW}PJ<~%ET&CW=5V6>*kl4SjTy85}j^1oQri!QD= zd|*h{yRD{rn87-@yrRFvj+9(#ibEfdlJe8+(^2S-+_$RJvc{RY47P7$j%XwkeTO_( zYRV~BLV3=NhYBcpFna+v^Jv|h>pTsnvr&8Bsal5Al$14mAO(T#oAA2;3bKm}7rFWn z3YWg7yeUh7bO4m0MY=g+BN0Nx)9mJS^6Ba;{?i~?Oqei*KNzJpPN%VMxYI_N{?G@0 z3f#mWdXhBp%DtlS>cmGu0Q*LO7l#dU0cMz~=(W^5$u=2ZY7YIY61?85sehcuO%zkX z=+Pb(aa7NectY#X0O@)7ZU2A>7>tL4=Zh>5IoiWE@}J`REszOua&f)J2m?_@)Oe8W z{btQ?8nm0Bl>*g-)%O%)M$Xi#9g-MYT%14d)y6eKYxhlZK@!LqfcY4htpR!i^vM&; z%RsV3Nffp2)&iC~fMKWJb}1AH8&YIpHoY2y*7ALD(dzl$nv!|$Ql_S*DdB_w_bJe# zE!5klr65$AkCXiu(8)}9sSnaB!SAzPtXFJAr4qeK9~!5c#=}d(cU8Q%iQK0<&Ryxz z!+1M%#g-#DTt~fGivLyHNsi#PR6++`rq>6#)+aCG%apUGfx}-)SEHl#Rd6W!UVDdSmBfYSoxd2)Gq6d0H# zz*c#ps8qP~A3yM>jO0yzh}5mfzI{Up?%aKTpd1Gm5saTayhMJo>-5%cvV&xuBOl{@NEAp4@&?2BJ)(!b7}LrAiA9Lc{wUCq z{o+kEp0fVo%_2E=gpKi~3D#T$zDH{bWaaiN*_hd_o(ko(cj}KHSlJWo=~pPfFGz4J z@O$dNr3wdnEhz z-vVOh9w|PF(dw>iVJvf5M(lGF|EToY&*2(paLkvz#ImZNL)qXnrW2T-ewQ% z3i3f0E;DF&aJkB=J$YDyov`Qz`kiKB))BtWbX8}}$_hgntV zHxLNA-f=qD)WDpefRO{a8^~cj`FHYDoFLL9MfNvSPN5|c81KQ_&IJ`0x;MyxItA4M zCa?mv&|3&FOO`N3Ep1cIe08I$Q9{_Agc(4)|i23&IMY0<&7`8XhZ;96R)bb$4naRlj zJpq~_BG2q$6y@90p}E$~w+#z6;Ix9j4UBR&jNP*$vLirEGKvriw95dquoY8_A37A5 zY^(4C0|p)hV7>v+mwj?lnZn%x>{su3c|fKCU`c@B z1;Du=4-tssxR&rNM}TR>>@d!S&o+Mn%0Lj>1+rCu6odm`_i};tl92S$r^!RU*L|y* z=?s9xRHyAaJz^M$(+T^RgmO;8YAnJmNEq2F_yLktevYkCID2PRgZ=6sXSs=D_Ol-E zN}D8&^I8Q7FGV&bJBF9OU+Z^dNx}sZ=Ph@r*2^Dr{u(00n;QO0jH)z=!|*cW`*wa6 zG0~50Hjib4uR&56B1c|-vC7rHUYBsfzA`71TI)seoR&R=&bW(Ycj2Ch2{2w3owt zlV8C%ySJl~SYOZWEDOZP6@!0(`4OlJ0S5+D?(S{-x?K05Bm*I!E>AgqBy5Um%2-)h zY52~&tf-MkK=LKJYNjU9RT7*LH;0~%{fT(pqfZzMh7D;jn0&CH%l%JP> zOv_zdu*l_2Pj<>QcXcI!S`iB-qD&RbNX;pE3*q!oB&PmSZW`(~ zBJZ6$5qRW0YB>^JsxjaAvlYWa?#b zA-b7%MVO-AyD#$JMT!tzl-TAJ15H?QP;vAb;%|A>s*5r#LSm{^Z#m>mqqimh7gg1UiJE;!S0wTHR9r|4%FiR5Qt(w0 zAtI<6Kd~4U*^8YiDG#t0ZjAJ3mi}WXj?|+!_L`UJf5Kp3RZAvKmC#jF;+nx3SS}Q_ zS)VatS3#Hp5y(k2t`!*S} z#<64iVOcmpVD@4T!P_LHrBtnqu4L~p8GtoKo%rzWrJbNonTdP?%<~U^s#R+HmM0G) zgw);~V*`U1Aj()bZtG49D{4{ChgPC(U9T4PmgeXlC@+EMV&!?AFT%MTn$&8Wy^DJv z>yt0RudS)M_7P0rHolTL|GqD!2&}Q-L4elczX1QDfxtcZMWd=|k}rA6>_IP`W`m21 z0c{3=1n@J;PI;ldqayIry@BF5#)m+&UsngNAqBu~g&JaEgu#9Vcsrov8`Ug?_Zi8` z%B}*#2}sTa&C_o47+CTHMm^xETU<;{DWmotZ?IkZ4e|qkVg-i&zeA<`N`B^yGS@0E z@yyD2ymgEU-V$c9`YL362#(>F&S3E_d`GjszS!@{)Qc!(Itlm6Nl|S~-g^3aj`4)2 zS?zL%E=$a(V|rJRFiPsdGv_HWx*)D?jS+!x(}!pAY5Tv2%dX-D3L;})r|2TVGR}|g z(aCkOgNTI#U#>JV&ZqkKN-q2lBrmcF-pk*KPUz`c|y8wBgjDM!c_iI>OrST)4U{NmkrV6SEA zy)Ew%X;Psgj`&_va8nffoXLTMPq6IXx-{07`tDQ^j^!r?=rHvW~ zK7Wd4t813=bd386wbyzY3}nmp1;IV4{eeSVp9!mezp3*XagEAWY*sOp`yleArb{cY z7g?WG4}#u7^SSYzM3Zv&j}b$#zQdER$EhOYdB!hbbE_=2>bzzV>f}!Io4n=k_kF9d z6zfD8go5%K>O`~A3igNRDg)ih_51jk8|A-f90biGMT*^aHO5t1ia3g@2)aCMXq8Da z-_a46*H(kb?gEWipSq1FR(?qX*;4LQ)bJh>E!+q z)ETfN1X$sK(i{NbU}VczW+RJ9EAnsB8B-Y?8y#imjDwZ77D<}zj$bmvNJfI8oYTrd;|W{XxS{!(TL0-T>qwnJM81_}-X4MWJANQpkXn(S=7IlIj) zC$HDRo9-&_*BkX+cH6iC~BOw3l11Zp+N z1!YNs<#ND+WS@_qkNiN+0v^`3xk*SZuXSqS3?XfE`G5QeI z7^jBbFgueW){})k*_}y7Xi#=NEOHv3zt;#2Lr!P6a0|2CJLsSNgCeBhn)e`SR@WFkOz%J}ky#n!vs;o$kMz?-+-)=S2)cL^ zChj{g?JB)isj65WpRLb%Zzg9{r?!FY7%U2()z`$slSD!=pDgu_$3st2?urh1L!+Xi zBGz?t-_c*GHA(In?jkhmjsnf*)%~?$^Xf2(&p{=}Wy^_VV9Ns}%+3De3^6*Je>eVU zs;yS_8wLKqw{MWYBpaiYu_=B>1NDroeUF;|XH~N~R^LRji-K{Mi--&E)}HF0EslS( z{wFTUX4c<4c*jD%va%))mzI|)aiF1DmK78;Y^^t2NVDI}A>!mB3fR$gXy5%!4MXg|cCj4r0q9jI3o~mx z3>27|nQqZfI5n{O0ohDs6NOb^f$UeDk9^ym9#$f-UNCFdVd6ZAVoWF=FWpBFxlMbTYPv4lGI3 zor7KY;oQT88()5^Buoulb!ulvJYacsv}CtoP@C18i26XywHNTnTe9AEg7aegn3GZI;qEl0PwJBm#zvEQ#N~DT*e`(V8@ic=hTJ05Vnlt(7%k;=&td-7>Ag~$hqLFt z_JX2Xu}?=xo20wu@fFU+eXmms28-HEYMEN{TkA z2hL>QT;7YEC}VX-Z>}b(4@zA*mKrLIcfw@X{aiQp7`24-TFV59 zLf=}^3$}X?9pZ;~B3#^JS+`U8*h8E|L{y87m{&ucH?v$!oK*Ld@9o1Jkc4jAi{Cs- z7OEJSWy@T25T=+#;hg$i64>mAT$AyT-s^G6>-n4Ol@}j1xIypE3qP4#U#iB8+BD0x z&NOEB;{ST!W7mKF_>*>7=V@U;L6shJE95H$7F)#g=-6Eykc`9w7^1`P*%kHKb2z{= zCp(U4#i}lKWlOJOu66-yWjin!=WTm&F$lCs6FLAXL0RMGi%v*LGwlZnOapzM)_A7? z*Qn3dAb_S?%y|F5!u<4C|TKi zB~nx*duQ*x_m&W{LkJ;z@4fdX+1Y#VO@7z?e1HFS9M4e?_x<_2-`65=s<` ze|!E2QakYJfhkMwwkHen+HYDI_`7Vr>$t(|+6(}r>;@Y7D^9{P&{IS^y zML;XpwLB)MG^9MDCeCn9_H)f4TYJe}jh)z^vT79-S>LRe5-=07tSy;)1zj0x`uh)C zUU?H&(-c|d?cv2W53PG(2Q%$iuRdX1R;aFb4=(zE*r=0iDB$%^BxF~K z+4fgk@Ma>j0qO!5&7HV(@9eOC18djmGbE4PIKnpRL97IbKbDij2R;b+`9b9Xe@J(a z$j$~`F6djwjvv_9cXq=Ji)$dH&wyh)=(BqSopNnu38;;NydX~ybrIL+pVsGsw34 zj;zs#GFKD4<1JVpOt}bN5wSdJh{^jWh<>fV&__47$)6R0YZW0`AS*zn)2ixq~8+>=_r%U-iTG3fH+=(r?n^7PiaOLw{+X+w5 z3P%Kg&rs8M;2INI!15T^VxfZ&h4tW|2RUWPlpgRq6Mw&Mo=go@gmAO@-o+@= z#~J2$3V~JZ92~E?Bin9DJZvsY)G*b5k+Gz@rK!fh%gtz=d|yt-q(Hw`Ej$@Me_lsx zB=giPVJfg@%b=;+i)W5{3ETVOAIFA=m`M8W!Q1V@SP%Vl<_?{mn@#lDV_sYH4sr#j zW)Y<6gaa^x-~-a4>XV6!?6YZtN(l=1_!U>D^cq1Fj&*&(LPhQOyT@c ze{0s6$YW#Lk})7jLO5SK{w^z@5|#_jiJ}iGM$h1HOq^-7L{rtzW1s)!o3Kvr`c(KV zI;7o+d6Qg`%AYpbN;5;xSw8HHgnHG-x%trt1fQ^_0B1?Yu=686*_#sFfP!4&`F%*P z9T>n5YFpdd(gRu`tjeGz0bBoHkIQX1Vql1_0;v^XS%DV@vWURPh@6dFEbWDH%rB2N z1%Adz0*GlOIL31b+U6hO+B8`o8Bvh!BG7jHuI2hO-DrX9BZ03TW1ET2-S}xqQ>srN zN;EQ@^3ur^N1_6gf2JzYax9x>y9sAQf+{qo&|cCQGs(X2UFDa4Js5P|DN-*jA0wU? zcS&hxx#ao;{a3dzCcw}@W9tKLYX_D7U1yej-^W%!Z>!GNMUa6&9kmK50L0cTK%{f^ zkc;~vy9&$4!#|OVlyqR(230RCmgN=nVb}%*Svf}@j@-^0TY z(~RId8H~d0oE9(Or}2X}oA8Bq;oU}eU*y}m>~Q8(DZmLlp%(pO=mpt~&F2=^5M1~3 zk8aoJ9aVPvw+m|cZK|g&4AKqvop)D~FDc%fE}cykNba@v;#cN+i2G6&Dd%Rp4H3|= z>pIm?G#$Rf2|3Jj+mGEn2&QG3->>=bKE$T#Yn#b(i|wUz(u%Isz`&fci(mL|jFYuK zTE&zzQ{l4B5YI}>xkNzZj&;baHA}gI%yb60tFl-Y_96)731KhK_ZEYpA#7~Gc&Y-qKxJWnxmI`b$o}SGArBIq3u;GIi(JcuvOTBmt^TTE#|sTC$rl<%_^!i zQo}12ZBrF@%kl_w3!aW?+>Z0%()%~wiu2vf8h@rZNYazoqwiQzvwh6>GSn-*d2yh{ z)-Z>veiljSlGW))g~!cB*|U9`8EsZfB$R zTNDt2EFRNLG)6?$WRh+qs3amYI$rm@Z|_UDYID0{L6i52;oAOR-_3RXmB~qx-RZWV z0dBVEAGHk(BFr9PUE-G@$&OakuQihC}SW0+xxwz4-K#8HYz=V+hxAJd)|(PfLMU}{w>pFEl|phOU(j90g$W|M0Si z6y@Z2v8X!tY|+DpWtG(qsZZyLS%s~qDZ}i?k57HQJ7m>&W8RBK)El@lh#tMVqwcd3 z@VIZg4>=Td-?jF~A1sDn5jR$`CWk@!AUh*hh#y5E4d0aeMv+%sWv>ngBocO{T zO53!3XEXj6MdsSbV^2A)$krR{msOaC`HlVFCeNK|wO`{k;5y4`ezU;0#Da#;-ag7r zP>KpKOJ=?&ny(mLvm7<-=@m4xz{;~-!NkD8Ko}Z;&{ls^Rk$L4PlVGmJ6qte zm*WSYtsg`+?bV;wg@P#|qU)C!`IqL3PqnyH#EEM;Lkf~Y&VK6al0SBL{D`n#Ytnwh zdgMC#YD|=6DClWx^qZ=NuC|SiI5A|7%y*)W^1jics7$jG2W}g9AM2 zaA~a3p`RH0yr*ShHCCAmsh>i#Fi+8AiVgRakrv~zyAl=xA9b>tiqa#tc{Co!nY_V|gZg3Ll81NF9v{4c~XPK{YM>zncVQ*^!VKsgmI`a9In z94a%m!)P7h`^-)*DS>r@F3N3@+wY1#@cE?HYkcBOlBaJ2FF2S?5LQ>9gC@Eih=C#j z!EBQ!4Cr9tgO4JJm$IXixpOh&7d6S~V9{wi6O<*8Nw{b~Wg2(Z3*5e$_(UO-`G zX(w?MMR?8Pwb=`U*RCc)H^)nw95*e5luWoFXABUzQ!&+1z(TfQ(bAM~QAdze+k7N~ zn(An{U!ASOz+Dr(U=*@8$UbQS`N)>Kn^AdytZJf~hJ7qR6`=><{J>#K1yZ}sds1M> zTR<{Me+Sz1Ol0Ca3WzOwFi?J5A5eU6IQDpI-K{z1EW!1uoim*k*$$31LTN@zhY$6kh8T zcArOL%w1^Z7R~mwwN)^P>RIk(lgK3T{UkG!zgI$dd;3GJ1Hmyn_ei^GniW%~NUktt z)8pmF$Lli!hq0pl{lTf2?n%)lijy_v^V_5^(atn$rbEP5X4}m7-Ir)-zw=v1+j<}J zy1J~Jkp65V61iskmExPUSBE-(l6UuAOwk>r+mDq_wXp`XiY@5Au|GQ~Qee#Xd!5(s zX^%mNLWi}m@Hz{PEG|LN@$GSJSu;=KC#(48@@Z<$m>92-w@v8TBYq0*hI-Hcnh?Ba zEkS-^ZdosM#PCXH5Nk0m;HWz68F{Gf&X$U*sw#}ZS{JPW763dXSgzpRL+-t03YtS0 z!ox%xECq z%!Kp`m5?xJI3Xfa$CrD1G zY-?X?`7WnhOl}de{8$>dC+Qv3)lBTO=W{=vx z?ntsbJmkO?Trx?%@ABo(ftbeCly(0FZK1K^@IZ~;nwynN*eL{1{+GK%dYZdZ0_fiV{3Al{} zuJ&5s9)fs`Hn?XX=OLw}BoZRLz#a(V3_$jPF976qVAkabYJ{Ib<#sVwyRymG)uUA_ zl!PM`m#WlVY(&t;iz~m% zmDT+K+8qGT7{IKV#JW9~lN~{4>~FixgKN}Z&g?5yWd`c&r)ui{@q)?nm5SK$j^-b<5{sVJ(VNGCjlj_AUM`-9#%#$%yVV_wOS$$q zKj&}3mw~{GXF48F%<5ampKMfh3ZueJltO1AiB0bBbt*+nsY!?f#G8x@h9^ib3%*;qZYwI=JLjruUXtyH>F38|0h)glMVLm zQ5rWz;>9kue&U6{MC0BA3)K!v1f9$C3 zUJmahD%7e~%gryeX(I<#yE00ablB)kt)nZ>&rEk`t$H25orq(YEBT4_ezol)*84F0 zrPj%Bb+;x+ZuxyLO1jGX)( z7sys`<2HF+q!#G&0l$xRi9E9$CnkTM z;y)R|fglT7xohlb>~CToy1sv!#eVq5of}EfIu^8_Mfxyc2KO(xpfJ^DP@}k?sP`vz)BbD!H-KDUxqFMDV4llqX(f*bw?;ZpT(&Yx#yB^ zhI`-Zq71A#cb_vxKhmgIS0o`Tvm08{Ln_Ya&b&9I*vuVkvR_*)W6=%R>sgL8r{kK9ns}=WFwq!dh-Q=WsE%BEnqar5 zH`&kTO&5H%Ly`R9``iNQG(HULOwxP!cEjF$#RZ)O)`M<7cm@D%_9h$+NWn(T==SQg z4}$UT{h3VobGgVPOGqF1iaqw1Y!+fGcu`ZY;(P8v1|mCHeMuBp$~P*~C~Umwhrblr zwRd$m0BL(pFevZH5IlZXf4yyacs}5nhyYPaxo^lp$jBjt8G8|HIC-B!2%_5xM-m%a zJDea3`;}S9QfaaOY`BH|>Mb~mN=rYFZR$H& ze_z=?JxqLF&KCJ`VS**k#>V^$x8?KekC%`~`7PDvZd=Cj-_M=3ZmegfM*~l@h@FqREcdPkF_|-lOUbON)oWcXcuqr< zD|5MvOzj94%kQW9A1HHXty$!YSkMIJwKaJo`Loi=brQpm3sZJTDS`hpg8dJIPogZl znrRS?L$jA9kDkf&oh~;RS%vlso%R4ewm+zBLCKG#5Fz1|8e|Jx3NW?6sPG;z>#(sw zMcd~UyfvV9<2EuT6E^E(5~d9xKDZ(wB`0`xcNM(N5QBwCvVq6Qd8}rp4TKGdq*{3I z-~Gx~*8KR9V@k}`^^(iJLRP_At=0;+#U!lD5Rps-y-{jzOh74|dz()l1hI2*iDoHN zCWu2X34=|TWiA9Dhp#BY4Knzi|9wyo{0fkTC#tDQ0hSPud411nRm^#m(G#4VMM8LY z+Dn=74IKeEPf$ViLQ1L)o-~AHZ;4$66SFqo#Qa|TNc&8kE13D92mrc-={{GYs=If7 zzwkGU;BjKPuvWWRO1Ab__$;5fI~pBI3Ix@Oo!urOPG!t~*dXhlGm*O` zO#e`*M+s}151tGvCqI^>MFwbT^Q{2L3OI$Xe~pA} zk`y%GrU?%I$^2;sl(|b`8LtPd7!zphLSO|~(f@QsOn->zxNAGhIsbD>nVhUrs%z@W zK%zD@Hxk9I;5f3#f{`RtsDL738fz_K*(w!Dk1Fhg?jD3Lhb6F^k)ZJz+f1vdh=C_= z=OZ1rC{6S|WOx)orVTS&pwFNzf}6y728MsKS$Zg~q7;-<;CAw8<0`;u1Wo5_1%e|R z=Q^9|hmK4NkG1yi-`j1xXGtp~UQ)~7ad|}^JH6V-?LWM)JP$%@`8ka<=Y};eOe@Iz5;1wT%0*~M=}kR)0JYx+Mzp7UK>8tyq>eP5@{@5$HM|u+)9{RA z-`WgpIXRB``f#7F9%a}4D(O=Xw(u_ZVO?Gu-kU0sX9+0;p+%fLEvupp&YQ>lO($S$iNxhuPxi;uD%XeP+q9<36xfZHZq=$^&bCn=b#Cx;H%XGB=(jW) zRDi(z9h?(oWkaK*ey~D>@3qMjc8&nDBtU25;_}rdfq8l?Y31eVE-gHCyu4quNdP|r z!VOVRPhjQ7hlF55_i!6-XMKqAfa#^f&R;Rexb2B%0=*S(@SF9WoqBy+VPP#LyGM>R zuP^slf640gCp>k(nMM|P!mL)+7_@`Qv|Db)x7q00-J&F!CmrWb+!TOUZjH5~#yCK> z@H%bPnCZt-gQxHli?wgtin%WyhvsqfVpT}doKtPN>J%WbfFtKfA}t(!e4*wODZ-3!Lq z6mU9uyu+7}A8yE(xT#-_lP<{Fw)NijEZsdbTUGAwXzr|H)?EMcgz;J~@+UVbCfogS z)>tAIi-L#Lrt^dU9{XD~M1D%2ud$0w6#wDNBy2{kpi!)>eCQ&qVErcbC`s@`ikd-_ z1+8Tl{@9{kzMdBOBoh-Ezjf@WqEHO>>2RFYe&Z6sb4H@(is^Rusq%SV=RgKI7JT)D zwyE{xt95i!mX6LBa)gwb2;0>YHKR6eZSD82#M3WE&T~M^TMn7X98gV@R5xu$Pd#JM z7x%{VFDFkaXb2tf{C5a1)B^a|jE+8ZEipvpl(P_F5h?vlTW=RUJiqg`@1^5Zywc!N zZZ)t&H;f=2OW=??*y>RQ1~OQ{6eS zpZ-xL&+8kP-onRNkBTA$y)N7uh}i}lWSW{uDv#N~Vq?4t?SvJtnWFo^f8t~)1>yKk zKiz<)464Zfeo44(dYg^nM_&Xd)1fmlF+tj%+S~3?SL~kAckBTyf8qfbhcFZ}DCGkv z;}xuu;Y@^n7ivW4clF>tIyya7GJiuv3}-t++$v)WT0D9z?>Nqz3)i!QNmi+gqzvl6 z663#n6JNL@x)7m@p-^c;!ht5%A#X}0$&mdN^Dk2;6j~i8k6_3Sw`b0(@yp3rL*uvP zp~G67rLCXMz00*2Y8-dLbHxs6fv{$WbNcOZP@yfu^HY@Aec!Vc-O%}7ek;BNMBQLh z^-`gbIo-+9h^NDGr^)ezO4DTpt)D3uSNW9U6!jBX{8ue^?a%s3&o5p6ey!^W#gmt~ z>!>8f6BXG1d*M!~$F@w#mn<-ZAe?HPHr{^$J;O@Exf@>S9M&}gvt?;UqF8{3dU(v# z{(Gfj4)IX{J-;T`*RM0vl(EdAYS2rOxUVOf5eb=XwhOIjiS8#V5Hu->Fo+?-W0mR; z2tkB+mZo_@4f`R@^KK=C!U={`eK#T}l=J9CGI%cFv-?ivXlaQefi1t1)?af&a5vkF9BN!oog)VqfaFG=+xFiOGyyR0QVIT#=9V$J7n4d3Pzx6 zfP4%Q^ZxrcLf{4u9CWS2hH6JR%rO{1&oPj^Cz^MU*&NTN02}Df)zzx0!q=`zx6C5`k`2f z-&0ejD07z7fT~$N1h=4R|8-e;tP;OQY+=D^YeB(#%ESOzKhQ+7abW2C);&HDZJ;Yo z2jwd1vd8Rl{2eUNPTS$?2X0dhEc!k{e-u z=K>QU$b&K{2^Ux32y9)2dN;NUC|Mw$e_2-E-Q69yuKq)U=7Wx4Opi8+-+BxSD#ezA zD;KXiW1KyAt09Qcpx`d0!iyCy7X9IN-FjV6&{Ptjgo@+cP+3+& zYH;sTq6kl~C^ z2sX17Ch>Vz6ocEba!6DmDg?S1aR+ZOkvkC~J=>L|B8tR3 z|D>Et)Lo6;{9rI$o9pM#=!wXJJ*%u{Pt<;=>(<}YGmiFAO!yB<-cl^BJ#t*YIFq(Z zP=5P-y2anw`t0$CCSvKlR4Ov;z;nF7;V#{&ijr><(r=m)3sduq>7L!~OP=4@iww;=aGiJXTiGV(8*P^iAySK8DZf}p$TIf~>LvWdR2j7n*@KC3bo z+H$_vVfvgi_Cd6ud>yF1Z{PZhE%i`hVGwOuJQo+44}VMkBv#@8;a!1oD=R2rXd`oYC45hw(MieA)eKZVG14OJ#L>HA|{|_)ML4#NY^mr>?GPPQ# za3~yy<3z&HKK-z;umFExY&6xp)wuj4ba3-9Yu0`q*ly2O0TebK_&C8^rCl<0@ADnI z(lTh&v+;)mh54flp!`fsBuAX>VC94~#gR|7OAp&#k9jigvM^!W#*E2daPq0*`0i>Ay7$3}whpXmP=ZK#d+z$yTRuUig4$`#hV}rYhzHv1Km{a?_X9-V2y~i!xIY;w?I-z|BdL1 zk%i<r-UP zL{@+DDgVC61)CRk%TKjlIr?8>1&ooBxoq*@^*i)1s$c8d=m)NE-BBzEb^mAH8fUhI zpCeL&c2cqRYr$Ijp1tnAV@Zbx&lEkiY=)!_8`oPaD~gVbosKNEk8M1%g|DORh@~ru z#=<;_J$nLAgONQfPYaKt(9U+y&N7n5zaz6HXDMIbR=q~mUKMsZMo)8#`};GbWxXw5 zd5_SnH}v|;c|V~`f;o>pW_)GYm(mIznzdj2>UVU^ay@4aN{Z|^73VIt?9WRmotQpV z9JqS%jdsmO3c2P$H3owhc+n9V#NSf1g7fFC_&~D6$-^Z>A7!0jqwSpE?DLxAN{hbx zb6KPHY=v{o$*m}yD*?wD(&dmE$%BywTiXL?+JO!JoU}Xp^9o-ZJ`F|5;^9= zTNm04irZ!;ozkG*qpt5*{WvBfYZ7-ZkOf*^U44Hv} zDOsPVA5e^S3w+Ek)GL!^hT@rrqsjM!&WqN`-#{UU!dWs=psOpAHsDQaL451La*oHA zzk`n<(#TcOwZd^_3wFbqT!ETUJr`!fY0jJ*KH;F{=k7}%9JPn96;npcK24pfKMk{t zQsn-P97;BOc0+_wyNc3e+2Yl3NiNZ=xUKt1a7Om?6%S3gryY^v=p3=2-Qu=@ZL#=C z!zQ-VKTbxG`3&+}K1$7D?tU|;jAreEQH3+HE&->q@vv4)y(}2}Lazv;OAc_O!}(ND zFu)l7bn7)pRm2Rwh$f6}LJkkxix+*{6|?*U@;=HpulvpXDf7S3n34Pw0f(9B{9LPd7Q(}r=c*E?nD3_C4cZX!6*?C z^aNtd^lq^2gIW<09;4t6uWzXY8)j;DNVXB9Bx6xwWn;8A(^_@Nf7p?|BMzxlmZ(a{ z8+GI>;asI2Dw;)t_o76^#4yqOA?Q9y^#+hPuJI0d#V9fagiqzvyN^#!;xqDbA-GU1mT0+I`rWh$(EK^pzZ`&NL{S0j4yx0a~e>f5>0IU9SR`}BM3 z=S=^+#aAutlp?7`s4j>F>zV>RGA%n$=JXH)U%j%&RIi*|>oWflATwfB(2I{>)*XWb z7hXPu7uW-r{$02#uaJ-wQ0)Pr0%8=9hQvyYD$BqK16*lYl@Le)Nj;mnI3n@)g*K-G zD;>eh2WtCah!}Zs`nTomj297A2Q#D<$VG;0)4#-U;J}x~%^Q&`0orS1^)VHo|AgYO zzE~v`g;}u8NzE$n_ZOY8C^Vj$eAA`WoT4JlL_fV+OVGhCAmsQ!bXTP2hJBw~>yisfR}f;HLSJbkX|&Jr;^tAJrc;1at{cf> z{_UN*hFejl18>u0lT(xmY0b>eH`xs()#rMns6Em_8{#PV)zd0Otvq`N;thchUM^B@ zHJgTAPE`Ea$9+p;Yrdz1LvNdJxRBi1>lQl--Oa3)$AcnQc~d(3=+7v z^FF%_fypSbEJZp_y4J8n#nv@t=gZ^TX^RTd??iev<1vp*MA?)9Z1Xh(c-7gf9I==n z4of$zyElh!|Lb0D;LGAnXG$SMh~9w_a0ou&b==Zh<_lxHXa4*Fe-T{ku^Qbv%*%HC zP)x#=2%RbX0|v?3xLT)|*Xbi+FuDZR=0sQuR^VZ@sl%7%ZOTJoWC`y5i||ani3t0l zT76=>(t7<48HI8N`m5&-B2o|Cmj1;nt;I@blcI1}Bt4L%CrdexXt!~Q(lC6e zlrdjbvbTOZ&5vh@&+{gA|Dp_e##8N59rxbN3QvO=7&Bf>zo>j_k1HMdy|~JgaLH8tlB=!aM^d%{nSG7P&pwwJqddp4bsLkywSyxaf@;S6J!SSuCq^zm@VX__fL*X6zPZ9|4|P7v-`~C zD%6$mV*2m-xMQq&$zpwNbN9*g-%SUrrRk|>>!E{0Vr+usdd5vnFK79F z&#U}(-PSATBi$vvObabbHS2A6%sw6vm)12chV7eof)BXb}9n%uZDEXxSn7 ztz%Rtfw@ti=pW0hFyA#)rYr4u$@L;irhP60!|8GJ=K#(}&%-6|#^NVwVFil_tbk5- zX9r?A4115eOoeGG^1qEfj+^rvnzTbvT(r8JiI?Nf*=WD*UBR(5CsKb8gF(Uf@(i=q z3ftqv-BN96cU7__O6=^4Yw_Q65(n3jY9svMp|I95`vk}l8%3tuT&B-Qkx8musa3_) z4NDp%`iIEbUiqv&`IjQqCQWZ}TU}HplZ5cZ#o+)a`f^_&t!PwpNmr;8zhG<0%r1oD zY7P|=@94>iV~F-iEOu(|KVjDrMZ1{jutlgPT^WV95wav=B@6-oz(F z=72JzUkV&szJ4cM5Z}4+R-2C+{Uylpp zX#qzK_E^KGMQ?m@dL{acE+g7+kF;VV;BktMyiqszQ1S19{6~4nmori;Rm9E<0l10voW7zmeP*zae5tV3_2w*g zf@WtEd${O0@>^m}_sDRLThI57lq`ej&oJoSDO?=6I(n{dG)kz*sNa2lyEgx^kBw```tGrHqxS+{_|z`dzA|AFV~+*+>@c5>eut8xvfHmnyRoXY=s-B|Bn$B&{*S{f!4!mV0mi)VeGk-C+q9>)IJZ*9{ERaJtv6%m?+TAa{Adz~*7KeF7?z>$V zuh;Z3;I|7F5o!7H`IHnoW{Va$2jI2P9?8x8DF2&6qJ-OfkFYCuv?|z~#^jt0(Rr!DpnLj!eRp%UByU@p$beMv?4baEb<#n{KdyNnB1r=c znnM;2DoN_WAwKo2`-e_eRgcE8XkV}2`zToIGw|FbE_MA+Q#d&}ELZz2lOfTZw zdwtIBT`T@+< zIALp!bD!z>o99W2g25xk)SF%Go3Z-Z+99%Cud)c5DdLtJb$isX*; zcegr8BQGYRO#QWJ_gFL7|AiGl>s$WR|5%j4 zH}=ktF=Yvrp40vWYCwxfPim%hV5(EYTaA)D=E{ zAH!(zieYJVO!9X^KftLK#G7TEdnnbUUeQ#9bRWI;#GHw_<&OZ_%;n^+DL1O-6_MMT z_ePod=lB=14$rEJ^Ooa$hZoqd+Q#O`gwQkwOoe90d~|RF(>DF7 z2Ll&6-wzzY=2ZnlHP{-GJ$LvDiv~naI|SZ>BWw}zB4(9an3$x%+yrDwV#is*a`V}C-$P=^q=Be$_6bf=LCv}FR@W~gs)#@dC|r#= zyAkJJb91vj6~9)tAb=X76+5zti5huD%9I<}dZYiUTsBJ!Qt9u&31@aB(IxWruc8RT zMlX{kFToH9vpDFzz>^F55I}#x;A*4V-;D)y?NIMt9Al)s&)mCPZZX}R*o27@!?M?q zR4?-Cy)+}iGo|jIK2M!~gwEItMb`02dKUHGy{0T`qqB&Khlda}9Wdnip~2ht-XDc; z@1;;qG_Ph&#InQ+IIZ8m5B#(mR+qA} zb34Cueqj+jtR1)%uzwmWOCM9H^vH?*`9yhg(%X~L$f+c~wLJw7R`*-}?+d=&cR8>~ zB5ueD`Y9lhPt^F)*wFQ7cxRn@W;S*rhk zoxHbE-U)){5U>=ma&{9O0Q4pXlv6O=6xeUYhow49mcdT#mz+CT5~DwHYyGa1MxJ7@ zq2dwGEBd!bhIhUZi%AZZ_XV)Y@F~&}5Q!1r!=VWGBAiv}b>2AUhe>f*ah5zi%1g^K zRTwnDl>D`+<`pN>0VUs){N&6;JilTP!GJoL>^&70a*0OgDyXdfL&C<&lw-bVUQ)LL+0Pi>17>>}U7tGw3!*2}AqC&_5` zl;~fk)W#SOr`Fs!8yUtSlQPNsR2dhCt;S;3)#^u!|7iB!rZ`m(n_J)npItcyFjl zJDH)78`m1G`(*M#+#at>mJwn7@(s6TS$$u63>ANf+Op;Q2LUb#$@AL3<65`4V*@%c z{>+r>^eF8)*D2>JUj4fh$L%AF!I9c0o$^`gFgX@E7HsQSSQR~eK=DzjvY~dIPLnRk z$uz+km59Dz@o3uJVwk&_6nb^&VrAme+-XrJlY?r6X0|X}R&i(|AX%lFCOiz=c>tZ% zp0KKl>BHLl`h%~Fx^OhrQV#oXWcfenu`Wb0hj_!w&XONa3mw~i(m9`QPy3YXJxb1` zPm}d_6NLRNhaP5(BKfSinL6r6i-Xk7%j1|YX5=9WKILy7&4qpzOw_7RX~fYSY}oA1 zH{CUTAkn)IPSciu_L&lqLY-LOmN6Et-7DeT>e*bFv{oeEq+NWK)n!h^U z1@7qm8h(V^_mApM-3faxj+G~W{Z`?%!Xux)+)2-pL=|uu3vROi;Ch2*oq+_uuPV}* z5_WU4?Vixhd`HRlY`~`O#0sTy?0em;^zw7}!vRrL*0RpDi2DmSuUr~?_p0%C$$5Hm ziQsHSfWQ&^lD}1vfa*jj=;!7h1J6ITq5=q2yiR+M5dt{S8VMW?zIGBIhm8nm%(;}q zn)f*4``Ed;-|&*9!;I_YV=XU_W0!;+CBF%qE>VB???WS|?_3s)mQ69|sueTrvu``o zhzX82wos!=zK>cQqQu9y&W*6gefjJo6X%Eb^54@eWQ>@7HpI2DcyQ7Di>!jZnZ)oq z=ft0*VX8PUALR6kKfMaSx_7V|Z>&)l;F4zX?)g%XbF;2R;$I=DV_L%^ZqDC|#w+I{ z-f}z6AjARL!G-fTss|bcg>{ZEBG1LznZHKl8)9-_r@coKd1zmFjF|c~G$a8P_#eLK zRflJ7u0^SqG?b&SUBr#L;$uhtlg_>7CF533FmNWg-HUSPHdN7I1%jQ~r=~fq9)i1G zEM6=?79d&jMkSwvbSHt!trEnCnUUxc_&$btA956bkB@f(TzjI_7#|jM^Ov(Xf^aAL z`JsS$2u>%h`FQtRwH`d4xX)jWMm!<6a~P6Z3ON;gMHr{4b>{ zgDyv>-@bm01X~*kDXC4Z*eSFr0fL8{zdC-C6(qcM=(KaNE4FD92bk565rKb8)7;!o zY;pVOXPjfS*#s5b9%1M52Si;Fu0zEMZ%MfV`k#dn&Dsvy|i%JrrHuKcbc+Y1} zH4GfwqCo)!pX9llhLn?hw?vG~dAcjLDaF*QP+Ynj$JLYQwgnP`wX%H==f3Lc0w4YWBo+W>nba$Jc)fMribU)IN6k26*3<9I zuN2Yp*)m0IBJ?N1^zj}ijjuk^or;Hhq%&>U&alMJ?^R};U$*gArq1$vErTXyCbx1| zs2CZULy50jWpzhGU*B7CEmP%M(gLr8_e(9ASJG<4^J%|FM-8Ybo`&D+2&JGU!7PTp z{AnzxIxz2l^g4i>1_UHNk63!xqr}^8RjV_@__QO8CP$wBjeYRiRQ3pcn+`6x8%jNs zwOL9RMDKdNbK)bze!Z&hb=sygq*W5+9%Lv^HS(D%tWvR<5kT?5t8#1O?;}K*V~~!{ z!)|pZNYX;*lvxVCX!t~jsOqOw@ z{&5QX%Xe#fB@>(XZZFKB=XpHYrOsyF>0Pv7qBn`+Nyk|zuc;iH!eTmqC|BEXr@a$XY#GTOrC&hlb`+D#52Q30xyh<<3u5jNYi0{>?Q%*<>HsM&M%l(Ox{<-CnU5j?vt3hh($o_-LCAKdVJ-N z3#uH~ohpB@^>YYalD659YIcQ|42fEZMu*s;I)oxQ);G3S-pxw&sW01vVSD?|V24qV znRbaS2XQwsFNafH(;P`8HpQyv*=j3ALaRY!?73**gyjHU9QM4m3te>JyJC?vH7fFo zMLYM{*-IaVt;vzXusu}ONvnS~H;vs%SIDk;?H8)SXXl4x8$0bQHopglUK%RV)<2^V z9Pyu?f6U4+t}OFzaofF6g2iO zp7G`VQu=s4x+!{5v`6cGYs44*RJQ7C%|^OqA&!y{M!vH>OTDL2`=!fqGNy9Va`QnJ zZJ{P(1B1ja=4hPkgS>-rz$L{S*9*D5d{77+TD-4=S7p6*nyf#iw& z_QR85T3vPH2gt9rM(AakJ30$P zgNXI%N6^6i^VNRMl^VN_qGdo?Bqo|P{`2aL*X(5k^YXqmM$ldE0&hR+VI;9nQnNT^ z50-*EUzc&3*iYx4#VXmG|8vZCi_|x&@h;XbLKeE9cH5Y7Of1&7vC>E8p8a_t z98F{(Kr#QPstnh`8ny98Ay8lV>Y+C`1;N8TC57SLMZEVP?#2}Fx83-*h7T4{P*6ai z{C#v^#BNwI2Z&fr{}Wun?inULS&BKZiGV-A%o)WC9A08+vU(*dK4>JED8aYKP0DO` z>rMx0$6}q2kq2u333P<0iHuU2luh3GQczg`TS{sw@{hns zXC{?21^?;re}-uyakgSLN#=(Fsf6t_22T|xybjxhLkyV@f7Zkd%#JmsE4b3dh{MqS zcNOP6gRqO_z>t#x5`%5skHOzp&Rd_Y^H5PyCWdQJ-$wdCP$j7#-g|uQ2rArr$VR6B z$I@8^RM~dj8dN%^q!mO&;H67i5hSI%rMtTkkd%@V5NYWy=>|z@L|VEVr1s?h_9+Lr za6Qj`&$z}I765kHLH%aj7Hb3e4^srBZxe469un@=rk{hUCSWw?x1Aw+eoFE+mtQ{ci(5b{1$vD@P z8*V?$cRKn5UpQ-1e$c4GSRBO4P|oYhGM`8WGTc{{qvu4wxOWmbvJ6%ua1X%$JwSz{ zR%4H{7+%cMaHDDnw_BXp4+)&zNzR}chgEuC0t(Oamqpq8?*v^` zleRZGuddmJ{vP*YydfiXjCywug~`8{!V>Ex@rK67{QSF*G&eU0Zq*SU<#Z1_IYoN2 z^-2)t2}IS$j01wWg!7bOdP}y@yl#`=f9_B6jE29%d#|G?kVb-s0z0*_0bxn=KO%tg zlQh-jbQ|5{0ALYmqr*id{;>fbv@isNbYqAP7L7N89uEi=2xPi8P$r>5farst+uMb$ zuS--4f;P%cZNLz6cvu*U0m-~Tj>Pr$fTo7pPZ{?l)_W(-IYlO9g6^9DRJ+>74w^x5*CEZK3$~6 z)E_`Ypb~;mq6k(cS0oVrw~MRLc!3|mFC5g;Mm5IwRT>fKL7?OId`@-yv>2k$Sv;-a z&f9SOJ@pYT)fIb^Zw*n-xDu~guO2b$(_1#Fta@*~Yw%F2ByA@5OzM#i(q?%4=3PHk zk@kgr+Jsd^?@QNz&(1&UYEWuT)#9l*b1k^k*4eMH%t=Z7_TZwL-l_2}<+J+`Wv6DT zmGU3{_kVl7=Z~Gl@uXCn@E``H*7k-UDj7pIz|k{7+fhF|I5swR?^5&ZshO$iw<_h5 zRdNt}czTj2^obf6JcT_e?9c3AX$wwSpz&M+6Byt)4AlYLg+z96Y%&13C6u8+F@h$R z(_&)b>{5t8c;33^Xh8%gU0Oz8$cfa%hS}_G{3DM79{hJ*m(SNziz+Us=*eAX19QtB z_FK@=RR7dOJAH8BcYHrZ$VI-Hqy0z02l3mNG6gD&w<)TN`ERCmx=u^6W*E3C!-Mi) z{5@*7oVWdQ$wz7{K4AL$9-e90lamwuYY65uDP7a$2kxPnMN=W-|;8WXcr&4$Ox|P70bPpe>J#i zacur0)LuM2@x{L6Kr7@2smMqV&(F(_ZM3bNJmm2~#(un<{nLa*W?*!iM9=(vs6yUx z^x$Jgw#u3o?zA5QIpsBc*r|wVWD`vy^HvqJiLAPetvI?5J}RSByI41bSiJWWy2?j$ zomi;59u}x1?wBtl(s)1o%W*m2x+s8VR~G8nP7I%snTizz7&g!ds9qa3eGn?pG7^{TcBHe?v@tMxu z`u}K1Xz1U`mfL#z$3zGt>4|=N2f*#j)Esp(dq+d~h6qk0v@B3bChmlE@(M#e4TB_* zC@~VX1ElvP7W}^Pu#Sw^)aS6nadjT0zZeyV1N3bqr8a^E2lD;Q6xV!lP1WF|2@-Ey z_asw;0Oc}e=#4(iPEAa70nae4+aNvvv|hccTc%ELF{zK_owRmF_sm@$EHNfH*h15l zKNzaY{DiN%;!KfGeRh%dI#&PYW}TVG-46BRfHe&&oTSbPA5hq5-2SjjiCiM*91*_1 zWOAr(4I3~?FDr|lI92ha@Gc}FixUxD+GQbAEm=M~bByWfPLk>WW%sM^^s$WMj?K#U zQ_eZ>ORG80BbntJG&FRo$NIW--Hvryumlr9A!Q*>YWr;K?fn&Ax)1-MGro^QM|J@+ z%iR2D)LT}my~J#q{y4;Ye~Xmp;gAAnBEaJ0=mK)gK;m^rCBLDDSQ>ENC84C`IxZw5 zBg1;Z6eh~dP52~Lobpa>@NxE)q5*zr2KYf?C8ZNGsNjaYfvv!MP`|+q_OxznbhI4= z-(*~tdakZhESAayfj~=${Ck_S1$Mi`91&VfZ)sy+#n3e9lpJWGejD7G=#y0~RMQui z2Jf@GyOcwjU05`?J!F3E`9oQRQYiCjX=(4i_OfnD6F5#V9x($dci`-1S8}|}w`Fv; zJA21+AT&1RYA*?EKB_;h^v@DX1_6Vit?jTLN!Z%&D@#}nia0-w?F9pP@VWB+`VGIA zX|e2yArCAJ;kb?Bz&leD=W6A|)%8sVKJIn8?OUQ{F1U1H-Noj*5~|cuf&|xFf*AW?8+PU0Y^VLkUyg=vVB763z3XX6Q9eCoBuefm z^c$~~$3^uZ5gCvM7^!0Ql0D2wtI{YE>umY+Ck4?J16PYi30%EkOY^+}H;w>YOTSZo zhgOwMU*(cz_3hfl$#bW9lUug&ipVY3H+ZNJlKeX?%6PWaM1^=Oe%1hsvhg z(_ia?v=5J4Kk&6Ue^9WiQS|XkR^HlM9%-Q(Z2D)Qvg1zRvHoedZwC!adA!zyz0#-r z%jEOtL@`rf+#jT*PJ^fK==j;aaS$$$mtOxk!085tw3J@Q@?ftYMH2!VJ(wVd*Xi<8 za`O*Dn++T!{Qd9_1MCS7&w$9@LEl*JFc1@@-d!rwGrCA<3_C?qJE>4-3@e3BPSc3E7$L`(ha{{j5Eh zv;90P(5aEli(%%(Zq)ki`!e0xr6>~K$*%4GXZGn&*0d-K$Jt`brC%%O#r@P$R?B4L`E+V9>t7Av7Lcv-jq2+7_--7qRsE;*pI@Z_ye~~hhOe?#163;-Aes6Oxd}QPf+oaew_X^l31WdN$3x^4w{3pJgL z@yYJwtRBCSk-c2HR8=3&KWh|;6REp*dtr9o&fM&Rd;9Kcv$I@r6H+7@EnlHLfpr5s zH8ROu+PU4{6;#Mvh_4f;GhLP@3^v~Ao4I9^w4hMff~cu0pcJesC|Y0fFfUK{O1&}IIUfs<1*4v*cT0^k*> zNx|PL^KE2IuOR|4TxePDTGj~%jYt(2RVX_ zoAg_gxPsRh)o*Ru*j8v3*07278lyTM&R}>s!?4YeO>9Y)<+NhDFrA8-CL2BQ-n8X} zo*Txp<*zQJryxisL6ZY_UYgIM%DxEmJG9OvKmxQl>&f5yrc(ms8aP7+H7GUe=#Fs% zp$3u}%#tU7;G4FE9jLO*0&FJ#>ItSTQoS}V&4Zpj=X$JR9r0bLDn1Cv8@JJr)N^Obi&4c>!~-9p9-oR_z+0xs`+63gc)RLt1+ zxa5-wV#6$qQ(2U)XmkvTS`;G3Vtaw|u~gb13KI?b_z{pk*6<#YbX@RY^A$7(SOZax zjsPP3Kq~+j%G0M$;YWZw|4-AOIieCn1FK%hu;mng`TF%v`+7I0OuKQ_i0iG_cD+=( z7SsOs6PM}rQ>}Jn4l4YLs|!=pH{*1T(>gkqKGE{JLEKVCO}<^()kLI!thMUMtKJZv z*br_a5q6d!=rCRg{%Ir=-whewK6}dSfGIN?g^||z2dNq5r->&+EC?Iuf z;r9AcPkQE=mrzDv58inr3oBM{_^yLq5W#a3r*GF|2v=8F=WFw0GUk&-!$X(Vq&@Rb zC}%O|FIc4qUh7Vt+@>W4mc6*v`r2^z??HbrhV3TaRjaCXN<~G_{!lYwf&1L;#URa- z*ua~a(h|Od)-J3S#|E9*4n479|taP|+sqp|QDH$1*ji4qcY57hg z0jkO616T072Eiw>m6@So2a6aXf(3otNUKKVWR$@7$xT3YxGbkyepgw*IBFHBVE~dr z7jzdD>Sz{aPC-HvIT_fuL6iDUk&XbwaoKfs>XSIt(@95gWe*{GPtM3*q~j{OMKQHN znGc6;j!p?XFGrhftXWn(Md2(-j;r|>A-;Xp4rYRVcYaqd@BFVj$L}y>1?Gi~B2r;| z$PSyQJS7c7E;`~Y*v#r_VpzRzWpm<91<#{)OV&6^lA+Y$Cq&=kS?mbD73w9Tt5Y~o zTbYrKa10scERC8EoHRe%tS4MPP@T^ECf%2Dl;V4@w;m+)K+A-cc`{Vc^ zVGj|;;0ug+^@tw|YXjW#f1w-gxT+5ENzK8b>)Ya?Cz!j8wY+Q zCFOKEri_eagMU|oN-`_M=^|hze22M%y9%ZanzC}zmoKkJIiSqI3;{1&__&x@SXjr- zXZG7uU`LyS_VJiTfrU5=$b0ed5D$7^?&w0Gzrwyc9W;cQ{9?>AfW{z%df2H!fO05< z{s9%?d*rLY!JF=glj{Q9FZp<8mRWxt*_v9UkxOf}D&6@xlCG!_mM@@bW`aue*~xDnp~Gq(48Q{O^WlN&7FWqpcmZ~OPdGbcnv?Z58n(wdN;I&^n&ZD!lR!a90TOAiw?Q`aLZr4rk7I62>I(5)%TF9zh5+s%CH*tWL8#I$i&R6R*<_8C4i@VuTAM4xhBm; z01iZnwSn)}fonLrucx5Rwq^s$pABwnHm0l++r@q6i`j|iWt!W=^OqqH_UEN~Vx)Dq zG-$O2Kc!9${qPK0$am@s>&;-kdYhBZ%1C^@Cy=vb>x@e|=j0HBF#ZKw%`@eTXHjul zeO=T$uzahW+1K>$4F9l&{+U6k;st$D<)`3|@b~mB4G&B+!`YVz_GHCh;y~|YK z!er2mEkYz8LjzW5uexvz7}q;K!T1#cRBTvFsq4)Y*j`^}M@HU$z3-$ZX~0?5Sa0q*{;irmr9?AbFV41RoMBzW&L-r)<@V^%E+RIjD{JzjOia|4 zQ)nDIpTo=Fiu+G<4fMBv>Q$t^j=jd+7SV|k_RPgy8~cUSeDEIzWu&tr@ei7fdh9@s zlvB3sulFvjNEmY&#YNGou;T*hHws64j|3lk#RSy2#{95A{rEIot4!Xrv4!k|jr`e# z8h+Tw#I!`qo-RkXS~yx_Qw$oSXWb#*b6ISK^8*tz>y$2Yfv&%QF-_P=ax6H>%cT`r z#Pj4jC~RYg>Mz26Ner&qPqC2*PR{ftSCNjgvx{lMz+!TiUEb*>yMV~ar7|NH5u3;8 zcls#><&haK2VR2rKUdmpsuXlukgZk2hkW}EdJzt^v9+yN*w3~w53{KxN)Pnu?tBe%7$l1$E8hk4$Jgbjou z?#|@hVj?Zh-7^D#1R z>xTP(=if6L&9|Q*w*gfObTu1bJJ)CPLz$6+Kg$fdU00J#h{(71-XE$6@H# z)RZ{%HGaY^iQ7p=8V^_)glSu!5Uv>*FX3Qglm703&K)_kTp{o7V&WkOGaoYKLa-VD z%8Scpu0KyP7hLRM9dwOyQZTMxA(t@XJ@sc^!Eb=v4;mAOkm_#f-~~2F8+EqRaX;sZ>r>^ zy&EMqr%4-faI%fcWiS)OR}ZvNB`X)X+q3|@HZ?UxErABoeBRVMSBGJ3BHo|=oJ^RM zu;hi9QIJ$1FyAA`e-aVJD@T9?!*1&6;VN{Q-{-5<1~=N(e+}Qy@l*+Yce8qEd*BIx+Yv^R__48{B?>fbhXT3jt=(J4;#vtk)#Fs7P&1Tah3-_{4N))mvRz8>3hf?gRO2`n-$ zV&O`?j~HG0)X`7kBp+fTW6?Hx^BrG;+!awLF}v`M|1U-v+JADwTu-EC~uSE5afNF+T z+ER2xrF7+uC`IY_^0$esVS7|~FMuaV9uNcQmEN<%Z8n6gJFblf<@7eVghMD?D$YrM zTsARaa3^@e7Uib?>(Wx0s_DzIJa@g-e%U!(dM`hiVl3@`z-CI? zp~%8=ZzrO3RXfqNiubC!IdDh-fkE&A%YyN8{m|y*;@p2Z7FjQPV!}oLorga)6|VDF z=uwm&lpoA-O2R=Skf0J2cwMCNOtCNX$M%BV2O6rEztgva%3hFOfl_K>sp2w<6HSTm zSu*SJi{1_4L-*)Pq_vjFSCce|McUeZ71f*r`$DYMy6dtDO<;|nR$)BQ)=kuG6F)<+ zl})Cs5_%n4ww?Lq$Y~hHwR6W+TD4r6hjcbPa|@es1)s~GDM`Gq*2+jhYt}I6=6!()-OpIFXzaK6A1C-P65lhZi#rMA;U+{}7gc!1Q4zIJEj5@W2 zuvAH6{ULThSD&boQ~1*LTP|1`8>Kx7Q?e>_W+z9Xh=uK?M0Qo2)N|R9U6aNNKg;59u`f`uUXe=w(CY6WSUk8u zb9#{E!y~%j|FP#Lu8@9pJ>JNCbX4mg{cBqNgDneN;yeNxx23m6cJ>VqadX z<99R09~DCMe*QgQM_+-i{6Q>4D&|dR=dro9IVd2A!CFS> znDDJYnR{NFN$|{9hw5NC;aiQ>!R_kkzV0pM&7x}U;*@f63wue6h{qh+f=P z-8Wna;H3pn8^jns1Kj~wV{LA}x3?cbz_wT0u+}tKg*r>D_dIY;*M*uL^52qi! z>zX!=oyW%bl>Fb^MGU^LvhX1-i zSF^==L*ta#z4OZbuQj;p7O0jO!ygv)0?bo`Py*}hMTu3>5Tt#!jfdggeWSErdn_%z4N#<)}8m)&|SUrj-{f@O98) ze3ZI44Icm5=%XkTk2;SN_ol0J%AbCub3jF@?U+9JUlroQ{y777q@06 zGt-&!@#HuOO$G=1NAXj5eZmvIdSMmZqVWp3JevPqO(D}Hn4X=kpQomFVDGmyv*yZs z#-%x;{bvRJD8i$;f2Hf?CSjw(E1Cq*PGw7mtf!>qGEJ7d~XHd%fKT{7Zj&E!ME@sa#s=l)(V!M|w_9^Z+4h;1!)y zpectWO#U-7GlPh@N>PWopKJG14Zf029LV{)qz-^Z&|sdp3Zu*ws-7-_Z-(|LZ0Z73)lzBjNX~b6ct67S4l!BoOu=Lm%XJwNWRU->iC!V zYft`}9$W(-;obaLR31|ow_rRJ4C#fv(;IPq5H;}>PpLw$tCXi_Ez)KqygnCZK{u#q zy3EWON9d&vSD@kU8@4yc2Pf{c`+N_*8I3odQZ+vP1V=JF9mp8EJqaOJmR!lvSGA)i ze|Tc5$ZaSuNo0{-@M67&$B_rmBp%;B_&Bs-u(R7u!c(6%l05XQ;@X>WuJh!Ui{a|m zq?6c{eRThNn3cmu!;IVYDZazLuJ?m8tH7sg@hAuQW~o)H_Umc4Bkk@;EfGu1KE-RM z)kQb^#na0kj=t1i{e!+?EBxIOwTvN4K7Od;VM?lG{=Ju`a|6vdrx>p!=Y=?Dp&x=u zq{}NVB!55D-6BmpO{?Pv?`s*~Z69)Gr5C^W{1dBRi@!53gepr8cWuQ^Ng`8EUhdIf z)jwDfQ|%8wGl-nm|Ff;E946gqHM=lXzuFsnJGbuB*XYAAGuMA0__Il~-VBw(e5~~Q zzr@eIh7diFWB=ndm5%VZlI6SSb(Zn=+5Q^z2YOXM15cfG7>NK1_)Jg8_&IN~giVkV zbV4b5EcQ}Q4hPuwQBXK_T+_R{B4Yaob?y{ISJGd_SzikjUT%x4pouDeCp@VefC%Zd zfOf~pt!+tKiO+rHKi5D)&YKAJvKrG{Pxns@2_?2U8<_BQLrV+E8PVc!%psuQxL=GU zFmTjvDS2NR#K79Z)9>Il<)v@e&mga?Olxd`FVwjMM>A`O{gpKiP`7J;_(W)d+K;o8 zK+a=1irGO*(!0jW{Gtu@7wUYi#+vP2;A5AICJpiUc?ROiDeTTK;IQ)hXJTEMmQveRwiIO76_( z%3tc$_?4LBa~hqqgFa_8B+4Np#^N26tr_LNZs4XR$<0UvP18feC0* zYU-VXV^^0LC>kIYilZgKmH!iz#lQU!VqtflH@O8o64-hYv3}Sxr#MSVB@`MO;V?Dn zFg61Ja*)6Xqr_TBrV>i>HOEa!(2>2qpHU*=DoL4>lZ*LZBmA!Xe3$}lFb3jn|2)H| z_ZaqP`|8H`)jv#Hpzls|IBRVJPV7-z5B0(`=#|Vlqi8Ih$(n?Hf8>LCeMGg}YCp+` z9rYp=_@LRvV`xGC0c})wJO$iVpkFG~ZJu+bh0*wQox^jG#avyj34vp!ewkXZ8^5cT zbup$^PC+IFUbTf1GVnkYFI3_|yS3t<5}$v{XcP9`x%Un4%jj#Jw>{K}1vDKd{l1Eg zI^2ILtBPcfPlwGQQJsl_;-sY zl}7#b2#utdpttLd)u(5&F-nS+bJzd9#^EegH)n17aFLrquhz%*yTY!?W5Esk)-k1| zz+?J!{hhbP9+&yaCUssY9NUfG5B8bOP2bLEan*gW3VHBf;bKX{eV!C-`W5s8SMsn~ z$vv&$qWO|&w?Ca)E^|@LcvjjS_86fnk}60TVxB6MNa-6pj=We&w1`Sy@P$^ZpZK=g z*Lik-KO}m+-hpz@Pqq-PVW0isSKND;6C4BIaqW3ikzH+&TSZTzhrvEP(3Kz5D6qa| z6%vZsXygI)!IM*~ni;HN&6FB(o?sI(gxPz++^Ro=n=}!Q%fX)}H==3m&t8~`s#1UO zjp``J@^7?>n-LRvM(2T{yr?$3L!Q@^^2C&(^t`PT1oNs_O#kd#R~>lB#cpZ4(C(x$ zT!B~dQ8akl^?Y_-1o=pxzIytlo)CSxhsEnVZ`)maGTUZgSFXQ&U#r1B;0Q%mZ#>AO zl$(p`ch?QJaDSxkD2X+WW%KFWDd(ikB!S=UfeRI>mbVY-{^ZaG=2=mJQ_HvdmDC{t z-7)-o#<)JW62XDrnzugG=@hY^&o>uX?A++yYMD$=8^grFZGTf;l+ic;riY@7R=w;`o16MGjHXj-Pb=+Xdh|MX zKP^=v^=jNhvC<5Ek7l7$ODyxFe_{n*4)^mMcgBj$4{TC==gXEjhiRISYJf!RC~>4)#(hYdSJyq zJQ7DSuj8fDCVFP3Do{1x0~I6v%qeg3i@$S;*v=y9NSe6os7`1co5iHRw~)f!Mj2i!w!(82jaL=zXf|FaLtQ-{p# zi2&=XQl-T|)ie>&s1}26rOwW=`<(}tx&z1guU2PC&l*TGjuM!UCbk)O%H#GGaagY+ zcvbe^dD>vvPxj(pX~m;?G;*jHg(KagArjX$o@YJU`=&~+#L>7}N`<$Wv|$#cL|CQK zsb52e+`mWksKmd$`2HvAd}TSMRBaumttWduS=Ok02|*YoEwh?Vbupv&_gz$}QYQz5 zxl7z8MVQFm4z>(G@Z3?HoFgNh^qU`VtXY1cPX6gE$-`6cc~4E$1Jls9O;T};wCQr> zrhlj@wWt;<>w8$AUYUepPu*NL`^wH{MpilWt}xu!;me3jZaxUGF0beK{pHy3A_T+T zeu4e$mDKXdOwqP~6E=^lq)DOBNekP&@`TelcTs?;8p=kPk-)>l4uMJfhdS<>37G$W z<4->BUKzvk^*P|}r#*JKXlviIbf5vJ%b<)vlpPv8kh5~!4 zeD|6#38`Vfam}&qmBD>W?X$rd)%^X~gvGg?Vf*_&AM#$FZ}jbZ=-!*WWWi~|=l*15 zf&oYtAX5fZv_!^j$4V@*oqAwi7J*bX&GAm2psTA3v-&y+i%hM?ngUis^?OY-YNqJw z5s|TTd))#=WwDQnGcUXd2WJPw^;J$u1@;BTB41gNp|=U&%l6%i=5=-1Kvv zAQ$LOe@yZG+s{H-b5En01d?za(E@?>rioZe6ma$|U0 zY*l}N-Ee!$I3v5FDj}~_gry*9`!u~lLZPRZ=YNt^tpz2`L4AuHSt6c-X-pR1@@R7K z$Jpt=Mt$5h#d)gwR-*s8TC=wRQ$ko@0yFrZCqWx&?fnU`IY`>#%I5`dZiyl7qb&XHb;F!x8RPi9-bhT}_q= zw&(Zytt5R_jZe9>*z=Gv6(t^OrwVNE?)Wh*Urk5KvhRHDq-S3D*QD9~0&?*R(oa6cb))dAEC072F`Jfa^W?3oePWG|lKwX{^!iR?1ZRIM ziz>~KRcijLBN9p~>3k=$$Z+HhKHe^+sn-pe!OG>tn9fgsQN7ZxmOJ4Mp`$#M^y`x@ zCws&infyblgcf&FtXb!q+d_u}x)AX-8Rf4DyGawuzhoZO@ z3Tkk34xQxNZeG2Crrglh92*gxPw0triR&q+jDfW^cEPwL@L>ox6*N-tdr%SEEXPxL z=>O03282b>tinu8Gg(LW%g`DYGmc&~Nug5b`9{>&)P>s38>ORJ&_0el;Zs9DHhiupwkR#lou!gQ6D5BJf?a%< zpZoOwb2?kHs(;x&QzGPS5a0CDQpGfE_WTxa|1ym|X?ym~)y@YF0}7VusL2=;&^jft{UZj~j;cf-k3VOI`S?{{yai z!bt76S{W|fqt&Na=y$ytK`ll7(>@_UN%JzS~hk^N^$(a=sd z7Yovrx|i;TNg4A)7IElbSB(z~RO~i)YF>=j3b2d!36A;;}zu((%Nq*FHN^ zFME#!A(+T77XEEvnhcswjZt53KFf-`=8Yrzrh^iOcp5!K$waNv>rp6-Vq!c(GFSeQbQar3=x?X}EtPKx2s*TvGl&g-Hg%K|BWe6)j! zIz@uRAC(zu^e!L_A&FrmJRu6NuR>SWA&f|GgRbZ_Vk>s9lQ3x zSF;?>OxP=={M9Ho=a>KLt_MvPWpA*(FC9wtS0bhlRmB{8(}n~e3^f(sAK^B5!pEAK zJR*3qFc7hq%e>JWjN&}|rzvd)XZ|Mq9nbmP5Jc)+wU=zpq12GN*o@=T-y~Z;KH+su z*}H1|lHqQ@h3$LW+UYb4kTIY(Tvop;*S*-k)ua@E)wB5m2*dE`XvKQPdwXiNjF$2b ze^Xu0)P9EQpzotawQik&hUn1-F|!fy;34+sFzj-A^+DG6;k~J%$t{rV7|7cQ?!u;` z8~bsl!iI_c*<_T^Bg2m-Aq^op=@O*zv=P@PC>J+VVU_C1=g;|?`~MBS**GiKppm9) z`WPB&@>Al9d1(JgWXNH)pK+k>zhfVB=4OXI(#?}Et$N%QnGBK zXm*p6*OD11|E@KPj6I5xzQ=<8v0cf+X*Z(e{rLOFKsiDspD{*!q8$5--bnh?O&AwM{z>;2S@^F*O~`*ei~*6C`5usWh= zQW^=B{KLrZN4>x`KNxNff;p1q6VEkYLR{ z?ByB~a{tS{UOV~Gv%IIzhp%-$&Gn0aRXC$IU$Gr_`5R%hh40(O?d|m!OCPv?=uRYF zuDrN`hfDNNY!|&I^d>>9rJe6v-&ZZP_StCdtc9g3*H#y;e8o5WTQmRH^_h77i^z6! zZsKm|dWz(Bu{NSC&4VN1qJ-L_(6upQnOTOUy~-uRBo8$D0ir>q`{Zsn&uQi)%gb{k zf#mq{;|DQ0IfrncWcK?~3!5>V;8Qxd843iNT{pAU35>B8wwD4=y9 z0?*oq(t~P1Zwm^Wk{>`v%-?ce@>= z-Zm{eqj$r>G=a6nQnB?eulLfH@l|UT$PJ20V)aCu?k_Y)uA6T>$2DEp_ItGcu79}F zuDiZCYT!vlY9%_9KU4oX8%n&6HDsLCZ);*A zZ9x2|t>@?HQY znV6Ue`$$;8hnv^FPA~0AkR**q&G9E-5H$?jNarM^lXSJ}xdX8uC=?;$^#XQBmgYIt8psc`Oedf87+RT&e!9Jsg$C z3!y1-=kJe~a%Ff%J|yXRS({+b*tQsCO#Kc8hU4Vt7n(lm9gjWkgV1>f_UTu0-#&x=EaYZS%`>cv=G%b?BVB7+-uS$Z-&J;tf2_;M9ABQ$ z=i|&&(?ClL{b0*!cAJxQ zOvZHfovC^4f!g)>^Z4e86W(nhY_|Oh?h`|ARkEwCd7Y?wl41M@-g^Jh_iT={TJg^qnZp!|TP|Lein}K_CZVD%><;|%ily$DpB`kT}dS+c32 zv*}D%#{PM6XL+5V%&45TYR=7vo^y-eC>8UOZj5nSbtE#P(T=S5PhbR2%+cvRK)U^& z?4Su1@e@YUy(8AXakew0nxi^ahV*E=Q=D#jD<{T7&YTL%xPwRhh3-{9$>Q%}6{F6- zt6C^lNmMyB6?OV`ifkYkU#4s!t^Qw1oQcGwqE_(qffXt~HuJ<1JDH!ksW^o#r}p1m z6Q5w^DqM5Vn0T9_<-C1!4$=Bu_I&ilOT(BF%Ej(wlnW*KrC#M3)VanmM*-0~r5wOR z7$2FX>>ur?^Dkn!ec2LZ8mvA@%^@&*nY}eXN$}c+P)*&I#WUfxg(d^2Dq#ruA4YH( zuCyh)fr9V(y+pv|d&(_)vQSU6&cj*E2oxUnRXwzeM5;BgX6Q?@2ss4nxx?XXH4oSTf^xk1VFM>$C7x<9rEwwA+V6k_2api>Z`2m{uh)+_>wTIos zHs+k_Uk_DTJ2(5pZ|vgfS?vA;X%EZEUs}Z2c4 z47^=ke^qHztdGOPZj(32;zQH4Sw8<75fXWv-d7b#_wT73?DX= z{vEMI8mMaT1grL^L^e7ypP8nB+ob@k<0$~&}}RPO$#nPhpLnTsP&;~~l)&uLMOEBI?N9vc+}hCh?(6_hAi;#h_3lc0kGJ4la) z&kka}FUiR#C&8Aj_y=+tUZ2)~wNF(jZ$34kD{1KO$XD)QAVmH|X~duWEV(yoz*vGd z_OFARcE+eVSjrQZ`y00@*J*IA;zH=n&N%(q+R?Udng8)hpSUrLr#^)#MFpEp((@O& z!3^k>^>LE#I!DZ3IcrYYPrTC=>rBsAGj~$(eqQigHTJ99XQeA*>oal_f5Dtk(N!xh zMpziTeu3opgNlfpdRaZ6O{>cLEJ8HwLM#K57zPcr>MwN)qM23_6$V*<)#FS&n?5d# z2+v?C)Q%-0FnscgzjWFX8jZU_8D8`g+_~TEmFG4!Qa)ZsFRu4qKct+?t~gm+b;^r^ z3E}O{<6C6s!VkBTdrd+S7s&!O$swk1d>SoGe+0cb!2QOi3FyP-YI^}G&#u+KDqukpKRSW z(`7u)KtHJKmujJJjyI_F3!lS-OSjpJtK|M{^L5}>5}-4HqBHR78=Wm#H0A95o*$6E zj$__b#;E6NxcqEth`x%)8{Di#Ahoaibpk7tPvdxPqvWe!i4W;N-jn6VWDdpj2dZNF z%4hx?#W_QMKM4h1?&~C=KSFjQDUhA@xJ1Kkmb9Y?W|qL4Rto*y@t`_#E6%R&i90?R zjFsYsi?9p3J=Jz#bqz%v!CXjYc-r3*K*C5g!hMg2m24vTXNVq)tG03%z~K8_ds&Cq zM^}31EXZfEyHzV2diOtgNA_aqy#o;1G$n`}u*#b)j0BKM?1Tf~i(zPIxxw!3h_@SyUM$y}f3pgw_cych;Y{* zp;t47`wxiq%1$MEBjQqY zW?>J9ale@z9YYPKE<-8{gLkCBh$u28fWkuT5aD?96XY#=>d=q{m=)KB3X^MwlPq}$ zXMJ@`;XGqr((uvxODb4S_xZaHi6OsW$D6R&0W!gey+3r8It3+7yB(Lfu*ne2-? zAwLQc`5gK}Y5KL3KKanf(KcpaX+Zmx&yI63z{o00AL~^Nc1Mu%O|}3MTePq5{mT}V zvibLKmi#zmYoEONF!Zr+qm8KAZZg*8;Qfl5JEPfPAg_GT+_w|^2-U98euC#o#E&N< zHZYLP<47-@+!*WsdxIm^OIv+`*M4CZlS?O;ZjkE2`tifsr^mSp z^dts#iOj$Vd0Fe*eaoXiDwpQZ{dQFtWSC$(P0^rKatI+TQWeqr6GJwjq4tp>8@eAdu+H(o9^yz(>Z2h>dURWySv*o!*q8~_w(NG*@)c)!WPndK3q3Kkt<5Lb;F;{{u&DMwqCf&(|JFkE{nl+o=$H&2KuHw zuC=04FI&ALTWRC_#QgzT5bc)v@f8OzIrt1LwerV0sg6*H6A%|C$?B<>x09gQkiB00p=pa`JZkWyRI>!> zuR{;12Y|B4bC}ZVc$M72=>Te-O8w5$v+0?6APKC6B?95S97-YPWb=bhKhDRSH(p+1U^C5f;qThUXr$S$ zFJ57iJzTy$LeZE%n?}cIb@xBjCCxu6HLO{{cx9L}8Zu*P{vb=|RWWuU*sg1GjFwjM z6c}{ULa39`#d7F*h!>7H#E|34y>{~}H68k+|FAUG&djNfSPFjO-3AZxc}67L{Way% z6D&}`@H=e{QrUVtiz1b?Q;wDnE@c<23oS0OS9O=4#^p+W|=6$ z`jh(l_)1R%O-^2333$USEY`N6`n1?TfECt&#u8M!N+9pwbOehXP_4kz18(B??_Ln; z_^&7dbCIelNG9j$q=iM2$WiRUa01p`0M^9-=STq7B?K8%;Ln@4^?D`56w3fqG~eh* zt^c@zpOlianFrMaH0poxDPeutW6|#qwC3<=yzSZ&3II7wl zNR%3zSelo042syU3~skuHn{*i+@qB?;)a3I!-o}viLVi?UIJBGmtHuL5`c&bgsXZ3 zLV9*i)^@x`qBaS?-(W!VMtnI#Sw9M1JbmRO0bb#teIGhID!lR%`nSFnS(eF@9XwoI z1hSVv{t177u>?3yWom$dg8)2}faw5ec_Ut$2_WSqM9~M>D1gHYc=XyTDu8YI)sJ`} zO`@)1(y$3cJvn!`0OW3$t>NuzSPm2kAQoRa68xAXqdGI0WJoRy@sw z|FL=MaOI{G)6;2FMyDDLT;4AfOVWT)6|~^M^(%^E#NLaT@m(N-N9rU+K>&{m@C|{d z0AWlL)r_E>_e*)uWOqX;Vx#n+rinzj)n|yus2~Kiyu|r#?vOS~hERn1rc*VXKFR+= zA#IWzq0-2TuV6j1ArYiz{G>qfCY(W+GD`GUjLMQ`i@4VZ8x>PC!LemI#N0nx6dRW^ z(DlX|eS?u9z9i^3UA}{hYs{e*1fL}^h*Kc)0Mp-3yT`7o%I<1ehfH9svpr+FZ`^KK+}$-~BA!%}%A}dQ^M6_dEY#*j4w(g;neZx;q2Mmi<3>uNAlL zxVWCS-Z>cb&^{#(8N@TJJ?^D{_L0lU4)wSRbO9KI?5wN+pt=&%a|H4$Q2N=j+LYd z9oUpG`j}uEBC*=L%UFGSq}8g(%BX%lbs=cJM`FDR^}DB6-_?UC{{pM_1EsKC??Pzl zW0`V3)mJ0dXU?Va(>PhP!nrn$GW#zj@s7>Q;zUFQK!OL%>DE~1AMEnNPP;ShD({IE z^n!x8UipIkI~{eR>!aSjdETdr)BKbEJrqHoAhXjX}f9z4Ry?_>3rPpL9C=dP;M#!&?U0*`zpF zT@F<9lIE`b$#f?HbSEJ%7ZsV5g%3lIPA?k>fe^h?$_}^SF>Hn1we>cKIW^r=vdiAP zY1Ta_UPf7`k6~!srXHLRouZQ_ZRK912v4Vv%i^V4(KXXtZD^gxQ*p4vkvA#oVhSa` zehIX>)%<+!TF@Lz%ir@Ceh(y%BJFLD9^W3%`o3S~&a?zm;4aYvk`s^a1DTky=ai)4 zT9Z$6(QylIJf^}&-2k_^BNcj>46nVXp@U1;gNhrXdAO~MVPe`BhQ7bEgt6k~I{lmH zI`D3Ioh>>|5#vjOQd8WP#OE!RT}c%xX98*em8eG3qz=!_G1WxrRE5s%i^pys<~b+4 z7kkVNDK7s1G-@c~0n}Ipy>d*5BJ4+C7HbEaL$YR@nZr27N*JU`({}(EI+-5xM%I${ z2}ANjERJoq0Xo%Sx!Dz*cQFBS*6oM@G=*TEYh4z`DF8vth7^Jy)qZU_dSSquIQ|48 z7J%;5^E&3vmt?DQ3-MRrRrWPj4s_0Wi|_#!#0(M=5U}~9TyP5%=1n%YdOzE-VnTz& z(tX=6zWQ~Y4bo$_^uX}+e*KS$WA}iL@alAZrNYJ_Z)WHgOW^|FUU+mZ=6&fD_pESr zFMJZWch;Vv@eB2q6F&d*CcE#X7vlHP5SyCH>_203v99;2PbBnM!RNeD>_w)cK9#pc_|*x{jCNI27D``o6t3pmE$ zu?vnHfTIR@HekaCl2kyUFs5X0@6-cNexb8Y_}bc9aIYBW1hxq9m;r<;u(ET>LMs5+ z1xXqV<^yoI0uvM1BmsmsjH;?5&<%2`S!gA{VuEO=r>4>nMOJ%Un1O6O*0xJ*fG?7a zP9!YtX8N}%0(UcTVigA?5Lh)q^?fyw8xPQc0Z)Kp{}td90S8s7ZcBm*#}GJ{0dasB zl370O(C**<4FHe;3&UO@4efM|n9I8v^RDQvvEu2`EzV%*{Cu&xBTZaYCi&k|On>9u z>tm2B@vG5~+y$l6-N2Ne4zZ%KHj%-t$ z7@yWTIiD~d9`5XQa~)U>gR2}+$lt%N`Si~$mW~hD7BFrVbJjH8!3eREwE*f0UOVua z+(@`5h9U&=OIgbohUEs_W}qnAQYPMuCV!?8A2AN$tKYjoWMhr(0`3B~KHNE=tS6j- zGt$0j?P1crJj4l>g?rdmEM?(cNI%vo9mkG+a?z2>f{04;s?zz<*>NAm2G_L-5?mtj zdF{BWl`V!-*C)zDM>@ay=BJFTl6Sni|fC0{`&0hA36o}ZqVW2|52iH zSn;LwVkX+a@CE2b%gdv{tZ6^k368*E7f@V`jTQ{%-AHsDgAAKTbPHVP6eHhoI86b5`EUs;K;FCiuB` zOLh&8QGGg+iHqU<|H0fq`ZA{Xf43beY5s?gV>OG0wWtDJ<{5$M9kK?3xI6GP`BZC^&lke}Opd%iCg(Xd0I2X&+ZWlJc zly%R}%)vv|7?;|Pm!oc`VBJrc_bk5o{f*pq{<~j_S?zoAo^(wG=c#e*hLW^erxhPH zQ;E>`9?g4mdcqyOvyH!bA@dOFg_vYIX-?sTJEK>tFb%4&#~1Ui0#48NtDBBOx`x$J z_nG|(eQ3y9aKqYH5v;so%x=1!_3?~=^n||tE_r0{W7MawjveBn<}OOe{noCxtIs4S z^B5^}O!j}Qe-05Y)2&stP}Z|uwZvrn9C#(-{^@3KzS8Ra#fHZs!hg72EUS!td1Tg5 zpX`!6-5-B7aP?v1>Z5N_sl9y%MBnSp!1$q)1hLva(`|}n(9KCBS+}bI@GmcmJbdb3 zqfc$a=(wAYx)xfoUz&KiKkI~9&U#H+MWCkHZ`lyXg2U&&kG&ijdCASITs|YYeZhqo zL{qJK5GML(mwM|ekS2y1$9-pl@_$*<=nRtxJGrOhx?J5`eN zuDPo;ctG#}PDp@f^9fcfF{-5aUt%iQ!X>9915XDa6cNZx1G1|z@Tkd6yX;tSAraxA zLt-zaO7R#4zn%aD#>L-Zu*+!rQ)vkAb#ub~(c+)GXGdHap9?_-kqd&%`_B{%@NO>M zx3`VwY32Y{YM2nF)D;q`WE>w@@U1L6MND2+mW`j^(qAZr$JWToGYtRY!4j)N^zdjs zY;<7atNEFi%RZ7J%lz{6=qHa*$FC6s?OOfmdPA$vPZ{j4mPC2w26dWAm61k@YL%XI zR-(%S!&SiBe6c&;vH196P}cV8P|;u>7Olf!&()H$>&_A-W8j zc4%91)CjyK;Gq!g>cy$uc3lgL=20WqTgKun6dDU z_+Yu)W9WYhH-g{qV0P?9iAsI_j^V#vUq}bd<#jNLJUtEv40;R(yUaGqg}S3%Csjzx zKPwqF>)rFA}{U8WZFhECQK(g!7c{TlVvdY=(b4DX})$|tgux5UNLW@~VDy(B;Dh~M9R zNFCPA(!`wNPZqmqj%i*HKB##V|Bi6Uea&eEUX?#3rN{FD)_rK3FJ#d2$fM>Te^0?Z zL(&Y1`GAand@Z z$CG<#>IK}r4rg@$%8{*JSId!k$2XfuM&*}Pve^hP#3I>Da?e}CSvcl$Y}*NJ0Fehg zk^KZOIw<n5rC!p@_3COy{m!PWf6x zn7u=V{%qISIHF)0&_eF10C5=o>b^TwEuo5OqAJCTn+!Y*X7;yiRUuXL81~HHmth4v zoBDsen2IFn68@?&O)i$}<%q;+k??T6HZ7J;LVB@s@_X`ld=9GJX64kQXD=!qME}@8 zBZaia!hl_diEIc(x6kW#DU+zu>MOP!>DKRcOK z{|3V~?_A&bWpR2fvyie~dUjgQ)r~9Yhlo6evFyi;04MIAMB!;3eR&Rq7h|<%zn^I% zlf3;l)E5&5zq~t!^XzzhS@`%#8Zt-KplN^XY{&Z;RI#$ar%@KzS6ovKMTbl>zO~_z zGw9?7toDMXAK1ckIK}yLP2Rcpt$nm5;5MEJXZT*@ zSw6y9aqIakefupA3!V3RjJ2O2>BLH@I#j5GoUB8p!vFOY�oi!S0nRQ8Lo1pPKoT zy{^~Ajp#R;u3hrU#Y&p}wZ~E4lg&nwKYy@FyjEU(g%32Yt784{bTH}I(k0hw7d00r zyOLtwOa;S%(s0p4viSp{&NJ;g1Zg7)qskyU^kpF~3pQTs6)L?N!$_{uf5ocJM(o!a zBI6$pXB{03{HuV;hw1I5=MZkV&Cv;M%xHEY!?|n-GLN13Ghclm79Y?cea9m2w`%~< zqw;AEJ$Zcc@}XiT?i-vclEsCQTHcxxC`M z%d}rPFp@>R1%6yMo*IMa9C|ds-sXb&34(9g06qQr=>hCXkWwb>8i@Tr6{&Fe2Lmk{ zSPg-53E-i|44M36?;l?My~ub;waT-C!E{R@{jNJlFZ}g{_Y{#krdwp$frBNRmI6n6&#rW7C8T+_}jit*!9>dx|1c4zA z2xYaiCk`sJ3Wg0{YW21M{Q2|Hwv&Lxf8&a(R<*TtVAq|b zK$n!94xr{BW27I@MfUb4NNoVi0U477@Jc{70|*GRNR|LJp{+a~yCn;nH$blq>Z>W3 zB>%+}sxTlLsBk4R;vq0vf)#Q6^&cP*g!Xs_xFg5j0_)%Iqe+{Hb`vIDaV2+U+4UL(E!4HA9()KDYKSWrltb( zEkVjq4i=!yBMmbBdWLi$&85r4q~b6+$JFB9UuHHy3Z^Z+)o8G|+- zb(e?0b=&Bnds1~CyMa?wq)7-{I^HhxM_6_iFzfKM(|v?zPfz@S48)iRtgA?&X*H)~x&L+yR;uccs@Q7K|* zwpAPjJ~WEJy(Wi|Ysnh!jNH*V-BNbt%wTGV6;@tH8jy z>&lEXcP6W}C>&zP29GnT44*$^x7T*I03} zyzYFh$d1~1zM9GvK!cHsrPpNAkQ26;K{Q?kiewI$ABPA@IIh0gm|Lh+zV-#kn^%*g$S6LY;e#^lsf#eU;uw5Kb1!>W%pQtBNAauu1)x@s!PNPaIe zKHh_PE@>|*m4UFA>|18J2IBuQp6UA)!uOdet2(C=`ipoFJ&)S&ufWHnJuZp_D?MY>A@oQI5;IPqPTXE$#oZ(oz^p>{2IZg0(FKCPxA6aT0Tk>-s zFY`I+K?_IJ$$&xZGG#3TLi1%i9yeFV#{*UA83y(I{KR1s2SF0>UZp0IV5J|Ggft8XBqo>z@&E{d|ttI^EL z`Pb8}Z7|k|8mBG-kpbTCsevn)6WqALX#g}2z)=H~LO}Ein1RMr(*W{ikw_OOCFVSL z>~^sgr$9B#Vc+q@^G|cOi=e>_Lk55XPo`N(kN1ZafQSKxS`mQr0lGS34CyX!oLCq* zj9=SMI!#W&8ch8?SRxTLQmH~7Q;E?iAN;@>f(Cp2a(^1^sN9YhAj-;bfkX+w=Dx5b zBoSm}R)Fh&y&EQ(kOe`L+ArMfER;B7fs(~-CqUN$OgIX%DAwWZH*?yR@1bf+p|+!* z*Hl@QG;a~UY`O?kaHeuwXNR+K-a}em8>A90@xJIws-xt$026a$MD>+>^fEPMjIY6I z#E&em*y}x@Yt-a$E|uAtRa7H?o|N9Q4c5vQZBE_+P(1_#2Zz^k(|~R@t(jSf5M)Tg zLPtb2q?2qTY%NQLjD!S0GdV@*1$!LRP8nVb67fMYABjXlB$`R&`<7 z^gvxqFr+~lyz{@L?vVN7#pCw!d&$cv&=COhEzHKot>|u>3WH(8A*yO4QZc%LR)=je z>=Hn-20ek?ymQYs2_sFIMXEcxSbYC;QgPP+KJ}Qy*H49e1EU<8I~NlGka)xxk5;4- z1~R=WcM*HWz{YlNm}H``A-7~Z zzXBDU3N3KVXeU`-8ELj9$o}ctel*q5m?!$Wk(v=4|G@#?=NeEjAtS^+?VE4PQ~!K^ z(g?_x6SN--u%$#Aa2@*QcQ;C0gSBe^`#>PGdZ{{JYkHNJ{6UQnN`CW&TX$uxE#a!8 z;)_aRqFMFOr;@`Q*D4(W^_H~!iw-o(9aL~Oe0sPs7CFl7+c7B3S4?JR-;Dv|{~ruO zK_8ue#AX8JIt@Npq4FZ}Qeg?16bAvMFaJ5#2H!c@ZY7@=Tl%GDrgBW{Q_%FT{9o#0zCM>^r=p0r zbgD9lBo`WGJZ)*rlDj|7HAfJ)JkuV+A@x@`HB)9iZf6vL=)G_l45TD;!(f(>3NCG` z7KoQ7RLZhzi1YNp&70EeUdOK#%s*GLDy^7n%9f%zDf+Tsxb`9_a;1Zsaaz!rX7@P6 zzzU)24TrR%TTA%JS!%*;;#$>Jv+usSh|Y^|Hxq@`(Kg>>eFf-PYy>78X|y@?fAGq~ zJyy^P-IR&PO(*VYJ03t!#2IPmPveY!b)B&e?lNJcxnUz_JO7&lAndi15z z|NU_I6;AKN$&KAg(-Awmz?T)0nWPnR8uM%y+K;=DsrYaC(J6`*M`{WK;}0Vx{z)ZJ zyycmo2~LM3kh!E{dDW9t&x5$WY_5co=CbNp-rK>k=d-o7J?oo{s5C}((B;<@;oOvK ziWO4iBr5hLG{pBo(&nc`wW^{ zbaXLQ)h4e|qHo-Q78VdG~@jR_;xf6$7A<0=)pB#sKa=@a+O$ z6Ik3|US9rNi_=H}kqcpGKRBENs*x%HzV9peB?CA>m4*q3djJq@faV(nxK<1U=|Q~0 zVk`d=fW`;^9iVysV_L*ZuV37K!Rd?EVNZGb@hzaZ*yc}V0KkxgMHV;;fQ0Vp*;xq% z1uXm4b0qL#CE)&{=Aw1LD3T=G-#7+7DBw}Lovz4%Vg>MPfR_Z=lW5)RY@qniV55R2 z8?dy&@C;l#e9k)&>`D6a0(~}*#%98a+s-2y_-j5aP-EcoWUJId+e!We%?tmY7t1e` z=O)f%>V($07wJ>s?D(gP{K_wg&h4s-r8&(LB2wX07hylvSD?p?EfSmQ&Mk9u$=|-S zG^~)Kpj@HyDpRu6#!XNVt>pIC5$%yBaxtzNiQ9Bil#?Fu4#2X){7aO0e!PS1>Xpn@ z8c~Z%A`kg%>E`9r|32W>^SM&}f2b}H)$YLY%i1D*$(CS31W{fvk?_qj$~jcbF`20?4%*;Sij( z_#NGfy-WL(G8SdyYh%JK_Wc9!ss66>pMpb!$Df1r_~f(|otl;95Vs2_(~k!4M@ z78{P>s%@;OGT;WOf~Y;Wj3r3jNIQ%6LLK zS%FJ=5a~w0g&p|A^|%HFsOIzMk>eF*j3{^#e1!nae$_Trbfe8G|$`WK}|%0Iu&?^)CLJWU9awOR`QG;{ zvu8|y2)nv~)YSwZnC-$%_ZEmU)e4jdyUZTm!$ZdmW6&|;heyZ+#N`!1#^8>f)W(WQ zY?emEH>u}*wUTVh`}=yG_r#}Ikr)>lxQLpH^vn_8tyCe3q>VbUlwEW?$42R(>D!h@ zw62pr=tX^wTpl}73H$j4<*PBZooZflWjU^KeIs<^&&G3Dt}j4{#7t{R|{c7Kve{UxN&8qZ$>nyF7jO7EW;GW1m@8L^*4^HrmX zN2Xe`rxtaZ8eGZ}Dy zs;znF37>2_pnrGuoAgxzmZNT~t0*tg6SDrZLpoF(?PuDIsa|sS!~-n;ohI|dwByr5 zSo4?V=paVpvwbg@*Dro|tkJAJezyf{H=P|170vr+$$F%vb1Hl;YS8BSW~4E!uHP6K z3I`Hp!{5Coz8oF_(Uz`FwT<}kj~oe_YCWOq3n_yoSoUjAQAP?}IW3(3`_+ux9rE1wvAQo? z27w#0UbR<7vM=8X)ky!rIy~4#A*CsSh7j$)<3RAr0gf`W)Ka5OFF8k1I$1)-o;5i? z=8Gy7De1lFirs)+-4qUHjup{e@RQ6(Z8k}(tQG?vgMCzJvJN-I7i&@PCK>>IrEV|9#W~{bB6pxr9&h_!4c_r_tDwPI}GY-)YW-G>o8N8qQ1MVKH#Ikfdw{uS!rlaO+ zuTgEqie_G|DGbW16my@5EQFe`(c3@CrAKe=DB~lab1n7w?MDHQ0!HSS)(8au(XP!T zTp_2C;Y+kvs%nil?}+1n|3l@1(WjY;|mbH}?T*xl=w z#`%nhPFAeOS#X5`z=161C~Cvk*itrVGmFpaQu+v`Mn@ni^TKciG3U|dKbkzy(;Dkb zMl9lSXs^K@|Vd7w5`# z8?M@uANaE>SUPv^?mTjc`aqL9yd4o-YM}QH8`Y^PwafEusq;U3>xSr8{lwAj3y*2I zwvd6%ETtj>RrxB72td@M$pv9`MJm50h*;vKkp`LjaVIOn9U)A5i2f}1e1`uq{_&>@ zpv3zV7@)?47wM={xj4N2m#S<5=%xLycF^c4GpL2>(m!X}+9znroDfdp8h0zs?oiJ8sas!@scz-1v%0y)%;Io_8<1jYB&4ne^Gu})FWpP%HgjqjN z6SLB7As|)mlm0F#{36zS6ll=sCwEqD#S1Kl*8Z zQh8qz3+h|}sywn-EAc;54s<2K%|5EnRBzJ*iBR>;b&J0tHK`XH`vKYFUNFeaq5@Sq37>!AA2g>v3}}L#nsAx z$J`sEF@PXHLJJHBv@|A*fC&OFmHbs)#ACES-j{FEeTPr`T*zSt+4BQxc zcPu^=ZvCfL+HYBwi)U|_RZ1X}97KNm{4J!>?5M9G`KE(q>ZnDB zg&3(pcap3-fQ^XgDnisr0JXEpd6y3~oIptg0&;++$-e!L7VM!yM!qkbey-nJ%_{$0 zq~h9d#Dw?H+X9AkXMj*8^xT2@hklJ$*P9GjU*Il+$?BuicmRQXz)(CIpbJJUe@=*ERR*rEs|?mA2me2pQ9a@G(Ym$s&x z7NoirH1RIJ5y;fiEgVj^WO6hT-%ctKp^d;AxM!WZycK9)sDiaMq@vdoozqgp`OR?T zJuP$pi0b=@kL+l$n{sYOrty`0J8~K4ceiT>ZrtBwtsKUgu^@crh{rRI&uY1M2Zs1B zjU+jyqj5T@a+F0(&2BJgL{X9DW^=?rso~Zx<9WB_N<7KxehHhSIT}s0Ig~?q!h*kp zP9GiR2dGDu&5f52>JZ=pAkDWj?|2ic&!8(}&cS_7Go(8R`b8>JbeFUf6REG8-;&z_ zE0I82eo+xBSU7@+_pB^f;A{lr9iS!wqbW9c@dq}+Z!pj%8#$3N{=!(s(ZLrl!K#|X3O=xCoZ44F`JLlucZFM<78epIx97+b>=q< z%j4G#*IJm?!wK((W9fgyCQ?hXQ4PQ%C58?aIiHjlpGGyTCLi=;pdd+R_9D;eaPF0t zm!GN4T&#>gE#1&?&7k=UC%ws3GQZgN&bjW-n>%09c9^Dx4J8qxgn3|H(Qh9S`GDGB z_qObay#K7(a9))F$2T)(D2CrTdBv1WZI-2A;k+v<;45)_FNW9W3XsZbW)|WtJYH=& z48mi8%w6kQT1i?SFCRS^4)kcoJt40E*&h6we&R?n0dL^VOOE|0FJP0412YrF>q?VL zrK10~)pPLk2unhGvJ!T3?NXE9nnreS;nSV_^^A|iSZ);YD7mz-gPoZ<$8R$Z1A8Gv_Bt(xTn?qYv?yUFHgj0_l~!IFG!DM zlrlS}j&Z=?owp&JHt~*PK z>TbvgIBkc~e>#F&!wT#Y=0ejw-bRG>3rreD4}&Nu(o-&(_In-UuQ_F69Z!8uP51Lxl*TU1@zmSgzTArRq1hu! zMU6k`iJn>u5%rNaWa`zo<$fcK99G7@gp-^i{8FR+?&kJv^!L5ns7{k!i(R=%#UkBb zPz&(W{Q|-ZkPF97&Fytb^&1~9WRsP1l`T2m(L!kBDC6a(xwQM}%%SW2+q6oO)mK$) z4VYg!w+JXnFtxFqP_1Ngv~e7WS!PY4>tlkGX_=-tOOAAjq9Q&H4$zi(CV2H>OrM}<(`oa{6A&JMtIYg8oF<-6NZXA%Xct#E3Qd6Kw5n)-M5o7l zE5_jp%heO$_hsAN*B`;s3YDW>tFLXT)6n9JA?^Et+FN)e9glWFuHN-?V+)I1!JG5J zo|gF~lG?<}_<_%or-^(unEC0c>%B>va6`Iu=^&`x7R*80?s|k%NP6SE zwGaC|mt;SwS-8Ibs-be-*;+%bjWpu#sRJY})njQ$pY-K(^W$=#v7~-@aI0MP&8U2MKlnp(8(}@C@mFP1UE7Un=z|rYEdVrneYq`Ih=N=}M?MlD z9tMLa&?bTT2?cmh0R9}X##B^QHE;H3XVt*w473SAX$GdrUjof5GP%?H9JCEgkKn!o zM8`nz#vmk(m&PP6m8t8742B&b@&HruR43Ht88{d@l5*?o@fsFwtFCCyn8Jr+Jv8WX zBnzh1K7CyIoXe#kkXC=99XrYL=@iVYRfAg}J`hC$aaySz>-@4Y0a9IEotjriHa(Ef z0dOwJM@q=I(bXkw(kUMa)vbPhm!eBlFC)?3%5pp~w^BzDm4z|Qb$;g!jzB1@(NlHc zKnMZ@!F((eE2Ve(SD2+kfoO9`H25exnnTEq^hG-DQ8ep|n#q6F66#cMy$Prj!W`Bo zE`Ha#ajtGrTkI{dZAzq&2Gubt`jXLqAg^|?I4i;GxNt(7&{~$hN=N3Kdk`>2ZXYP# z7W8m)dDYUuQ0w!Nc@;w1ej_AQtuMKqN*-vw`c35V?+ouNMzo{(YJ>C!zm`OIb(V|6 zs7DMF3*nJBkvaMVnH8E@Rpn^{yH_4<3}K?+sJJy0=i=t3)i(>838Q3Munhhe_6Xd` z!1&d$qKzj=QOQ8Xm<0MZ#hL-%pN4%Z{`0G zYwE~61%<6U8s0YBmhJIb*tc`|bs~5^1Z#SUp)_l+yj;8Th|Snlt*+CQYEw2-Jg*P1 zaiK!<*N%+O8bktrSl-TMyje|>?P)UX3c2YJ3&>+Z$!JxE8L`7(YV-QU`RvYm`KrfU zgjUvqG#RG$6HGg7#oqN_cZ#^67)Q!o<1#@6YtJ>m=Nh(=c#KPNwC6*S&c8e{f)R2* zM0=^fepI*SzqO50#?SmkNAMWV{lK3F%r5w0n3!^pW%Q!b1^EYmuSf+D^)Ph@eaj-e|=8m{VcBlCBZ>JNui^4@t+E7 zlMb`scYc?ciu9c#!k7)?8OCsvu6}y~cC@q~~9Ot|$UZ8s~N>^Z$H5#%(_NX~ABYIlj7j%_0o z0-@Exj)<8rpS&!Y_lDTlN^`k~-a3C zIvD@S6-?vZnwSgx83-a_jsIA-{Ce^^`Dx&}`L~7MAGXlfn;ErG0@crjSHU1sB4H%N z5cB-&3Qfn?L)Pim_upg6Mk>KpCE+E(d9PGf!iN(l+SgP1_YWgI&Jz;; z><*z2*JqZDZI3w*&xPxWP2^X$ljCqS%}x=vzv7NY|5gipYN!ub_P|fJ3N(uQ%puD` z7G$RX_9jKpomxneAuYSPIJvo50Km@iKPbe{b@(t17XD8DZ+KxKfN5!A;JfUsNZ40= zCk|dNuFLj?xor;+xytC}!yc(qG|YmI9NxxC=N%)t<#U=-ewbis&qsn6+>}g&UfO`~ zyX_-^hx>sH>)d_GDhFz2`B9U&E_Df#qX-6O@Dv1+HZG#NumGjEda4lZM%@lwd4%n# z|9%5`91y$${Xt(s1LxWH69-|=QGTTa|do3qNwHAta=}tvyt~9 zWBbkw*GD#RPI7mhQzIvd2!%FVv2y98skMLji|BqBVL+u8uVhpJ{~V>SWpJrW@W$Y| zCH{j(gU!1AIQDc|C$hzVx6b6$o4Et5j`fNK?XHBnD;a5+?H`V4GylH)ou2_Yxxj%W zCnv|G-<}GnG(ZRlmWl>!;1oxdGODE~U(E+(833^W%J%=vEmPoMtgTT1@i-R`j~kS<+a9mfYzkc*4?657OhN;cg(LWfo9U6BfBIaOgjaf2;;3<$qC z2s9-QoqfwcFD~YYk>$v>EL2r3%saXL#q!DP^QDqFqn9LHX!#)^{A8c=*^LgtJY6<@ z*Q_xl71ZbJWLQJUjNf?zQ4(^~O!gFarC7l3yKEOup~!>>83?4Ip=f>L2y#5N#zx4&LYU%kHZb^qB3^G9i zckBIPtVS<*2np>ow9)dvrGVM^`nJZ9&r1;|Uj3q#9_JgAqyW4^JDR@x+AnNow7}!1 z$CR`4C+J~{`pKLPf)$)P3(k1RI@U9e*5P`CFyc4~jzP)dtCwy4o|1vCP5;#=l2R-D z5kIJM;$yoz%1N__`6E(N+Z2@fxjdy4`-xbhv^ielb zLf9%v)BP)+yl&&auZtw0p^rvxG(t8fe#7W{f3c~-_%7!E;$`>R#x_G8he_q?m(7K9 z(1Z?Mn1D?12i4M7Xkum>t<*-EEd;~ixaKOVM>ic$oQ*HEF;R~Pbod`1v)CQwFn)Hg z3M1)zOOkjMz@N04p4&R}^*RbVXbgU`)p@6{$`4$A0Lb*l`S*Q>(((6yN9{S7@=bSyJ9C6_%Mj5ZyXTonul!&p7D zzanZ;X9qEJ6T7bMP1$K)83Y1E+jCSc08qxP z-*}2nvn&;cnDQ;`RU;1ud`_XmDmqz2c!B#Jxx5if$MWe$&EaXL-315EFIa1O50pZ* zhcUPHQ<1I`Ki(e=7S+>+XDtoSXuApD9V??%-eU$Q+`TTzNZ$Gp6ty{G-e@>rCVW$+ z{k{>Mo}Ru~)MBh>4GZaRmCkRl{Z+&C{G^nvZ5g7IdirJ`*9c=czgvC*7r}opF$h17 z{3C?quT8$P-{E?_=^q6DGYbdb^6Igj zOXPrHeII>bViUrp+EV%_vk=Wb#r_L!a|$#0;_xo-viJ=acB-)J&yI)h14Hi9KsXbg z#;ExS7R&|1QYkAVbYtD-g~o21WqitLRJi3pB=;+8Z!@wcR>h-j{??D&-1hgT^Yq)5LC1neLtLdL4uNyDl#BhMXt6v-q z@l0TiX3zeY#vyIUgh@^dSRAD~K{a8*tKqslMzU5?G6%vBU|9!kWdgu+%|88maBk}3 zA*iVKZJtMu?=qL^O>>n6=9xUGgKY&V9B?{LdBray#e3dWzy0)_fX%05Bze*xlg7eE>vpm2m;Gk96F7lMXP@q47tC%@BZvn$C z08b=lWHdzV3JM66dOcp@aj?b)J0=b9TzH(zM&b-AY)Q$|(3`x3Y<&x`+$r0nzw$b! zq4VNR894@PuygUi{$!%r@sTgvSJlg>yGR}6ySIFp1#u_IM6wV=13S!Vwl6sGMoOQb znx$pK-;58OKY0HpLb?EPtOaqo`ELfdL${qUFt9G-?mUok6wT^nERxaq*yLt@m6`Hp zWYhDh;O1#;*%idq<1*fsXhb}(8%oq@%JxufIJ|b^`y%b^_3$i(*Y4d8554;{v`LY% z>Ljo6+qD=S(bFXj6&lWMUnq3>lD1K%6$eE}%*XBH$cVofQejXHVfUwa00Ps%tk*!0 zL>df7=YJp?pr~rf@;bAj0s!Ix9I}Im}ZNv-ch=5lXsD1M6Bw`SaUt9^J@O=F0`tOupDp1R6MhQW=!9ldjiOABMWXdF% zEaf>YK@X96U>8ATL;I;yUM#w9y1C&CBU6MMDUc8(POPt+~5_?5QwV>meBcqgOh2Qk9j z8cb12x~&i;K2KwpJ&`5CUhj1HpqSgpx)wuhFsRB3XgMYynGx7m%8!OSmyUuxZW*3B z8{n*4HZsRI3h6iwcFJ#7q;m>Q`tNVu`p@W{q>h&<23Ci>?*f<+tJXNgH+%r)`6=rl zWGJD-a;q%x#xv=+fI2AM>%CMI} z(5|=ecsp5(m%wB7duvT^jq0NESg10K??0OxR3gR1$+Q{REYl|zHCvRFjSUQXBssBB zi$nma7(Z%ia#CRcGjTV|-v0H6V{dDOB;7=yAnNY0c_$Gr zoZTs){oGyRbdCg@Y8gdm><;;O$6btZcbDLol#~=zR1~zdqzRGwuA%8|(Nht)W34I? z{@X9-aM%2;nyj|luvDdu{$-j&OUTp7@9Z}6{N~`QNI%G@h$r&akDypr{d2pzPb#wX zVl|Y36VuF+QkYV6lXah?Djfsc+D&knSF^!#-V z4fY39`QqK~ym#byG0yRYk|yLzdJN7`mrOq>k&H{W8#^^jZc7}pCY30TF zb1@?B4)#BtZO<|~yps_HMakOq&L0HTigp{Pj}{s%sQ;ccPJP_gI~~&Lcv)!NzlzCC z+X+JHWeF6Mo$U9t<7z!!=w0FU#LPmz8vP}A`TXNQd8o(oD@!_x*(guTC1{4FiC_h& z{gTpByJjupziT(onun{l`Tjb_WD-o-Lq>l%E&+O)>B``aX7$r?yn-4{A8bH(_H}{R zx`MKD(BM|}sa#wlrPBuGql|!R+>j9-1cR}y(GRr>(LWQvb2BpjK>{NQ+c;8dMJt26 zq)CTS&=THB+z?YTGj>GMd}P94aYaRgktK3()oCmEZ$akzVZ3IGNcyGnDPrl3BA%o{u||Ru7iRr z)4fJ>eI<)(=VJIhaMSNHOxw1`qVnCW66ZTit zAL<3a5RVOv#!i=5!E~G;nCTA~-Y35_Jlrr5ZLNLH*t@^PWGBw@2WHGeDo)MO* zba1hyg-=ks3n8f@>{POiZYO03i%(t@dAgi`Rw>Odr?VIK^VyE35S?NHWa>U zk0VWF#=g($6;`AW;maI2u#IKne>E0f+p$j^l{&8BiEtYE8>a63NkvL$j-_eo$oM%N z>nUUike+E@b~af=m9O}0aK$87nw_;s_Mc2MB|3 zL&}&^v$RBvAy4T)1aq^qAT?6zzGg_*OAhnv?HPIv9a{eTE_cS;1;Y%j`D;O?WUAT@-VIIXGv=S`6kxb*?2^B&F3 zRvWF(IxS5b!KZN>QHOFCMW3UxbHn?w+VlHIoY%-{1l@-wz0Ki?2q@e}pO}&!i$c9; zww%XR=fu(E+fxkOt#3;f zE!LB?>-O(VUVjJbHN{AG@wcv}f2yiLQsc1M-5v}%-bvOX zGsobww*xJZ6P7(3R$We$YyG@%Wq>>ntAC4Pd$l`^l7s@SBS;m_m{{hNjA637PU3^y zc|i+V#|#TO@_A!9bU#pS61DSrv6QzUn2aLU8B+lFgJ3GUHg;)izqc9Pa{KL}V5bW` zra&IHuarqyi|b`*t!WxA$bSMT zA_Y~|L131H0FLynMbm6!u%D}IY;-tYU^Ta}SgbRfb}C(TX%B+=vfaBf)}Z-kVJb^Z z3F0tz*(9O#kZ? zbbb?07|1keu?OJ!7urW-xZ?P_}2z1 zK9<^6;tZLCNk3Q|K)KT0{s$gw$b&>*Yf2BID)e=c93cj5=&J1>Pu_ySu9rNtwb0pE z!{|_rEz`K9ZE{R=oo8xd0zfPoJWhzp%8Xa*;I9_K=ttfiHbcZjc?zMn)fB*f(o`oU;gq2!JP5je`?gZJ%zR`d3QWjWd0_shRx zX}$1cdPc)ewE3Tm0Yghc`W$6Vs!5f}(6|>d+H+((@rQoo0r~9g>>E-MdmY?$W2Pnwua^b%QYvvwJM!CSG2x}EB;mPgaNU>cK!Eke zQX5WUG}eK=i4DR89(TVy^o)AuTD6eGc2|01!=%H$ho8Ly5)^k9B&wJEW<};)F-d79 zQ`=?VdZc8xckB}Tp@u{NGt8AQtLB*z6LHQDw+8Y7v* zmguFE246=6SE&Oq#4&WD1nXp}j?dsyc+~kb^+jImG=2JjVad5!&{>_^%!EDy?`AKk z{f?>IX^}B@cqcH&b%;br^7yxGJ#eg)_Z~QE42om_+HO!e+!&UH>x$bNGGZf<1TzI0 z69;{`>8<@>Sxph+r6IGnAr*6%)8J?mvWf=@Ra<^9LM#^yp02=o@o?6v&A zC*$GOohT%?3J7q{2z;_9xsc`BQGL#bp(u*Iv$IN=NrJoW-VFvZ3k|nglDsxYt3h2^ zl04V*TqNOhsxtPLgY>q`l9F5of7cY>j^EGI45R(bNT1&Sd{WnKi0&6~AsVgSxl$7# zq2J35SNQ`i&oXiuZU30@TlQOZG#-*r$B141fCSvM*>59UUbncb4Hmq{bSwc9#vzKd zlTQ{{wWF|^ZmFVbK@Q4TxM60w)I>ulWYfGu z^J;yr&_0pU&rj+Z5@G(@+_d zNkFOw{hIAVdE;>&2a(@c-sze7an^ugwHDsl2J86N^5u`lze_cfnp}B#2E@6CWMcF< z{yvnrQl}+eo`mWmfmzA z3Ox>mUj^s!Hz9HD53u0yU((duCHzYN=cAHH1xD78@_^jE%aSlPliS}$?T-hU9U zbcXi!aY#5!^2*A_eh7(W>bzg%?=_*Ion`oWW6exKc&(`H0{!(h>-x7tbR4AT{Q_Cw z<_p#bW)ahBT#PW7+Fb^pmD8=^m}6s67k0_QvGmtVd_nI=f)T=)pT%kYU&<21?ONMB z-R&_fo{2oomrQAJX^FYB`d_y&JZ)CRbLqlFoft~Om|mQ#&WvKmqgoJVSH_3Z(7cUH zB9zyfyJ7@)DK}*F@HszWB5>k~ADWglZK)-#IaO{gMzt<@unE6}6yBc(37`k1#EQ{= zr8YwPWF5)0mt1Py_1f%&8SQabxHW!$+&qn~3B<$_X1g69gTLLjJj?e*pM6Ua6NfIk41 zl97q3_p1ILX^;bsQT_YN9bl`(h#6!|ja;(n%mi#LVxK2FfGvrh&dFJfdoie9UNHs~ zEp9^8v24NdXd+&2`|WpNM4iOstrQkV@pa;zfnIF!P$HWXK&8By*g=YTt=FS-T3VXx zL4GpeK$B*_Nw2zKVg|*Xlzof8c4t`u^jQ4R#N=f6-+BwTm;1fc^ejfhNvR2|;-X_; zweXzIg->;rmOV7)hp0t3P7fV@0A+Yi*=;3=%xZU#kqMX^A$rz|ES zti?AfKa-)qNkU$9i9Khx$ykruJlkHn*esya{FB9HPlPT6U)EshHj@9N5he{1X*(I2 zWtszsy8AY4CstOhR)$4#Vk!L$eXM_nmCl5|hYJAGv7U{pdRf}2{~$e^Jvr0svy7)4 z<^5lsWjx*1k_IPU7?R@cnr(ojoTma^I<_B@S5b%f7Tg0-M6J;s321-zt^!4JU%TUee>PT0c zM9^iDNm{~pT{CI%Xy}SY@yEK8U7ux^#tgT$3!OQ}+-ucxJ;YzwKkLfZ$)3`=SX7Th z7riee4u|^qk)$lCyEPOPC{FdbP0j_)#~+f$G43O4r8@pJPZ&6mdvt3u8B$k*GlME# z-`pNOdANUJp9YX8)uivL`!R!#@3(;xKe^KTGVF(~w-> zM%>V|+nyI9ku5^K*;e@|cImqddfOVgl&KDPX^1|T6YQn*QN*rK>jA}hWM3~$Uy-w$ zpo!amY5nSS5pqO7?m$$>2l?X5E}CY#o|_A5d&5Y#EA~6%b0MUvn0nVMtvJyui3MUm zaG%a$?=JuIPZS`*f*WGXKRNjDO@#P%YW?hvqs<0;;Ti2kw6 zcI)N@94cS}W9mL`%jE9o+z!AUMI|NVn26wPu1uL>?jNbIwKq->awYs=ycA%Rr=tG=6u4)pQ`u}Ma zZU3gEK-p>C`Roi#ieThZrqiDGrqVLUYG5CX=qCre$7Q#@%(jQaQZR*j11h2t@$@Om z@%IDMyd`A=TUdj|XUW~C2CF5|Lq$eMgE9Zx>=}r*Kr>;Y&-Rl5_o2tA>%=~p5+ov) zzXe;auIfBIJg9;ALtu@Iri|}q+uoiD0!ojXz~D;LP|UiKPvwmB zc&`$DJ$ZNB`Ml#>oG8An_kvpeyr`1SpqY3(1{sm2G?`} z-~8~wbm7~I0!B-Ko>GeG!#fcA*L!?iHVa9)c=9gMg$;4tcB1;dL!m|*lf5En%qri*Av0`r?;b72 zD(+*Sz{gW+uRMbiq`;Bce5#R)5npDm^N8l_lQ|ghcqgQV_*{~Ha&*hS$TJYOWi#=r zCK&THrDLwDBMVEE?I$gpGN)tZswI^^(~(>?%ug{bLg4azsVlFZDFVqP6N`^$P*fn~ z>Vz^Juu|ua|A&I7vXBMxKXiR@j_?}+;ivv>ijzv_hmL~o66J|=fzq#M29L)z73}Qn zN!xldETNmW>oYKu68^n3h{TOce}s2xzwVya^c2X;%7Z~Cw>Hy1gC8OSaye>!vEwY$ zVh-FzB^3kObk@AuOf1M#2X*2+NV5{0!vC9r`CTI5jhZnh2_&vH}W;)WbN7?2062P?R&hf6IBxuGP%KqBi`x#&!KF zY|Qnmg{$Wr^Iy6`_TBF2|gi4$|9Il3x7i5Sr1947dp>n@;!(e zhE+1vUF8sexJLv(dYcu(6^)RZUf_OrGj00>l~-fip!;Qh z(QjW&!*}b9`p{oBJ9@|dd^5f0+{IQ4_k%8@{PGM$=OqGU==kT2>b>=35)Ic~cdgv` ziVeiH7y8x>#oMlIPsOKaS<((OM7)&pqo4V92Rq^7Wc{kz^>sQgv*z88?Nu&IJHv%j z=ktP?Vgak(DJfX}<^2=|1_+Z_cc~sYYt$Y}0=qq|cdP8@`JY!iX)8*STqtk{JmMuE zSO#`_|8gL3ae9JJXUY8#Pjmmzx)R9SbM(Mvg;Xcj@%#@MICE+X~3DJLSL%tF3Gv%}^eqo*GNTAi3O zQ+wOKuU|bZ075&cERO%yM}YRl792BF|6u^FZriN2xp@iTwi~;x z*|*<_O;ps=;MEy#A%%(=h;6Zgau>krNHb-@i3rlg0{dB#U;}`?EyC|DQ3S9AvtJIf z->8i)YhEskO-b%QTPgr>x6BR?Y!z!w-!pgIk%Qi0+4E|Ykk2)i&^HEV%ed96a$o~X(NiYcl(?1}N0aBP6%SAS%cf`23 zRa6Rq=H_+x>Z_=jEpNXbY}tU^o-bi zIM%ZBk`-o+`l{=*Q-P`J5C!^ONog@NCQZ}Iz78|kX%1g|ErGxm*)NH03H{Q4CDejRcri}KAZ;KxqH_l_v7TTeIv zrQo@CHB!8n1toYILwa}jKwi`_l0tzEO>H(nfh5=F_(SP`sCDh7-gD^>3T>jUf?ZVq zp#m7&Y&b$AE3$~_Kud|zA`106B+noTmRoTl z?DH&o5@!!8Hdrdme>JXEa%<1Ka`R- z%Ne%&jS%^ds%SrbTu_2(XgAj=g0!S0yd9{Sc_c>W#|%kl3h+dT#*+u!#wo$ubSLE?N4#2f~MLgyt=wzK1`-w^p|`F?I%E7&oc$Qo*yAqzK=o}aQBk`Uh~){MKGcxvyB)#9i$aa6sj{z`2=6Ew=Vcx zKM~^Mwtg!>y|9;ve4R&R0Z^g}l?vuaJGJ`1JG%$X07)*>=tA!|!#~HwTETVQ_f@ z{gVk!+?SDv@Nd-SP<<{vY_}<%CUrxhq#cNk7d-E4thtuk#2pQl2IxcjT+GsFN-Wjs z2MSsfe$CAHs1mocO~1DHfga~BiH1R|c#ylSpx+kpHK6tx;cpp44>8O%Q7* zapoIL7JPBl{6l$^I};ieP^NDsf%W>?I+@$=abNB@m>Qc^w)(hM$ zEL|XOq`U%(7LO7`7aXWZTo_aA5C7%@%z(&%GPMrbU_rudGgfB(Ko-3O%U5^GWv!Hqd@sfs0J$79#3g=@{F=}2TMF#d&9$dE^dE}Oda z$niTq-n1B(%mYe5Y_7a%nrlIUnu@YGRpO=^Wqu*Itt$JpFrtK%|36~#!rZFZ1; zCc{FlvthSAWoQeGuAbb~Mjw4lW|s~aIwll7KrqjMv>ut+BF^fwwD7+!?apCM!7DU3 zN_wccUVni-9(|^^&WRFEq!cj0)RiYU&K%umFH;^|L(lRObWwJv z%&pN{y-MZKF*IM1s=&#A0z6ZRF>K7qS7yb(D1Y6x|3`)Hy0@DWJ!lpxq2QR=tHUg6)A9A?SY6;^wz8(S zBMYUz-cwHbelkZC8Bnr5CW=fu1rwsWBf^eMtpUmeU-n)I@p}ogECMCvzkX@Fr=)zW z-TPPL@rW?rVF+cZnE~U?+-&2YA2c#(ev^k-Dob1uVF~-muL{EES>%1~lqqe}itdDZ{wHXChxO?3j2V|rfiy!18b{!8@_ z`vlq1nGSFzf{)lwm(S;2!YTDZYB{KmFxjBo`9RV<>tEMJT_ zJ#TH1O{wHu3{grt@dcyB#V>UQV7h%-9=#e_KT_v;Td&eJ*ie!Cp1J($XBJgvf=}ft z^Zz(pft+^)5>>(-%zc1vQK_x5jXi|R;7&y_`tWJL|`3v05&|}_i}Q|g&$%;2KxH^s3x;%Dk^GfV7mek z>o>%SgoFgQ=Ur8PG4)~rn^6yBmEj;Nh~EL6#AW+o#R+6Dc7`*u()nj5N{z(#O%F5$9~dm0j*c@^_7yYb34?OcCtw8jHb+}= zSsNW@?i>L(WvWt;Hi=Hf_=as2ct7w`j`Lk1TQ{bImkId4#DPs|Tsr@o%3#n;V>Sq| z0;IAF*Ej3{2q-=bkJW~|#E+k^;egjR=hL$Kef_5z_!}O*x;vIX+gr*tU;CtVaBS{R0=V#!DJ=$r z?W;&0!pQIVD5&sUhdk5aJrcd7XO2^9H1fzWzX!HbC^=hor`3|i*-Opp`nK}I#Rp7H zzKo2VU$dKjm!o1u2`KT*l9HwFP>Zb7muFx_uPq6en{L{+jg`uuxODTs=bN6L?R)ZG zW&)U~KWxp3aIKg4RTeYDTXYej&InA!XxXxbj1ap12lkuvD9t<93`lN?mwv(e=K};b zYHOw>%n;xyF=9)tfill$I{!R>IHeDNwvrZc?atqw!xHO1YM~&>9@eIAWVuPcbdA5? zGEjR978_wk8Y~URu3oB38o`C{r))3CSFz}a)jZF3Czq6{k?)0AItl;Q>w7(mK;CUB zQan6z>sD@QEp{gfQA3_U7hGu{$zy(7WcVzXT~J;TePw9qI5V$EgZyTciB8L7!G4DQwaS9rGnDtS(SbKJgP3^tyN@7f z3daT{sHV(L)f$fZPrGJ;Y7GEu(7=8G3NHG@UqG z;-)l1aA{}u;rE2Viufsx+>&r9Wm+h4z)-fWvN8#NsvSqSvfMrbPg=p4tiYqq3(Bq6 z4*k=)?n}_f+AIHOLsm|#2yW^4s*)Pnc?HQ9Bw}&0a+;#>oC}SUA2UDgC-96~K{H4X2!pWKwrk3Z-@8NW@+I=_oYg>$7dP?8RUFyTE z9;4(KIY`^5tHS#scm9B>wCkRKmu8{x=c-YMPoV?-&23I$74Kkk#Mfrz5ApAOHybi@ zr?;z3#XpDT^!ka~4vwn6WDJu@`;H^`h`J<5&4OR^BkK5|#_=$|qE;E-GkDYp|M6tv zmKs4n{ZI#WB45F0Dofq>x2ITp+^IT*ec33z7aje)@W%>@u-Pvu+yGdG;sTZ zD@iDoB3xTX0-w23s~H{S6<%x&0_0W0jpAX|@EHs-&PotXq1s z6_0iup!@=P;9xoib{TJ?VX&P7>w$<3`k2h8Q=mhexud}OwzpV&Ev0l)x`%X1MSi6Z z?#UpfG3k^{L!#x6&B4-r;(8L@f;(L-L3MN80q~&v|JBftBu~=^b`L=DP~(`h(;!6^ zn(*I`OI+}})jF1(0jw^N>5{x`ko-1cQ-SQM2xGpz1(aTWaQ}g;gAf%StPPfZUZ3Cg zH$blS=OKe%IC1dP|58^lKzLz!xiNrm85l@$R?eIyJ;b1f1Q-rR1J0uxSm}eKiPvp6 z)fAVANZjeW*p{7izShma*)2O4my5Vt{-29#C2~tsu%2+csURHcDK?_@!BoYG!1GXX zw_>|LRa?zm!o zM}&eDnk{&bn)YslXfFj zT^v^Oa2UySADfR;vlf6iOG!{?$|9NQ4k6_Ycl-dpZK&D38%|hQwo`1Y>XAs$T9T3M z4Y|QP*Yw|==XDxeZqG2OCR9{E15)AM;6O^aSZKkwy7}2jLd1<3j!Vk+D}PTANJ|wv zx@Y%^@GbX;9gk^rWc^1Ux{N3n@-7B~l6VfdbQWDRv;<;GO6uljH|)9J!3A(|ebk=z zvIL9McU<4HD!{$Sz~!V@Lzmd4xF$rGxZAUU+s=d|+$*Gvi7Za0$-s8v7zdjX-V@mC zx5TkegIy$rq@JTiDkShh&)hQdcR!M+k7uN@$ITQjBCDcq2r)uD8}cDCk+K4win5Tt z2U*C{2C4c~?7S0^`1J4DIfE3c5;FsQI9TZd4wMix^jr60*}@B4o=?&RN>M!8rV!=UX~t$eb8&aM<%Z5PcMW2ryu+FnPeAu@LY_Q}MHpFjJV z;mE=~^muvb$Er@2>m~xIJOS|v7{(~U>9`ZzoM~whZwEwQ1&9a~wrcyP2cds1`@@`Pkx?-$+z(bMqvPQx zQUzjZaibzpauD4y?GPtXB5a$f4^UQ@ouXe4J%g3K@Ytg89z?&wJ>wD9%PZwf82$YDEsCUZP)75D zV424W$t7mxciKm;$!%bU(x}#F?m*x_sXEra8((fS)?X6lyK->L>GU3ynec=qi2Y?s zmW6IFc}DH7K}P7;`4AmTB$>aVO012KEa)jgxOe)#iT2M{@J?or@4{I?>kR|rq|y6E zf|rxzz6JO9X79HYdlqgLZ{O`c>puO6)w1UnyB!L1sA?0XY0;*&ciU*JGURXb7D?eC z`2@|&$(PwQ9`sU*Rb}9#aZ3z z(E%AK!9R20w@3OR?EL(ZurOp&3*v}?WCxV$xeX0-2EIN1#An~EUeIUam2dyRh%n)x zhA^^s079=F7=3{Z+Rt=}xgbqD`)Qjx$*pAVtkD--9;kp9w{bnM3)~-0!jwxB_=qcKx3e+j0I%Fy)4KDg@r)yQ;&NBt}H#4 z(B6%8ASuoV3k3q}Cck+dk0@ITX#>t6Gl+1#r8%&L!g`M#k)N_~!-U8?y~@;1np`>~ zT^Hk`UiV{H3hb7_hR=o%&cl@4le5)7?9k1`o?T@Uf+qfuRry@yzMM5{)U-TT8Z5biAOfsP zz}4h>Qa=waJ5vw>^0t@3rk`6C*GrxT91uq*Cst0*;OPUS+tU>w{&`!5fw;v#6+BRH$jw9#m2Sqypi= zW4oSQOR`S#%H=G7ae+zWIXyi+H8Zomu4(6nSvj^k;NQ&^Q>*iF+KV&Gq_qZZ{O!?+ zfNOh5#gU2v26h%#4bs*gEx6v0*X5O$DXrGvdiB7hgdUMt#_;cf$VW^lSscS~3E|09 z7L>zHJ2(y$k6#Lezt^6D(UTdUVrXMtZsb0yoKy_4nCJhe;~LSC{E}*%W34f_?E6># zHOsw{q}|IbYOa}P8%ZQ-{Z~vW za6W=On)5-Xo0M0jtShI)QoAA2mhGzp%NJEqXwZWwD*Ud{y66a1yYGEnL&q%o3mYh!p>YQ6Vm6Iw>yrVls38&~N_ zp5u79avK1tIb4Lh2R7dEQWxC!ae+S*h9S$CyjdBB5unf)lJy4>wmltK89fpHEg3@! z?uQO+9K&`qjPL$*foLfAG1apzj`h8k8z%I06#1U$(%4(h`=@bB*UR0`S6dm@*XNM$ z>E!)77YVF*(3}M1)ahSjLk$0CeqQF3b?am`RZ*g+)4jm4d*Bt>Kk#`VzG!yA2pR8^ z(?QdCLcfdL!4N~`8_ceF(tK%d!6C|At^fHwmtIU2vkf+Y4*HU=$;o#2N^HfphpT@w zjq6U+$MN-LeVJ+ll-j_F$CM}56|4U{RZM5g1KZTEol=K0S)*oAF$mc#Bv zm!DxftRl(k)GmUg_d`M7tn$u$FdtRAN^(q&qSq#_wOX}aGx|9r<^Z2{b)}-indQ)? zb9dn>I{qyr$-no#+0RH%g=?5od=WwO4%a$g7YU!HlA}yxm zd>1}Gz7f!%s5jeFf+j}K*?A5s*RUG5*%P&LEoA9T|9A=)RA~QhZ{xpE?oVmnU0zTj zz96?BvBUU7n&(weGPvo`cdG&;hKVbsd?y4SZ8D`^B7X4AwtO@*!mgC!00_Vx7#IMN z8sPQ?gh$5vn3yxSP!Ch86hQ$=pW65J!(Y2_s=}G0V*`4*aJUy-!Z7x-sgF9s$~~;N z;t5((Vn)%j-oNGRf^fnM*S0=A<|^LC;1KGDTw`raKJgOj_V0LD7`2hKuK^@aU2zpa zNmV-sy>83X=lT&R(j4&09{!nuj6o3N2-KBhS^Qua_Xf%v>}NqneDKf7D=DTa(ZkUO zogj$a0;<~$+oloBc@~tqx^S+|0n0$ANo?nB6?@vJG#`8?X~3)r_u%TK z7h1@Pe6jv~yXD;4d?7*B=dsZPTl%3s1#ZV6i2LzbMCZzxmg3R%hY#5C0HG!Tv$x0s zKnbe20z(*&pCEcl56? z#D`13wRg|)RfrQ;L_}wPb(2eu z9Mqlpg3X>Ghpb=|~Ns<~q;l`F9LZ_@0U z7ZD2CMXk~de6s5=d5RQ{rlHPYwTSEphiBxD2koTU%Aan}oE)u&E6QS4qf=)@{L~}% zg0IyU&NPCaKZbJNBctJw81-e6wYNlJUDKP{&9}cg>B8%~wvQz8xMK++z(J-oxEL#| zPA{)U>lio!R8WUnUTJZd|I%ozSuO|HFVYdq^t5zgg%nlg1o=??X|W4ec@eS!8I1ap zaEf=Mj)n2v-Q5-~F_+EM4rbs9kBcAQ>)pGqx!vlNyU1}1eu$8c>J-U!BQkj)L~|n8 zn1R*mzXDKwC^rtPxT1u`9azL5=eGM3F*dS?2rd>y%Ykw+g;|P%oDcLW zXbQ^6Uc9mT5}BgPT(K6;7~h(<7Vm9tywJA5U$$S;EEt^77vQ z$>P7$br0)|mPoB`ld|;wi~hTW|GJFDyWVd||~G59_zJNK1rPH>^y! zUHEuLj{s}iyj}h5Br^>dR>mvOm;9|6rS1Pc1yDd^g|qOWaFLf?1P{Xge$Wy2?8LEd zSEwow{L=d`e{*aFi#oqfE~Zm$D%A#4dfOE$IsFVCR!43(8%i4^%5>PfOy?QtVKV;0sJc89GFBpq4a- zY*xU0Ot-ElPEup<^W#q@7@ZRCW2rcXtX_qQ$;?=0{WI(3rpeHjZ`{)IGUo?X&d4R? zKT~4MS@FtcSyUf6eNOp><5$Q2ZgS3@F8d4ChfnldYponzm^0N)EnGGUGg@i#K(9R^ zEZ5?cc%BdH27I;-@LD1x#M-+FzHT%8oh#M>A=gRwZ~aJglMgwjlUH;##5#yTCDAB- zHHT%!O3_9-zrVWUTX#3dMo;WS>g!Gj?1cAan_dF5N`l)p3*QA@nfA*mrJ(`BT_H&~ z4lx}U!(0T5ErQB*g3n$*+P)nuc{J^ zj+@Wtd#~hqRn~3c4rYQXQZhd6)&ThB=iigfE11h9;vKnFQW zQr-n%B=r9g8@XU<16JdHpfv)~A>raXXx?+x30tktP5?0hz?*wlKfX}l0+*VlWhA%; zfov5t{+r#pP{I`Fq_0U+Q1Yl0nIPv-ny*)TBfa@{8Sx=gGFKoSgQLCyj4uTybA0KvPA;>-@&oNCIkA zAXovC?(>8^0#I@C^Ya6Y_NtTmp3#)WZ(nnROW9E*WqB>r}-S z10NSG5+q-aGe6W7^R*WynPz)rt&+S)FMB@)E_q;&WGpYQb0yg4E@e&3Hi>>W&XE0| zW4cIbV-Tmta0i2}FBMZ%e;1s~gBHG62?E2FPRv`BjK$Hdbd zjOx^ww&_e7S5e=CgLClo=$dNCr-w~y+wL|a=Inmhe=&~4l;-FaCOyH4C;3?*FOx}3 zp8FX@{&tqR=F%XR6l^L!c?wiVTaC+3b8Y2bjY4)D?iW}+n%i6Pbem5OffV=)SAOnV zZyk^3@K>jE5`_Vxq%0pWyyRN*WCtoXK#EShr&?&NuVMe3#mieo9e*rYyCwRo zS$yQZA`l8o_3E%y=2r%f@73}o=ONUBZWe6t%G7J&K&(JkRskqnjM&0}&yXEku5daT zPmP4%{mu56`UjZR0d5KiCx9Hk#`E4@O6oNLIeFOltEC&THXcnJIBs5kud|$??c-@{<8U5rXP3GTWS0J3$6V=3gCKVb!)*uOmrJ#|;viMGF^Q2gE} zZV6D3Ku0=Ri>o57{2^)f=`lusKaZVGhK#6wjsks}g+buBO-4 zBm~m?yT8!7u&_pwr^Ki9%W_z~n=b38as1Utd-uXUP@+2bZMHMypw-Km$2y2El938~d64CN%c_-j=}bufa=vzor}9;xHva6m-~Sc^ zrT#qiv2V>f`HnXogN^+RD}jI*BaTPc?O$fT$*Ri&G2XpD%MU9X^e#sx-6`nofHOh( zaUy?3=<_MvFt4Y97=2rG>t&j6>7CCVG_E+|BLBUPzY1ZJzpRhzQ88pOdo;Ym7#~yN z_O8e)Cc%u7J&2qjf`{D9J`OnRgm~S<(W64lZc?mz%=S@C31_khvV?oNVZF=Lg%bVf zRzBU^{{^XHljf5q8RcheEN0mZ%3k9{JDaTPYq&IoRpc40E|P!}s5(shIxXCv@`USO zo?||V#wHV46s5LAU5}NQIhW_jT9{0i&?(964v3tsMxlG#uXhV7Gn+T-O?F88%&wz~VhktC+`=_=!x z4=0i-6VvZqB?;|!-p>klqist?mq`Cd(pg4j)ooFj?(Py0k?!u0lJ1gj=`QJ(F6nOR z5|D0?knV1j4(Ym^`~7qbWq98Au=ZYS&G}4-PBzZ#hs{fLC+)Wf*zQbi#fKAqh+Nfp z+l*;}z`!@bO|j#^wpdiH-ixs}iZAUW4LP|~roiHoVD%`zh2-?HZ~@`h{oa>*vP zJEMN8>bHxYzA)A*Ym81XAOJV`*R8zEAB^;3Wdj36fR=S}`Ibbl3C4VkHJSs!yZ{Oc zRmun}FYi!S7erav*43BFd2oN`@qOfZC7DiJa>&18vq^+~Gl579s7b&908YPTMjbc3 zz*{ytveav7zoOt!kk~{T%MOBn!G;9XIWXFL&5D0`GRqCn%>l`Oa*B^YKba})neFy| z)W=mYYURpNp>Ujyo86)|K5=L#Pym96aZN)_p5^;=GfKD`lw}k@56?%C$pt|A0O=T+ zMoYLTLKp{&EawgUa7}huuq%!KiQK^O56mo$r;Fv2&2#j)L<7H(V*#sISU%0`VC^+# zOjuYE`0--wx#&%G<)-^~9k(x9(z4PwAJ$(w%v@*^vE>~dmX8$Xgi{7H)c-Pk=dgLe zO5rN8tgy~4D?NmfNv-JPwB)V@eW1_>lEL)tRs-N@wy!mtkIF(wAgKF=3hP5 z`3W=gczM#)p(-wjwJ~ZAJK`cMT|PYZz~B%d(~&%$kdJp$YK-L#{>) zSg`5*+^?kAme)3i*1i@@DyC~se3?Cwyuqt90TWnos|DIHAhZ+p`$xY+=osQC~RBix2& zdJHpFmWjoM2GxC%9vNAGYh?dY&UlWnB3s%IzBbd^p~I_J?%~1$0nl>;mnnEnf!_~Y zc+db1%##Ud*|5;UUcc4Twf4DY;x}*1j+YvMKs^8uh5l2BR~U3=gFk?`OxOX#KpE%Y z@bK>+jKHKiRXLe)@Dp)n3#n2mtgUE@W7wC)^%P@7*uI*3RBV$&J`6k35Bk1m*T>7< zvDjI^p0gt?E8BED_?d|`83>XzmDmdpLhZW#7K^rdsj~%fcsMKG-oP zJZ!$L|C$+J!ps^~+7-Qq>oJC6sBvfbVE)Y=qlF^?c}Ujg{@(=Vkh&%`d-_&ZY&2G1KST%cYr+&zhLqZUu(#>M%;<56&2P=( zDONNQAnaOtz+n%ulw|!t>y$Rj6Nwmc@u3I6?il?+xd*`kW7u)TK_pzFk3Oq^$Z~1=eMp@Kr_!^(KB_C=r;McGp znmtqQPe;1?XjDyShcUdrQT41c^QDP|Kb?nhcTw?QpM^|~?pY$`al;!Z2DTf0PYazSBd8DM5hysK0oBhvf*c}y>}B@$fVSAW8DQ0A%$b#i%c|XQr zAshxp9$=gkqpJuc8f|~gz^1>%!AT56<#OIG4#D%j{TOc?#abtm+%_&x!2OQ1sLGQh z%H|yN7e3+`{&&`5o{a1d?w$R)Oa0Dij8Rwi8;Q|+E9&iOdwW-(BP4AxLI+?T9%B9U zQXzz|=rT$D4IX%AV5^_oc;7&g<3q#i3nEQpdhA?VziYyYL3FzhRR=h=ildH;3%e#Q z1tPKs@4)y@H5f*BI{gGqe)8dqP* z#4ur*!k|xPgJ!-AiQF;x*x}sWL-R6axHx2w%5l8&;@hh54 zjZT7t$n14ym;lU*h#?<9F_i`GWk#nrDyM?lau?(B?K96)LK<#AwaqIUTZll>drhsf zvx{+{>`4yzB*eQQ?)~xYnz_=tfxJ#dG_A=nTY%5w`5@z&RQivyG8qQEUKoy)-m*3* zGyiBg643Vnsrc5}W-plF0XK~}Q%e1465zy#T5c%yO}O(&7-NQudt5JC0HHGpzgrY& z3jnqOC<2ig_A&$0AeL|roH&nY>~^%DAi_Fc8;N#3$oxK$ z>~)_Ie{Ob1Rqw9&$RH10hqSD)x2UDtkNlQ9)L08;O~zS=KT-dgv8fy@wVeU8LMv7f z&r1)=ILYMqv)-#BWhcSsv1m(r0)L6ttS4Ea(1Xt}?x0Fa%WoXj+wu#i-uTt|YDp|h z2a~9(Pr)uTxf!S2Gz{#Xl}g(l&p;cYnL_Nv@7XNx`!({BHqnupQ8Z)eT)BDIi!a$@ z&Xsbc1RG(oPjS=g?cM^u?EK}ecmH~0SycGZ_)^|iyUAOJ?QJD@e95%W-n{F4V1;k@ zDeNI$Y&}QoxY&p$c&0%6tvttA>)>zXArbGFmYLslN>MOIn69zjM`s|IswH;}E4O6+;O2pqba!=CrojP9-M3ib0Qm@ww3UKH_oBnJ6Qe*NW2q|aWA}wje%RS8|3vp2y{dqtj z+&857iggc8E#Z=o+ypn7p1<%YWO(@G-9v+={d}YB(6=1uAhqs(wJF7D`mttZVP1Co zzs-CkXh1V_=iM=i-(xqSQK~~G%QN8$t7l-C6K)(VZEXu#Qk*zk{*Pmy*L_Ic&4A86 zT56@&rYUOJ>n16}F>*EI*xXZA5Is3U2E%Z2Je8_jUS8mzy>Rcw89Ap9QJ8^8Wa;11 zoG+8i<@-FuWVvJ5`SiO1)BA?AY~Mo5N9M6YaEkQ{sYa5n6oevjs#)YyBb5aF0vuSo z#WC`2(d0VGs`*7Snt&aTk3)h!qhtVCTJmu^n3!Z{etqbmFzD|IxsOT7=7Q|ZJ+Y;B zBbtFV^-tz`R~Aegj%o`d<3)Z1Xp^(9j-0V7vcI@CzsFY}p69PRK5&!Af5=ID%f;1K zbi@&#Oh@EqXKHcG=6#@84!doEodUABV`5VR3ZC!3e3`4b>wl}5iZtBVG-+P)Yo#VR zK2g7TMm6d1U-F8@uqAx6c6sr3CwZwy0}t0MxJx zTtOf6j2c1s%*Cmc-OkziGZ(djKx`Qw3;pN;BruYoq;UvL{3_9XSQIAho#B|O7V2$M z72eo7LP*K(XYJY7 z|8YqB>p<@39(4V{m%G#8QZuj1tr5lXUcX1#+Y2$MU-}H0F-`-H0*JyMq#ggxX6wt2 z_Pm4GvXyI@a&-zg`R(7{>9*P75=iiCbZsrb5F&L zxXxzBH=|)89Zh0E5B34E$G8>yve;*u>#(t6sS$Pt(00)lTBQqhqaKLQ53pezRn+9nGkMt%DE1(r zJ!%~? zic4<~>v{{?^YY8v2>Q#~q9PaIy;`Y0!3;@EAb>BUJ9zTDK)sz=ty!ajomE3` z%!1te_B!4 z*76$oV9#e%6~lL+usKgfXsuEeuwg^2-hT}ZQse6f4Y4v#h=+jwTtE02&VG77x*5Ya z2_s|+;qYZ#RJf5hAaA2n^!cvvG2cTVnL(Vc_^e$w7=Mf`uYa|_D(b^P(p$V} zR!+|TqHg6W>cAtkhT1PW=+mEo_%V9^u)!PRC`$Q(leU{*wqSKH){tA_$H?KYadnw0 zwV0yeEfKR{Zd&{vRP&6Se_BD#rTT0F`m1dHHheqN=CGi^`Tbw>=)wD9&+8TBKTlMo zO~jq+%t+*@s6Z{LqN6DrS)G;@rcRorJ2wA~@G&$)ouOA!SkCR z9Gp5fUz)S)Oi4bcx}7U|ynlB=NEK$`QUYr?RD#`0(u zx@~UbV7Rg|!id-8zkfem(Gx}fs*I)#U)C=O_O1o$40Sw77zO)G|AdB%LFX)!C#geT);&}&_&VGMcS^Eq(;W?)LdyHJ;f-;6Xw24>Er?ELj<6IfnP?|Vm$+MUJd?0hO*o!C^hg$`2PZe0ndOp31ACWbNoqXl z5a~NsfnVua+$N0`7DAkZ3k#l-%xw`bg`zssP6u9d8)f!27!Ssn&yW0PL;Nr_5P^Aw z9w~c)#%6q}RFbTUMnX}>1U%~05$k>uO+EbfG^-7A$0h8S-12WfWetf?NU##U#m}N9 z$ugIW#jc!kaCMzpb0W5GNBxlWIFRqc`NSi3iEwB6DMNH;c+IT?4 zmxs-CjBbd~4QlR+7&eo-PMmveyQ4RH4WpZci}ew%tl*<#T7;)69=nNgRH@;fC^VFa zP>j$q`Cp>Ky%XW0p~+F^${=JkW??mKQ`z;6Hnlz!oQWVl$)tb;m?t=Bsp>#1Ml9Zp z?OItheeWYL27`5l?R%Iee2U=tXd~UPdFcGg`BV|y(Uw11tk_xhw!HUYpBuJGRtj_J zsc@!fo`~+R35I_};7#U|@2?W&#SKIMh9KUXw{O%-meY?*E(870_f?l+hQ zMpdyF(d5#6XTl##AUQI={Na8uka#IoGOaxqZvA4jdt2wH5qJ^VZm>8+|K1BP@&;+= zbb->2vAGQ*6Rk)o?nm1=!oST zj!h5{{t(jQqH0-}-gzqm(;WSWkU2jEg*-)$dZ|xBXIEJ`=&twU`Geiu6~h*;KPZ1Z z`6(0H!0rrn_PD){(ezYHt4!&8Kwel6mHV>h{6XxAy1Lii2MT2)68*!!Wn&*w^hfg{ zIZb65Hd=(}EBbyMRe@f1m&tyP%giMX2^~LZ`Aee8eu(L32G7n9s>SIY>4Yf#JO?nQKG9<)ZG>F7a!7ki$xXz>1O zKy0O^Hgd@d-u*bR)N?ZJtde@ujThlZB2(miY^tQdL4&~9W9(JxUhG|RU-_h4+T=F2jtg>zQyex4 z`FYj(O?Z;XHFY355fc+jem)qd!;#3VuTLBrk_MtfPwrle80$liP z8#<`55SMH}1%bAbCIXoLzs3Eb34q7Sjmg3CiG&`W=;wnCGWNlznC8&np-o&YJkm}QT;O_ZtxwI~pLiGlF#N$sv|ac+5drSn#i^84d3YHZDQ z0GiWtet%h`|2q^YM>6z&&6-c8+a^I&ChMeI51hE z-^+%>v8lU){ki>(=}bo%e1^$+FTS_1h$|GS01LM>P@Kg7YbJ5AJa*Zeb6So-m8-Tg zJ9H$AW+&8D9OS8^ju~f+psKSjoZ|25>%(tPM7<@f+j&~x zX_f3E-wCTg=|@b-@-ZB)zGHULNK=xVN!|!emI6D_v084*-m$cXwv*srCu?~6(!Ccr z+VI)+9qBxt0%OwI5X*GHxSOjs==|>c-Fxhncjrmyw#Zgm!rXg$1H5xO*V(#Z`3Qal z(;TJ1YC1=s0uM|M9mV@~Dg#BCNoGhlbmF3;EU3to^RBB2>$MMczs{*6ewo^pJ2%F@DH?O!b?s17Tcf7yRCSY*SWDfo zUaKz1ud}I&|GSu0SNkmL?yV*{2X&TV`86Z;oe9mMM!U5XU#)P2t1syHwtwxhFr%=M zrR{hJ#aPJW6PNKJ@q(m|wTjy5|L-WG_TxGDwrwWh_tt!}e-eHse=J4%q$mqub1ok`pNnIpH z)Z>3+D0#$uOtaw$BgmUO^eC2{y;5D8LF0elElh+qHIg!_(O2cT7vLMF$NffLMUZ1{ zRW$pRCUG&zV$LVeL;NmB9#hrHR1c}2j?7%%zszivWA;bgm`<3Kqn2J$Crut5l6p~$ z1)*IDcDt6T_ZK3tKIrR%iO2`o!02L2FmMX&&b=B1I^SDwC`($rNbt^XJ2k&rYe-}3 z0UE%1%wshaI-)%Cw#=Ib4VJBoBMx#Jxp=Tk2_+Tsf^SDOO+~2;=W~#;7PUKvq{$V- zFr(M)WPDSaThXs~NMprD2?pwYx@P&hYAl~nz7+1EeoGC+(o|v%k$g#`$yR3? zJ6-VK{>;2o1Kn$8d@nC&AC9xZF+Mz0|!f(T=B~`&Ug`(vKp#{I;%P^>hKWt_>s-)WHVw2IX7GJA*H6gtdvT08JDgfoJgVxW;$TCf!|u??R)Y$KUZ z-4I2tt&AOT(uu`cyRua%RViY<;gf`1-aKzg)$GG*HIexK!&+&9{$g`;r%U?0Ja074 zwNOKn?TJkk$RdR58_ROVfwA#2sqbJ_Q-PZ8`R3XtSooPS5Ax+E7Fleqn9t)vz5Cw1 zbt6V^LKsEW`GeJt^*Vm(nBOf?g{RENV-i7h5cGEQoMCw6XHy-wYH9z;@QxW*Ist`U z4qKjN3xk<=&3wQp0mahhyuxVzN5<(r+T|km$_nRfA3J~Ro#V1J)haIsHk8E2GQQ%n z0{((1%>JM-4olsie~O7wqY*HjxL6EAOTP`2_im{4@;>uC`E9OTaj$$^kPxj8fX?}g(F?*{Kux)4qkVMk(i5ldF(mnFx)pi2p(K0_N4eG|2n4?y zr7c?msGHWu!JZG~hFP@xXufgV=0WUwX$zVDTiD#(jKWgteapNIC7$M3>6hV*CGo6^b^z0M$J z!CTzMALzz7F7%kC->_A1U{yn^OxXpiM=$p1nJ?Xa+AE@eoXu{167oHK5=A5k5J1*4h;uV!Cn~(xlTx5&TKH z^1BOV3^WUgl7#)nlLrUj6M41d14W2-KPv=Sd+C+j$=wBMPji5?|EpvHm{CVnh~_Mg zug~1wtw294EX_%Xg+)$M-`@`DtncZb^7vL)%LVB_C*S`QQuK#ca6Km$6G95e@EGz+ zk9~h#@0=SXt{AT+kAizuS8G8QB%x|?w+Kf{YEPx<$M3^w@_2m&mu|q{eR(N5<`Fhj zgdd@Fu>=6rrp~A0;OFI`=@dUY3%Lb!z28l}+H#>NjjIv272Q*LusV`~n`Y2E(pN5ug5d3n%|H?pL-+ zdN5BJtX&7$VWy@75<<)(KAzUJonu|=h~`uB4Xq&u%g89gAYx5UdBxChCXf*F5{5=X zNo~2o)?fS3Umo%!-lhu@yMgZ;%>m;O?`HW(MjhHj4Z`LjoPu?}$iSZ9vOMOgbLYwr zAOC!W>p0Jb^sddDw_z8KIHWc2r5wxN(^W_E(L+8IqepC)I@6cTs*Z`AwTl{(p1~EI zJ7kh5c())uIH%yGgG8xfw6{M%n4Lz+Cal;Md^xyx_T3H&jjU`hx1$z2te2MdVy9i9 z$CdP7I=viu{fNo1h?A|Wc;t<6oAGkKpK0M*;*wA*`O&QO+Q0cKDg^P z=~bN4qXfypl8*9C8dfrZga#9~emWS6My!Z;q%DxIa%-6|*Jxcqa<5}tjw68ns7oAw zowdMtPc9X%!61Z4NlN`Q-g2%kR(f+X|?xkqRh6je3Zkt7@9FDxGrt2SA!Qz6B zLgU7R@AXJu7~^0gx-dSA(G6$P4m2BWv7xj@$Z%yeIen9H&_M}O5i&~sOo-a=c;~D) zhPwM$qw=Aijk%oCcF`G6etNj2`ndD>GGKUKZ8oIrr0Y~T+DI<;|~L+@Y3JBEsxC1vn>MZ?6+;Ea)rr9Cydd z>Abhlx~bfFHm1RvkkJnRXdN1UN&OP(cKnu6uBOY(*VUaw9Vi@5UH7XOZQ;Py1D7Y!p4LI z2c2SQrQw2Aq3z~bpBz4f@Q%k}LWbU8+gf03yRU&K6)Dd}Hpb$A-S_P&p7L0zW<1n>OG5)+QF(V$>{B|q!o zbwGuT3859;-$Dr+GxGlo^ZFUt`se%#!}#yXkD{(6Z^)P{B$F9tKjXij{mY7Qt{Kjwm5j1 zeb{%TeXg!WuBShwkxL_JP#$lpd;Om2jusf6U)uK#mp^U3HH=N%4~f`Jzj>RL$c)gO zt*)1ky!Rz`L?OsBaAY^X;fl^S^L2L)CO}}F_kY@!dR-Ac*-y=>nFe-Gvkz~J+yHzV z%>Q_@#zy2+aDiXm%rpO{4MN2xa>4Oq`HuNBWoj|s z=H^HNacQ~(rY*M;4SedZ+X#Gzm?MUc=FZ^Yz31PvRLgQG>flD{$QGIRyLoZ=k_Adk-XL!e`0+e?~QTM?G*ZcRJvh`egrC6FJ#xK1;n!3+Ta7*dZ7$Z{n*GAG!-hP`OyIfco?#(?-m}u8C?L3w!tStR4u+);`b-Fej zbIsDd%_;Ek5BqVooBAXDVx0ntr@+pgz#xR8OXjY=AABm6gaIiIcD2;4($QM`>r5G? z*YL}iB`6MhWG*K!O6L*Z6Z}M>I@xb(P!CBaBB4Gc>b@_451vQfLIor}hgZJjgH;#V zG%vowhn~XAV9iNLM#g+-n%J3gujA`hJ4W6b76SA87+cXxS=?8jiC&ogJ^axP58|&8 zM_n2m1`LC>Q&UJ0g~H1_Z$f_qFj7NY(j=8_7DOuc?-&i)HfR1sgG4En>(eB&D#%$# z4aH-hp6^lTubeUH(9}rH0pfBQqD z@KS!W@o~S6C`t>wB1}0DXB@Ircjwx!)@Q6D$O+>si6ycS8EwIZ#YfW}cC~H3W=D@- z*T1F^s!jn)>d?^8SNA$-&H+t0L7@cr<;A8s*wRoo9SAg~6(oc*0Ku}@5@>mQj*b|B zgC_a>@rvl+TLf2yD26U1e#|8r(jC;F++bM$Dsdd%U&`ZUP!5{@`YgE03mR59x}NYS zZ}G>ZQTr_qM~O99Q72))ry}j8hUXE{;N#$^cTYrxG&_I5T#pa!8w49@s+0MZKPE+E z?((99YDx_%)EmuH0%hHWHJ$$SNBMk8y^M-9Gv8rdsv$!tL?w)NYfW}!pvIF#8hv!N znggAhIigWYrY(Qt;$L=`QCcsG`aHByW^_6!Xg9aL;h*4uovxsW_kdC7Jpb~JCZZq; z#^|MOwDzd$+4$nCCUJZ!M2qlCS738VzW>Nuh-c`qybg_;kabyx0nrH#$h{@b%j$og zt-)b$evpvD$I8|u*sr2-+tNZla)mYw>M?D;gPayz?n6gNzAd8FntcDGGe-#Foa0g0 z5B25FJy`pAWN_1+G-Olyt^CDyN?vYnHscxm3$~pWW0Z@S5J3hetiO(3u-_x=;}g0> zzz(-?!`ah$;n4e2SgIeG>6TmLzpEWZ32Qh`mE{uDrmIa6yxtuNu8RvO=d#T9XM1Dx zdS&~$cf>sTw0qygAi|X;?BFoVyp_H&#S?RNZq&~knEnvTF}d}U)BX~Z@UHbl;9OC> z@Fpo~w;i&~9|~#Bt)O)=+eT^{XE7gJ!t(p3y~~c9cbZE;XQ6<|`I4Y66|Ls;EZx7~|KSubie~L3cS;Y^_C8#>XAsokTOi>;!!c2Zu zX1V^&LunAaH2? z8&pnI_CmTJd0U6Xt;@D<*5qbX(Icc#*CEo-Q>;zxEtb08e^6|JDRC5&T*8>fK?<;E-W~i0@EP zSWs7%!c`T}v-Jr+j3aDy48Xbrv@eBqmVEd5M|x-2D|ZrYtlX6k7PpJB`g_Y&niIBB zilQt?o#y`-n41+R|NQCSWhwju`jUlqFK$5B0K!t_e_ZcL--1 z-H(eciNMYVXwHYozd>2V;(A@qad%BE^3^NQLb`+4|)SXN0<~r^ADio59eg1MZ?#tY< z`mA;Ad8Wab@tci{OXHg4_=Oqve8iU7>}VNzI(^=HUbR8^;b@~%@Q=BEK|am*bo21V z)C%8AZF&T#g9{7uj8xHJmB#ir!A)a&+-iri`&%m4X+F=KW;HOPxv5iWf|Q#FXPbOU zQplEn0)u%F?}Z@Y0={+k0Jekt?AiQ%{5*bqCSR2gWa=#DJ-&t>V;er?PbdH0tC~QK z9XY2sJik@`gbD3M5dz!&a}hpx{nO?3c~r0UG%kqE5VBUkgw zxT@on&3z~l)s1f+jdP`VW~TPMjAVm!2=|6P`ARe!HxI9hSqMOn1!hffkpYu-5c`MTN2DJI0~6+7Y|WF2CZ=rw7d4sKs!K9E<5w&IHtR z+Zzd`SiY83jN))Z|J!{moU-{eE!X*LRDfYsAB~}D#47zcNqc>CCG6?ejh57FpsLmn z-p-x0UxhoI?;6hz z2}JR`MqQXf_4=~8<9Rz^!XgAuwhS-qgB$97xzf%qB2^t!P2<-!q!!P2N|CSAEmtWM zoWe7e-upMM8DlB@+xo}G;h{7}?GLKB-)F5CvZFD0c=}9;$0iNp$r%p&%uV-v*!azj zYU{sBML4YpOJpteFa&)>;Bic#X!g!vij@#AxL&>3H(Xh#^7o5zZX2+Ej3cWHVO$w$ zcbS%d7cJ?yiW4?V7}wfW2~avp)P;)80Z!e(n4WTR!ha%k{eMBiDz)b75&He1b|6<{w2_t025GX>vU zGQ1mI6im|eu!71DoLOOk<*)fyH45?dQZN>-G*m%RPDljLD13O##nVpO=qDuBoA2aD{JfGc@pLwZ)*eP z^{RxxFNVi7>6e?Z+lp;FUjol0x5{XEbNX{X`v5X~Vv0m*P~lMCJgY?j;UZVYd$3z) z-U;6m^KLvW_^~!G@wV_Hn7vo{<&nHh7v>FEe=XFRAp`aQ%j{Q`gFXdQGh4M>cmluWB~&sBXG)TeCA0PO#pZgMMZRw3E^}GN;60;nyZzo zbigiT*Um2frz$|Y-?(h|jx_f2@p8QSj~B}iDG6y212?P4{Lu;%Ncjm=2;aL_aNy!W z%OsnXvs?pr1333E>rx;c^rWyf`DVd%!|S9u3<&ek$b{q=@Jv2`{$=%UTDcMbLI5!O zfUq(j7_CIeyEZn+0k%lan}6fPsksV*b!2s3(>b(S<4@ziW+T2e?xV_OeppslJ?acj zJV`+K-P|;CJ6h;2l1%|nR*=^W3KlQ|XeWb-|J;_!>$Nzlf2MAyOHxuxSJxB}Jm!z@ zHK1!o0&We3xHS%PlM|on*f-?k+Bw9AO}!QgAFg>tW;q1X17%&}u-|+`cJag|l*geV z;%~Utj*0Hf@2V``WW$7l@Ku+m}v zN#;zcg_X+~!rOfETx1b1_WKEh59_O}QPywSWr6<)r>IIr8E# z^xFS)6%hgv>MQ_y^w+ZW9`1NAPHTM!MZ$~y0Ay{5?~kbI)qmA%N7UL6!zejw{mfcCO1BX(KGdw9D>Fsms6rc3ykc|7pOLaQ|E4 z{38)|%kZN?<<{OFxnmlJSw;a7GTv3r94MDw|T9bBE zlimLes;HbllZgR}fP}J!=}pGGRh8KB4$|dCO^p*n-224qVP;E|_-oS)_!Gl%< zHmODoq8JfX3U`;Xd=PR$Xoq)~y-ib#_D@}oOQ%-C(=w~i`wwlW6`@VV-Q7YSo8)ay zBqxgx*Eg=~wkh3$ZCTaBhwze08;Oo2?$IL&ZO1tH>!;qKbDyJ82CU4^K1@HdlLgjK7wQ}+<1B#X~{G={#HLM)(sqy>BYWi>C|^7SH4<;gu)zSsDH9 zGBqU0MQ%>a>s1!c?A-?db$=$CxCwop8~g(Fh}YAr?ypI=)$RTY+ft4#-1X7y=LO!lNSzo6Ky7y=5 zOdk7>Y)==f0|dx-O!$9%*hh9Z&n*8~(K9bPb7I46-`LF$UytK&SPOI9*EMVoulFay zb-gUYS1C?zEP8reaNh0+c6u~9%u;<}rhW!R4`{Ki=fUh6j92pW^NrQb1M+FWW^a08 z;;a+LdFJHng6bcc?t7;vZKNvQQcvotxNVxGHI}pkzzYQz;<+ll5iomsjV;ld$HsnT zk#1e{U`jyB&wjjP6Ts)`&yN$IqAbVwOqbLGC5{0DDTC=Sc;{c* z0fh-E1Patp@aUg(bpD>4>;Xm*xJJ|C&dCY>xN+pIzlj7P%74?Y$7QD}e*2_aHecI7 zJ=l*(bEoAn58yZ7j`G?m+M4R+WeK~Cu`t8}Ve_BE!`HA;nme&S+#&2MPH{@ zkz&r`NEv2oDsRd*GdK4NcLk3D@U`IXKe4<#0!nmL1*GkJ)rB?51WIklIA9b29A)4K zZxHdm%slo{XTSr&)!?aKL-3@8@0Ee63xqe&7k(IZ=6drb(Z{6o^mw}vhvNq`ikzU# z<>f5px1)_es9rafS`4pn2l)ESo9p~p zbMgt8h2#DiT#4>Y2Mp07=@Co}T{%wyhOc&!>f0{OU-9ZVz7l|_cqCB5_xlnyP3s~Ykw*C9h80y8K&*)Em66R;3JK`Ar=!Z)A@VZ zQl&bIuQ|FMNFK+$Lz_vTTcxUXf%9E}Jf9MIUV;jd90LJFqkOcO!Z9OMPu9duZPp)b z(`b$3G96#)PleoYZ`23Mm9H&5C}vbj<@4k*3Irc&T{%yOIag~8GIz&vwgFHXZLi5G zaT}kS8p{EG$lB9I!c&v?0CIi#VYS^WIzOEIsGU2kpp7LM?N2$3=*aJC^UY797=MnA zbkz@zpFY#GwWbtN$iMv5g*&%e9CTQWWf67bzqM^Fx3%~j=x@Tiz>E;6UeNtkS|Hc* zpDvN{YQGT^<9pAseK4c~!g^zoVEC@pQz{oBQ=Cu(bynD{6cdaov!*ZbDIaXb#G5F>jEGXm=Vf^P(E4LLvFon+3nF3`X6 z2zqhX5(I(?<&0ZNX(w0O=+|c*Ew;MluIZ*EV+|gS-c4O|)xR^lySSe|;s*(hc}g`_ zSOJ?-X%L;w$sEswa7l6Q@*T`XhK-d>xWHHVR7eep8k z$Y7^*7}H}T80fqk!DxY#&YB%vD{LltywzS`mGIF*9%L?Ykym$O&NGIvs?ATTl@bkrUYratJn>gt9gu6zg;5EsLV@-v~>oOA+4m z<}>CpSW@Usqs4^5pdp0u=y@iiTa#HheSUK@bLa8og39<-IOp_i3s>-8l(5L9NZ_gF z^P7t$XpgX<8G~QjDiWV(9EzAW&qU>dpQG6v-;3MISah(B^stRUUgBA8d!E{ebo7m1T?A{fhxdC(qjvdt!;tO%?2v1!$QZ zltGOZewT+8;oa4Ok8@+&qY^(^P{`Kc*B=R2+VPi?S36t=JYI^tq9Br{AunYy5Q(OE z4SzxVY*mdc;+)O|LW(V~?|Sb)d|~%82**2U8Jn2E0N1~Isx+XP1yBeN;Pm->bYwc7 zE%*vz)nyt4Ihi0sfhtP@8!6-!jrWRt03f7B694{wiTek@8V~?=%?VhQ4h|0D%s^TN z;eTwrqN4X;SOa#fc(Pw?Y*6HZcEirx%?(d){_o$vwOW{`4M~AF*F#M|Zj0KZWxE4Z z@CtlhsQy@`KWTy8G}Jl3!@Z^|gPaKS{BA-XSRHB4%dq zNn^vn0YH4IylXZN%XhOjd{2d+^yz(gmb8A`8IjaL3`O6Fb!UoxWSKQjIV=&EeLfo= z?3?VBlr8>VDdotN2H|#nW)Ok_eu$d78K~!!Sco7xTnQPeET4i0W<{ZC_oJr(DX^p_ zCME)s-G7d$?$euhBXzKFMJlv_EeMq7pk|8YXwND~qy)iJeKi<{U^I(KeRAYXLrok) z(v&G!AY9$`*L`r5fhMAlcr$`zk%;dhT5fT35`9#K`Bj%q#Vc`$a;PwVZx0pg2B7m8#Lf*5r2;w|_ha>UV7|Eki&b0aPsTRbYq*1geP4s=3&j zLDJO=AMYFUEfw|Cj4<8~&ra0bTxLkKuGY8@f|CbOJ~Z%Tf#G(?kb!0K)!|n2D&S8} z2GkJ1e#%tXkAOOjjEn@Y5U_n~!VFf0E$+vtX!z2m=34UEy0Uc?L$MPm53T5#BJX#SKV8gE5 zht(SN!Xb9{OcJ3F`)kY1{RS_{@|M>h?fR5bR~}J1+yjr=WaqS=^mDpV*?)iXOY-g@ z@_#YE7KJ>~w1#KD)n{`4-GN5i#8q2OD~Dl#BSER$S5y|t7F(5w1;dex_Ggj<4XC`{ zhr6Z^DC<$T$_XK>YZlykx2foi7)jSfpjnqmHpUh8Xo~_{{iY#-`~(dWTL4t13r}fT zM4dCA^nnVLV|j4(>R>uPAHg9)+>$pt_Zz)@{quN(?Jk4O{WdQDs=0R~mLxHK5u9Ei z3qXkh3mc|Gh2g@OXVj>Avt%LdHlK!qCyOU}@!s4kRpZmT3^2{zwKe$uHm|4uDoSP4 z(_vS4lY)4Lj|76L_c|(EpX=7m10Sw!&AW0*B;O*0?)(}!J`49kStOXo+dgAf>=oor zv6xBz#DkF2c5}=cX@QRtS~Y0Kk|zAHF?>X=8rXa6>ui}gJNlQyf9$WP7}0*%c=sR5 zQ6~N87@7|zZ-RSk3g!(}g|G7=6;6)0^qI5#$6s=48gVb`lo{M@v2Ap%{lj0jA3}*W zmB_QX>VV~TV?o>F9+e=Pmz}*C-M@$MgUs8k@#Z z0XG`F3Hbqeq(7WxXXv~ieP>}42G$3hU(Q+rAILwMihRXbcp}>0gTCFBXVCqp5(RHr z`F%%qEp|)U-T65?#Y4?AZ5iwEdyXu7CE8YIP60-6915W$TuQ$4I6+*HG(O1*Omztn zY#PH~`laSyyF~K7kAMD*vX8$-n^Y85H^yz4aiVWhk!93b_<-6_VSByV5hGGDV)p9_ z2AUpnoBL8(g>akS_jH&K{axZ&uf^uJJ3&Ymb#Y$3>+ZAoBt%nn|5}9GbHsJh=Hq)0 z^G?TDxlzI^!WeXd3(n;)xvg^1{#$i6pJ*3+7=@M>zP){MJ{3Z^LoM!{w)}{jmi|%vpqph$XY0Q^t=g92-C8L zM8WzJ5i>mIT6lXkSZ6Q|g1lC(PG3Q(Skm1g>KsZ81dv_-*~aE|z5|NTD_aOG(n0DD zuo0;$D+ka-aBy=2ZECCWx!1*xv~ev#9fLE7#{yZEas8 z=m5e9tEe(cpdEHCLk0V#2}q# zoqC7aaJ9B!iYr5uz!moeevf-ov6zDv1`Tv@AP+(w@O=hj$@W*8odLU5 zSyOYcrzf!J35<(UGcrsJ4Iz|qK=7M|Se z>+2sSACk>=7OI=oGHP&O>JC3-baFQ}uiBN-m;dU&l;gDIXy8y?*H9E7wE*!{U=VIz zV%{v+6wtsvOIenii>J&19aU9UmJg!izyu0ZS&%_^yxas7=i?xw3@N$tF9A}Z;ZXF^ zLM^leNSn7WX=<8pA$@So*vNS!2i=Pa=5GL-0Q@(vS+HT~Wai-X2T2~)ztCu5sbt52 zQuTaFmYJ1@=NE9L5_8+Vf*Qfa1-Y-u`gd$}G@#Vl3?-wYpnxfRo^jks|Nlrj%dn{0 zwhPlBUDDFh-5@C;9U>*&-7O7D$3u4uC>_$>;LzROA>H-eyx(7sIfP-)?0sL?TI*b9 zJ(1GkxGY81)0@fh($$<_Wow^~vy%h8Y3Qslki9YSf1DtC(Mkrui;?3ZSGgXlg9j(* z`vB7a7qtTLrv@BfCI~7jYNhQW&%)v&5Ufzq(10}dI{AT1`zjZ>H8USC0SJU#(aZ7Q z%(>e2_2G#5w8BGyxL>Mo=}#Yh1FoAW4ciBFmJBVY(nWptYX(Q^>hb^aC?uHz6j9KRrge`-`N0vsLn~L=Kx%fd zgkd}YB?G=sBG$Q++)=dJw8Anim^@q>Vk5fwJi#30`@pSN)~X>`qadU&Iz6R!qr#A? z!9u6e#HR7~$4`8tT5gHpUB0?PWJf2*A4@^0-(DjA8=^O_E_9#}l2vNJ+1*2Jf_N^c zo*#eQC0_wYS4aL)v_oRw2*Z^=Fg-zNM>Fj z&1}7_Cy;cc1*J~Loc@lJt=;@!JNcf3k%J~lVRoIWp74IAASaKSFefdqx|p7Uu3BYB zDlVyZcQsg-Bxn+UZB`gs|MpjBHlGjl0ud?{PkfNb3yt@BX9*-hXP5*#gAeiL98g)z z(XP*XN<05(BqWlr7X4%IP!RKvS%q&5?6i6Qhf`Sy-Gc{PN|GA*V9yaqau;~^Ea%?k zcZcY)hPP>71lx867pWl11apiQ+ybGx>4L2%>`ymKQ_X-;*{x{tlO!v$DEMKIpZ!zK zo^}(L4-9lVR^Z06$sfW8q zGsEJ6>(ego$9twljw|oq=d+HD-jV82n7@|#vI=a!WP<2}vPf?)$z5pIrjP?2I$0C- z=@=F-nbVu0+M${kbyn3Y6`It(s1S1KomBnt9eCs^WpUcfNVYD@h%YL=lo5}S*;tf4 z&VrDytr7F8LQDFKkn+B{biAonJRHfOwCxBqU`QvFI0`IHG0?{ zzxw0USyY;r3Llu~gAb?KzTI?3+H|60h)CNJ>%v!Qj`~6_54G>iZT|jJ9a}JfLpSO5 z(BqmWWNpYWgpnHC`X?miZ*10iTfPY2em-WJr8s6kwM2JZWUzLOxLa-(mOufyN@YNL zw1zz!mH}IRB+%jrwnv+1WApQazk?V+zcO z4QV)e-Rq(%xN?fQxG6O?1nSyzup06$H2y{~L^L&=q%qEby$ZNJ0GbLMmSto7yzh_= zev~)1l1=P$fjuC=9KAZbvOuG$9PzRXlI$eR@UJ$)qu&)3yPb$+TVAUVq`<_Lr1x|1 z+b7oSC@8616`8o#_LYj(Ya*|kf1pSFE76rhs*0@utzr=lxMxw8f@LCLh=VReFhw*l zy;SS`p-+c60W5oof;Hp8+|G)Gw?oEcs;}Ghaa9KM2ZH9W?GJNqhgVpGEr#t5lhxo{Z$Y#|#r+S4?v0nm4s) zGY9%lN*uUkz7Z3hcFll1C%4jBG}zH zbBA>-QiTlmyvxElt9<(>72NRNyxMDgxPYJJY(>RGGT7zYqdIXt{?uoPaT1?r#Z+#M zizW^B(;wnY!+*di%6wGAb>ewL#D=_4O!~HHO~SQ!pg0l}Gwc)oK1q1>@sXtyI$~Lf z?iX~8vvXUq5jV8|l95q8gyg5c;Dq)%?quL@bMa_!olBW&?t{X)%S8?(jTi#x`?1g&()5r&sRLBg8G z0dMLdkE-=*7PkSJA5E}gg^&~X2VVr1=&qvGKnWTC#bs*?i-^3l zzxZpl#+Z6$DqhQg%AISL__JeNX4AWslpy{4&OJm69#M(N?#H5~^lIdAm%cZ~zZEpU z2fwb>myZ8V_iY+mL?*XMNjOI~oiPZ=eaA4`ugu5PP}Hy*8u5KEDIc$5A~$vyzlkcZ zCo!Ks6^UUQ&VHlYidtQ9u8B20OCc^>sKCgJ zfKc-!LR`Nh-juh-kc&OrKcl=vz5IRYeCf=V7BTq6C;qVZw4@6g!m>Y5jyhe= z2b%?#$gOIkTa&RV*lP1Lh{u;kST^^w>1g+dun{{7KHe}=9ixXOf+8WDOM7HTgP3G_ z%8?MI;>QCer^p5r?+a*5ABJzDKeLDe!_(!WWx@jkBZtU?P&p%sd9|vUDn%K~Y>bKZ z1S2g~FW(f6&k9M7w1%nvsR?@bXIv`5o$RIA7{he?p0thl+bq#jgI}Y1_W&Opj1+}d zgInEAqnM_2ODlPI9jV7Ul+DcgtcW2Kq3=D+QY~@Y&36^VJRP2)ktmJof3D=&ymNO2 zVlBo`eNR&hQ16EO4z2Lsbn5cz-Zcv4j4fES9PK!Ehq#@gRQ*N1ouDm0O7`wVDsP>( z3B5_AX@hKUBx&0j8X5+KBj+Q3m7hc7z98kvr867aq0skL}5};KA(upM*3ka@jE&`3)N!pR{_tkZ7U`yxQ zP6mpXK!{!o40UR1_MD|&?@ALC?7z}?&y4)Xvki5Gb@5rbj-;gXx&B>7l|L+W^^c78 z76bV{P`>^Op#=~Iz(V2&OhE91lKy3R3dXY=W`Wu~DzEFK^~T*Saa>98YXb{_4m9fA z{M61>$|CS7yjHw|xk!Kg(r&da6Wr^;I~u_7yA?;VsD~xHuH&qI3<(aN`(ud%UR4AH z5a6Cdx#f6=eo;>os=|cF59$O#gJ2#QG^jpBzZR|w>S4eaK!uBbDd~wK?xavw)fG24 zr!8YHi`?~Tc^u+$zK3Zl)E}=eyiolcu0NcsZ)=mlF(7wyVP+8H^EfyEKuLKgkhr-# zEjaC-lDkX0cknOoe-$60vzzay@XUUF+S<=&?ZzN^{3Z}MS{w4Rrx+(g%bauGi?9DD z!|B4~+PD5t&E3td+Uw>OwF>4H@SFWNXfpTOvfgqE6BHDr0X0K|X}5v_z&#*5elb85 z1NeiZB^7PRqJTaR6g7$bakbRj9doev1Uocz5hSSPzu1l%CFvp$+F62yln-;4lTq{547rVP ziYI6mpmL^?aBmW=xr&D?hYaXXrKWIEhgnd*lM+V1$uS$_S3d?*&_~WA) zh%v;uW%HV@tAINr!mP2jvA#Pl@O96^14V7GJjj!gK_(`{r$T!z*r!7t8_uXRr&daQ zHjH&vUn{g9DAH$VjsS=R>bj)kB>q>6%;L9vI)7wfCrH|Vc(vgo!0-N#1O){JjM72! zG~%EVm?I2)+`+dI_#Tf>S~;BU81Nz(T_%TZv6cU$#%94UH~24fGR(fwH-!m;2aOPU z6#x#3YHHxQl|X(vy=`769%nFLL1^r%#YP2Yq0GO*VRJ~63Q8ehompOO||O0VE|5jsfdt^ z?Zy`S<59IpA5V~BI)u1ZWQ759bsC)+?F6-hcQjuauHHcYft2^LNufkLt{m>AgYP7} z9aZETI!}23s|f1L&Fs2T8_X3%=KI;7PPpM z{$9tj>y=Yll zp?G$`h8==#`^h@ZWPhhlwpKvtJ<1qN}@E)u69N7RxJna__~v6RPlK2N7ZOvF1ixz&di>iQJ9f zSpe;KGMV6;`V)==3Z01kCg`LHY--g$FEv~@J2uUeT>n_d&m(_L2XVtsUwlx6eT#Bm z?CT%wy}VdFat)@w|0>~FIBIp-9L_PYB!0dnr1CO+09onwYVx*1%cIry7a?c|SyNKr zOKorWgSSw*_shpp=Rk4MEmEd?E&VKo>X4m}EnsrHNGXW0s$mAI{zZ9xm?f}FB_%;} zwLbjPL!V+ctw=UL(1jjZtV@U0jN{kQ8dzn|41g2~G`MFT_mx#mn2e)~e8ox>w#MNZ3~;n|oUF|_qGugkQuQA((Ol#h3mtK19G&9k+jC1rd7NLJ8U|{1A_z0f#05k}Q5e&xc z!A1_Bn|n09 zb?IqoM&J-)!vg^Wmm))A7nrEdHY72D5v2GcktNIkZRJSX`QZoa;^S+N25DiMnn&4yTD7xJ&-7vH8menR!7`Lj6V=6e>(c){#JGa?a}(~rO+-1S=EQ!2Pj;CcZ= z;$}*k)K^%pw|-VxDAiKsDYV7A^bK%QCbSevq5iAx@QbU*jyTrz8)0TCBx716$zxZE zlI3!+Vb=nD*Vc9V_WKzc_w{$EQyh}g_{p5O>S(*>~2u(goV(hARlV}NudzFS2FT4w#bl%%#A-X$W$NbWdS)9k%`^|pN z%e)b0^OHW+qNa?};$lv0t9VK2uiekrXmkTQ8qmNwTCw7yThEcH>03TBGIHK$T`|70 zq6j8rz>nbOHVw!D>Y0b2BKVjC;IYk0%luc`Y<_11u;kz(sy)~x5&AX-Gq8Eqkk~80 z&o2X%C4laqRcPC_t%uf3^`L36K@6{H8W9Qp$Oj!m2QH$DS|XsB3=j6nb#A-mr&hD( zg-*i7!$T)Rw%*I&VlBahD~V-bV_rh${bZXzP9)PL9!X9v{P$DNKa?(z$(|;)IftC{iIFdCy-L<{iOM0iuL+`9im>`y3w?!zO$QQtBir(yg^udWL4_a^~(9Z z(jbYuy->KMymq{=nY_@$<$WV_d(Nu6qW`-&bCA$KW44cZjLYM>lA`~jHv|>R*|w(B zf%iDe)Id!ImGGV9k6mpKeS2d=^A;pg~=4Aoc@I~mA1C~S_p4a-xG3hJw8g%-hXoTus~L& zG1u+(>HQ1Y3+rHt;_0sb`eAc>REbKL<0H)%wGFxK?}@M9kT6W7kpW8M+n`$hH3o}8NXbBTa-oVcdE>LomXlV@-Sij}#L&5?WM znoP|c$M+(rEBHB1)Ne#I>1zhGLrr4X87>UAOYfKaEnU+R%>6Yy2+^Y47RJX@jiVqa&8r| znTJ4&q_d;;aF2}768DepB=YJv5~AX$j}xuBeb+Hd_cP_M$&-95BMmz*M#%CHJ`#RY z6ZRg})60@zn~{(k!hp7$_&0%$Su6EeI887;K(h%CNA?z8MI`FEn?;fcgGjn_qz;9@ zsdG91Q{yU^I#=+*Tc12BSbsA4XyfP@OPlSJ*8FbK!$U7ec7B9RAX`cW#h;?Y`SI2f z7~Hh$?My)c#HgwPMuPXfB@|djfgRKz>KLGZp`oF99~qNvE&{+J*vid#CUKk%JA=MO zpjnK8uPitc1C?AMod=k_)lG|&i186INKIb9v|t#r_j_0beg?4j)2_401tcNy5Ogi5 zwpJe?+!QHgOU=518#G8T0$|P>K8$x`W$H4kywgBp!Dm&=w#HHZO>zFAVCwGre+^F)`+wjCQjgV|Fub(q=1WShTJKVY*uGR# zk;Dbfl&b?j-2XSDIBZPG{0m#|!N-H;!sk5;`5f-pE~{HB>hmi)7yvN6yg)zXYc2;g zPk{%eYR#lgn(cb>!w0QB)N0LS$~xSiJY=SNDZ7{Zli>aTH*EG=R{P3i1I7g)_SrRV zHIjEe$QNiQeUWJD7Cg?uo*# zx0@^IACpiH5)k&vCGiGVX0NNx_1IfQe$j+es%~!f#JrRD2Nd z(tx`??yn{57Y>Gckk8I$V};6en!fQ+)UkZ5L5$hvTotNJf4}79 z(f@aS`>Q+>JEAu-uu)E~uaO+{mw!?@TfBLRr5>*o#k#~)COH8#rSqBgf?f&q%{3~u z*WyADG%z>%n?r#&I5BeEUmmkAVo1N@n9+!Th#yqe(D(#=Cp%@}%5R+UfdXn!830}gXv(i4(RR$h&f2uhT3dwp zN$L!_qY2Go`hB+(GKcVZIQ)G(b;(E4wCKl(GoAdXi1tvfaTM~$Ux{(cY5Lx(in z9p4b;%ZmcH-f+a^ao2ic%1a`DVRKT-Z71#T;->G57sf6M9Va)R>AvLtR^wCZvy>~) z&mSQbl~uWTGl;taZ(L+L@wWOyzwn)%OXd5y!5>7 zGN&M77u}W1KbaM~>gk3Iv;Y^n|zE%MHtJ#b_@Bg&?QBm`E(jR;bcd=&|0uD?s)1 zY%!MsVZTLX?@|tfSj<1^t2pD!6sGs3o95~pzb798B3^0@N@(MS@LHy^DW~vVzVKkF zB$7qvn{_9XTh8YMxqD0@dOpH5iuVlC0uqyU6F)E=x$007AIT=j&Q*Q8-0xW0_wUi3 ze?E!C=4P#K-rUNqz8JVYp^~LO@U3QLnkb#}sl}&z9)|{%9p;vx)!jwO2V5kh&i{1H zJbj|2i2wcbX)aj?eOZ3d+^;LcIh?zk9HZGcQ_zz#73sXC3x}9=*ZeU76=hEiKA16F zqIygaqnw&9k?q7k^V50&zTtz^Tsy*un^~$HDJ4-{BY!n488OHbM>~XaUQWuQ*ezwO zqcSiEUH(Tqs&xBi^g{6XPfcu;jrj-Ya#AsD__0+=k^8Gnsh5*wBiu&aNaAyOxB41Q zIC=FJ3*2wI!(78-$ra&&qtn1iD80c zt4Yl~@n_@{Djc|1u3V+7oaXj+HU3e@n$?hwCjD=tmuMe-H&KZs(i$nHU*m?0x~O;s>@XXskcy=ZFP98Vj@6qw=XJI3^t15l5@K%zOqMT9Eyc z#s1JtW_vPgv$F5N6!8DG?(=v2=ondRG`r{|^)Bc3ct(P3{~7L^W&$8*4Q+@@{{Z{F;)Kw(B|mWzeQZXhSn|YWEAynrC_TH6TF4 zNno;M=jWBsH9;fL#LMV;ZoiddB|$~J1!#4~4o@fgPU`I6!bOHcyP z*TC+TjQ}jiaH6H=_H=??eg*L=wvM>})FAl13>gu!K1EpCON$LoQ!E0`OhX%^jC_1< zVV&Caff=NabP?tI8vgbr@ViIZi3kTn?cnyZdyz{Q?y5gW*uQ=4*j>KNC7H{JnZr-? z!xZynqxy2ZvF5e5k&Bnu$QLwTfqUy~FZ|ubZrMlBdyJI~ag`)%%N~M52k;1u0Uc-! zLF=P=wjCdsQiFlT8|$`Ygtuk<$b2<>IrF^z@Ks?+_sAKFA+>COiX63{K7Yn2yd(iz zxICp~u~RT$RB7r!Q(L43cdu7gW6Gy8>dvN2Qgi8koHTVY_=*SmdiSa$#efo(SPLHZ zD%^>^jU>iYa<^7GKa;tt_hItrHqSi3%;}LFB);RkY$JX_a(pgPu-5j(`Ji)f=26<) zHkifOdZQqfDa6^e55O=U!px*MohB`Y4k%Ta6p2F01FEXa=={&O`P-@z&%@MxBU11>Tq!P z0@zDl7tT;1m?1}p3swZc{7OJd3c6-OK-CynBGDv^2W0OWG*0_Z8?{Sp=X5x{fV$;F+m$!bc z*@I=`TzY@0%!&z7LsF4`3|J7!frjoP9I?riPzhzzRNso^M$O3Rus2O1A%-3)t+a}# zUlh=s#*|oAgCI|YX=%?mEH_M8YP&32I|=>$mEs%8nTnqQ__BHkPpvmmR)sONX9{(- zsrOU&Ba}Nn=c8P`^fad$QVoo3{>NNpHmesV>veo&gh9o)Ld@PbPK_|d#VikO0^y%q z0_hB4uG~@;I*caL1AH$y<4euW(B}%Cho0s*IWi%}tz2@-xRNt}kZnK%#%Q)6hEf}9 zcEjRWq;C-o1R?)sSmyvAqZ{&Ry% z;BA0c9u?-nw!tMBs;7aGs)P9QG{u;)dd=lr zZrQX)vw;$?nY<>qQE?u6YMHgkzj8{t=Ixde$tkWcU$iHujD)Y8=7L_|6~x+=L^b9E z)i>L%tQ%ZZ-`*F|MzzFVn^lI-rHQk#-J~_bKSH&U6Ue3~*fMf>d+LbjJ|<0tjI6(V z_~=ho86sq3gmb8+Uq|q-uiTx-H-vU=&yp&~lvjo0eznb;UHAMmf|mg7%VzUw2^nwo z2kJL&iS+xZu#A-<FzdRk61l{5XN0kOR z_4|D&w3Kqxtw(7)r@sY&6dsiH*{-8Ftby}~^3kdl4E5{Sl+oSaWo7R%8_@Y>>?hTY zU3Km2W)TO02^L;$#beN6*09I|Dol!C7-~+xhz?=JXFDI5i0z?(nq8JYB`+it=(Z@az-3S#q{W z>jO4NJ|HoHhz3K0Dg%mfvIHpY@IH^v{+X8-_%T;hID7YZQP!)Y4hU0OzW1;HEyQYI zaq+cl3WSaNC!)Aa)xbY8dy*({hJW5qQ#||0XfI~%7c&fZ@8gm^oVsId9cbBP#o^M47IK*aYN zN~L$S@FUtfKR$kS{LsiS2WSlggv>CBE&{Kn;Odd?ku~%&mKb;E*qQ}CJ?4jBTm!q{ zS;9xc7_Odr)3i+gl2g^ST3@%61Xf`{etV5_jpu)Y2A;;3(f<0C5*RkD zXIW5Md_=T_v%w}>2g{_=94hr9xHVY3aaXf(t@?@3SlC%UbE%Zc!E8_=QM|~KP+9}m zv^Q`3S-xh}@cIJ!Zx%S>JV2;}k?R62{qgsl2eROJv+zUA6K0brIB8Y;iC{n?6eDQgG?gmh7aAj5-VW zLKp4*{N0wcF!L_dIbts#XAhqxU=^hk>Z9ooif@NkO9uP;_LHuEB9aL*`INlHafG;q zP6+)m$e{xle>9;cELRd=o6#V{WG>d_S`fKGS9dr$G}PDQHylAytmytZS}Zyr0x%5z+1^iro+07D)Tr+>X4w& zMTH`A2f;*2`tU6Q=KAF6?T2sROP8t0r zt?;SB>6_fUH^0+{Cmqd9QhUFIk93M{X`&A9(jH3Vw0I>|ISZ)x@UAzHVDk~>-GAiv zdj_@T_{u9KmCRYU{sh8f% z_e1QaZAaKY+$cl%{~cYO53SlAjx*DorQwAxVKCcMM2iSQKjEW=VSPB|Yc|*mUUf&Y z@x$SdU#uhcZ_S50(%|Ov1=txW<@Ging#Q|Sx)&!GW?Tk#P?w!8Q#)_;KdT(j;r0qrfRh(R=ep2Qn$ zYO%n6&y1Rkf^Y`!z-+NAR8q8aY}5y_lxqsgO;@=`mUd8+;Wv`)9L(vRrgTA$;p7kd zDDo&mE#rWHlcSz3irmAud(R_mh+{4MbK<}O%Mg}^gfNPLHKyMnQJ;kO0FGV zlpe$Hacudg?x9B@E#H7x;dlDFraBM-&JrZs&iDR!3m5WT+(I^3`A;CcW2E?jCqk{E zlr_TL0qv&C3Fhq_){myZ@UOW4!O=QrQHn%lZf%CB`5xY^Lxf}FTZt-c6ZxlWq(y0dDhlv*6OwMLSpD8s{AYsU^=pUW%e8f7dY#U*pHdN)Xj&Tg zy-)+{WK%|;NBtrSq9`^iqQAVHDVoo1VN(g2`-Olw-tL?hp9iwkONW?zJNE@?J)!4rmSW6HOT!-jK)>e;^Y0iKKmr>#lNzn-lhv5w;>f5dtzBcp#A9qUH>f_4 zHR?iPg>vYB=kBnZ>HZp5WzlWw(RE+$=R+L0v-hif8h0&`@A*~ zOC?2|hcgB1?QKY_;3GVuKJ0h{p{&i-{j=JFWgdl7(cc_cmcu}#9WAl1`*n0KSoVC< zI784i;0xbtePkRp`-czKSHD~J<;uP=6#TK3b%Kxw!A2PNt5Dr?dgiiPlB?e zzg_g*D$Cp2vb=>yfx`~?82{AOZMg6aB7v-!SqsJRepI*M+18;&znWsUfFwC4ILLzs zqBL-&08)%7o4?!@g(bN~W(!XUw92|D6sm0v8#+B-D&0ySsI7 zYs45k7JuYy?=#-=`_t1@8dAs0JeP+Qhat@?k|TkP9muiUrpt%>=+qieTTE1g?c$3DsoFqD;4zvH$QN zU4Q@EHCB9|ccLUT7?Y2;-1JvDV!f@jBdCcQ3`WAO6VFJs40S5?4g;J-kuI;nT zF5SZ9X6DK1W{4aRE&l4nH>b(v?}knQZE9?8uEA*7Wc67ueK|%A7rtUv92`@&od{E5 z0%1cI17>&gdpFl3_PMeazM^BGRqbmdC&Psy;__Ad#>OhOOVyodI6UC;l#&%HV~%r) z1UeuJkKz??Sq0mZ7S@#~B@N;U3d8O?G@@!jECi!zaq}1nB(gK87w6=MIAabT=<8el zQT}(y$*TU}kiz8SUntJ2TAk7|NfulXCoQa9Vklha5jEWJ9|K~9E>I`!cw@bz z^A>wI)wq$+5%*vQMFV3;j3u(m)_z=I;VMX};kqbv6UXG!V)MO2-?IO}Uk>rWwDib( z<3uhX8JI<0r8#u|>462<`1iGwx zE*aE|+%a61YyDQ$x2mG^zNgag&4LhjFM$5vibUq?dcChDCmDHup%Br_Xv^B(ZLiXY@$o7 zFZu{LF9F(U`|%E;Z?SdfNgi+PyLhwVxTNt7}>iCzP^p#FDukMR#1RXW07NCEnj-P7Q_S z6X;^j2x>pRV`k?aE`1MyL7W>6ie}iL=IgcOsWgOlUWN-gskbbi?OQW;|Hy{=mh0^B zQJ|l%??P}?u0;Yz!DTWkI5>1bcvVxrz#cE-($B2_WPGvj#X!s65GE!ZE=OI{Te?^#-Lhi*G_&SyO+S)1pL^#2>I$mcWuYq-)n$WgDbF|*QnGaYuDc*W4{ zBmd%(X$#ahfk+LN;87uqrHGeP);=HNdyW72?%H%zEYhUFA_TbE!FC^{3VW&lot(Vd z_&_2D2wNZ`q@#i)m1OGFm;sNPLLao#HL>qf4t0cxi1-E$2Bc2oMt6Z>QG&7)?6Bq= zCkJFWXbEvJecCnY`Ra*?>n}ePf*^IB+-bsreR|@*#l=O-1eovH{QZ!McSfT4!1h6n zi_C0|DGOQ>KIUSU4cq=<#D=XP+aUA%7H<1&M=CvYrq$2$%uw0$(Ga?kPJ3t)C~b@d zdSl~~&^-|Uz&v`qbdf~aGZ4Au5EizxoI(lg0NJKgc~GJpcT?o`%imCXKgP->vw)*@lyeXx6z&D50eny=dRihRi7rvJ zno~-yKd9B;?srS{yAJwy?lhtHWO5+J843gbPw-ZO!4B+mli(yJC3~ye-iPMpIue%u z0vv`{n;}rsfCUlIT|v68%Hpm5-_@?7Lh2-#51wB|`g9v>OW&PyYBBmdq`o*J+oUm;ZO~t9*jlR;Z(fj#@I|UucGk8mO)@MJ%D61#K zejajhb8DgUiD3d9I-WF1L@!t<_876_;o-eL`}X$tJCEJkcj-^;&9?g@GndgBYZ{NB z??EeL734ToqA=CJJ#*WQ@H>yD=|XjBTI#qm(PK62#kGHaW}|&p{@^d(hhAaYwACsR zvf)VP56z`IY<0?XY#%;EFhOQ+6fl=f`cfnL;nYj}hRj>}X;ViDYdk6!kM&~zvOqWh z2?!io;NJ~Bw76ukFZPz2gQ$dRxnlT}mU*&w^{CRxl$B7T`~b?7Kqf-w(9KG$ta_xi z*v}E1{23f7`l8fkR~#L^b79!@qGl94k$WB}V_{XnE2C)@KAON2#Wx7mLS zyCpxt+CrJ_JKn^Y09RW4aKq^sX^biXX`xj&g0P1EXxqowd}{$u2gfku8y82T_z~M- zbR8|S;<{iRmQT*kqzWfL{hqY&Y9jb96uGpFjf`NlxOZ-W6%`27y{1rKRd9QZVn>IE z9d(Azy7%Y?IT`-_49b3%kb>ay%@uL(J8>L2_%qX?>#TEXI8$QX zqB+ix5Zzk~bV))}&=bVvygwAG5ee!f56>g7Y(c@;F{gq zd@_>CnOCE0c?ek9L~p{h_#9xavjblq-v&LgwEZw08FWTq^Lw!4bL$&>vR2i2|7@9@Az8HJ9B0`+Rg*S&sJHUD462ay!n6;J#LaLC~*Birk=!aB(~M6x{Y)v10F^ z9#E+D%=i-3{R1mFgSJ7b1qUt4{#>Cjg;Mr?cpQ0gSDtneT~`$y9THM_D2wHQEsF~S zAzAY6%ot_!^{{ih1DWN-luEzvbv(_m{du~{;JI3x>^oQQSk~&GcT811#)5rV(GFxc z&^pjt$!UC26d zPR7;{mHuv(S4QMshy}9%*2EhkvxwW>9LLV#o!rs5@^4w`ECnisa5L`|IOYpEiPTbc zYb5jw$maEX%fzoDzpy$?xTcY*D^6hjTQ|EAo|%MDUU&!D|Mwn}xzwxZHYQslNzPQ8 zt3qXMa+8#pUBoGcwV7T|*!y*N1LDKn@t7Ce@YS5^Nuz?&mF5dZ+R-c_ihU@A0t<{rcD#X%c2sgrEH!JaG195&Oxdcg4 z1*C`aK+qQ$EI=urBsF$!eLbM^u~fMoe|^msft@~p?^$pm6F@z`8sI2nE5k4J0Dl9J z;b>@RlyQG7+BHYj)$w$saDmr@>eh9D!OswI{X0P>=zYru0?k7sBTgVd_DX#NcElB4 z^0w9ndH!o7OA4Y7DEVK4d(rt4;>#K-m2BFyDOo1+rzp=?@I{ zdE_CJFpgn)Kn@B{~xHL#`vZ8d|OZ`y9=J9U4~Lh4ZU)5fy1RE44?HP%oD`6fc^;3 zt4^T9NiJ_-WC`x{;pu3(IT=VZidlk|Z;NyR3d7AV`s9#B@X*e<+t%7r+HU9HZYFLt z(*&*j#&0J;N;$pr26!rnj1DwO9{UNa!xZ~Rl_V?|z8w++@e8EdETW8sZ6l5Ct->Ml zINnW)jEjw_D3a2czpYD-RRMBXQG`1(MH7sDj==hzC`$;RAI^|}Twi5t4qL3W`=c-- zGBZ8D$XV!>>jX-|fH(9txb|FGlXUE_)hH^@zt1#z)UF!>0lqL?<@qz~Hgw%fCu9+mQ3IE!H_b4L-0T=sGFkXX{dLPwz4RgYE7*cA}! z6{MXPbkzEk|AC|fe%j%@W#G}y4U=+Kq84kGDaOQ-u!x8fLn23tU7efe@DO|>;Ho9` zbKoD*beuRfmfj5|kTBvR&$x!?g|42^Vuxu`BRQ+s3CA483A)L!dO7MpTs(b~=9=;} zLftJKRD(Yo87ga|^o)^*>KcJEG>1}{m1flXESuD86zDwf8Qvs6wqMlN7F?X9z=y&x zG(znEoC-}vXPCTl<{4FN&TCUZkNoWgo`o5WbDp%Y*^ZOl{I*rNQ+)64}f>2dS}rnY&ztMa->V%kH9Gvky0hfR#jGZEG>}$ z-_JnW&_qbmKo2L~1@gZ)y!VySc?^t!XtS_4KhY`I7*2xHcQZzJEB@nQ_R+UZx4b5D zC?L8m^fQ=&;;=fuo%?X|o+gy!lGqy6%d8?y4p>(Y?~ms_cYGsy^AZ~kSbeQ)yIm_y zh@Q{-5u~5bRZ_mP{rp<4emVK45kBZQ89I^ZZ+pVaX3Is>BtJ>ab4gf#zazB<)A+M_ z-4AQpN?oje1bL9KII>pb?dN3{@i^M#kXl=Z7h9>$`Oy#Sxfq>(cc1e2j&8C7{BG!j zxF2iDx`moi%^Y2S(9dn;3%1pP>KJKp}VWNgr;WY!~rd z?lI~fr$^^q%=drd@4IjAprP1}8fq?^Q!=14e=`o=mIbqD+TxIc2DxZSda0wr}gzM!r z4~?POU&Q;AU0k>`O<1glmr|y;mACsAf#*8ct*m=~PSQs*Ql}tN zoOeCWsA0ZE#lvGUIMJY)j_Cd(&1}l})RR??@120H{~^YT-D4SDU)>=E-DmyQ>W1SW zcY+5EE~@6A0>~Jvrb~#$2rrA-#6LilX5@vBNMg8CW8}lJency)m^Y__VEQoVGXRV| zGjH#uZv*%dk_U%}zzM)8dI((89I0D{>2^lI%lKOFE={fZ^=lVEB$O4q{hW&X0n-98UQWw{k=8HDa+E|e zH?)7BB2)1-wLFp~B*#Vo^tdFDP$N1ZYIL@Gmz_G_k$sTQgyg7)bfdCb8z4>oQL@yi z*YkI=RaFXSD(Y|f@W1oqH)M*Ke&@KXBL^134Hxo^?tFGq){|iojxM&_uJiL*0HZNZ zG4YeT%C;$dh>=Q=`&-&xON^^Hh23Fm*r~$d+3gY@l##ihrY(Jh%g8sa{4cTYgO5_a z_}r|xw}(yLIw`~kmX3o)Bw)$btIPCW40vdnx&n1YRXH3f4l91z<~XO= zN~_R^o+_Wq!kBDz`*M7^jsP<7`9{MP15+1tkZx?BY}XS@eBk&)43 zOD1qGK==pM>@(c+oX7yJ1h%TcPy=X8w*#MqyTHvOM);l%crx-oleuOx+t|-ZDcJhw zX7nj#dnC+e3x;)@{&5CY5lke|`F{5B1c-$#daQO8AqWL&+88ECxIAa8PXdw(JF7+Z zc^4M%i#|%?s-q< z8Xp!0`19kNknZ&yz-$4uE4lPJYRnYWMo_B>)YCFY!?yH`YAwM$(2&QwWH=od2#SBY`QE#DQIw4q`5|v~I(r{{Mng|N@dYXpj zOe!h3M*i(1ZK?LhR1%{M6Bb0cGZng0hO#QbDmGqgh{fvd!tSlv-N!J&G9t1q7rUr5mJMy1P3MDcyB9-*xZ@b-)=X_S$Q$IiJ~QLN%bx6S+9<=jdL}4jGyh zJ-0Mnv(ZB=E^dOMVM#FZu6cT<8m1`$Hyze7K`|U!8FuyTwl>&`0#VlZf=y4{bj3{i zg#Y43cYwr{#^)TntcZJ+Z%qeB5}N*a=*`!>^~d#AkDfMr@#UZOELyXG zIWM`(4q&L(!6`cP*q`DuPBV^q(j-Mk1cq>!Gx?CV*0SRdsVjOdy2`!KS(Mz47Oy}d zC5bOhy*eUyL|oGyq|Ip7c2h@w+mBd}8+w1QouxL08~OIc$9cgb#6P9sE!W<0Q#FJ6 zI7a8j=-KYb5WG`b)MlHAFYYLMSACXWnXpvldYWRVt@k1lvmf-o56@U6 zA7FJxve{gZ`%a(=;9%Rfyb{_sRr|z>Y3MzLS%&SxvC}(ZviNtA7^u>c))R;bI8pqH zsr++za%*bLGYAFDAs_x3u~;=OIr3(mdIj_mX2&a#0Dz6yhcU?6<_@YE--rd-u7OKs zpqX2UntQ@0w;=DMts$?JIrj`R_e9SIh&AjT)bXDS$+mtm^vN+oyku&HbOFmEMy}J9 zXA2%@+6B^837$BJ6{4bj$yirK#mb<^4eF;*)sRI*CCL;%dmN=56)W<+Q^?<#d9nvM z@=Z=CH)v?I3L)8shX1ZU1{vCr^y%Phcv?iap1}uo`Z&;U$>Hl!H?sSe6vw7(QOx14 zOB~Ux6}^1YwOZ<(1^obCOJImT270How{VLCjKjGM<{E^XLlo-TTF?F1^;m;Z=VJI! zDm;IZs?T;N`kHvlvM(edOAx@kv<{br>^7O5xClj`=X{V05H@1kQMpejU+DDw@G<^I zN6q22JY+8vyAF81QBQ-?1QK6>;rWloFfTO?eiewNm}ebdXZ~Zr8JW&!A22$qAiGLS zg03}Oug~7!=m-J55-_xagod<{$>rtmG}3rRED192+1d5;@>1d_JuR+3RMqVH;dT^0 zHRm}n=QV}pJ+SajBt5Tjz1^AzbHrEo(o}&Wm=s9??FGOoy_%1+1&7NTg-9nTnrDyb zga!M=WwnY#H2QAKX^*b@hZ)+Itl3M;tR^HwmMwhlyMGBieIt*fh)c5Bt@AvA#A{hH zB1_7Ov|OehMW@I*Z}{-^jjg#wB+;W&TK*_n9Ljj$`Ki+}45Y_LzILP+Tk9W8VISXc>0RZH`4UAiU_v#qy zJ9L4m+F_baxJQ2`f-;vMZ8+1sOJyWsb*ZQUPb;H?YzdMKefKCe2 z{?l9I(b+M(Xo8R@);+s!3=?6~d-CKQb&Km@yCT83u=vyw$ zK-vvhx`ANsBfB}k$RG7S!lu@rMjGIWvCu=&&|b8oRo(?h+X!17K~)H=&OLfte3iFo zvbM<1=hEsb$JZ^dShIB&vzdPwl7a2$h&V!jXjK_K>NI7Cx%D@ZY86JZ(wiTs{@%Am zsr(eN0(y85MoW&KiLD}QL(HxBFuUf4R974-|EVQbS)%?k}n1S)Vofwv1V zOdo1kz_4ETRJnU$!_~`9r9fMKsc+-b%EwWuWLuVnAk-YoxpQ%1W{#MawPC__LWyF% zk@Xq=$;TOxAc;b-0IcWa&!?g8*9&H9ID0%5vj0mh8Ze%W+j!p&NXHdvG-_!T{!hV@ zc)x6NyNoJrMg-UPn~iNIq<__iNZF#nm-TBKgzqm41r{lR3bS{HjSgRQv`6Jf%&5lo z+qJh~oDEe>6*VUh`mxQ`hhuIaq7cU!o-~7&Us8<451qABY#LXSTi7djUqE5P-I-nY zD?_@-*yA$a)759a_Kl;|7v7awjEK^Pn+aU9cpyEUjY+xfJVa%yOKTwFf6pHg#- ztY-Frha#b5?BzuQu6H^*q`3^h2?zRMwf_uZ5?fMJMiRic4^JTe3(QXU_V&Q)7+MO- z6+}(1uId6xZHip)WQZ@XJdPxo8v{)WAXj6@u)S`VhuGMN9F10!`v536qPP^PG;PjS z?`7UZ?^wTTC8id8Y1q3|eF+&Rt`U8ji``^XX7=yStmL(K`O!Znu_uRircXrb)@wVz zzZ^@jJ-DjHudqNMOG^dI&X%dYzXCeMVnTcF?o@03$;BnQXP&uv1+S?B4MqF-Wf`Em z|2ba^Z>=Qn-R;=&Q;X?}bv#}3S%TWB;Qo4bx?)TA>Bik)smWv@P4f0`XnX~l`>pyM zGT3sg2M31a`*Jy4dA|vO?jGa-RH@KBns4Tzj=xT&$d?hIF1t!4$+z$ygUoY+N%%b$x_x(FHtTO$o&(ymL&+w8 zFO2!{RE0|s@pn^#zNRQUpyCu4^g0z6&RksowiSS*_oq_kt_4c}Ngn>bHBRZx`o>qA z9^U04qkXl)C3Z1?7_m7l&$-!)WzGZ|TLIbOlO4JjDNTmzy=GCGcN@a3;cMSsUe2(6 zI!an1de8ZA^i$vX1nNP^ZxOGnFy1B`L|=?TU-R8;UJBZMiCL|UfBcYwDvg(%&j1N8 z2t^thq^7uRn)c~B>^=hT z(OWowFaZLS=Qx^)@o`b`29Kku@_D*va_RypehD%ltP;Fw0eerQ4;m@>Barq1eR|m% z*dBo1{xq{T*aG}B6WyGHGViq&BjWgCMy3O{H{;ggKduG;j}H$(n-1Ju;5w$Pr4>nm z1eA3fHxDT(89QvGpYFCtW2(*6gcE*|)rs(QGO>|vo;5~JPpiF+l6r#>2m&5tmt5hI zC=Rp>N2}L31L6{t{0h87Ei6y+-p~8V>g~HF8c`*C_=hgxyZ!68_!AHTi*GO!Rf7aC zFBywQ_bUY+O!ZzJG%hZQJ$aIsLD4bZf7a^4d!5~*RnRUja>V&)>Fd{gnpL@~i3Xvd z{Gg;I#8iY1Ky?IiEX*h=AS?Syo=g-7JZK@;cijZBL0N2;S7C^Wx0+jUE4&poepuMQ zYZ1+kzAIsGSJ$f+U8oXuS7{ZQI`7XjngpiZ#0{9Ms?HP>eqK@^xtXF*S;RAy9m2Du zx8iqwCIQ@CJcc}TWXU}9_jWYW03vG#hI7|P3tg$)R#&e5(&RUH_U`Qf0&cNNP|$%no84u-fqOWGtlD(?SeguZ7-Z5QV3gnZ?`!n0uUu7+NQD6&mqxmJaoBh%Z9Q5; zj}k<&jF__Ak+!edj?lWUdGmqvaIE`{AG)?Q68Z>>rtK8T5!5gdK`e^6FoS${&0=u&tkN;C!czqClF%``n!(Hrh z>@-Gv-Tud-$%jx?8;>_LEyLu6*mitz(Gs_b9H8{~oixv>^HsJ0ufLS}%-A^;NSFNjwsNYgFtkvd>T%TKV-&nogJHQzEXUoWyT!o=_d4y6It2 z<)V})Ydk_9!TdsYUW{K;b}n!N2RYsv#J*o{c8U;7Z-LwEP+m^O8~9B7FK>nI zZgdOFf)WLc)^7dI_$J$}*PlCu>QOjyifpb|ptxwNC)F!z7F*B#0 zTz8bG0YZ1%Ox`hjh2WRP*3r-BwZ#}Lt{O_Pa&Lxe2L87jRYxI8V1bY0Wu2q5fx|LbyZPlA$L6M5 zs;JCXhG0@6;}95q?{oW3dbBP^wk@4WBZKo6Oyz(t7<5*kr_#vWVg2W!CHg@$PrXxo z(z{^~BB@Ko+FOK-Z@x^HJvZ0$>p^w)-v@u3Vl&Pqa{&A*`bW>G;vjNU(*g5z3GSeV z-?yLzPMRDz~SA z`BA9^+MP5COir!vf0-0b;@z|YXDDO`R^>4-j!O=8{TxBPmoRd2;$k8D{I`1554?pH+($U@aqFvjvZb}m1&sJ=BL5naaId{3j?ies?S|cYf-@1P@@&*Kk zpTfc`7ZuA`SsfzJwr1p6OYIB|>?NB@HLl5hS`*5A~Mv>8n{9iH$5r@q5Xu0OdnLm>R(Gkx2UC$J&=JqF+ z?ylT^)F_T!e0zGoIY6si^fMvT0*0@toSGv0;N6g`Ydj zD=CQt=Idw@{*SCloZCcPGw*cw92#FG_Hp8d$4#{~S3Kw$!kxKzpK!Wy1qOGJ(-%o; zAFdrxBOKPf_n(jAkn*Dza5Snq%atn|Kx8Z+=2*Xxw3#TTfqvCPlUf8DVGr;g?i zP~d?YAvr4xl9!}wXlNLa{*(G}cwGgJLin)1l7Yn!s%nq`Jh?UV`9NxMd2{pYPyh@{ zfhx=%@DhKqNkHpp+4wr&!Gp#F955i~5b%HNte0MQh=5TA4w&A)J{D^a?C(i5;Q%ar zxCo|({GQJw2{J)zU+b`l!_HS4Yr2UH0g$n5yrAw-A#tdZ0j;SlQPsKj2-Wl5HCnSl zNs932y^FiAm1A8S?Ea!19-#LF&b`8-qN+Nu&jD@tH_2HzCh>ck`|K zLNV4569g(*{2(xe1We`sY*=dW)?{mB3sO2`0OkjzOLP!?xzJ5Ck^R^K_ay&g749W| z;CG&P)_`%TpA*Pifq^y6ht-F^2MW{ITrA+Yd%nwhN!i%gz#SvGSUwUH$7Xo{FaXY7 zZkh5V$#k&;rc^$1V*RHDXc8??wOusdj$z9GR2n{luRqLv0_T?gcZTWy+q4m>a%BY( zA)^8TR+U%+vxV z??)efLzv`&d8XQFxN1W;dlLmkcYJn!5~IHKWi|$tL0}?7I0BKXfNvoYLqzA^P2pZ{ zhq7th<0K4gMb_*DE#3}|j1hNPG@fSYUp~0E@;?XMCAf6NF>ci_e={`E^a@KyXo9O{ z?iUGhanTOQ>E^g3)hLwiK%kZr7!;~?+}}Is{rC3@dbxz@AY}uKJJP-|qRnb+Kg3&9 zer_lvC7l%?B;WuPGgzGhJD3^po=8v`-1P%68W=lI&CJwp^6P47Sj?y`G&wT?T@I*6 zKo|wa48Tvq%^=ywG2|{l-A^9AoBOK9DIHge zitQP4wqrybY!WFco@&IM#1b1sE^GyL0O%GG$Rz(be~S!%Ogy9UI<&`hzMbr{)vI{0 zBTpv|S$k3CFhlM>VKGWkj{+C!-wV=&Km{ZDNJtneqkifaQ#D7UqT1Ab!_Q{_=uTKbFBZ=w%`Av+Hnw>p z2p`zxWqH6ooyC@YAjy&Yebb(*!q%v~IC_6nV0q-&t%O*;6m5dUhL+e#iLfx=kTG<6 zJV?=@oz_E~4h2#1?=;D!6VcY)wEJydOhY5zMUvgRfnvPI&YW8BVlQzSOl|Cy@ae>td2%KP|(V>z4=pZw#B%Zh2 zwThM|ZLOnN{sZ!F&XAepA0)g{$svK zF$L~Bn_{|T9xHam)_y_z%Viohz3=Ln!$rgYfGl`JQ_~Qj@R$I+-{s}>o^n(GcWf?# z!GTlW$BD=V%HMv_9u}3A?1*x7O0!6teJX%ooL}k~-Q*!9X+|)xI4~)qwn`m1tw;0^ zQceFmc@MMO?7f^UNT{Bn0P{S+c43iH8rP4 zDVj`Jh6c-^D+CQBO#xY+BG9CRKZ%Jxj2);TbvD){1)E+0_-6SXwvoVbfJV$?ce*YH z$Pvs^nQz*_Q(wNHtuxBZ?!3V*PYvkkfHnxGG=SU$V6>%t<*gmRggJMB37#o)Vn)(E4dVARgFZ@ngFK&Sg*YP4j^gNnKLi3&8x*UT0fG!Zz-5p^XByH z>E?cz8;x!yI?U6q+EV3IO)TSj*bP~!bf5z%=F1K!Ab^#M02M1-0>pdgm6u0@pGXyp z)Ts|zRwHOc7oAlHQ?n+$W6xQks&qzbX)NZN+u@|UM`oS>?w@?DR;x}9TdS3iee0Lx z*$K4mZSo~z+;vQ~QkIT6cz1{39%~kui&O^VRFhLvtE+K`kNg0H3bd8xR#sbrYj@}a z##q2&&68G3aJ_q%GKP4O>>|y2;WfE`>1_QA&z9wvwcYO%ij~l6374a1HC4D->PCyp z+41!c>(f{De|{6ERsl<-&N9VUkfoySyl==0v|a_bz0S zP-LaNp(Ww7@OvnKpbHRUV-E`^G7Luchr_p!;Va9-S~{a~#$twxCjVgjIKI)vc6WM! z6&Dg~D_pNn!H{y~5UkMNIUn=2)Hu(I$U`WcDYKiK6Y(N4$QXBp(4`d+6Key=DQT6VOBgL4h>s96e!KZZ6>szjOE`t1UBe zU7Hv-aY*?v!}(x>NPLQym4qgj#GNg@XGqYI3OPCd;}v}bUas9U_L4(Bd2-n~M&`Mx zqM{6@-Xz0C1+LCF28EVk5b(*w$R?4&F6Q2sS8Bu8s4B7b|tc!|&J zz}}|yr%O#SA`|g}gUe6RwRxm1j+4b%p{o9ZD27-Nz;u{nCHI|>4#dN{z;8uy=au*FkJ(k2`k;zPr@ot-=SjNaUmwU3=#uwwvy zxmI5TFdLIUVsIGGcOdxmj=B9nR5RZ$dB;qfP32(iz1OFBG2Y6ci64WjOHGN&zOdHe z^+=VqjJv*drRDC-6;0w9j#rhbvq;8M6Rc1b-@eY~7OeI;=>-~<3Hwp!6#n^_3rcgh z&h+O%6#T#EB5&W)BiP#tAFfR{X!dvJ{Kgi3yA{3i-tf5fG&UyNil|SapNn0#j3(&TX0~?}GW$8rUC0RGvEh3Ai}Ith+>1dsidrg`+vku7Vd=l$J~$g{M8I z;bK&o3}h2gdfF=|8ZtysKJvpz$^*r39~avu2)3xdbU15E?Vy}qk#_}>H?{fu`$oCI zhuI$FA2dZjwBm6#88Cgbv_uAH3;>{s8e?}e707;LQ?Q)tt{0TfL-lF~cC3|^} z)*vGm`Cf?ZLz(!cm#uL`zA9}3(&kEH7=p?gq6U9U>S zVo6?o#Fcf3CFN~Qnzui~p>I=g_+sN=JDAiReS8>q$T#AUK&z2B!x)~+5Yftu2{rN1 zx$kY-CW7GE@Lni;k4iSY>NFj(Kn}D{W2`40bIr@FHQ2aKegTs2WT^(Q*_*%g_^?3? zz2`Mpt{G4oSrTB!dR)4?x_-*g78e&YOXV}4QOqYR6vT&wcxVqX@x92fHS4bSwBCKy z1{sVX z2y_4Bgq|!$i)iMWhmxErYmAefy#vIh0pu0v03FAKZ`5y0?d-;jISDa;Vt>54yc}Oy zi7GC>yu7sA?tl9lFHcNNoiwCTN+mzXa6nrfOwv?7wYC;xKmZ1|;B^Ki=2u%zrr9S{ zpZiB8?F5C$3@RFdqnnRybV?_GEhsoOkG@kh8%IASUrS_N@YuS1!3kFMIgg*7o6{0F zOERoYawJF)+|7$Nh`}KyC$Fa}0Jrw5Qt-pUX~;If?A1zmn`Gp|&%6-(F7t~LevNUT z%1qoC06V8&l@8tU0=so%`U3f#*9S1wzFGCG*pVY6Cf))Wny)KQz?o#Kmdm7{AG*}M zBD8)+@Up7d=*}z%BVih^{zfgPczV?)*{<^C^QmA9Glp{|-+Zsihu*ts%z{5Qmdgo$ zSZ%0Ueq(c|gv8o^FW2pd$Q$QU35jcQl>W*&WH`gwLkK~ZlKi3W?N{0!p!6x^8{^nO zr}*~_p{`BCF?Bw?l1aBomqg7NafS zrCT?k;?gGg7Zo<13yL^VHj|l7;AG*$`24A(n=BC|a4{vIkCJts+}D%JXg)AJ?K*Db z}-)K=se_3l?+XX4> zfNm3cYQ2nd?^3UhS@H8(HqUhI5pk}=j)PCI<%f%Fy5?d015g=n*dQZFAm;sZf52!5*$+SuvuMg?aX3(QISQWOOuzJA3O?PvWXk% zuE#Zh@z9o-Js&&Q$nQQu*2Fe2Onv@OP43y5mVcvrelo_1}kKallR zxpPj>h~d`5ok#}FK63VzHx~cG##NYv*>0x1vQNdn#Zc0Ir*ACX;ugYgJ zd>x^&i{(D=M3vFwWd(elN7$E+G3*KTP=J`Wr^Vel zqgFRj{4HONe0?nXpJ`D=<_&9WeA&01X0N374con67#L(fv;UrLzG*A)&hk}m7sYLF z`Cb(J?zUTSm-PZ;~x*F>uxD?dy(SJLjNcaN|rx~>&qZ?W2 zza6v#y~idrwInwRLJ2CEf7p~8HqCV1;j&z+%vBb;yq$6$kw`~lp7y38TC%vF-m>>N zbIVwE4b87(ef$~sIZyS_SBr_M zfSL{}0FB4i7L_SM25jzO@I4nz^6Q{D)+fUmcg7_NDSqN_zzF?BJOCRC%YOo`g~jns zbg$L)k4wGvQZI;3Z*6Uzm5?z-@9z@;)4W#_os*Lt7`XA+t`37XGg+G>_`bWDNeibXDPZUUA%$0IapE2TU#G9>zDxG?~VgshQb#;O@DEwtrj8s5bRGe zRdFSa`4)_7^@98#JOYXa7{RC2!2csi@1#zVgVFvep_VvBNJ!XucvbCn=Kv_~Af=No zX~=#?Rm~o#C&5^dtr(?|3}gT=fE+ZD=d&2#nM7VjvTig#y7fpalZU{QpHB@JTs2N`Oe|nwWlc?hYDkd3 z%A;?gJfr~6&mqNbJQz$dq(FEk6k$~fo0?0WY_>VJq)oRN1$AO#LE0Ie)R*PpEyrrc zVIjHc-aK&JtnyA{EW?fMd;^#VB6~n=89Qnqpi4zMv!+i32-7*aN~Y|5kowOpeB6_g zk{W^^E3e?jcC%9*QqkZO)5lpt{??fWYhETLI+iVIB25)u+-8~%J-;CO{CU0!mTjb-KmO9ns*GA+veH#%^$tBj@FUO014 zrJ{SoGa8k(({U;76%k42isrn5u#7&(<`cmCgC7_1Y8455@t1Xcwn_grwJY@dFKKSw zuhautmIm4Neq8xfT?@J{QUM|Xc&>b6OFk`ve0ttNC)N<34^q}rIgRTDJxEn6da^Td z^0!2(_A06Y#h(>Mxi-tQ6A%s^6^7zxtL3(hoM=4;EZ~LEdBqB{4)SGw(y{Gv_bb4! zj3+bGG33Ou=GkR`-YPbZa;3yAUmwdis$jtX+E{E^wwpjijMDa5f)U4*%|(Vt$|?18 zm4rE;f^{2`0%A{PRuK_Kyi|1HT}>gwbYqG6^$eC%n@48of7U2lX6VW(|B3bZvLQ~j zJUOsnqP7)>+-cK|-BHE%m!3diBG?KPeT0*5U3l&d+p`j8W`vffg6l-ZNL4>a?7We7 zOqf&nhP9;uRK6hwU_Y#+3Lj(kMos4m{loQpUSb}JQ@57S4CA?n>_Wr1cS2T~KB)zn zUU8r$RJX!9rmtSV8r?nws9#cF=Tj$U<%3$E9d zY{+7CSZm4oRUQhpI3ayFO+*p(5kT>bNkx4UFW6w=P4ie}Bj@SdXf|`I4ec8-l6W_y z7qe!D5dL%#XgB9f7w`7YW>p4y6P7Q1Tp2@T^-b18<(p*`t+sKmg%Nt_DdE7=VKO&M zHaUq6!I-W=7j~*GuS}6$oC3Se+*rCen#S-n0)0Ot66%p7ucWIdbYy;vKor!|6n>Oq z6%ilq4)=SxTpEOj`A^|k79W-9&e{wIxaCXtTsCp}8S4 z>lE83Ypo!X)n`!g?!CzFSDT&VmJD4F`*r=FO8>S#038UJ4eCR6z?^qcy1leg6zCot zaOQ<@q2bkcao0R$Yq$42zWgd!xuxShYo4pEIg4IFErATYbNpUmmD$oaY z?OF|BHSE*Xob(&(yUoMhV37B|joK7+kASCF>@?E(F{Z5C%)p=X8Dq7juJ-7M(mg$DS?%Rq)zCj4CnrSppn3V-hUVEA%?wNdw zB;Bs(JRPDHty4UJz#JXRVF~)>9SQ&e##eJ&XXn}-p||>9dD6JA;#OFT(@IXGZ*L*P zlnA`smEQ&&79B~!asdGm@wIURJo~9Bqg7(mpQVO_YlR3A#o2s6BM**2cTuWQ69NR- z=ww15#jz6JEAoLh@b)h-H787EgB>|QZA7xQy&^Qu+|maI1^~Q7f3u`m=6@c7zwc`1 z4r!ByQur}Z@lS^JhH#%E`40NW-3))q=V|^d`A0SJqv!Bi^Se7Gud3D;S!?;@QU{cg z&(P}wN(3%-<#rVFS08sgzm{k8qYE`lOtp+?@iXB?&i<99`G$M0mn%FVt$`B!mw8?7 zi0N_`_&*a!zS6kjHq`=^hsrxi)+Er-r6|l3dV@Q@nKivteI!I@^q49gs-x6Q(+h8D zKI^WU^3>#Bw}E1YR@QETdb8WrB{VIaSdiKbk81(nf+fY?1As^)l^cM$vDOa*cG({mhZ|ZhS<9vZnO<b?9ZpqCB@kss5X$XyowWN zw^IQjiRA<+oGYv|!w3n+9`#-l-eaoE;#}pe_b2j_6hUJfVo$UdlVcV(Nq5yL%8U~& zTxgrp>G4WLO$Fu*iR0ovo6ce(8ItI|W0)?t8U)`cw^4`Pi}OWc>Hi`}hJO0|ZkJXX zVr_%HwOsMbB2|h3r^y^$Q%PeW%4+U>0{-~hQ@5b|w+piS_SsKst`Fnfq|=doYYr0J z{K%xNrA9J&Sin>QE_gYg*L#WaYrH)Oc#cc{LUwL^HcAOVgWYJ*o z)a#a|avIgxz`ps7K*Ut~aj?XqF&6J^s%VS3$x=D{!06v=lJ`$F#9x!U3cUB2aYimy ztKl_G?N+n~E8|yK8{C`!B5!2BSsYCKFLgB7oFvh;!x&YWpKk)T zL?GJ}>bdoWU1nRurys+9T~y3~#cE=Lf7oEu9$nlmIw(JHJ zg)s13T*{oj6{pB=u$;y_dFtL$eiS@*J7w>LYrQ?l=H9C<$jP?PE<51O^xDOIM`OD|WcV+&K5QO$hLc4XoX~|s|3LUpf z93(jXGsBBo>ooqp0aF8Wq~5-bVZwABh#i?wSiP^G-55nWK`y+Xt`i~yD{rF|FIt;N z^a}Cj-2{AL&kVCn1HqBjC&luR!3d93?^-Ud`?KQq`Sd0BVNcx4_NI^9Eh*O_T07u$ zpITXY4d{J(dICu}VD!V>7%588A&w#34OR{6^)?ys#dwjDuLh?gm0VCeCIHUfjvxQb z?Nv)_W>&zxj>4lMD~pnv|DKDhI{+R9m@>dwDmVW8f-f0=*`>u>Cv4fSsLP)Z1Ga3^KNN(`-RetO6)IFrf!%*56b6)!~ubH{f_$ zX?Ar4Jx1&pM4ARm=x#e++i`>&+~Pr;y!Cq~6Mm9LZE*j76+100S zDwZ9#Fzl%&m<0T)_wU7+@x-UNfF~)Iuvfy{k+`|p`-rbHK64yrA6&K;Jxh>&*v@&y}cEvU(2($EufptS=PK1?TC$pK%v* zD|~Osx_39C{SrqjTWXG~stRV4G4PiI3QP~&W*meddTUO{m6To~eI4i^3yWm{>TqRc z1qdS5$AS(Tp!RlT++~_fCF4QDRf+tYaI%;=aVu5gdRqL+wTz9kXL>&UpoWWxrEx9J zTa`7*v24`xp*~QH@Tlvx87g$hWS>V^duT)y18SLV5!F2wk|tZz>-B6oQ3G|FUEYI4 z4HUajlv4LD_I_iI*&6x|pEJ4L3-=P1#GwZ$d=lxulu-D7|9}jmbz2*~gBerDr91qo zXE`SwE@e0_X(ThU*N0U}f$#_ZPSQ@pwqr*yL_S#vA?$@?NaxbbQF?x!6g_vjS|Sbg zG7{4z)_4_!P5~8Sfj`ufWa}G!-@Ef2AZ-P1_8uTy1#?)M_yJidsORe8B0lqoKNC(m zOddj`mv@fe$@n`5j#wi;;LH4uu#?CBr;ntU9U!CF!wjw3e$b;Og?L%ZcDIxEVQZfI z(ugR?NPEJ1PxB(DiOB>4%T!c&*Gsg6jFf$i>wzR*Hs@u z%KA{+54>{@M9(m78ZYu~SHEnPNEk*x)*Q!WIgY5pQ98*+Idv>j{fZ0mt5+MenLFY1nd@hLzrIg%)3D!TYKBiBv7g9y^nfrXh0o>t+pcUC(-#N0 z3R#^YHYS<5eWzSLl~Gr73E~VsPMc*;XSPqg_bqm}Ki%0ZOEyxHHiq5Ro8dy}l1RGlrC1@Y1PiP7h+=+yCGBc)_J&?p_DG@_6uFNU0OG< zf`LCLM1GkD4K}dfbgemtx9r^azjF~ev5bbGv-WOM<$4a0Q%&F&QA zI6nJcLP(@n>{4UKVPht}dz{QWjV>axt@myH_$+qqX*Leq4N0EB!wcG-qP#>3v45Ma z3JzFkQNl-*5@A4A2s$gpOpH@#vUO-GiM^aq@{6tN0UI6Giv%{&6HM*K-M_Z`%$KMg z^Fi)eIyQVWXy~DXjlY;~FQTkToQ?|8Y`ktkjpU5R<~tWt5UL6}UXpQA&7xGyY~QlI zCDMaPXHrR_`jK0TP;pg-RPcZBU)u7u-c?6lwqF_Rsc#sc4-ivtn)b3@GWE$C>)QU! z*yFefmoAKgh>@!xY2byb$JKQ%fiW~jv_0KruKI9_b2#ztC3t!hUQV~hzb%2uonz*| zsW^dho3dQ)$*{SL8buiH5xH@%3)RX4?&J@x4sf~xFy!qghK+eI#n&OQXF9C-fYuI5 z(rZ?erluxCf(+_b3nWmn2!K&1~5ByI#1PipsEFzUy$mUo|jZW zEO4hxwlY5QhaAfs2m-*tMoqF%T8NIU9l%!ks7GHvTDqfh*DG9j^NHlm8b)I)UTs zlLGE0&Q>Lk2^~Y6SNldYOrcha{qJO(Tgw~x2oOARfQ}3$P!zZiYhHucuPLIqF~8glp&BYgU}zV??A-6>6rCE za^eP-Or@OPQ-1$IvzvNp2{+^YAUj6yN#PG4mjHWu99MZh&kZ)8(GV9*FSD>Tn|Ueo zN(|D^@0eKD+tLTlC7HgK>i0z8wmhty?7pUh>ph<*5fYQv+X+5+c$BNrU~T*pJfY#` z9yn_?yPZ`KvGvu;v|eht_43ycz1~TN&R1{B71bi1=|KE&3T>lN_r3h(!uNJc*mFKj zCPlPdB|1xTN>>--naT=Qws@R@-L84is7!Z}3=Qk7$;?=tO$b}D4epadXUNX3Sv$E+ zBl05AMx$-#l5H?C&)A3ON%Y%6$a<&Q`Xjq`&FH0`6;ZdcsiDS#&8p?#)R71@sr)JZ z%N*SKnp4Kz!vrVhrI=aT8yu^qfqR$c;g<6RgD-fH@T7ICtk9Py#@kWs)4Y=o@;35W zRuct%UXq~Wxl}AMT@0@+#2;g+-(M0k?DFS?TxB!%$IZh!uGBhU6;q-EMIMfY##o-I zVv2o(@#&c~hA7do=|_>MohIN#e?yfK@-bs*6uV=L!QLf-d{)vJ zR4y(uWzqs-cX-|GES~_lg}x8k4M=HtKpTkY{zIJPqhwy346t=khA-^NH3rIRnvZ*Levkib_EX9yNCeE9gD_I&=!()OAi$Dj_F$lWV>YlI>Y00l)fli zNDGn(S`A`)@0I0K7nBYBWG_Zai6#rR6!4r*nHG~3T)&sc{2G{;`Qmd8z`R_a6$So5 zDh~;WmkoF-qu&?>d}{Vk*YTtlRuz`x=%EP2@wUh;yhnNFPu*OZX_xJI+v`mDg;?K?fe>^7c(PUko|45vi#U5!!&B+uM$z$mO z+fXjBBD`%e?|ZrB&gBVfUcLeB6*r1GI@hL{5ZP;q%5zW# zlhe~_Qsk5wa7rsVV@tWR#=zOiJOWlD{iZd5>a)1G2v#fkfK?sZ1=1&Q0euMwXn{ox zB8NZ?CHqg*l!aBVEge)Qsa~ltMC@tz!&eCa zAV1Yw%>mZ=AP^UT2Ljfv%kK0U*l2tg=rT5FGdZaP5$s_-hIqstodNKr+Kq7_mmVRb;LtsT(0HpyOZ;2qOg;m>}b^%uzW0N44 z6iMm{Y|B8F^K0n@S~q`KM7d*Q)YMC<#3X@nzn#9;X=k%H(<`Gz&V)pV2X98rwFmXx zwZ5Pnvsl-3kWP%o56}P(?$?h}%>#bnsMVuA_Y4JH41&zY*Fnq!RIr*Zy#-J6JHIK9 z;yaa#B!HPILjfCPTZn4;neWi8p1+q!b7nw4mzN}Kn_Ty&&oX|zV}y|kSu<~oBc5HA z^UleTU>5ry_6SfHfQmjV18MGap_Lxz(9LY{hldm^*S;)+|R{c6g!p&g^6SdC_L1T~_D0zE%h&Z(z4~_a; zZ86}Pf;?*+Vs890%m`aRa~M^M^K?t4rf=M~_{`9GVt<>+4DHS~zOdp!_bR zts%!Va!}ho?Q1f>i2z5#qZNqTK+ozg3iZDvmOlh*0sAbXci=@n+~l#2aFyxa0ST0^ z_q`&(gl)TidkB|Bpde*y|&&qyMza3Mc#Ms^%#&G?I23pqE8 zF+19mWlcB;Wxs%a*)F%mX7_5{!lrX-`D1d_ZiLp{NQ&n>;hN;H3<=0T0b48r-xwOC zEFCSwN%_FJ&*(@P{Twd+eEH8WEuhc9X2)s$`}DfgsP{^0&X;M~T?0=3<$=Dnr;yb!V-EhFs`@n}ByDz2D4Qr>2l!x5*cH;X+O6smmlR7h=3*Jz zljuM!vh2PzJH74Wgh=CjVMeVRU2I{T?>`$COGJ&y4#Iz$jHqgvf^*zGZjWhAyeLs; z?ge+ahTT-FQm^-Bqv@R>;b(T%bc9KmEQZ@hUO@p|E(aoTnS4w!@9-P{0eV^{uns^B z8HrGF#0~O{XvvYi!`On`y8kom9?W>J#>&?GtiV8?P`2)ew&GFU=nR}3MgvL9;Fg^4m9@M}cYinlywV{ncgy<-|FvXMg z`S*x-USWxeU%^^6T;J$nMeFGwInamk5Tcx)KiR zN=Ff&?}iK0EWM^e*OM?}%011mU?p%pdlURO{h#v`X|OyKWrBbGimB!Ni!r{}gRdSG z^h@8TLGvIZj_Z0oG|jiynSMzzDc^2g*SP0uQ=shB+EXrPkApp8E&uv?)30~)-=?i` zhwcKRLiP zi>h%|8-oQCgAxoJJNsv)aBQ$rf`RLgd)+44G?`7Vq_)2Z?%vf`MZv%e>>Hz5%@2MB z$cxNP#=6R2C}^8q)73$(I~cv}RLlE)GyWm|0qMU%cMRk^jG3G7$~Q6Y#9eCA01KnJ zF%9vShe>_3OGpk%L`}jLf`XB}ewv@Ki&IfE(~`wT5~Q_E7bYTv;CrfQ_n>;Z%9}E` zA{2j1PZ3pg{AcPvYI?p-LWT1uPWwwYrci`Up)s=6dZ)K&kP3sGMd?qfep%;m^rp`( z?rega5AI&)kuAQDzNd9*daW-<#32>lAky6+(nCmtba!`1igZeMw{$lMNSD+- z-~Gc6STn<#HFILWdp|p#%JIJXp`|moIDD2{DQkcq$N0~8a+;~3#Q_VFHha_@bghpE z27_O7F)s3(#FLd!hS|qf2}TKe@O~J!j{Y*G@ji{Ul-YVJXUXNuz1W=GD&==WFkFPS zS!VO*vtsfR!Cr*|n-!Q`%Y!CeEkh4bS{Mo-4PZ6#?IZ^_A3QDn|GF%|Z+#wb(_yzS z_fj-%fp`dz8DO7+0kA}j&_F3laX>=X(9i%I8o1K|l>7SyS0EwkG};n@*7*MbISb$` zHVa_p^tc6p!2yin3q^)~A`Az6O@57aN2kP#oYn7Qm_$e4hc9+~q))>MC+d=-R{LUS zm)-w@M=`M7AF0#q_znzCYRa56|DrlQS}$%KZaqcNYb?p*TSp3fApx!jB!7Sy2bnV9 zyxV(v_^|sH3``rGoB=DRmf-GkveFa_d;#D;WwFL1a!(O| z0_DmR*+S`QX#hVPCtt)|Tv$NwPUC~$|wA7Begx{_#EP&3$?=>|}nqn7U>>Mkd-dG0Ca~>O}9qt4pcnfBO zI!W*rS8xv5zJk47n5?tZ0Z#27BQQA9Oj8TVZqUXaxR>$TzLG8 zCl+gEWa5LDKu};enJQJIbBjL6O2kji|BXw2gc0CqUzFJ;iyLH(zshTAdAPC9AsEZg zs2YiT$l##c)MtO|e*+~R7^#z<@xh8yf{PrKO@se-pT<&!U4Z?G_4B#F(R{w zzrUffyYW%AD;)0`G((4!Vs^~z--v0kKl8kdqMfY$y1l9N_js%_g@uJB5%bLgdc=Pe zl-*tG@$qpGeE@tC0Mq)94+%bpwHB7R4MWz>FHasI=4(YW=EE|6a8={;=w^dfoB6F9 z#teF4L4Q&$GS}4n^KOp=Z)5vYdqt$f>rbb=oNpou_o<3WdxcaLhkOflVhTy^CWQQ1 z%JwZ+$_4pvWXL^-e&>ejIJ-8xpZeRb)C`NGz6KyX!qh9=SbN;IzFg+~~cwnFH zt&6`%<7M+?|3)0kGJu$GTBOdN4zzs6y7RlnArWcyN9=f3`CQ~f7~vW3mX*Cqm%4G} zSitjzJ`z_RQNhxWZ!pe0_IG2|sZWmzxS+vRWSV$rFcQVfEeBDjHXs?$g zv^(B+s_w4_b$ibusZ--I1DjqdJq{hD_}r3qc&XgEZ!2{iFzRelGbRE>LKOuvf6RCN zD|!>zEA|pvCjClB9`GxDH!}kRQy4?#Eco+`qIs)z8FGh}GgpFes);h)>MQM{7m36- z)VX7)-drEFb=OFu=(!oF>BinZ`zPmH!r18#I0BHiPyDhBB~$Bf^Es^?-OWg{EEm5O zzhBifLV3d&utHiK&C6--xKo@UpYeGc-tfK5U>AjS1o@R&Pf$zrifp`Tnu)Sw0JF}Y z(j9@E!uSummPvD3)d3dFJDJ{zYbV8l7%w@U2Vf6+iT4Ac;$0519mFSpz6;tIr>Gw- z85>()@3mf%!ClJmuLYtI|Af0rQUZ0qS+OPCx<6ZVHQ~#5NwPQZZi_ zx$ilQb9+9%{i?a(S27O_GGFM9e-D?-mt?}W#;~N!#(A#fY(xk7v_p`e*`f`(=PXv* zRTYIHU+V%ip5DF=cudS{3H7_&)0i%!R(wHmYPw)p9VsfiQpStP37qu7`rC?E*+8=s zJ+O(W(mj8}HIcV4+h%yBp@sOCx2tu-4(4&1{`$6Ol&x1yC7(o4cKibQBW?JJnB0~g z=4@R-ASt=w@W79aNUBYpltJUkk=kMZ&GI%n`mUYEOaHt$w9HjMC@ zaUz#KbIXh7{ui1BHOI&I)1QBPiht$wZ-29(E=p!_$B)GIlm_Sqr3DNp{%GD(1)zHLX zx^U)ptf`io-s*^pd&bt&nEKdh-prT-JEA+=2wj(gmjN<6Gax<6Qil!hq%?Mj zKsT&@*!65upcu}zu*&hCfMC5XVCJN!ql3zB@?f%(z-d=!9ETY?jr?O;!_P#ZAb?m8 zLfAilj{o6fMQmo{6HDKN%OY9{!qJV=k{FOV>^Oi30H+5{6Wu@BcgeJkVB1dXA0beM zr9=_u$L(+H+qoEn%#0+MN#MVsh?mvIz=V#o$*>$o2{()UO!Cf%Dyxl>&EHr*qDFec zfr

    KhL59M^2=ZOsKdBM_aPvh?_D}m z@=u-yURb+t7>Jn>?c1#z_JiYzH7IS&opc8Ej6GZI;J`FLujwsH4zBN60?q>?$8LxlYfCD9x_~&+dItO(LT3`#^ch=?Ib3Q1#v6YqooIvsWnb*v*$2^9V7sB&(#) zE9b|BhXt+nk_%;(AJHJB*FWI#Um!BC%&%OJh~u_ z;v`*^Fg@sQ?ds10X;}c<6LgSdD#By;@6OH(Mn}2X6seittwyW%FnxIMa27is5yI5F zx^ap-{!vZ#%pFr?fAebW*7#vEs(YX57u;Ia;!XEchpt%k)#!Djh7h8;f?cln)2J`P&k9^<0^F!wq3PDq(7(8g*x8BxnLwhr zCTMwU!la`npX{uJV9`Jgtw|3qy<^6#@MxW_1(S`A0;b6I?4-xUPPZgmyLUQUUAU5W z=-D~hdT;isTsXFJ)`^u^?q1y!sh@gpBV^ocOsiT+dVox5lnXEuX4&mj_Ca$sSFO+ft@@$ zQ$T@D?YwR;rR)Jq?AG|HNY*C5z{ID5aLuA%NfJt_FpY}s$p_~r&p5xC4v8_FZ4IM~ zCmPrGANSete1-gDUZwPPB`}kx@VSHLA%2IGTiqol3*y>~D5TMr1$zU!i@zqK@agf# zd0&}i`7CtujX$I^pJwe4U3%u14SU?va#HhVH%hD>be3 znc)ttahBJUhe?9T+KEka__6edkwS76Hd->BTl$QSYbP=JW!36DYapJpqmVpk44i07 zu>A0){&%LUkrsUJD?6Nl(}4pn?NUQz$+kvK*=4)bv(whVnfKpxCS6h2zXzmy#&?)dB4?wyl{MnZ*bxig zuge5$if7$3N0$P>6<|%kGXhdsmkW&4H9MaoD^(mM5oOo<_~PQid330SmIzG=3ni$u zqJkPbJk4{TD`QB)@4-cIkjtQiFidHN#JY$4!eo(<;P$rInmAoC1Z;Mk=~+eL%%gvY z@>)owO*-iyUTmr6noqQKG^ZGWkdq{ct+x)btfhNuqDjI^fzJ$c9lt^mHb@%*SxVsx z9SO$dOmj+=WW7;-Vy9_;gwBF7A`IK|26UB+@_BDyRh&F^xBr>Ch?4J;9x|e&#a&b2 z3L*P$E~Q3#iK;cgzD_MJ8#lDJKzNe4R7=3q0!)C29t>e36~nICsItHoed5Z5zU?FA zfUU&UE_U%vm4{rmM{5#Tt}i{Dd6^aZ!+d2lG?>J~Ry*K@3_lM94pR^$n5UZUHR437 zESY?)oOBV)u1g3-74evUX*aBb&xt&S{?C3vSsGLkBa3wG*2;2}4q(Bwi8WbR#S_QD z)U}i~w)r0^(iOpU?&mKQIGFjgQ@2(ScrRtKxQ&My}R z!>UxX!I=L7+;dt+(FOFtSrZ4qkf6`%=;XxQ);0>nRYB0oXx4_nZ6}&<2J8U7=)n?6 z^q7YmCepqFc*)89`mFL?$`BI*X=@?$`T|QV6m<=04a2=87exY-A`ClhTYMODfw;WQ@92d7{oPxQe&RU zmE$_8piONj?dChaP8<#INZb9hUy{Pde`IEXC|4~efkjrW-+H0*RhI8 z1j5O;hgL4X-{Da?> zs2-;SeR1+)`?rdEi#yz;kzOvu#;@izGFF;+yAMQd{~Q|?%g-u`be9>bK?*C0@f*|M zS5?Encl4#+d!CAIvqmMb@N=L@UwRw15+ zUmQWXo0^v|6Irj4Q$_aKV2;^8k8BAOWUY#vaNnUG0&@SmHFUGY^9IB%u1=E=9QSSK zsh#~67gV?;%$6MJ+>U9zXdF@@Xs*Av`bQ(%WC2M_dH>4gRIjJ|r{8$#qcFn(u958% z3opZl`CB~?%cdm^`!z7F@x8|tZX#z4oSOb}DOstDF6K#=<4wfN%0-i2-m~w6hPc_j z@=nb^8Fg!bsfBs`+35ErJij;ba;DK57DC!(%v;{HDs$}H(?Hvlp$mI^p`ER&lmmVa z5h;_quO2QYLEStw^BRWTC6}EtHU%M#%gHJK_WZQ2JWNu>NqSdo!b$poD5-SKdq-Adn=yfYE2qmYbvV z%NP4UDvsB~s)nTk6VW9Eb<%Sl2R9DItv(t43t|d?#1WQU4F*5DEH5w{7x}>h!}h&* zN9~xGlONF9YP4>zZ&B)>fRU&ew~hW)4)h zZRil8cpCmboArG=Rvf{@V2N&G#NAtlo>}SL6y{l)#fz>Vg1INWTDcT5Na454mzzlG z00|dbd8`Q+8x|5T?v!2xQij0J1*`zT0m6dc8K$0;xQcSy#+*!bJUr@oBjNjDXfJ7Y z5|Oz}BwJbUlc1?D?c{XOZcHh;0D-?_%p+hCrhFv3+p~!i_rbcgr$Y}Lf^sq_FoFnX z0}8kp=^z}_mdS+(847tbe;NURGjs`G9AS46`>%+Oxv9WpyH6S5YwbY=ZtgP$& z{MNp?JK{}U<~Q-=PyLx(U)giyrjS?j%iA`u@>})!aq;@gHX+T90@=;0WJzBLo4x%1 z7|hixHx~R-$EBm6W85+&ESxv?UgHm+c{3N1I+jie#79XD6UQOB4e>x_cyBGfZHN(B zG$noNG^w?|Hjc{|;proK;1UHO11OJ)Y&}^eB?J(hv6_Hu z-a@d@l+bQ1D~F9G!1oe-P`oC6nt1U+D?-(LU>ikwzZw<8&VJr9Mq&&}Fx^bB(G;(Z z8^&@pG0>*RJummrWC^-pNJMTsXddo(9rLmxcivDE2$8S7Yf0+DgaJApy#EcvS zI6tLa!gq9m)!Of&(>p@tV&RD=cfu#ev@x<+Lvr`p)7MkDcP(6R$C z?)|SMxdxq}XeIaR@d?A4^ZIe(980v1&)H~e`G#*RP2el1-3L_WFChmQU3_G`MH%+1 zFb==ElT1+%H-GYV&w6b#i3P zDeK_&TInhOU+SvIY1LWZ=Nr@6Vdv|5B8|(|GnUz}OScTD+rZKalJu4=CtSNaqx?W{;60FExwGQ-RWN^;O zQ+ks}<|q(w=Ki)BRu%nVGPnM(p74;B?)kbdXN!f17tI-uMOs$0PO)73v`sPKXZSnnGLq=fU1=yMS385*KMX!!3qU@ zs?0~(-l7gQE5OnKf)JBv*$P9OVWqTSAnf=Z6|vKi9;vKQkya8&`((%7Ism-D>nRJa)KWF^&b2^BSzl=x5K%~unNqiZ{-hJ+SM=c(%TyL{ z=)9$+UJnvJsY(p5sRWHy;8~TF##i4mp~Q4^2)f z<{q`lZ)0$m^oAhwKjL_2)V0)il)TO#e+)Gop;ZV-pX3u(_Ob>PQIy4gr>}=ABVF>( zzjc1PM;0Wo)+bsHy>ooC7lE1Qj@y-%xM$CBP51^S=sxcD9Y(u%*k5-(0DTZojXY~v z^Zv6ckTYa)2>DrDx1;8LV&?1imt<%0f<(_IROby-b!T~iOJZUr0^(d~sCH1d^_)1b znfya|SX+3wlXr*p(+eQ!dfc9MrrOE;M)JF$V|aCl>bT{DqH#Xb5no%vHbjFKxtHjCrlGEwxuz2b_PwQ@$q;q=!t zJ;(aDzOU{3JoD;ZnGPXTB_psoW!&D+kNb^3QhRP~HvRnmm=6BQS1VqB9>A-9g{z;> z+#BB8ikKs4{PE+PP*vdR3Po~&g9sdXD`q*PUksvDO>*H!Q`>*suf30a)CFSF&YyS7 zT`{!wKf)k5kJqcit_tF+t4YX+n;+0wdt`j34hTde+U_gMgTW-DO{0*F;}{6T zE()hzww4j!qO~`rdMhw)9pjuONdl;vxVWIf8VwET;_Ypza9D{Qu+60W{%y|=fS_(lPbgRd$M2BEDAHllDN` zm8VY>FH45A0_sMv18mk>>yzZ;Z! z(A^WO6ZlH?5KuPxx`f$7?hD-`elOOEO!v4MPkJ8z$O^Ts$0uRH^8L~>Xb`N#Gy%S6 zzKcFX-emJ^hwZgukiC(^Oe5Pqf_4@}^_yZ++e<}I?9 z#bB}LzTbSXm-e{rfvbwJWILZw2b`R>h0+Lodskr_Cku=nOa~-23MWIf%T3Hwlp}Vr z*zqf)-li)+ln58?&}N2!Kt4#dgHT6&@@GS+uFE=1G1x1cfs@HbNBkkVj;jY@unXDp zq8igoSAzE`N1;214=oVjrWlg}%X#bS0i;C0Nh^MI@4v|AuV2eE=>!>9_Dz`pF(yog z*`hxIvz)D5Qe?zNVhrZDinM0ZTOjA4vr|f9K$S2a@$1rE7>v&q4Cw*NURxE;`1WGh z9HL2133~-oO5kHDBNNJl5e^B5gay0PCW1x^!z2;n)PzER`IoUh=-Z#XAA#%g|b(xgq799wvtl1 z;9P!OO#a*Ne?GbYy~)ecWS>Fkm-yCRgzb0caykF;jn=Wmt@`gbD6P$Z%3H(ejO}Kz zGKvfJOWZxE@6lR?jQ>FGLUgWq`8@SvRxe0$vIa9k;a~(J`k~UJfNMcm*D~xV6@TaN zNuQCPjllD1@v&gUiuBfBK2_Cf_|u9Vdb9ov~}k z7*p#$#tbxr>{kxCfJMOGgn-n$i7Y-EyLsk-ai%TBsxndo1M4r#m>^8uPf$X0;i(w+ z>Vm00zWb}H460;Y)%cLsi>MdQ+lF!c(Ep+=vehLON8kSkw&)86PTsS$BA3em7mo0H zXKLz=L!ACIa|RzK1}SXVq^psCc|e(8uCxAmD8eNM)O7_f%l)ctzbT0C1?4#UgJ*Km24%iev77rBpcfy2NBBToGf zUd;jA5W)}pDSVZ9ybtXNUadZ~nm#9$aJ>&;A);ajsYJ z3;TNIlw(ftOq5;Mfy_-~_iXsRi|>IJ7VVr!v=?L!cU>nW9+?`|M5?decwgLYEi0W* z&01dW9am;~l7!0OveJiU2X4-V9qTOm| zk8ie!H2no?2-D!e3g-J2x(#3Eoi=2Lm(2x8b(%DpSEbV}H0zn6DeGEKjXee4d^}-O zgo2`s&z|xj82$(B6GcqSfiruApvG&_s;0;lHg=)E7Ed8eX>d#~bWnOZ6%eIak=K{I zml~y6)cMqPyBxu3i3ZxcMfi3DEKh){47?-?3;OGt^8o~p!)K4%p;Fb-}uH6cD+6;ax32GBOFiL1w0 zFx9=BqIoYJQH>stt+b7UX;qwZ$;E@Wrf58{yXsW9ykpU%$E62JX=moN14t(B1EtjC zHuuz(>bg@T83F*v+^JN4+iD*NS$9T%p)1l#liKH>LiQ*krJ-d?&hF+(~ zYurF<@O9mH$zwJ^3RRh^DG023Y3)YbFjQjP&gT}4P?PXRgPqag+S;n(lv`_ScT(h! z|MBC8(baB^gOrfpOB)ZSdxJpnCyij6V;#(yI){431=`loc36^W2J|c&8^*KK&a0NH9eO*!J%SzztJSi zXNURd?BJb}nWAegAKrKM)bAh9rxyv|tFq2#EpUStV|8ekzinLM`8MVa%-QJKS-aFn zF2uM~F4?g8Z_@X9d0DxeU3VQk&Nn2Obvna&Z00|$bOd?EhVtO-B)PHd(D8T-YzT+E z;P4H6f_)au?%RSJ_%6B}U*8M#{*c>w^!yB?e+JX|!;z@dJ z6u?2tC5ssK4MSVCgY=<=S(_nvPtShu4MW*{@V`*fI^Vk!JRKA|?tQ`OW5u_!32W6a zUiYT82{;RZHhP5CZ@_4*;Gj{-@f^>B~1BFOvku-Vb(b1!I-}z(|;}~TB3#^oCS*GYV+Qaf$ z{AGCw2J2R(g)u(|@R(Kcxq8@pJ)=@Tgfv%qz{`A4{zRZR+&ILWV?{uWVxu#Pu9Y@+ z_b&sL;;EuzPor5X0>+^g4;OFZy6Ze>31gtJx?ZHGVao;-je}PR!lF(8o~XP&utKPO z;I8NqmgSdVMsl!qle^<~Gy0xXX0oeO7!3fJ?$)pVM0r*rie747c=w#GI;^iKB)=|+ z?7#ADcy9^eg#{@NE~GTn-DxFV4i^m4Zh=QSboAPmgifS=V$-VPu_y{M=xp(>kFtHc z)TLS3jkVYtvEzDjiN-~gk!^Ahg?Rt~N^G^sL1|y3Oi0NM+&8ll@Ip3fEhc*CwrT?%P z|G_QR*C&oAJWtuz?#+4bLO#CWEJL-#Idadr=0z-i(;KIJ7^dK zj4-zM@fM>g5BIy5I*}x766lib<|E5q-QNS{?`AdJ{wl-xpKlQlVkPhOr z(#b>@PT8fi6wjrlR}t`)q%Au%Lep@=wMpe>Iw2kLU(v%T8KmRAeK zoP^t*PSALHEfZtr%ivzxe6JB9q+lE%4_ZC}&a5NS;lk+CaQZpO4 zPHRf{Xg9~bieJZqMF!*?%sKJ7^izCmh1fy24I!E?#V_V>Y7EBlT!T92mK@ce3#+t0LQ|Nu)i;5haM8xjmmh_{XSl_Q*qU`%89x6lML|>c; z1rtAGF@vH?RI`$TxUVgxawRQpo)J{T{Fpa)S0~OYbu$M$220F44Gk`e1EtL?fpyct zHcdFEr6Hc07Tmn@lsOd1%2=_3$e}%l=z?vCPbv@R0|vrt>mwsB#FN8`igOiU=(@Z@ zYQcdTTK-Y1DJ~`Dk&xt{U!J+@_nU0yS>(C}@(hzV9B87I^upGJCu$lbT#rbQ)$?<9 z5bdlh2uJU&E&v}}0*rnqEPN*uui!Zar7q6Y-0|;zM{m53P25+;9S2>{Tkm=k+0y^r zvNjEOOdjOtFaI8X4fON3neQcC$gs71aMEKbb89nugeQ6%`ekI>ybj4dcd6^D+zr*vC!HejOa+YjX^@3{6)A)Jt;jglhBc4|B97T7s0#i9s@cA zn<3-NM$J{9)URIfBKBWHzjjUZo|lk+^Kx*j4x*`_QDi$f%1>3x>Ip^M$X{`ft;s%U z@<}0^xbmLEyvM6nb^{@AC1-Ba$1b=Zr=`31)uF5Ti_&Ga_(TZ^^ZB6 z&k}5zIq;pC@IyUQo$nkd(Y_>)ZYeFK%eDBV#wYBdBX6U+8SrLWfc5~up#*MgQ;rEB zCIZJeTwu43i5W0)1JY1s%RVuvqv!W~5e9h3|I(uV4uU@Ky#G5~18nOj9UVC@FCh>P z0%X2w^I>c-B?D#-aMWWbGzYO-2SO-v*6LI9;#N}Gr1UEYwlEP=67)X^@$&Z9)+fX< zgmQ~bBMlAky1-iPE^L1Ui~4@!>~1n)$%7|x>7e%ZT;KRn-}vcA&Gji3G^ExbK1v;m zdoL|)PrImg3EEjT*G&hug>|oX`5V>a!-#d}sPRvc{7O>UgcYe4!DMlYB_e9YLy?t2 zSn~&xmiDEUI1#@$ zGXMN;Q0ev(!Q_t<$9k@Qi&J&u6mtcEBZl+~Rw4Ag*Djjw&tB{C5R74nnX*6`$Axd@ zh1~kWUy9^dkFtyMRc(XHHs|c7)!S`gv~D4}wPDj5P_RCpSZR9}Oq-tSTAXmsI{dLc zYs5CAI@=X8V5V;V{%hBnAN0DbP!@SmDu(3B?Luqc)vafSVvZ+^Vono^jI%J=e`N;VYLg;Z#HB=WU^&4>RIqV1iYYUgmEF<<=Cd7HrXgBPYt7eHbS`F(Nfy_4C@5*w^etFjW*=#d&tI$y%$yJbBLTjv z=(vIvzf7K5yQo}vajMIaF*sh4Q-r7AH#D$$Fp!r+yjtDVGc>gP2nBly?$DST9W@Fk z-Y?xH@ulmrYMWgUqMyh{|IXJz|4(A>D5z;gDw}P}{Gu z-$~>MV~|9#2YeGxVK!_7oShJ^W+$!zLOy4%A3Eb8ITHZa@H^q1WCpj`7M-mnmth+m z(q>mTej{+e4gN=f1pyrPUTQgP%04hMLz{d;j( z`mBFLtGKXLL!cOPO(mq%QoK?Xuye4vp81YAP{s|e+4Wd{enAToWrjOc_hko3;l{#t z8`C|9;9hj&z{@)~0m0_DqYwS~*!>8Oxh06Kv$(gztol1?ITLGBUorgi{?5y3ZW=^g zr43GD*|;|%l1h3kEcjert@2h)N$n*ocd?2gHgJRUw=paad#m&SwwuBk`~jk(v!wSrJ|$+ zN|bCpj-kcqVnSLfvg)JmUp_r1c{y0|p*A)k zLE|!ie8*v&YEnCT9`-MZXK>UyXC-~1V4aok+Yg^@rU{)GAGW}{OVPbcilH$(BFCoO zvrqmp*#?Y8Y68Y`%&a3Ex~KjbP`i6x6ixjt*w~{hi=>#GL-e#2d(@5l339bYiCLR9 zS+l+Csrr8mM-_D+)>kI&Qn%8Nn>n?=eEpkbwwdZI1>}ffTI|7*3G;j{hp(*QBvcTc zV&lBM)F?zYD)3=cp!Q^1Dix-F&q{WFtW(`3som(!$qgjlz9Po3^w} z&FzQIdw8L<5JzA3pt5~rOxCV3g$J54kSIX(s;ccW0?&GVc2*KNeGevcOTab=S~Nat zY28HZD^I-666$lF93+&tVs3Yh-7>K_mbW+b;Hp%m z6Oo3M*3f}m^VfV%(i#{z$Cal>4}2;3(1sMgONbdNc}?K$qNv27%Z!bQKs3dTov3z= zspxoXPGHxXTk_>paJ6aO6U*D&QQT_qeM#7dNcFT7w-eEh=M$Z@wq9GM6P72P2(r3C^}U z4{P1y5&rZ_3fq3o_KW|5My4F)>y3#TWf3pu*Gv}yC5G&Lj>T$hL0#V(US9_7-s5kv z9b5xVMn~JNp@zGQ|H!9C1&+UxW}`5kZ_`Le1fcD|MLA^Tw;c{vMZzhT3P&T#;twBx z^0>f$*TcU9hYU1?u5Xy+KG$1)a$Mu3rQpO#+R^*GI@zE<3XK6!Bs_D}a*(W@D0T@_ zSE(@VVW*8=FZYNN_pnfahM|=HQ+5D_D4Xy-K_0&*4C}*~s6VsUk^<9DI3&jqt{`L_ z>LE4Ze(aQUU(v26k=O3!BlIj4%&8f|g1__j84aH6W!@odY%j#G9JnTdbY1yeWCaJh zi@7nE!FO3DlGd*+XW8XF&v#v&Vy5zc6xF*$7Sf1s#eBNq`dj~*xL}Lk>*K3wZ_}&=Rzyc-n%?LSxW9fUO5@@9wA zwT`zTo_Wj$KbnlmUM{9OT8MjhYx{{1n1TwKQRaEO14YYpp|iGGm@8107E)dgur%0_ z{lJy*AB|EX|G$35%1R7_1uG6zK(YZ88^9vNXV&hzSuk=4j&5jZ&^hCCSVv2XoW^6) z)Lw3@DnWiWOdBu7+rzE+a6y!Yhhb$kIu75l9IMJYT#V*o7!hu3#fVBP4pMo<(Ymnh zz|;VY5O`fsS-6-}Y^-bUCoWB_>}6zQvB56i zeza~a{Fu^G6HCgT`HjsF(AdS;ZkZ7KM*Um$Um%J;9^?;Ake%qK*H43Kk#&YJ*`3@-ukc3|iJsF4f^+}n_r!?QE1l}5V??HZV-m2sd>+RRtf zTzbv@{>{$Mf6oMa;c9TOI}BJ4BQr$`2dfi5o8^+xe*Kc5X9`h$ymAk1o4@zl8({Lt zJ@5${>{aY9Nn^w#V#F^C>rV^oZx+QbTt41&@D}aJQLN3^?mKd1Pm!;iJl^?iLF3Vz z7bhDx{C(I`UiiX2OiF*tpvjJ=)-;W}0{Sa708ITY;o_Qjw6kaH}Qr7Wn=iobt#GUE#I z?>%C-@I+zzm?_j#(19>vYnxZjpjbCZ0ofF|PJ~8NDkKd5s8~eQSsDGJE>>p7fSrhJ zACvvAMhskd6vaF&Xbc=@CuGIU80+e9lfp6BBC{-JVTun)244iEI%@)3=z1v{aq-v z5BV{liOe^NnSnMB8KpA_U58FYekvq&Jg0uTu~H=cH|aC2i2E=u#v$Hki@&OjQ{8rq z;QU&aR_5iP;+r|1{(j{TO(;74!?oU-?jOkorTkF_sy_=*_byb=r)9wX;)cI zX%CEyWWv6$AAMqFM zfm)*UJYl(n-Qk^ng&2~rj)<}6NIbu*gIS(XUwb?}brRbnhCg8*H;iX}&5>Xr%t}|r zVxX^JSR38^gUEopY|X;6rSBCoLqum)ymmN8ob6(m(9bf)KK2B+MG>V0D4g@mJbNj{ zIK@xnE$`g_Qk)2(Gp%e@+7(|R%_Ri^fMt2v{#)~j8=ltm#Pgk(LlJFND7C{TDv^!5UHoj>pvK(?e<=~kV0 zPOjQiE6OIkv;XowX6}1BGC1xePpv|+MAuRI%;>0b8C4F#(iz{qYaUFouV4;4bL8ju zzCS-6>B+L$(v5+qeW6Q~11OcB&m*Lg2=k!3ax~}hQ{>IUERY3I30SlG*Bk5NPj9rC z@vUfH>gy8O@DThM=5tB4aiN%ugExkC2RTu7PN=jAIMs|0T!JTBz`6?rT{ggoNB!M& zOg8G@J|>&0GgN@~kRG0x)ipWsiES{bQK4c812uiz8nNi~RL-(=BCDHN$aUz)O#7ZyTKH~7w%U^2h}U#?Q&LHECOwtk4W-R;iM>8GT# zPj(iShY22;fSNTS+$5w&TGum~tYfF?8*(}=>K3}F@1r14ZKy3!!Zzl6dk}%ac(?BB z{dnh`T(nA3y!r^ifPT;&O+J_#@eoio*lT1VkfTkQ706ZwL}Av{(O(r-UqD z2nctA+~8?v(o#5Ar!8u*M1^7dasr=H(I;@tOaqh|Fhd2-)!*~;GjntO05S7l!;WFq z0%cFz`~t?lHZyiZFZ}uRd$Pf;sds^9gD59!2Noy)tmTg*)w3|RB7}6>J<-YUHxa|t zHL$XC{!5yN4HCU2+A6wmN(iTZ8$nZ^Qjf!s6gFT=je`uFibDs0S*oZVzX`G|>Wn;z zS_ecu;$lP_FcUvi+rD3H(|nOSGJhA7&DOK7#V-16O`rS`hjH$C4mXrXGh4qu{u&Eg zKEh3Dr?`?8v}arAWNaJRd`V-({YWDb*j603P+)q34hO>>+`9^UZNW*6+y6ZoR=2G0 zDj#OK2cejNR9a`>xQD0P>5SWEl5cw!1;FMjD&s}@l`_{qh_e|JvTtKL(vux*xnv}m zXmhIsqkbwam+W_Zdq@UFHaE{O3Mn~8Sh~(M%$ur z=%gd+XO+dCf2$7iR&LQfkP0V?MR^_29T{wlhseII>~iun0~}aBzAC0m`#Y=q$Lr4c zQm-hzw<(Z{OKW8U`+n&toUBdOzZvjP%i~i@P_LsK!5iMKWg6>Zrksmk$wM53VWP2` zov5xcG9gNd9E8ys?<;K4xwSt@B4d+4$W8s7cfUcagrC*Fu%&dY^wyM!4bRya>8U0a zk)BUCWe^{uH=LJ!?G~~RmKuO-@4TS;T>dRJCT())tZi^rrZLTCTe`bLq)S4&q`Q&s?(UQl>F#bM1mxTA_s1C+IG*7-vtzA$U6%$6 zTuV`@cKrw(2zB~7Dl!z2nEup} ztVgf16Z=TH@iWtl_7dD0dVQ3L{M{hTg;RO6EjL#-kiT|)B1mv1mU&g^^?0u}e9&as z;?s#_Th5|H>Z3BjjvVC3^Rrx|;vgW4I}M?iFIi4!b9w*cVBQyHPsVSq1fTv}s(9Q} ze0lRASY+y#AU;1ebmj`SRm-SaqwV5-%g?9NOc3+phxi-5+X2c4A{8Xs%y1liFrU_| z=OFuG-o5+wPF6xxT@CFZSORwRoIH|g!Zi1LYDclN$gKXmm{;9{gb(OgUCx!ZeLqtJ zmgRYA2K@;N!;rSxUvw~tpn`*X}3blOZjMHCd;z7P-5oaD2yB@ECde*|~&8j<#QYpq8)3@r8iDFY?hgU-bP#(bi0wz2(pdWj78Ttt2QU}mx zozznr@TdS0r@xM({RTLiCPf$duAOCD*7Az%Dq1~NIR!N}nVck`x>8Df+^61k`s7;X z`t;T58JmF^;-qw7$gW0O2v~6@fV>b5t;h1eK?f#nM^Q(elyZHrfEveeZ994{WNn_i zf8gM_$uRuNggbD`)o_2@t|UNOqRo_WQ#j+69gfkbUd}#hIhVzoxV_dUM0jG<=Q}EX z=E-$zO2nx3@kX!b6_*bZf*1}pt{fgCN*TPE7^o)=yau)6wensmkvR!lN4X{WYswU< zg853uFR{foAlfEZlt7T3%^0WS7oLMcs%de#Z~j7M_PwrGTO_w97L8w6%z6wn$q`@)HA=b$vQhH6q-$a4F@vV_q(!vHlOWL}#aZ?jYLC;{0EoJvNHs%zI9y z496lFrro^~iYUsh`bnMyG=kJVhBhp8^aX$;pCGY5{>vk6hG zZ+U~=VuX@v;K@C59r2tO(3S@+2B{WowLVFk=O`vzhH2);2F``_jAfB2C@6jU9oeuj z4j4J1x*;BG4jh_Xlh9Wab=$WvA5`}E9k~6quv_08uq4h-f>QV%4~5y&A0}25>7$yZ z)c)>{OlQbagP63b@lPK=zvhpEJht^M1ASVX3o|B6g0i9$+Xx+xjel3qjN!nDnZgG| z#Awc6;%G34t&SK};drck?J&Wqg7@Exc|;UZ5mCcCM8qj2BgsWI8!`mXKmb=F0#I%( zlIANdaVo&+HZ0crBm%Q21b1i9rkH?MiNpMnUbsjkfJ*jPVO#7oXl8|D6y*AK_u{oC zFd|?M28HpR92F*lHdofjaY-&T!WyXG<_Ew!>`BEqA+s8mmx2(4l1rpU`sYUEbt`7&ajbj-O;}CV|y|J}BJ2Jz*rS=P2|wyEUjOC&?W= zC&wgz|DeRk>=RwXK8%mZpy*9YnIjZ>@nnX}H89+){7ZO`O7$~j>(9czM+?5V=E{yM zp`$S4%%|=$+?*vCE}W~NlI^p+G27It!oDS{HAfhMhsdX=oYSpm<&2*%84Orko6XmO zq`r053yI|!XFktG_9jS~OM?iz_zvrNM+pWk#Sur}-B*C4*>H#YV|_e`*_C)k(s~BQ z-a0w#Hp}x_ZO}Da2RuP~o_u~6%%SEOe zRb}LGq-&@-e-}-XheLz;AsOiu?{eSQJUvVvLZZBUO3qdn^(u7|wQxK!!I?bjo!NeS zLX8gW#t_%|gHFl}#-&Bvy=pz({n?2nF;x0FQCQf`Pd2E@I)u@%Ycsv2)e*t(M`9Ja-AQQMyD+2^&X zE4-dD6*~9hEU$O|8-5so-vcaz@;5(G6$XZWIXK^?t$D0woAr+e{Bq&_cz(IxNqp12 zPi1{}$x3bZ0k8E-%Y?7v5f2RwE6HLAJjp7Ah0ev(p>y}$hi3%XpyF-^ zHfxBhK*7t0X8;b?%q721o}iGvPI4i~MTB9*cFQ z1K$g%-(E5B;U%1}s7iQ+5_;kei zvd8<_tFW`$a5yQ^SQSkZq&ufL)2(PKYvo+LamTEu*gN~@LqeVh30pQCw*z~C97N*z z8r%fG$?Le5@bK{uVqw0ui7-7EAK&v20^42;s^XsCbcBM*AKR?F)(LB+~_>WIj+ zF3H9QvYh3=7x)e0rE;~Gq_87`{5F< z2Jhb{WgKJLx07fhlL_aUfX|r<=YRaY-z~6YqKpc4&q2S`EdL&bK&@5gA4VDfOsx5^ zGa&!($TBHZ9NP}(7mkFR@b zMb-kgjRQ+VcK1000ma^ZTE!LH4n#y)SlI+?YcP~&#TzAb>w(1$av453K&3c+OCTgp z8J+4iUlWTH8K;n`%A2n|=Qamnez|*M_mddLxE=t>)ov!bcbHavkK3n!=7OpAG1@xS zbj08S@_9byLF&T*TewsKKs@VgihA7}wT<=a|GjZ0NrGzM|9qD4!JWK*tZcc`M|dB*^}LqWjq{1t9{DuC<|T$uaS^zq>+!<}8>jN6q;5tqXOZW4zMlE6GZq z4S!}wmU`f8PULMwdrE*NMB&e(kT=_3bS~^Shma{?)s%)9Rh7LFOya8Bw@adA7>AhV zz-PU*<4#Zi(&MqO{jYv7W}VkO^@U!m+WA4%o|3k|iMFLN$mqTl@wsmA)?l2S7OH6f zqUO<|8XjeNjPg*PZc*tV;WDko3&>sVs@p=D^_sQ46rkfy9eGC0e-65UJXXn^O-SWw zJK($J14QW5FZ+*np?$QNgQj&lDuzX>V{$w!IVka`Qg^;P1S!-jX8@cKJ9ciEB^~o$ zU>AOwwJvt`y!kJ}duqyDwY$&x4(7)MKrv{}(U8*xD&OFQ4{VFJ>>B|0mwcqGf(^t` z{~vW0vin+Bg^y%m*+tg^Tzdu}@@YyQc@xfu~JP3Y^&?Hx+c5LO?tjo=wRuOY6O=S;g0;=?0o&J4fJq0 zIKo!V{co_qstwMuK!6OY@8aU(!K?khJ$@%vDreM}McQ_&CnE|fLx)suPM-^L=ghD; z|4IH$GCH$a_YDtE{q|R4qHFdatSA)BTg6?Q`yKwvf;%*7=XPFyaui*ha3q#^@}e$CieUH-Gj7O>Co}$Ad;HCX&yn$B5G%2CjLDR0=P$X*O)r-uW5U3${Y%XjgR>@mPm}$$UKQ!bk9haJ(!4-?c4D5H znNKR|mKl&Rri0+~L6S|(+aD|&Pa&5CPGAh>GI6~DL9m3SC8XRA;CSY|_vw@Nv^OVb z&c4nBh7+8}r@~S87?nbqP-H|zc2jlLG0>6Y*%cU4%R1ony7{d-G12)Gzkn&XHCd!F zAb>h{cYzYS{bM3MPk88*v$zeVfh<{iBq^zy-?%BRi>mPCN3Oy7>#w{Q0{v82OcwO4 z*O&;HYtyfwwa2_zpO}r055C}`hQDjm+WKL&eKLRb@2jy5Z7HID2ZYcg-Y2{ORzKXF z%`f%S5ao;tp--d1=`XG7fmTMaEl{{DQ_e{Z#QSV$IltQ|8#9{D3FNSKIy(c*uvWdQ zXW*)3|NVNhdbwbhw<%qo8kh#S3(r;No(w;2m8~N2tA5eavS8(&iSMv7g?U!!nyjJ4 z-j9#`3hCu!mx0QiD5Rd43rrugtAG=xv?1q>ogUu@$Ic54n13EQj*Jp?+*g zuho@Y(;DPT^#36O0TaS^A`?%cn9-2cM6Aun$9l`bZmK`P1@>7Gtb6tn&fQB~>mzBn zI3*f`l~%Oc?6}}KMcHyi>-2#ZdQ541j%}Bx+RnL^J4BT9r_`>~1~XFnoDk!d4M*)U zo0qhJ{|pb!a_VXNgQ5R7z_v24yJ3QYA>ZmuWhqv=}Wm=X&3pvh@l5OlaV4NHz)SK2rCR~mo*Oy0LR zJ74qL+_MtRQnuWjAb%~oNPJ{%G3me>+87>}%t~@WUCLI-XE~2yZktS!M`vhw9%@jz z$XQ;#=V-ND?9G)AJ&ay?n_eXvv9-1Rq%jYfuA$Kcs_PM6G>JgMs(Ze4?23sPQdzhI z*6{xuo53v?NP_?>x@J+H9KHAOcG8;^o{!0A{dfIis7KKY~*!D1riJD>%)9?3^Qy0&q#N zq$2ff#tv))B6#AMxn(r}k58kfLwHe=6-MLx&cK^KK|p>$3fe)yxA1C-Z@Gb+Iw1*g z=8ivVFc0G?Q~n!Q4o-b$ZbJihsJ+`K9ogOxgeOj~ES%T+>QgZIQPCZ8E9UNs7}oEz z34**a2dl4;TAKfY1utz2H!jT}h|2O4Xfoh22V==VephvB_4G5K+JLNUh*(V-%Ri!d z0NMfF(08Elp@(7m;}~5ErZ9+rVSsvg&5Rg{w1j=Rx4&VXM@ot}q`!7L*2;o0;uo|u zAs;V3-+;-3Y-EP05VsVQpwe*=Uw2yMeOhSF;#lfUVWN!-)12#09S?xp0yhyU3?54- z3pW`ja&`B$Ww#<%!IMkp?|aM&OuN!C3CH$do<4^9>B!~PYASSFw)XiWvlCOlDD`_f zGDQlbMN^@w8c^PLRDN42?GSQjpFqDTzy&hRbBd9o!MrD7n2*Nie+?B)%&(pKgzrLs zMtWk&M{2cSXU5caErqM^hQr8h-tl~!KFCKWG6YVJ%#jAEJ(BX;UUzcMdoprs9Ka1xd zbnnqU`Zm4cA13XbtJVEjVtOd$L1~5jjX)uW_<+tb5>rwx$(m8mIc~9g@xHq2ex;o}NEHF}r#z9-q)HvX>& zk{wv5`*4lmJbr&Z*dmSYM|l(D?Hp`4eG898GWqvvRej)+jx_Sf3U%GsWk9r`5AQj( zxBbZ5(NS16I|coCpnO&xj2GLNLi#m#?P~+cW5?(0&&vB-w-3vbDA4>yJF2BEC&x4V z@Qk7g3iamkaqt)vvY0S15YKA@(*hI}goK!wR=n~VoVnW{!2WE4daLz<16WFz*IyfF z?!#E-wO zf7c?S;x{+tYSR*YEvnQjhkKr{;fH!kE^kjx;j0Oir?1X_(9~n)fri$%r&L?NXiZRe zJJ|2E+81(?89!OfeyCL6tZC$FOJbfWV$v?}z%-n=`LW`@rJ91sh;zyq#Xi4Xn2JbQ zMRQppxMFnPs#6B-k)reYb6rA~d-J@CXSF~|`I`rJZK`UzQTdT7Nm2)gzPrWyvcI=_ z$AU(R`9^XoJ-;?e{UOKgmw5k`U%spqa4(OYl_%+$ z-)xd6p-rW@BvHMX=i}0pZPn-`Uooj8(U2(W6`FIURbfn6Z=XLU^tEoMaPI{lb= zf-&3C)X4i(3mqDCcyxGZaLEFwa6qr95X%M3JYv)WIz&Z9MOSxsU?H@a>RMaFsbs-8BIw(KR7-XBe}X9B+c;Zm!x~`2 zCm<00zoGWepFiL~(qhgXGao&?b>J3rnHvneA;)GU1se!td-ByXWj0BR$w9R0_MgUIo2slE=)!Ft|gDR-Lv4H!{Nz zBo`doH=8&#Xn_r zUK7DYkN6oo8IHzfC@wD`7w^L!5N5-+#qPm(VT&Ql>Z4Y|hoV}Py#8|a%db_zg;(*~ zFWatwzxB^E%vALs=dBcE<$sN0m3b5l?vPS?Mg8-keL^*uCUQ>n8woZj=}U-FD5T3Lk)ma^rQC#~pWNJ&{Mm$Xr&Qu1*P z^|rfFwb01mBdBU3`s$CALqF=6M6lGPV#J0Ku8U0Wx3ZuckF>jew_onhFdGR^qV{{E zo%^|md+p^T!;c;M1y{z$CSrM6M`3R8@ET*8VCdE_VCRPvZqbB|-4|(H)M1pc0dSfD z{US!aHjS=icAM`Df2!8pCJlTpzi#gK!I4pAPPQAQquvw0(+K_QP#5vCO|QM^dwuP? zO!GLbytS&_m+Ob?&~X5XpvScAP6}m49`0^@sHehBlo_h9KywxQFfek_e&-r$!aDtw z5qm%r;ayNzNaZ{PCB(Wrju}c?GF2&kPuDppufRTp>i(ax6eDIvim0lQV+b3AVxq4J z^1WE03`8@7KKuLkG@|HNtYPKlrPkKa2pq%s2CgP1@wiciAw0(MznPlLn+1Pk%7e20 zJ1FEP$?8HiEwg?`d&zOQ}eMK{Ma9PGh#?2u8t^+wV_;~bi^LR z-VeXJG)%bQn9=~s(ta;l+sFi$D$Z3S)=Ul(O7ow}g`;~e@pV)Vm5C zBnU7{c<8$nRzq#7ADW!9U9niN)g-7G)F0u=woiScneBf>ap@0RoSC5cPvzdeT^Y$v zhdmzOUUi^-D`7AbiVvN#e2m&`ew*Ik_W!yi_N|;wj00{U(Q&WxGs!K{gB|hc)T|66 z;wPq*wkFwtS8M?memDGaJq_=>q|Np)8bpZ$qe5Fg&#!Hhp_G6$i&5uW}$X*)}DJ zpF<Ak6C7J4aVxL1^ zULK%=a=Z=*OzYC@0#sR20m?V;6J4h%x!2v13b(IN=H##6zX!np6)>(NHW*px%jtAu zrq<6uu++n7^BQp3blm(&rgHm3-o4VFmyzYRVMOA3!Ze_wXK4F0KT!^hl&H`8HeB`2 zo9Y!^T9`A8uM1iZw{rDe8BE>SHa=xr{mBNX^LsK}<%e2|^*t+>c3xXGYbo+5goe?N z?#}F-iXAduI$gq=?mC^iefb%2hB_j;ZI`STR=2k6kf{u~m3Ik7ZPAReb;&1cU)!VZ z*zuIA7jEjId+XV%7(%)&ObKXe6>`!UvF|1>zcxYkjrac=e`j&nlze(hEX`QuY#2T0 z-*h{`pm`kyE+JqJFk;A*E;5ixmZk3u8Vp{_easv>{X;Rqv0Qn6czWZ`XGCy#t<2uy1G~Zz)`s9+PB}4Y0|S%w0SU)}c5r z%&81%J9N=0i&bcC>!cFn!tr$-6a`VH$Tm74AOsz*O7eeE?b>@R1CL%w4xl}l; z%x!S!Wt?K2Un~c3TtOI7kt5r%)0(iZuUfJ%8ZY`hlD}FAm8>s-bJwr|Y5o`DcGE=6x$-SE4I+X3^0>4RS{t)Iv>X4|AIO#CIyMLF0|u;w`ElcG3tl8+zdNVrf` z)Xz)Hb4ud%f#4T!EJ)68zX=4o>W(E!i{&dUQw#LD&t2o^A>0eYu*;e}HKD%;nrvae zlQOGd48Ea{u%n-T1eRK+nf_{`@Jb5JOCL59wC_Rw1AYLql{u;&lMb6bOW^UzPI3B!GE zeN?TBkRjxk*^%v(xo#shwFdSGPj= zMmbk!Rv`^fzwlS)2Cn{{nh2RZukc$PieXSKv*b4|479WG zcixXPUrh^#HdUdQ1$h2yUSMaM;ncJF_ZW56ukzTiS^K$$1p%Si)qd;Z*sXJkPh4&a z0+)I`7=e9)$K4Ay0I-s!K^h7Po>5W1u+8n)&RpSb z;a?-|MpH39*=)?Kkd-Ct%?u~D4gQ<(e$=u)Iw`V6s@54G{ly3lx7bmV(4vlNmwLLo zpx^<9uqoo89`QIjQ9M4bGY@jjDpU$7QI&XI3Vw?+Tz3Lf!(tcVt9DnOx8F^G~rc33MGE`oa z_~WgKhnv-d+NP#>r|$30*uk5%Z)lr7Pt|y<_u2o}Hutcoxky*TzwEfesf27 zV7l?};&3Bmj8FD3l_3!hCrN)eGRjPJY4WKlq7WnV@?;PrODPa1a)ohm87qC5Am%ve zG6`|i#9Lgyc8A79bajW?80)%QN2$F-hq=x_*VmaTy+G7nj<36E(JgzkJ&ctzlDYk`Q(&!E&jlncM-{O zj&ppUqevB@Hycf#PKkd}qhv{iB^9)v0oyeyk{mSxwbkH5Onr}P+14NLb-OAo=hK%e zzu1P$ifODVkJ1%qR2JxG-Z@Pp7vg6UE5gI4WZRb$uPRfVOIiC>Sk`X%Wv0$3mm$sT zFL*$dD{wPP>2p^=Mx8ju_VMFzyW1(cWIWI}{Qdh^TU*<4WTd_N12=aVIXuvY*P0B# zg6(MI{*PjYAdrAumv^+9x8)sx* zcEqQgzeSv4A_USZ852J9xZGpEHB{bwt(TDI99Pymk#R3Bt*9t)tHn`cV{gC>_>y*} zPe}9CE%1Fo%&>Z#fn3Du4Z%MrX=bD**4sVa?COrM;q$)X_w^ydi9?()^}O-BB{z*t zLpDfW$Jv<$+xz0*wfNHc3SIu~Q#MX3?53JGI~WYaPt=I}ZANminA}ZEE%N zXE2nHOClLNJ(hhlJe4}fp=F#R)+F@iEPV8{@8Atab=MzVmesDP+C{W_h2l8Mk8={P zj!^L%c)k3g_G3pbd{RaI#yk=_@oW^E2XVDegVV zc0p@f>!P^12@aa72#{V5L3S_%B<0hA0P9U3nqS<%e}1SWe6F*;ex>921^S^@s7uhD znsv$DkRNBgcO6z&zq0#YvoEN_y{*!Iwj&XJ*VmYP>*YCs4!zpYS+?PKreega_`?_v zZJ{QhsIaQ{_1_1YHtRSdUwTsPe{j#4sK1o>xgDYYbbB9o@7j|lEziF|_+j!6H}v0L zyd+Rv?-VHzV8nCmYn{oDCBToP1UKlIBJmb?*p7}#213gw4)^9Mq!U<sj^pUVw)+-pkqbr61GH@sL{BMC267=ZeEoLe zNb*ee0FHIJ>r1>xt}M|r1oiMr=x59F_q(wB^H4y+DtB))3ZDPe! z>L0AUWiNU4+$uow9j>;qfuY5qkrY-QbMnFEtG|3~ zJxpwoSvaJ@-4)lr^tlC5Kj}xci$kHn(8GDPdjAM`n5}A}jSR1@llNB+_s6&1U9KJ; zU`1T&_T?`xH_f0yLPDx8|8lxe1;Bq`1^bUi4A8?saSfs@0E!}$AOYmnw+EA)+}u5Z z$UfZpe?K_E{;q*bRh==4obllbxhGntt&u{lR=?^o@NBq!^SU%@^Q}px^QWBa(X{Gg zt^a9+UE^;5(rI=O&2st&ef*32SEKXC2BxU{7%9@$H^dAELHJv)!c@+LGRPuTm%vrKHR$nZ^a%hQ|xHz%t>+ZsPKfN7!{u3KDxVq)8N)*4$jVeLw@q+^6&3#201@Le_bV?urc z10G1a1HCIvVq0lAPP7yVZ~{^bV8q%DBu=mXYl(sU`ToFHDEE1ZQxP*F`1C6vUjquG zF3n~+l$GSH1CmGc2)z)WzlDxFg6Cll6*gkqkVA>_DfSG>ye|`OL2)tc02??d;L#sx zxzB5CmZ(=;XCIeGRVoDx(ATOTmhcP(o^0ugq60c0UdSsS>2pSLTL?thmXS@5*5@zx z4&DCxLkt_55(Vf{eOu&bD}R(~CK)z@fa=wLsWxC`MHlR9^-Oa>KmaPk>A*>wtuzPt zIDh|~rl+TGgY@3PMaLzqv5idxD2DR!@on7Swt|fWC^5lK6N*A4Gl+#>AMhSuVvw9@ z+(H$CjMmDMo`jhlBTXa@=C?PRoXGnwhaBta=-(c$zvkB`hZTuDkG7>f@3*C`_4K#A zWXOi?p>1=YD#!HX%LL>{MRG9oxmM5ZZuXpg$jR{+ ziBGRYZ`?8eYQ8jFEyd~}hPLv?i*PX|MWei&l6k^s*&91AQsqW&D(%OTnZHjoR}&hk zf>Z21>4B@N2)MBTz{vYsyI48=_HXwAXfyN0`TFiDBZFAh`xK}0r#c^MLqpoUA|=z? zR71XTD|OS#w<%JBKHAcL0UbTerY6}2pD>xM|959C{xH3s0W{cW-gG6bd(SIfT!Z#0 ze+U|82$RIYwB{)OM?Oeyih6B8?m-B$X-u8blD z7~`jwXKvavkKQE`ng6Tv8@7)UojNq~CnS>RH71ozItRuFIo(lX1Uy7i=3{bx?U8`d zcZsGEm1&|(~qTmU@yVVgl#@+rZ=1uOx#Jmo`cT?l!vcGg zs19Lq2)ZO=XIR}#7GmZ3R$Kn>sj4qy!uwBW)du=a)jyl6xE`s}$+9M9&h54`M-;1j z1SPG?5*x}86^At2H-r^jX5{@lgKosg40rjyE5>fmizCzDzJxsHK7IX{!_v;8Ye<7+ z^c?SdHe!1g1EJCwl=46tl3CLj`;aR=sqXri`6a++372=%3)1g=3W@mPF7R_rLotdj z(V4Ms&opY7pSQ5Rp&i!ayA}f^?R$ajOWn`VLhdE!QD1awx`pI&$48!sI}U2L;~R{2 zUvQ9qlcBI}d<>RmR^@K)jq?3KB}1MrnGuZMmms4I+sR9pDt||1tSei)zt%9g%492P zovz;20X*bmr)>844SyZ*));Kg_r# z$_+`>XlrZiI6)x5!004lz#zz?gMW0AK2gEcoE0(uo?00e`rH07zQUZBKv>Ct2U)V< zahUr8W#=5eOkEPE=8UqS$p4}-fqYvFa*shrpgyctSG@djf?xV8724!KO+@dUp`Cuo z@>Gqj@)=MSEH7`Ds9QXBtJ2LP*RaYvK!=Li?8v7}ny>(uzaO8%fnJji+ZlWShKIrW z3~X=h3?3@j^vQA;b;sA9`d?lFToUZcpuwTefb-(lQ?X#w;m({u6)#r=Qs+R|s>N(% zWTdR8M+Cm7Ktqp>2wnqJ*g)GJ2fcyN7V>ep2!_zk3$-WyxM zsk&(;6x+ZDf}|GS@^9WDOxXmG>ta!X(l5;Ss0=P2u&F?TWc;9B&i^yZG~_m2lL6Cb_ zadL7xKA*RA@Um_@K2jjHwAiiobr0`3^LGEK`cmh9uIoce_Ed4Rw{X~Y(Z&q@Jd$>N zV#*m$o;rz%AU#9mc0)EjCx&!A1zl{tqoM(-f!E1$61x0Hfapf4udLgi+;~~SX_zT} zBct%*3TdI=cY2$z!O*Er=UA{9M%_2zjRY(Z{KBt(7j363F(h`Twt4Y;L0DOdQ!2BZ zk&>+GKQT|a3m+9$>3;aS2pHkLH=tYby8zttnphBfsPfQs!^nVMSYI42 zUdi;j*JNG5f|UA|&$YKb{qXl1n$PRnnn?bGQ-9=Ow_{pE5$0r+eAc++l{!!&5~U`YZK2L(KX)D}LNXxh=^PIf1f!xbnjMy7D+xG56%ZGn2w0=H zPj9dF>NZWS>}jQD$lXTHEAe1*1YJU}b|_ALgg$;1cwvm=P$U!=B}AmSE>ZmHg-(Wk z{p1_|CLAAG&fcU(f7wlko+T5mE7NaQw8b4=?w04wcG2fv z9nXHs^!(uwF_&c;K@DyQgN15GppeCZ2b-oAj|`)fi2f@$$RsdrZ_LDGR)i8u;gdXb zG-rO^lAJs8Fag{ade~835V>#cr@Q^BrY!hgEQ$U@ zKRntk8_}{%=KPdtea@sGjsX+fC^@}qq3o@1_cTTfI=M&|k7(fDXgoy-j!t3Py!DuY z?E1{BwSn-Dt?4Z+0c_?dNNPE;c(L}-Yv{A1m8m%Il!g-s!bwd+yp|blI2~Ni6hXSi zIfjGQ*yl$?qxVW#!h2{0R#|?QSLH(Wdyjxu?(soSxTPk#JLo zW;xDVpt1jmoCfONlt4ukaS99+bXJ$ zs5vrosj4kirpCX2yqhDmqgK7y#pp}b7E4Pjq|k*IX+>TkfbcJnB!?1P2oyu~UFen5 z8QtdWSH(3%A0-kG7sToG3K*Bc<>HS-zoIxC-z&lnafhL2Rhg0G*nVe#;`_)Pp-_QW z#Ue8l7(5b4blHy;GmC3Gpr`gQti{Pg5Jc(UN+{?X*y8ESOZI2;UFOmxYszvhtdLq0{z zQ5BOj-p`Ni#((Oi_lwq+* zQ?yfHig9fBOb{!VQ7%k1Kg!-< zQ*aVn$<9dG1J_pKt9cW$;aInLBoN(qvNQEkdbig7vAkChmes4xc55Q?G(BUl*A3PE zA_ya>oR94>_J^=3G_55i->}d;37+1hJ{cK;_Z!uC;e@RESdjEh0t0P?mt7rGqB^gn z2m(1GCejeE>zw9S`|5S6#F}((BPd~#H+H0>Yf9?Sl2hbDwI|eY4JiK)6)!>S# zkGZPST%t;kJV1_*+`e(GRGUr?4;Bm#Uf!|(en`MV_@U3z(Ap|frcRM87e9Rn{AJ)a zqf(~6R=WUNI);=`0pBVfJt|Eh1Kxf3@S(K)1Q8PWi$P6HqCmyt6&sO!8!d*~}B5qJNz zU$bplL!_2un?CUMbu-&~h@vkwf6n}x&90aTCN%EPSJ{!FG&I()Yt5{7upB`F! zl-_*ehlnIuQeDpVhzJRnz)Q(2Ns6KYu_manMVHt1w3&TyY0dgsF{SG^A z<8o%?{_8+x41>=R#$!ZkDqW4CmcDnf`2wxFHjr_S1Ne+_I3~c zlHuf$-w`2ED8g;OtK}%){?Kc=&CER>yhNK_tDMCfyA!lWFm{sG%LVjsGs4ryi_neA&V-WqI?u_-jP>L5SQu z1RmjiCb}NlQ;a~FdV<^O4HYI1l^1_NKOdj}4e^LyS2jtifowFZMD9{pWaNI6^_}NZ zmkV4~CO3Qc7h(B?!MR8=<|{HEp?id@r-axq#1XTs+UB`q`8b@x3Ev83M~#wZA|-b= zcoKKbv`@(j&dBlyULd(lCo6O-a1p(J9bei+|;=hxY z?HQXTf6N8NjunJmf`b<&ztXMyW5AEEvwAp-S0d1togoUa*`gfolRAO6Q`cBUSq8J+&P2ho2Nt zg|b-WTd*D%>eaNFIlJL*S(ZNtpb`-YZGKS&LkkHc(YH-}gpQKjd1o$Dke64G$jxyk zbXYJ$<4ofms>Bx`XI&I+Q;d!tj$T(nJ&g&X0g@zcg~-v3Y+~x+fFTK-aP$dOvi#?d z*98R~-LH_4QA`{^+2(dQxeVSAhGt3( zGkIg8Fi2LHP$wpZe_6tZ?@4#~eZqiyx;-xP+n9hnu$9g!><%0dX*}s&iyTel&iHlnjmyllx5VftS)Noy^B=lhx-5S4lM{ zg}bYxGl3@`Ry%=I7u6WE2qaJWE@Cv&!-fT`wqj4Tx5elKNG5Sw(NwlVd=)NH%XQN6x`*q*FxsWgbF({leT!#=*91pdOe1vY{_QJPz8a0r zXh(Hyum~}12!-c=qgoD`h_p=jo+>jeUvt_O_%4BpLJl&Yj+_zl-?zXK#_j8|(fV)s z;W7!~i>$k7qY|f`o?RS)@byePf5xmWunO`WZ$`1r2CR7J{1a%5kQN*Drw_URu}I?@ z9`wE#jt|#J;kPi2o;kDzDo_WR5Q37J#BcaN8?eoT%_{7Szdb3!17*syOf%0)`WC}O zB>iugs0$><=s?#dLq+Ptxc;IuB}zAqtNh_eL2O*jUK~t1BVmn6HJf-tPjbGBxq*3? zVv?L8wycE!znonj${Yv5M9d8C*_QndCw0MK=#gc+owujujqGqk!Mh9ZqZB3WDjn+U z3S%8yux^Iu%Wx7>gAK*J*-TiC4qHEpcw~5}t`H=4ft|?XFA#Zx8&S|Pm*T+bpL(}b zO?3?mKffF>?MQ{`bnbm}dJ3@4?-R#bCmdxWK`|@UN2y5l(Psh?IFU7)pcVuB$Qv3O zeojrbBi71L1x_Ch>|VD@xHqBq)-$DcR!{jkh2NOg9aW3Fp@z(19GQRTxpg7sznr#g zsGe7H^K4RscC_~*&h-ZMGy(?$keX9vzI4Ul;l+wUiJQ~-L^5@1UvqnkE;9f0aY_JW z&xTBA&&B?Gw29$Ec~z5|yGH)6{9PX_JX8A!rbz_7??`mq-3}LvDn&OhSoCERv>Pl@ z0CRrY|KF|sW_LEL-*pr)ffFCVQ0OB65T%%9#9)9ykjE67l?I8!^YimNiLcr{PJ)K9 zcuaJkwt8RuEDu(^p2P{NiP&uXP0F)4UtSz+`kDxC*Wy7#EOYAUjZ?NXIcW$?bq`Ao-*`EvgfLX>wcNjl4*HFfU7``M zA}xK*)k1DGKRkM`!uOTcN>Lfc?Oc~i#k8a;kqgD{@nGtU^Q%X73EM4?TQUb)k=mU+ zW^9UcTF(zGR=l>;Tn+WApN-`}%>}mz>eW(s8Q>LUF^8Yg*UzZS{IwjXJ~rZoc()ov12`OKHX)%KFqVT ze`kjxDk=)k;#`LYUW3Yq2j2e`=J9W=u>%4piSEhv3y=L-KsM3#G1R9Sa$?WV@)!fb zHLv&yHkpt9k2bBZgnFNSSLd6-jT#~s%{H+4vdzX2e)9a-b6)_9epPC(9)+#Lx<*fr zl9(5Yl{7&3k;)Z1gJ4{_p0PIPxh)qck5Uam**-xQ5nFo#zEic} zb2~|qI3?eiec$d2iirsh{hPiZ-#xep zTk!;i42hzenyMDch_GK_Qj3Q|BPb|j*hq0*N}8Q_fNodB?_au9 z7AS7BoG9LCi7RYj^HBOEosn#U#Jl*bOQC3F()$I-ju}dPAk?saRve;<>Kr%X`CWKl z`H5b5UjR_SK>ZIQAj}h<)lgmC)wTUt3VTqC?ut287WSB}7`IAm-TF4r>Iw44HNSFkhkx#&kit<*mCzyZWGCI<9+u+kAv%1M=n>a{xH6F#+H4k zOz;D$ zA4*RH)wj)_qo#Fz=lrRYL`fc?u7shY+TC**QwKZTL)Q8^#>}ufAK}d3`exPE$Dos) zNw3(`S*`d@Pa{M`Tz$$B``^P%-69mkIXc&0Qr_C(*^(9%6aaMw^ir-pj(w~Fw$q|& z=#(>V)+ZfohxGY%ZW>uw@+yTN6VmI&_&in>yWcZErR5Ggn!J!=V)~|nBcjQ9Z8)X% zM3D0i?rFI0?8@v#Hz^87zKG6+SGSvn1{3E(A{_eW1btK_`B-@){Fo0M2nHsv^C>xW z(u|mSW&3c8xTmD183Bkeu@hc4j*TTTeFcIyyEf=D;P;*<{q00ekqb!zW!?z6>Mopx zGCP-qD6RGfthX%FI2NWIY>@`nvm3S|*m!NVlX^E%DaAB%k{t=2de_2d+`y}uO6dX& z(og%BcWvd$z|aLkDXGnfo@|;GKT=JJVh6>c_%xa0`QMo%^5aH#fyvkYX@_Mrzp*g| zcqRaM7)TY$j6ubg;B4VYcPas5{(tlT`3byll?Ls&E=NB~#4{eAd{Wa~p@H9f^UB2s zvNtqCkq}p^b*1^wAh_QHiz55;myr*k^EETtvaOnL9?2ShUbcznXoilywz2P0St=iG zulyy^QRh_xqpSx9ayc6E0zvI+L3U#HWPizzyPUkofoHnDYj{@4-^c^Q?XT^!$@`dN{=|6{+DpXl?(7~i0(Y=AJ|V9PA*1BHJ6ie69dHFjC_hO8Ug z$o0Pt-4QCbfzZ>#Z*`98OtnyDjkcyWDNhbr0n)v_VEFp?o^CGI6c_r~mL)-~2S02N zXjHH2jEr7Ybi{}~Bzw{R#U`HTqB@4G+#w^$ghEglbiWp(uw6?HLd&~mO`FCimN_T?(&#Au=Vo{VEs|~2O8Vm;9 zQqt&B(h6gZ7#O_V_OQ)@iQP0vf+^#*{rkOP5({(@y82~tCnsiHnY|E&xwoZ-N_1=# z?ATC$1G^qSZ}0ZyyVP;~yHnRUV`J*)5263{ujfwE zM8I;Qo*#=YYyMoC_-u%l^A3UHCp!5(Q5IRvYXQ%tjm{UuW{2gYcL;RYLf)~84jCyG z-%=$kN*gLIQe_V z5C=he;elP<31C(xos6fJ^oIq}L`^&RT(AWjpY=+Adub#zwtjhIGOQ|1hRy}tQDC)3 zOboon35i~QnBVL~<#HJQ%VK-{o)vlRI98MMPk}SqP&VidI@)*humk5EIoQN*WEXeW zxSNgXHxzIJNra zVbAk@BiWo>L%V4==Yx^=JUouC9U4YX5T>sAq`B1yhL!$eaQ=4}DG^01SlhVbF@g9l2itHx*SYqsbLITK{O~NjlUfBy;lnpP4zv@ zB79F?7~tRVtfH(p!!HII5AIw&{u$uzCzxwNS;45KqO{}j$Xv>|eW_vCAI zOWVAn#K%`_LH^VBFD<28*9c*jQ(&Ru<(nVAh&N4_p%vo-RUr^CJb@YkT(h4(eFDy3urW$WNda~v z#|nE=Umxuh@RgPOKg9|8`h5OfzZ;PZy{c@Sv=4KXPCkR6kovlt3-i&oCX#J*AtyPf zoMG+8MCfa1G`;CYMssO9&vtel@-^Q$)!O8P$2RvaXL0%-iG-nYruC0+S2$I`T7JBAxVsJ zBFU85R?0&YJHq9e8Gah$@UOW15XrS!^6?AxQjb_X9{w^x_;?>-CK&@=kKSw8zkU<$ zqw>#L0aH+wyHynbP}np?;Mn47k69LQTp8DA5d#!2p*IM$RzytHJzZkfbdwemR|Q=bN!je7GolTG?G@)%vHvB4Uj7+j*hTTb_)RA9dY*<(lqg z98>&rJ4>GiTsnFl_ZS|2i(p%#E&g*zyFaJXlql~i8k=9l2(%7bBN0cbvmo|6w_xLK zU5oNgl7OTNeswiG$tzf{*)fP(lAGziTMCpqf4PQ=8V488XNFVe1NL;yt#n5O0p?4W zFsNtl(Oc=qyrZI~CKm)l^P31w^cV*KemahAcJ~VWo>t)GcK}t>A!z^RI4Ah%Mj-D# zOj$Z((~nuN48Wp##lOX&mWU$!`hy&Q94&5o0o zhWamKEHyQtm$0n#xZbhOJFtL|2pHbcD`8PlAp>x@PP2-f84Im zV{KEZ%gW{4u=K^fTHK>#Z}Xg}`I!ThSNlF=Kc3_+d{jE+7ps14)BpWLZVJL}fl}94 zg7=TyTtAkt2I<(85!HG7<9Z|tqo;<*h@0IEn;9oAq2na}rhpi&w?JXb?KEsWow~=g zj@*}${m653iTCV(|MthO`OV38Xo;`L)!0q*wPctekyMqfk<~bcgX^leraW(a2zi_T zLgpvLyI=aZ8mJ9iXo0|O2`cQ)J=(!t6DY1AaYmrX3%adA)H=^VGqv#0yDG~`?#@f@3Hh=&`b#F+96ZwAwVrPA@;u_l#ym|m___1u zmlC9nEpEypfA$Z+DltimDh^E_QQ(ND=&fdrD~S1{mjpL6BUs0jy_X`jrI0wjSokFJ zcjZk=A~S<*a`wjZE!{kw=5TB5B;90l>|_aoKD+fIBj+fa>9`hpLpxkVe||YRuj1^# zXjiEIcWZOtolP-q$t%SeKDlsHhV(a7*w5|yi*(Wb0va|jwStxaN-WBB1%S3@Q%nRw zN076SHzq)VSC}oVtc=lRl`d0v&^Sz>#YTeDHU2d3ytluvCr`=H+_<#AO4WlJ+#@Mk z^}(>J;ESsO2C4CK&0sw3uwF{RCr!vM-n^rE`Uk2$VB7!W7P@lt@Kh-ob4kvi*>#9z z_aiK8vVYMgG|e@F0wetl@{yE!ok^811@qVPftSyO`N2Prw|~Cd#RUEr%)rdWTw30o zV`{$JbM>(Pc)=RT7y-(^+8JaY0a-s!*)H-FrlE$gX~mgSxYZ$JO&2paTHhZAQ1?tE z8-GF#BqcGvX`%3%+wOH&BBn11$=+*abgJRC3W`2cr|$$edQ5mg{wnRnjlimAh83gs z;dY8P7m-B5L-qEldjoe(hx5Z`=0iKHVllPwoBrTk3zn!%Ii3D|69iqjA^82*Q{S4* znXK46pbwWy8BaB0C=&k|8DSdkl?hQS<+r=16-#YFQ+2|`rQ6!)pIrF90n})06j~bt z{pE{)4nr(Yj7*4y{)ygB*PXj!E{;5V+5}ldTkl^aBW^B{U9*0V z1+faWe+_H`$l{51i)NX9yb23*)}BYMjZ5$$1Q?(fs>^n*Qz5_7ZrTEq>+-RON?@Dh zkl2#m`BEM(m=XmA^fim4YuD}!7vzH}$vF;i9FTTV1zI6aUlz}T&syIVRn3RKIU1qu zc5i<=@+0f{L;hRK#B_85AM1F(VGGt>!|Vgjt?eW4@7fd`x(ti_K#U1P0%91|!qTD? zvy61}oWv{>mamri$Yj}QM6HMPLF0AV8*t)1?l4<@Euo&xkw4u67yyM7M%0NpjZj7g zaPRG7J`=*;mJFo}If;w11*XX%2m`yU+o$zNQrpj8#r>+WDE)E;-LGq6SC8rClE4Z- zMH>nQvFppMl0b|Ut*x(K(dEq%Kbs?~F1SBgY_gLVB!7fLCmd41`i85-vM^rIUErWA zG`7S&!{g7z=I11pKM~oFw~`cqI=@irl!$GD@Xy_=i2nI59i(q&s8 zWeJYanmIyCrJ8Bs84PZu%Dt3r$wh{(EVj(ZJJJJqLydpwAQ{|oo~t^)}ulfne+O5dyhi5n7OqqPQ+g}iwcyP7vWjf zQOYxtiL;759-2yUpLY@MdUvaBf&*SE#28_6@8VWp)zzT>u5Y_=hxa-Uj%|N`luq5x zHH*fnkV6W%{p9Mur-qqg>MAb2Jh#}#4QHwkoU-OC#BS*vOY0L-HdlvM)w|f8jJ@_^ zzP3zS;$4epczQm2S@X3=7*Cc9Zf*5oPDbJ8<|fcHTxS9CD;nt-yX#|ZC%yf-GBt3c zG9*M0zMqbbqYVc{;SbpY07#yv&RpYqrY|Ke4Ft(7LH7jkH{gZ)MLz-XLB879=nniZ zcXo8N-eA;m;g$s!(`qVsCY6xLc|1 z)$A0+(4IB6DlecZFDO{jIxtqIBGp*5q=-|7@dr-jh27<9Hf_pCz4O3=w>Q}(r@I2G zKx=PUf(X0s<^VUT%Hb!S!2E@l*DPeBXtVhp(@OOdk*1=GbK>H46z#?{OL){D_v>E& z&Uig1@!o_pgVUv;a(b|x!eH=N-QQ}7-q7`AX*lL&S&swPs^1BO__2_1klMP}It{4! z`dsJ}?T3NiLXHh=)orvDaL zh*ZmVm=`(I(Lg&kc-ukM0eP$%b23O$SKfGnZ$Z zTa2gKPuq~U-|_DKNF0vhZvAwyO0W0N4iB{(o`A~<0)KtlP~p55Xma9-_g}2yT_mmS zHJ`_whb4hTUSlKv{|a-wmt`NpG02flONa(SB_LfAB$gLB&;k~K2d&Q;dHJ?<_yh#2 zU)}z3D~T9(r{=Yrv7oPcsK-W7c63}cGloHC;6s$qIbBSm(i1r$=(ukP`;;LZ+}uO? z65Hy*wZ)W-92qLz4~AAhieJ48=do&#i|jv<44duea*vAu=bHrWD9^B9@kWsNPYq7<0> z$+{{1?b1@ksq`~4O)E_tabr%t(aN8C>*gtcQ-&%tr^?)^5fTO7-t%1y@C83fW)Npu z+S-~M8wY^C*N3$mA&^XA{j~45PQOQDYBm%9>gFXt3@-%G>>0 zXgQ{UxY+XYFmrwpuEeN^X0q$Iep*@$^8EyUDYEF4IpU1XagDWo4^?J;?5~AC9_DNN z(wni*1N3C`uFK>b;@j6(@5yu}HW<`gs0R13*=zVna*ODi(g{8*vG0+64$+Q)08T$$ zN^{Q9^fWu0OnkmfJRMcHbP%G2((T3W_HB<|U(hF5I4xsjGO|}7!7$jV@I@2%))4m| zuNy{1O7GcHUhb+kBx;aa9-+F9ekAFCHZki%RY?&AQ3c;c{9R+VMOJXn=#=|OyuCI)G?`R zO%XTmIw0TgXke*#DK4`eu^Vkg>Q>H4{1XWm(cp$6S!wy@o0`sG&fb~f?$NEu;K%xu zSCtlDj4Bh1rW}*lR37o-t<<{{N9|sOb7_;96Hd6&4_Ph>)R<0xLd9&RC!5GaF;@&j zS*s)z7layFMlnj;@8k|Fe4h5vRq8u6ou`}n*Pf^$qjvf06XoX}qooG`;c5s&mJI?V zgzRELG6}TeAru!hQbbge0oFYj7!tTncP{5v`w-76uEqJxZC$sNq_}RG+Xej9i`L0a zfQvApHi~7^`1dRM_Ut3b60-{nPo}Wwxb3BzTUcBFS3=z1F9{-4z*Q)U1*fjzjCcuJ z2P^-Gsz89!2LMVAEm4Epn~UbT@W+|ipp&UNa8~1oF*9}gGCW$eX%4s98|h5`OFRILOfPw{ah>_ zynS(|@m8M-T*ZS1QeXmL0!tFpii0Z`dGm@b^N#2>b=MWtbYR4J-5>K*{bsm~q1;K0O-;mYfnb`F zuM^;UKEDU_R?Ts8U=0dr{nQO`s(Q7HR6W`5BelmkNa*P3rw-XRu!EllFFIU@9QFa+ zTFX@w4M>^O* zPvO5^&8$`vhQ7}thNKS0gg$tU0Zg+Was*{tbc^%y{6U%lL@zUn?RSQ-g&sFC)ymWf z$;s*QBkdn=?ZLk<$iRGda|63%04VvdasUVu;Pg*VOEWxKY5?iLC)Gw#u`T@L%4CDW zOWo>k)PDr=JR;P@ONPjY@->g!GTMsmp%ChCj6Z%k+f10=5>ydrXds#YZKIuId-sO& z4MF8$6{4Qr=w^A!Zkzk4OI#O>Dq&rlK zZ8mN|xF<~a8hUvd86}U?UrgTzstztMuWp}|Nj`Vb$$kTsxw&{U3QC_Xhzq(YV<#q- z$kIoH+8y7jdi(A?;yX$fO4B)MOA~1_TG9cHm5bQa%4!VHq3siI?)RS4itFutj9!Ly z%$pUMWnO5g&7M`l-y!}5cVtxbDny=ZG1;FYX3wFMBJ`LqS8QIlE;{y56rSmq9eF$B zsZ-eIGqZ*IA6654UE4LN$Yd<%xxUMd_vtyIEJqtTnJ4!ra)J$*8Go$k99_RfPq$iT z%+YsjJ)v}Vn-9gA`lB{xGw}I`4N(TpsmceVhz4k-WgQQ3T95Pv`?zT7EYe$t`23=fmxFBcNi?%#S3rkGgI&Gn6V-rlO(mM)mm;j>{mQqL#Jg-4^?`8ECao zC@dTs`*4CO!Ot}F9I6mdLPOH*A4s}W?;KJdT;81d6Og!x%z&hjm_;ic13=L^TTHkJXC}@eJA19W1u1vHbLPj#(Jz?%V>61rh*t8?KX_a; z=m_KC5r5fbZm|oNMv;8PUHx(LX>u+~VX+!jnGRk3&KTXFvI|eg;O6j`q@d|bMfBs= z*^?yp6@a4DQlyS3Lq%yHuL&?&;nAZxOo1d~905e|YVf#fB{iQXLM=`tJ^S6EU&Ap3kLi_3mQ^+ zboKAw^xWK4C7E9(^Mz(jL=)zj8Qrs7A3?-bu0pk$9=hi0!pO04R{K8YEcT~fbQWHA zgDi%MqP45mHas~mJ>Kv>!Qi{jhC9>18#fhbHNJ*OWe; zV_UlM@&1tRxByFk6&2-n`rU*N;0pfh4LfhTxdT_E(SpzJ>JfDxfn4Dhod>U!%6sbP zZ(=;!pc;e;AMFcC8*QrG*oWQl-*-PZs$41x|_QRz|lT5N1Itp~v z{OQuKq5GwK-Om$qb906n^q@)i{@w%VjVnhT1#YfTQ*i8+OzvNTymaj%6uhmVIIPU1 z$!-7A{if=2fvOi=%NMQi_2$6>9>fN~4gcod_Sk4mpZ((rS$Xys)1PWE_UaEYlU~j> z1+9#mXffHQd{yrx!~bmP4JuLCrE2Ku!mNn-s|DGs-%glsm&%q4JDTSJca0I@)%Eqv z!ouwbiej)gdxxqLG@fald*XW7Y>a37ehr!K8DtWHkraI6)xIx2Kp0qQO9MZnt1GXe z&Ik_=kHh(fD9C2(X>>S_^Mf{FPzq)eUp>Z(n)U>mPF35P;d>p7-P2uH80 zBPCJJsQr;c-Yhtm^*O4$_ciT@ z-R9<|ly!PF&&!h#XL`>p@Jf_+|7KG~<4QGLa@NGmCkGr&U`&P2L zW^g2^2{>%z`l*dOB%Z`eusZH&o!fB^N8s*6;%kQOcZ$$5)hvn80%HqjSM(XNPEILb z4$b}?dF$#}mALmJ(0|fd6c!j!7l^hb3`+W``NB*cNv4ac}T+E*yPQ-;^$0;E`NqdORk6c&n?19%(=7Dlsl5^R6Um8tF~|A5K@E#L@fYi}r{4%VdB;IP z-$&m3gn{{8FXmZy(*70+7Cq-vNCi`)d((`SNA<+%=R*BK2DrF5aH~@!#!VD-kASeV zDJ!QLA;>CY$Fps3TLf#z+)Jsz1(O|vDnBNbp4gXsyQME_X@rCpNvVOBicooRe2w2I z-e~MWVKQM@#KZ^)mt&4`feIY5F{JK)!Tz1hnQLY!iC^5hF?H071Ylsr2O5z6l;rZ+ z^Hc*|srz180mkbPE*I<$NG473O9A{9fiwX`Ljyo#1GUe%{qX!MwWVf?0 zTN-cb!MTo!Hy*KTxsz??&eSN?Kcp7m8 z3L#LrqjxMOW~@#sjwOlV5hB9`@SF)|%C#fMjMgRGbCx<;Po!-&bRC>p-c8-x7j~=8 z^DVDsb0-IXSLgsV4%dGfG6)d)j@Q~rs%1-yi|M<_4+f3dn-tp%3VJoNK`q~W;Pq<6 zAG_B7uG?qUJ9T(Ie>af4b&Oa3`m;)f&In%475o^t+IwCz*za1AKhE_;p7q#&{~b|@ zK?a%ve#g=J$9HqJM1>e>UHyo)`!j??^O^~YYQ}Im$9>O+7TIzrh_rF}2Esvy63o$R zRO>p4X00cRBTrXf>pj8alvwbvXL*Q(V^C`McZ#|@PK>@HPxIJYdF&_(qxc*VZ?E`o zSiVS+ah&4UEdItI)9x#`2|ZgC2;sY2s_dDyL%rKd39z`pTaM9)Dwsf6d6o73yA50U zc0uKlz~Yb9i;WAnm79KJc1_V!Q03^+o>nX?kWCLr(a}<18D#`mgnIMg64YQ-9nnu6 zK&i|K88WN0aTQTijQ+~BeLD#u_E%>Uivm)-^Y zi{)+LlRWwe*Ft}Oul@3dY`@Bp#Z~YmJ0BqE39wIN?$?paoKZ-A>0if0M_&?eFrSpa zcFMltTRwagDD-xgv2_;hViHncCgYcTXWstGHRH?V^Z(ZFcbb)(?s%QFZOH*Oz;ao6 z1cgFDTkRk?gvZAl6^Ew_q=`sL{}T#KH~?QGub?0hJV>pdnL9Y(s6de6V8IHBOYt+P zat8|_P|~*kIMR*+9i`432YQ2{6Xa-&C}`Q%S8qN2eGj>63)fdnc&5&C*b*9Sxl6hq zKCfisk;_n|@6>py0!r^S49)0!ixnC8od58FteOQLI>-Qc#=QRC8eCS@#Md_O@Y- z=3nnbIQk`Y(B%`iO{7cMyo9K`Da*Wa(x7SvjBM0MX+6OpjY4?ZF~@b%;~n#{*jU{n zh6mJ7=!%9pzID5>H$FS_XSWDj%1iBZDY1tC3;gdD;BtMlDA7vUCg6|RIQg7$9hp2V zDy&;K>*IAT806KM`m`f>RWA;OZ4p#=TCUxny;+!ituVf5)D(kx_myg+^Y$g~c>nK$ z83yeK9P-X&k_nT=`KOn7boID+%c5u~(M+L=vPEG$t?d0FgIE&#S6H>F3u(OkPq426 z76QY5i0(wkQc_}vmO;lizLYtkt{xm*&Bn$| zpmEMA2Zs3}2O+Bzk43i0grk^wyr&Z%q+n9+CO5aR2n#DMH5tzT28gZZeBwb!Mm<+E zqflUlJjeCvk>Z(=rodHT8|P|O&5Q96bi2hd*!omi6fZTB1ePpySw)E-geC_0$1P1v z?hkqc5m6(N2M+U5XR*@L5nCNsmX~81VS?JUpJ{j?3n|3 zYDs9^G7yX2&M1O@9u*Byn>1?Sb+N&o_FJCP__iDC*t;JC@gyxBX{$2LH$&KzYR4Qf5>WPR!OQm!iJU z-7c>nra8=gWc_rz8bEDcfqT}`yyO3bPt4aPI0~`mEt}Ua77gzEQb zejwkR9~@w=;b=T(ic(c^vKv1@Cnh0jxlEK1u(R9z`1>ePn5L!btSikWi3CY6JY}rP z1_pyG3J9~cwt^2z^!hbfCT$WN`X1xX!)B~lf6ZeJkUBw&n^%9mN59F2dVq#5F&KPw zeq=c7RF(2YGm^{>gI@-zLdiynLm5A6B#TgPJii^SJ>stV{#_mo#GJSk9p9glH8j)8 zR*oyyXgR$Vc`Gon7R(nJ<5-D@Fb0H zPFD#-xu1Rd@eIC`7cjI7>bqfNGyb$vjp5y8;(|-I`7Cy<#`&sdWgI-zRl5UJ|Syc%HWr~bniN7<&aWY#R zPvM@&Hm|*6yzvDW4%+M1e@_@fhH^MLK{bRkr#F_sKMy!aeO)5L`FvrtEI@`~1Y!ZO zxN0hFtca)Ohu;z58hxa^ZO2-lbDq$~&#dgoNGH%Y90sCI8C&j$y0?Ud9p#y=igvY! za1F7)IfQvJYbC_3S!jA`8oNZUXhwZKvYBzeo=v#EC0A1hbzd?>+?8QdpTlG&d#g6O;YoiVszUsfvn|G>3mt11 zKOX-Ep8GyxJa#j5?K@vT^oPnzhVEl@PoNVd4SoN+MEjC%q+>~n-ivwNwJ&U}vnzOk zv*KD_(Wq&{m~_0`;Rca1Ki((6b!k2+vhkgWUF;9o!&4FU86Mr89w+^QwsF`Q{o>e~ zSylC5eqBp2&X|wHtRA1Lk`D|V`B3F4lA*gvze2XtQ7rl>8_Th@g1#a?YU+P;xKsh* z!yv@~+}uR$;&B)gpZ2k!*y2B$FEtepGCBDv(u;=!uEo-5oTaDWJXavpeYA-ZVb$@` zXq-_&K~W$K1*x9Id!6+eDH2XTE$zo=GCDb087z8*#Kj)#y=>BWOuL**Mn*7MVP2b5 zkfv-R@+%ReWBXHz%FW=^XXhI-xuqV;3;TSs0FhbuJ$80%Y$mnhP;$-9Tn42mLL!c< zDe)LmHHB#@l5sB1A3*pmb5M_t8~-%16noH)R=WH(dJ#{ zdo)>hvuHk@ic$XWHy_zVWx{AJ}wsyyYTm8jQe8vFY~@~_K(cB1)bT(Pm$|| zc`jrZ{q{eU)={lRpY0zd8xeW1FrHxtZmM1}z}(FFk?lODd#*p1=K5g@c^#4XcA9pr zP|wZl5UQqA(CKqj`75X+C|2_d3aAVdxao1dao_dRTE zP!nuVUXuLLFtJ%gZ|izRj8#T`pBQwt(tsIl`<8L(Y&S~}CNUnNia?l&vO-4WK>M8lZ-G2;Z8 z>LS%nHnrdP?|@1&4?CbzFP|U*EEW|n9AIjAk!z;__~)qyADJs)^P>c>%y)e(0z+0^ zLo$K3seDpfI@Hj0$aU~$m8zPooP024aFJqyNBzxV_N$+l`qJG7dRTS{H2`cw+b%x$ zF7IctC1^-oc~$$_TWwWkgYiwa6{Wd|9+}zE?bAE>us@X%f1b7#jv%C@U&;0_opKyo z@jf~R|7Vr|u{C3dGVXbE>Mf6&Gtov$=SUrIm+Q;Yy)-hv8PKq_OhUG!6^Q(9nt5RZ@w;m3iN?S z5fZTEjl&$~oJ2Dj16ok2N-f&s8_uQqLEf7)>G53)Ud8+Uy_#D5nhvbZGMh^GYxv@5 z*&Mxy*(MhjP`bsHA~%;K5PUTqE0(OdbyYu1gK6I4yqWpq1S8MqnO78oopR$1^0k@c z9D;&lqi;LMc6Q)Ed`N-*EAHXwBJZ!&fB956Zj64+k?L@fbQ-(oS6pA4Y<53r@6~wa zjQo8+Z7@$)4cdYSy81kz+tNcGG{vuezY(vQ-Lq5Uc zXQQg=%r$oxqN>sa=~mX83+}>Oi*;E%GYTws;T9}T2Y6mSZ_TV(P!ne#XE#aXeaW^m ze!tXWqxad@~zq8K9wL?=bj5c!i^1XUbLTQQgk?>|5;(<`rVPxhln)d zV`H<}z4P8NOJ4SIddt90dMlI~lm@C=Lp2;(G!8X&MZKzg zlIRg60bqQR7}Z?fpHS@Eg9>llJ&O`Dyx@O(^vq)Euev|>e5FSFEiM_rBvO`SS^Xy+ zr?|$Ce-9h$f915xKYi{P#DX|XArLuL?AM8E3)>UgW|jr$=+R)&%UTnuw#5zvHxxXO z=M?Svct=8YrAqe65bYIqx3Y|ky+XIHkTek_RpZuvt5Pv8Ts8~~9)*w)_ysZF*H88E zZ6`4TgLR<{Hto>IMnH^4#sRzVB*sv_py1%}VU-vhoo8Sec}*%J*&mxb`B$5K-=3#7 zN1-hz^?L5|!8IaCJdP@wfFk=J%Dh1`g9I6L8OL-8L{O2poSYTeic=5J;Sav(7$U)A z>JZ8uZlq$YoNC6@szn!dK z?&d0j1qT3FptMBebtRDQv?RF^lo-;8M;*4wPF7wr-yh!%%ST0_T|8HM9+YX1swKv% z%|xDEeW~19M_YyLvvS;DrlgYqAD@`u}ZU~LYxAXD-I_f5vXWIY{AHYK05F`Fa!OBPhK zbv79Hzl%F-o{@lkIGB|U(@RT#KDBquZ$O4X1_|V67$d}>_@C*ym3UTzHP^Z)WtG0X((bH{~ng4%a#lm&I0&#!Z2LQFDU_U%$)1@UOM`ed5ncz(PyuCVaEUc zbIK7Mjd>yEMaG`K zblu{QOqT61oId2l2g$TPt2`M^a{Z^iUV`t;yU_$^_rtx&-TXe1#L*W52`PAI*3paKL^ zp8`7*cHp8aaKr!W1`-4Ft+Da<_dD2+1=RtC{}QoI)-!`I z>dP602%pp8wgO}$VjN5F!lMQ4<@UAKx+UWD$Hd!-&!W{&7mBzjrc;VK{+Q>}@2uX% zcRnHLHqAB?Sbhz{T!DE@7I@^^p0LsOP@MbHZh^@?4JrN1$m`Fc8EE%Cm268$zx9M4 zp#XY;>|hl>;8$>XMrztFz*RxFfB+zddH7oik|eI1B|ZDPV<0^*1eroTHx zhA@7T_;-91!1hMIXSDR@y-a?nR9QTRK-j4LfOlP*3>@;5&RP_AYqr(A5JKQvTw0lk zB>A-xna%!4KM~CLpwvSY1IOSwJ`M}JtRP0v9S-jAPB?B!rVRulMIYB%K;TB@onwhLEX+xff((VKB~W@+l&=b?~WS&k*ZH7R0@w2?7`@-ihqc4WD}Cf zE=iu=V8>FA$`95;QnpF}#l3Ih?|wp$N)$Y1B`fb-*9#uY>flI(`>wj9ACD)rE3Z!S zgZFr42n_tz&0jin42@LsB_be^&;;sT=Ho{6N?eRP)J`|||d_JPjxx07B8=&8uZKlhEi)u^5-8|dotlSlZ^ z(V*2|1SaI|p?IU_^T|zR-pdZo%l(RGbJ3xV(9h?l+vx-Gv7M6j!(Y1nReaD<&>+~{ z2;fia8l~^9d5bMuo+-Pxtsp=DiG{_R zhFq}O!A@WF?p-Gc>p*!#j)WBfV*wy4tqY!xQgnj<-7qCj^Kn<;@j#A>&@D*#6yOX< zMmEfIh&&Oj9uhuE=Wo$xCHXaU?di3mS~!k%)a{u5jbX$!yfjgC;f^nxc8 zp=7VhlvDPhAZLedL4GkIiUvpJ%S)(+XRYE%*oq(4oMBRo?lYovV0DyFP_5zxUC=DA zGMnBjCdO~+(w^7H@+{Q{3$5H##{M}j`XK=+eeh1E6v}$i$L*R))K2{YG6}Al;Bw|o zPACZ^280Wlq@dXYNFg&14+^BK7MP=E`$Nd8;;ExWzrm{-9~xm2-2O!9dTe515cHs$ zf;R@?0m088Hjpk%98Sj3hG26bSB8rS!U7QW6oMZE7V2*DkL}Io?8Nc#y1OiPe6aQx zYZT6d7wQeDqu{XxDiC7&_x9eDZMqtDYt4MZL2Xf;VF^#lnM{!sSd}NB_l&=aw{ZEqp-IE^W7@3w`Z|5W zz1ljoj`1r4M3U*l9aY7@-$dEzlYKK(*eBC#>aL3VZdhat<` z`cHVihytmBSij-qM5={hN`QPB1;`50D{{{2l8; zA~vFO0iiIGvjw(5AOjmcf29do7e~R`HdlyxTAOE;m0_SDUpkxs-&5b14O# zk+oD^|2=H<`T~=Dl}!VS(Ryh`)1@q0$Hh2|rAeA6Y7h(XdkpWY4w`-yZ}E@JW$A_D z>C!%?A?A`sO{eHUkivYrkDeF>Zh>#n1-3u`V7;P)5e^T_3HnChO~Ls7$5q7XXzK~6 z%p&Fjdr3zGxv7$J?Ff_=>o%X5S^^XgB$&I-H&Cnsjg7#e%UDVMmMnA_xy4@Q$HfmP z-2NAO-JlAjx4@QZk@+Qk1#u{$pTxx>ozs$*4*KiUe=htxFx$Wy(;^JHJ5XwG@Y34a z8u9^lRN-v^^;G6*mrLEM8BO!4n4+rulLxmz)?qzi^Xl_)S6aoCoKeN&$%jj^9yji= zvGs2$jn(k%-a6;NcsqG#84L^{+1mz!D;qMjvb=V#fobWOhG@>wL#aNO^ixm6_d`wX z=9+WeA5|V^FU|BBdM%nLOv*4Olhu1|c#J;I-DNApTP@hOl$i;iTfOr}kFvAzU!eJd z=Ktof)PZ>MZ@B^q{93qLTE>@3_3=7na(HPtlJo^!1=d)aMUpR4nK7&_`mz+9V$KEG z_`DO@8`&d%H>a3M^>bkK6y1<&FOs~cF9@GNf92WP84pgDo_EMGH}_2xz{5G+-K;_p z6sFxR>IL@IxJSv&%8BE53)BD2Z6IjKiF#jmhGX+S;$pa`rv=>kkAYMJQ5ih5aM0z# zPYvcZp`~~Yk4#VqV$_4N_ou?c{8_b`U`g}{gls@`aClh2INWv4umKU;m-_epKLbDoYM+jRZ0=XB;CY$o}#j@u%Cu*Q`R`}wh92~ z5gXS5HM?&|k9&3aj-?hVt#kKN*^Lssu0Iku7?eckp<$h2$zp9Pj>wyh4twkWftA*B z8`3hxBLZ^6}A~v32QHM=m~4C_4Psa z82rpo#KES_sMqix7c;%NaSZ1)@JOf#^cYYC0X*F5kAaPZRR-MSU${#aPRaS$Vp#UL zr|S~2#Qylvx8(4zyqyScOeBj6m=joZOu2iwne6)%Nr$*pl50Jv$T5MkW6%Kxw+(FAz5w#5=Y3 zl^>r=^b(y@H@2s?B0FaH@x2_J2}2irtD*F3R9!>C5hmK$Rr^$t?S}Rtg@PUR=IhwM zUxGO2%70R2X|U(R%!C9|5mNUvos=VdLR-RV5KVwTc*X0cYWQziU} z>AvP#{|*NCva|7|5LuQQcLsWYm4lw%s(#!yL)5Y6GW);iuxi}@(BU>>tvwdUY<*O} zB*nMf;f)ZHC8lqVRbCV+XlVQq$pjo}6xw8}i@_YP@3OSUD^SidX=H2pl|)#_ny7hZ z|4AszWNDFkz(|@+uOAoo#6rAEmfN^Mw^;HTS)!gy|8F^M@l?9gi_T$Re}qc@(K^D5 zq$xuY_}SIxz&*hSj{!iru*)(GJ9D6P#0HiN5h#O~4|xSXd`Mu+Qfe*qe%QDb_1StD z1hCWu!L81bdXMZM7)a)FF3^E z#R_1e51;ulj#GpF{khE}QOC=3LNBY1TdnqK{F2kRfO;-3Pui;lv*muj1jIW8^^ zo6X^CEc|*~023m$J<`-$A`fV^#eWmP#GVb1E2I#$AS!B`7DMkMc0Ah@+ZpR;|KKpc zzKM4w7Lt{|6Ry@-4R_$C+q`7;WZ04SBwM1Taj2?N^U*U*FiiN6))Sn97az+`IO&@p zn(I~RTy&D8tD+@hb)4)^SLM#j-NnxJBDwOzMn=Tng0MHr;y#)4>07W{z$z(#WkHy`7NQKLV zNn^908ihL?Llk5dFNcdn0eU$#{0U<8LsnS4h&z2~~ObejTmk{F`Wd z_P%8yIo|B&L%qxhOy+xfaflXyJ^~7T#PhUuafkE(JW6H6c=$(J@l>8W!zw6%tDOvQmAs+!FYl^Wb_`-~F+eY-n0P|+@-LE82 zX~Segx$1HFKpFVDO-$}oPQju@H)A+46nq?@(kkr>~O!K8zo3U{J975y5t63 ziAYRfUSAG-=J&4LrR1Z`6H|*h%4ptF8ss95hTI%2EmByNp_wNZDlvf#gW$Dn&|`u1 z1-N6_5&_phdXVJgg8Z!u3`c#KjJdHUf%+J9|6 zNOL(?a8Z28?_@OyFa=g1idy(JNJD^d^IB6hL9!1ZRsdvMN3wb#&A|#6Rud*BeXz`! zdeL?ED6UIhS{8dW1l-y$w81e_s8qOvH#mX>-=EGGu=w zLm?z-6dH*PlimjKIhJ)>ZMbTXlLuC1KyY`%uXcuqTl6)3_k|f74s)1r5Dwyh;E*gt z0D(j`XRvtqv51w0x5jOp=`Z}6^mN|cnQG06yuL$bx(9}C+i|+uF9lJULIc13Kc<8Y zSVX0qDQP_~_KP!Ll07gcGwyP!+KWqglu)2|(Ys?|As|@1e5yH0hQ>VkL-LN`{O5^ zI%I5j@iqNwi8U4CDntz2IxqFpgn2aOzB{Ke^bYbo+ujVq zZwbOjxr!dIFwa#)J|FEje9&u{QaJ-ci*6csYLKlVUkjAh0=)vj_!PIp?YO7J3B3QO z1sE}F(rgN&YOK^9sL*R!4$H~81!4w-1VZ)>7Z*Or*vm4QltX7ah}su^A&BbF`dAv_ z{_Vu@&hDgxQ`r|`Ie{n(W^tC@oup$uE6c=f7R7*aYuocs(Gm-y1UeFng7I@RI{t;> z{|syY_)>->Dz_Dnf{rpw$Jlep#IhCnHxCt9^Ho3CNF)X(D-@H=6y7kwdN{hL30C>O z(j$Wc>M`DAf1GZ0mDKVwuM*xgj;}Bsw~Y#w2qbOOvp!;=x7W`4DiXBw4C^6?S72y@ zi2ZgRZ7mPVzwGIQR(vRg*#bBN9M&=btHXU83Rgn9=W@!=mk{;f^4JCR+>SEIOT;iZ zN6LLNQI%t88DRPUW=}bN{hLTN06d?dE0&yagX&_$Zwhe&AbJThZ)E3q$wSCJUd2XD zfUu3rb3kn!a*04zyb{<1K=9%Z<>#Oi73yIxU@qvDMB~9*0JqNEq;*y&aQqChJrvD3 zFB*P19%}=S)&x?Ei;J_}vq=m>@g9B5^%=e4^H*Wnen(l`S5Ytt7L}DPk{RdvI;K={ zu=dr9|1SLitOd{<-0qObFy#Qd2U(qJ10_ znJ?eZLFK?u?01ughNmnUYyXMzF4laLC4Vl;NYO6Gd#^70idC@1-$XT zaNomV0L#YAqIr32M`WA)<+_^JVd|U9rj?y zu?Z9f1hOfX&A3a^l8}b28@|pJv_yB`#+p<(j}jy?!32H zXW>at8L0W6%B;}ry7#o_%DKiit@qxDD&wnvXEL6D)QK)9Ws~qclL>hKJZ@7)`oh3 z920V3BEL&vHOV@T**AvFbvAZx?X~}wognTWJUuyi47Ioc*o4Sx1aVd{(6s@0n#{OO z;-`g%V(9Hk>QOC`ysfp_xq`SNWM+E(*hQLT*FA9B`gaP?gZ7#0{o8&hUSZYTm*0JS zu8JiR>Smfq{%%2Y$-ZPas|2ri`N1T04o(*9aEYizi!SSKY8k=XZH9set?il~+L25m zatL4%Ds!})Yd=t-3ZDjoz)7D0QI4R4EjiLCKd6;-{>0)VGub*yth#FI&hU9mMT`{a zJ&yxnpseiUFY{N@1K@Hwa^FCq0J=*E=vNZwrR%fLe4^dIVFahnmMg<&=-HwI09W*U z!o-&bwRHpy*kj}zZAndgOs0H};K_@Oy_^ra{cGzV-Z%auEoz5M+aog&nb!fq6MlvU z<@}u9cRtd&#m0bw+0l|IZZ|g~*I6arF1O6gIV=zw>fuY5gyjbLIzjsho?k!;9LaU& ze{vm&y=V(LFKj8qizsku>?!Th;GJx_C~aekBV|_|5yL9g=n8n6sW#}jm%%EYK~*ea zGcI8(&aXUqMBc7(NNYBuJt+S#EPF{%W$2=dP>B!U-ZkFK_}zSD`0;x@&0J#s`@ZfC zVFO)tiDWCuE8bRey!5Sj9kEMH8bNVttO`x`IjZXsJBdm>M7v5|wRnz-`P0Qx*{n&F z*=_T|Qn!k;6e?*gny%ZP*Z!v%K9iuD5@f3(|hW&f8ig$PK%LV|?0z&Zo)7$7i>bw{#Z zf7V5yJG%X|eCx_il{0u4<`AVH@)f}pZF8dg>A?fm>wZM11ei%37u{_zO1qe30v9F= z-%PEI`JA3uIF2CZr%tc9UaG#Vl((F0!DY&pJ8x<8$=>0t^$w!Kf&h8nNd{|Km~X5OC6V-bcVAzEeG?CcbsSn3f0_ND zTLX?cTP;mO)U)Il?UgZr0wQAYE1+f; z<|gYV-A7YCej9nO+Km=-W9>WXY5h~tly?r6w*AwkhIJzskGexC>DZ%I$rKl3pI`0y zEnUV|Dc-qa)?Dc&i?HCA#Qz5tz10jWQp$Pmy-RKvMKSb~+^DWE?DJ+dRbZvZSdz`}DeB|6@l3t|4>Y$R zBZIbI1+@Dwex_dEkL~y2lQk$?0J0VAJ0P#UMNNPR-z3pZt?2nrxhwP+v(U!OB)+<3 zoK9Fgf$a?Nj=It?kf;G%0GFXNt{I%%kZu8yi%4V`9JSv;}Ojt63PC09cly@uW^#e0qzQ@Y<+#y@UQe)8EYMnwr6(VQB z3g$TQ{Rywsgd03?Ank?ekaO3i%B9Z12FeDK-06)J>DqCrFxZuys4JR$Cf;whsXB~o zPZUx_i-_vcqOO??zB;sRY4S$7{&YDM+iGd=jutx5`!%}P$#XG_K{#K(E`My5bc5HO z&fj$2Sr=l98=krT40n$F$mCYo)&%bcPz+WB$^KxdfE70ns0riu7q4AZamu$DqKF%h(QiLkQ6sszdtk4_SEqyeg~_g1!<{hN`Wcbh=YeG~oR1MEwO} z)k=iAmdsk)IQ#P|QJWvGt*izz8o6-dRI2W3-)$(tY*3=q$!Ei$(_DLOY$+M0peBex zscD%%&Qc;&OoZ=XMafVq*wx%ue^<|keGrsB&+oFMTWYQmkqSOVyBXaLn=t%3wv+-2 z3gmz@qTdD5VMfxwQWKt9_#+tZ{B;O}y~^+CL80KE+&#le~d_ zP5SmV{?{0kvTqzm9&E|Bg|xJYVh9}xzaQB0&XWmLjS1iB3&6PgmLBH`I%S51edgpXZe|{s~afIiyHcmd zbI_8iL-eVB8U2;1Z(qDDdMD$8y9sxf#kkxuuMRHJawHOTOm5bBcBeMX;JvY6uiHQO z5|4&(M(P*epU6HCh*UK8u;QgeK*8o_iIS^N29c zqig))CnM2vt&8vwngOqzC*H;E$?)lyCM&7;KdOu3(D?|A>l2XkB4GwdJftCKFd$7x z11dyuTgNim_Xg1@m#T6EKL@@$uZwm|uB8#uBv-G9*E`;VOO6}<2+U9c|poi}n_bC|yx>5CK7dK4~pzmNEnaY<%7?PL|` z1bhfc!k|?ubTb*V!!)>O%yzZsneI;Y;?u}$i8^;*_6-Z8NUKh7r9InkHhjfJ$4*VF zVl?raEnFKve_+L!avX!;ioW-ai73Iu&&5l)bD!jLnJfps|}uiK9V(mv3dTqi_$vXUpQGqbK=$YvZ=3J zo%};E?<%G6GKsun5b*7bznix~-5)r$)%Er}g?EXp&9Z4@Ev-4_H5ElH?JT=raT?0t zoI^w=5O@SJmqGBR0rAXra+TNjRC4O!v%^52=@Ab8RilxCq)eS7Cgy13cQYrH3m<iO%GQ?2s2uhiFW$FwwD z`&$Z6Ci0JIfkG?Xi$6Q(KK$;hR(JI9;QwWuQODazkDsu+6>L+v_*D2sX0@S$Y1dP} zuM*}7!V{I$fptw!nETrDTgPf4YgUc!>+a&>_LT@Bb`WomAg2U}!AJVI-dPAdU|AkW z2|&V*kw=w4;>?j<7n(7lYDtUa?5o$3^QYWjd?G~I8vYLr0LYOxF)^vRZ|CSp1XK%R zkjXV&12q6rdl3~C72@#6@#!%#38DN*bM+%uS>;hDyy2gS1*NOfTqTy=onkCtaG zzVQAH37xx&*1Wvuhn{*ft>RJ=jjQqMY-eoCp0`93p`{07UH1doKZZ|(1v6C4K|F$* z{$AN}TolMf!%ix%ft{J(*y99ml*j%zoxH|O1c(FIVbR4~pW1YfChJ~<-__M6r!1Q+ zHKalnueruO#x5ycvvvt=Xk;qUNws4_{R5bGw)v0Wxnot)azCTqn0vA3J*@4~a=%Iu z&8{*22K(-&-bW*oYEHd23T&@q~n@R{VUflI8 zGyZ%N(q|*>bYK zz72E;P-uuWNN73Pd@GR43k}X^43weo`91=kfY1op{TZW0Z$Rw$lRZ%aB-YwOzW{~0I2*pC zKK7!`I^VEH`smM&x+S{6=Iwa0RtN=<<*oTi#$ix$a1F9hJ0Y9A;`uKTB<~tL2X%8n zRLB?dRYP^I>2$Ll;KtZqi+{fmu8VmtMEH(kG#P|SDFMLpkoqxXq5|j?;UL1rli#+S z(uvBeZ|XgWQ75-Z+_e$zxar%Y$Mxa7Qs|G9N`}N$G*VTC|qt`*IlVJcYK}- zCDFoP=%s{iVr*_Q)X_OjF(@Q%JJw}kzgRZyYb<@)xa_2NBUt+Ef7O!${oZ3$t>)7M zX-@Nk&Byqlk7Quh-WBBM*Q_y6$;?-0yr27FVe(&b>t>M>WaGit6AY*-LTzv~974ozXu%8g=ioV5`ygB7j#4tw zpNmp3$G{%3_!ABDY&SL5kB@tvT0npw2@m#gT6jpLPp$ArS6}7M;ioHEVujikPyf7F zX|Wg2k_U>&=dfW0u}&ii8?a^M5_0WuTJ~=`azCC}`1Nes7mY^fP~G&Qn3#$y>@c5 zKX>tgTpAuG*eBC=#*g4Ng~%ifl`Y)a@WAf=-K9# zWzPgBJIb{kWb%izMXe7#^ZlN~dHVjuDBbk7{X4XL(L&yN-V@CbKb3B#kLsgbe*o5e zb+GXOz78Z-x2dU#C4;Ov`D zUGFLC)Lh{uwHrO|OG7liB!nN5Y3I4o=etJS^nT(7yGef&2z(O%m^I|@|2N-xY7k_>PBDL%AoN4?V$K|ntE1y zD{FXRM4k@GL5V=ZQTVI|LYC(Iv1wbx4u1xKo*R+!)tw(qjR0x#N6r9}!;v=woY5r6 zp$Cxx!442`re=DiXmWC6c{nQ?^qDuisa^1(gMnIDKVK5KL+y9^fpBsYAo)pfEM5GW zxxi=BE^Dc6+UKBl>bQ;&{hN)uD)!$i(1NL*uWmN{ZOWy7Q9J#T4cQp?p;Zo2rhP9D zeWRrbgm3rRopcbZ&c@2qwjz3-wCDBLV4gYx%0C*?TIY7NE=7@i8YDAa;&gI&3(DlM zpb(k2X(!=*GVa?e(^<2^syEqJ?$=O^@0T&!I}J51@p}%7(n>vhDdaKtOjspnht?tg z3fobpG5@P@bE9sTy?f&QYKKQ#HY09jt|)Eab?3}<_Imc1Q-FC!c=Y>kB^f=42)E?~ z6N$2N;wY4(0^Vk;wn4ivQ^LlpyHRV_Aax$=Q`LPj)CEOgl;W zGBq(lp73XLE$B)b*Li7k8{zY2nk18LIii!D=3^>E)8Fhhe+|_F7f%>;T*A92f2=aL z<~l-PF|CJ(a=#eM0JC0)rLR%TKcR7Q=|^onyC9?UTDd$YxI=!29FqnoP%3t;SH4o( zJT`jU+4ncSELn45ia%K{jH9BO=c=_i?#g;Yl|K*Bubec$ zh+k6OV@gmU?UmZx=6skKjrzNRE=T8U)xb1#A3K+WYRI3SjfG*a%BXimUVOHA?GT;x zWa;%D&tYuh=kZV>(@%P$YrHSZaR!;&%x$7}Y`!$U`RzEf_EKNx-E633bPayx#{GWj zt##gU(Sc|B=C9q<`&=?&hJu%+6a}1?T<@Fdz$wUW-i7D#jLq)FHC=o{LUS7%mel(m zN`HPekfY?*;=b#v+`5e<-NV`hZh01(kgZ&kh-;jQ;hWZWw9A#)joUmDn~Y+#{`07O zPV4jWopC$NaDo)J#is9e1Rm>tjg3VxUr0gRICA1oO&>M|BWP1`aq()NvIwE=UB}rLw6otj&255B+xVb8!9a;0R7U@M z#36$YW0Vj&(6=xLBW4LFP)^7_>xsg@CIIIjHZu0{*p0LQqwXNoiU1N(Li1MBmf*1v`C&)jH<$s0>iva(?2_cMpMrz0I> zN~XeY+E;imhKX*SO74O9G3-T?o(lDDUPc$6iUh{D;m9ir2v!Y?7L?4$`ctsQbPnZQ zk@6&%J8&bC!mjJo`wJmiaI_<%F+^s}!-a^b@$xc;PZ$I0B|2lj?kw@-A1Cebj=z&c ziw=mnSQQYWFTWM3rm=IcW@bK`^6k$2$a;`Z#*eL%nDK(b(??Uvv87I^@UTD>2aMYvENK0% zV`q|Qz%BSNUtO(24{@xHOdZwY07rB*e0ipNwq$Z)>8g51y;pIW2TNfyzjVU{6E}#Ki)CUC&v*m?6udN&wQTW+>2`x zpT9-lc?TBQ^!q%q%JHCSGSp6HOE9}QV@!}la57)LTC=E3yd4p+m*}q*-+ZU~au;z* zFSt7##UF$RQto9>2bz&ro-+VUHQuXcNk;|dmpY*AE?I571RgYKGa(ffASW3fKLsK@ zFZfsznMInt(tw!>Tmq0A12_+WER$- z@;*K*%c6TiS@SiJK!Sezf4E14p5s=yJRotW?W!R%9HOr0Z7v!9^~y(wZB#p7_3CG)#TjcV~TC2b}-y@VFy( zsuiuHO)V;qQ0bi~Ct)YY+HQB$)E`CHjkwaOZ#OXc+oRX*0Qj(rer)RK*=Qw$*5M#c zRyk)0tdF|p@#)H&Yt`k3K1a*$%X@r^VZkB1M0%yu53vmiso& z$zFZ2cQo(Ys@f>?d60)EFMm1Ix)Ge*s)MjOPSBwLj;IWXBK=ufyB*An6lbmDzNe_d zDlZ9B!quXRF7=i$QU~*=3(@yvcyQlDhr2v>Z%~?B{fX-{pBLR$El!`E$Q6=^21{uG ze(9X6NKSDvD~KY1>#1gJOuK+d)hr)|QFBd;n+^Zei}s$K%B|nFjf#HRP?tWa&vsw; z51Rm9aNT}VmD(hoV;J8To}Bff67^uFYhzBdk~M2&J8vNDDDQapx)h;(LY7FPNc{}w$+g#*l%SB#aDNqg_QsW>o z50pAOAUsL+$o{N@gTue2iJ&yf0UFZ&UiFa#SoyK`M-%`+a)GmV2*CIu=@sO9p+Ukp z)Qp1fuC^x2DhW<|(+gP+091E{gUw)kK~lR$dig5QM!#8GHn7{wNq+mBqq`UDhul`> ztx0$d4g2?1FGPaqPHC~D!9KUTQt3dUN`Wfl7MUh9DIE_I)lgXDBr z`|TKEOG+MoP*7~t3n&}=8>!L_pzHtATFt#DW5DV4N>TFs`m1%>O*6AA1}!oRyql*j=c90-_&OB?95WU*W=R#o&S!qffL9)~laiA^DR-yGku@dvNzT z$xelwhH|=v9HvwF1)0g0S;>+d`_p$%+}y4AP`XUGLGZjGC=VXv_hY})R5C6HbJF&n z+4;=TZ9Z?^D=Gh;d&gv-lXEBEy3wy@UQIr{B4#GJbG9p!R?C{ml!x^|Jdj>zO>ANl zV5_!ky$maeVOY(EwhRF=3N$b;H_rOtrktZ?V|RMZolVaNlA^=}cTvi-!=a}BO2eGh zM!)S}Oy()PJ+X+cb^{F}fVd@j*t~uFmczTTH?aPs!MPw%f4JOsXyC5{U*9;$upDu>;ORBMu9O910*F-& z_OC-v^EPOPRL=&1E`=5xLm;z&I`$#>aUpF6(x;)I_>DUu3jfj@pthn8_}&g0N4LSX zD;hX*SjlWk)JiGQ6$UCwh$RYve;^GR*x|%if1QJ(Fkp++MPQ7R1Z|2HKwQgG4*_h` z5I|}vgI*L&B!Tkj0op@WIzwk?=Uk^v6R?<5xYZN~F4h1!)A4_z4Tu(Aj%uHvNFSkq zI&|K(?HE;u^pOj6tV-5e1(LK6fGQOTfZT`yloV+Bqpj)~O2F!HY@de1KLBBztNoKj zpx^!z&jgEyyn?|VPAHKM{ZycF)&(C0)kw2*41o-3)fmu}zBtWJB~-C;9|OR>(3uDG z04suE@dH#QwRV4=elyv+WT^~dL_=m?X!H#&e7^-Yeou#^#5{ zT4x=PWTI~?%k}4q_avZ4Xu1aP)xtE{r7ROP=e#s0H`qn-p3{9yCsqpIgb(uB-C|Gl z-&t$LdHQ^=&mi37Ob-@3tSs_4Ly=jN`4n_hbFpH|8U>;DyNuaAkCxL?si?G$n%sXK ztp{IC3qY{laho?PtT`n%!grSHW{ANPd;TLzzGbr#jqS_6)@0*Z$*mZdu^V8HE%B2V zwBoKlFG$27v1KpP;>^(%`7Q_8(|IX9Ha|bVB$VuuyigMu0)yb;JJ3uzlEdDDOy^%d z-)|i)8LN3$1r(}M6xX?3=3|Hp-6kXYvN5nMqr>D=9OA1BhWwLZcGWDGcx+Q&{)OE& zeVc!nle#3~DtFhBfy2pgI6?ke zsWb+|PBz2ewNX@5EJ#w<%=@F9zy>jEe*UA!%9iiH5+b$N!G31YO$OqAGRpm^Ghb*4^HE zeN)&;6YfsFu-wZZbWC`J-(2URmgZ91T8o(!6X}%g9P&NwA92gOUv46y@zy!F> z62OW~2%eRhX~)_MAF?GqOIk`M8AG<3xb0uOjSuQUD=te`g*Q{y!I)VV{J&GL|E&`S zHNy+^NzZKegL&mLTYgCIfWQU0xw${88f1Wx5}INWU8ZmAPCz;!$OD7*!eRVPK(z*E zLQgm%(S-y*1q2lc(GHZLMCXZ&>KG*LH$PBXy?*^#8@OL|fBPOAsm`%qR8_a@dDFH0 zk~WHl-7J@V`MFhtHB4|HzEUUlIw(dvJ&Qck*fr+a5KPfib7`WJ!r;Q>qUf=n=LE)T zFupW!^^wV8Q~zZ`%U3WY6K0&76J6WEfa48@O^^Zw?FVa*yaWD$!5i`E<>@~TOslb( zm$ZAf?t6ay;?j9n##N>(sQ>j1U%(F-1M52d?fXGM>4-dFz5gpRaR(akaGl8j z|4=|Z0gDDvW0<`*5OSEPNjL-01{>h70i%fU@;&w8|C4NjTV})`VVOvB&k{K{E5}#k_{{rMYQ8B*yvHrr&A(k6jjLP;MQM8i_7X11$ zC6kU5cSEbVXc!*NY6K>fb~zi&+VQP47C1Y~)h<#GHUMW8@CXX6iA`Od1izw(sC^#& zv#AOpuQ=Ir@VBm1+ez8sEc)NcUuR3b(~CRoMz(GEqpOhjbaz7U+JGAZgt3zXZ|qhd zipLk$_a({?u+I+&799V*+g{XA&#PTolebMQ-@@T;SczSobMa+i1$W1M3)v61B3{b?=$?-K;Jn1oG#_jmEFteY!7O2?}6i zb8O-(H7HvFEb`zH_1W5?#L50UDr%nY2Mx&2E#HCm_oYMc^Ui@mBB=V-Y}sZ=1mgt^F0Hl5D5^_TqAp$gy23JjBbN|KPVgI9w^?R`+ zz+%*c3Y3;5_`NM!qkyTOre#Nk@f6h7fkw3KEx1Sr8`V6;NDd4xD>Z5x&gAW~Zibv?=SiY5A@Eiemtccn?f{ zpy$$ZREk~P>fg#lV9f=qqoR&NX$^P9NJQ!r2NhqbzKgw|v{EI0vv(!tVbMktbfV(V zd59ZAR;Gp*ij4!cIBYwqc{m=N-nF%or?K2cO?Fb#J=0Bi4pO!Bbia0p2Kh--KXEH= z^Y(YLF)10lz2DZ&SP7^H!JJxHOs?R#b@E1TNs+qcmsxzcSdtnKV*GwhC~ea6m`fgYlo3h55x5%lx_HzJ>Y}-UCSEl(V06Z zW+kgN<$}o>mFZ5#}Qc-c+1{PEJ_3OrSLlq7sMRWYc*-quzdyuF}(gwTwmA|AjQ9+t1z#=o@6NB9aIMC)77 z31+P7(^c5+)%oLt4bzoV*ni{>bZuhF$zhXM8yA$<6`rIJ(QH}XRFMYu6PZ-+M>JZ> zbOV{<#mNlb$7XChl;wM|W8+Bu*c1J)O*sY5-(NRQ+swoowu`YOo6$F1x`2&Kdi{z=8!I4C%;j zP(9dAvzQ0zFTyDho|ocJm`5XIVFq(Y_^QWa!*ki61y`oe4a4I^$FWA4Pc|!fkW??z zUfWLCf`bPsXJF>_W0xCeEMdA@Z!C`}RjIhStja1bNM9XL)R-)k^eTU4`*T_JTqB8| zaJcID+qTtMBv5|6Bh{bL_sivcm+0qKt)oB}2A|!d7&C>-z#ZtAIxZP{747+ZoJniD zjw{j!{E?Oir5QirsMe8lUO9A6NmC{m9!O+7tz3KE-`-!=^2}nFMVBcZUq%cE=da}4 zoNeu#Ib{WPb*o2x45&lA4DBE4o9P_E^ur3xxAed$5$u9{&N9@a55+z~D4o0mG>@pih0t+m%TPd^%md05D?WW}>^$@f>25oRftL&PDaV&6h3_VAxSVy@~Ps#+WzZd-ChG8^#qQ zn8n!-)5OFEllmxA`3QfReH(Y|PD$ZMLy`!QrngLH5J)KGhLj%GA+4v?$$l;@-{}OsE@lGI!9)U9LA-LYY;;&m+ z$o+dfA>v1-o>hUj&fc}zorRZmVyfcIZ0QxH!C4)gtRdI`2zMSZyX@Y-;jIK z(3FtO@#NHHbOuNC>!0Fx`GNq|L%U#4<#5Bsf*4W>+qOmtJWtyTh{KiZ_s{lTu2{RZ z3{^R?Tfl1pnKi-S`o)+^FqY6|m>RMd5%XfP+XQ7=o;disq~PhD>JcFs!6<-dSPVjf z*ARGT0@Di^8i8IPeS=cmolA3;eWB|fwNz`?-h(Z=_3Icb56|q2elr;s^0tq-2K$_J z0(JP2$T#BJ$s|~FC13+21{XbvajDu)3QsD1CD3dc;RlMq*r;{<-yCT7n$K9xB z7FUWFLJej5?VZsH^K1U-?CgG_TQOylF>CdC+nd3k?39#+?*@ESod;wEJ)1|``iu2yzEzf9IcB3umwhJ-e z<1&I-=I^{83t7Vy8*}{DFC}g&uk=235j0=heKHV&drZ@f=}3Oop0srCNl)!121t@V zHe&pkrVDau(!>8Gj2reYmv~SiSvDsyESObx18P{v9Gcs&zf9|sjXCO}dY^TcoUtw< zuV^NZ=A^o`0w=drsfN`3Gy)Fxg>_|xh7UdpcPr)P8qUnl=GuHpuU#l}g-bU?<9B2g z7>7a1I}q7wKG5<@;2I*%44uvBr49t6=i6`Ivp)X38{4+&+Sp?Ehrc(7i!f*{f*KnF zEeHrMLa@&K{B!@g8-79dbU(UGZ7M3U_@o$Dm;xh5Z%5`!dp_qyBUElaF~}N-K{SG3 zIXS4mp?AvC5+{$%PByNq$xE=`(LQu%+;m>N8m45dp{p%<&QH~=vn+_buU25A?P=WG zG)<08c|*JWLr=v~l*o7&%fVE_(P-ZOQ7OLl(yI~m_&C4a(Zo=F%h?YP&#kxES~(|o zCS!30J_{~J7M(|xe@g;V)A1dS=8o&i?7=i?p(jkC41dhv9P9?6`rNK3!93P@4e2_=@iQ zt}%rVXQhl@QcKij6Pu64e-zVH8O;dKs#xmW{2qKiHDLQ;Y0ASm5mLOC?b`m8TBCOV z40A+GI5V1H!;t}ZvPDN;6NGBr6$_cOAD~M_DrXEeXGyPV50}Fp$}^yS=59L%S)5>= zT(@%UQ2xPjFiMcQXnphBNQsBPtRcHk^vZLp54bLUL{kJd@7x8G>gRm%U_=4teztbp zF$%1x=XsM2OphK1-3?USeIgg#_>7x-EdA7>CV2lYZ zG6NxK_ku}{;$*C`L@Ggf@(+ntJ_upjSno+w#EaK#w!ziD8!vKPvwgK(5!!v3J$^i9 zM*Y#zUo-EAGW^>8ZJ*7_ZtJ_x3AK^T8E!ddt{D%mhs!@z zG!kNJZ#UzTv9F~ecB}w1f?-#>ey!)t^dQc2N@{S9*o=wZ{9V<3Czo+nMzi|S9d*j0_J6MSKl>l z-p0r2PZl1kNGu6PA^Ol`S<7n3K0Aqub(LO03?3+PQ2z-I614L|Zj@X9`zcew|K_&} z|NHA)IjyR`Iw4X(RSd7KxZ0trH&4MbRX+FN{S{2upTV!CT_8Pbc~Bgxx)Xz)i33@IAjUz;kW(`k&HHJ21Ey$!(!F zQdC-Czs1R6o9}fGULBjnC!R5!{1O?*)k4MqB@4W(pkF6Av_Rzqgk8wl0>L5M4U*KW z@Vfl9j|8-@^sT8af8N{;)PLvMSZl7Fw-&9t811}xOF?iQ#DEq?t4EXl*2U**KArcW zu*WHlsz@w+YkKa{8X6w(aNL)}ReQt22xgFL;jBBrctsiGT$II2)6OBAH_wYP>OhL)*5>TIigi-vzGX`9S}dR;u8Prr^V?h^CD4)sDkw4U03e zt&0p+o!yiDm$saQCMixG6Mr|AiyXWA;754DU=p3idvd06kshHyC9iuuaJs#f$&4;N z!rnB%>F;P>=E#N3-G`*?T9QViVUNyX#b&%_z2l~@*vM?hSPbT5OB61=2o!}IXH;Vi zZ6y_o>(}~3+tg^EjJCpzVho-V9h`1^g+

    eF%>(Xu@M8h|(d`+hzv$3W%dC9S)& zSV-u|p*&|?@fuW%R<-?wnr!1GG^w)NIJ4U_x6}|Alz$=wdC^(VroVV=?pCw1tZex1 zy^&zVmP|%pZA3!*YQe_~i7I(`i(8uZZUyVyb_F&`1Yr*J%A{u&q5MTAmG@VYCk>&N zos;vCP$At|%zYq;8L z!t1T@o;bAO&k@1Y)pZL~*YDALiW~RlB?z;NC#ZZD-p!QW8IioS-2aXkYjcEkXYyHa zHnN!34ra~J-DzyUSC%d5!fCNAHIF2;q!V;Im||62ld&pAycQ#2W#9##Ke#^_8SeOO zqFrbA8qFX|h%kRGL5=?U9qEju5mgV$<6+n!ryz5R{GjUb7O^(rcR3qRi{FA~KDi?V z_iEjsrOqULdG!fPVEq8yLJRTtTR{oj_4SWov}iq<4Oh!7ieV(LTh?HwEo0!UEqd4L zR`4kSLDoT)E=6RR+>J2M;ql*q%)bwU+kD}ixLS*Le^pJVjG3KV|H3}Q9@kFCfUa-< z#a({Svq-)%I{QC6`Bo~hsJ>Xr=b49BC9FZ)Zqw9}*^^~Q41L1Ke0h|K?qJ2?^qR8Rt%!O^0MO8bhc;IRPg*L$Df7pFSiYJ-e9Np!VXtiEk49eTR zJEw{YddQk_S!n(ztm9+Swc2SA*#zPgl(>>h?jn)A!Tk%~HxG@)5UHQMuMJS^8n%&; zwe3y$@>pBciG;l_#^*-r=x?)hB65Xq$~1<>T(rCox6ewXu@C9&+=}VVb)W8cexbAa zW7Sv^Pf57^`Jp#2v#XD$*Kenx`MfLHQ1{!5LsxqE>C;y1yr0jj%6*nMr?#nFwLkdV z?zjLk-9o}gF?`ib$0)X2wAqx9H;K>e74EI&NY_a5GY_b;Y9Adw z6y>*R>3?A5Lz3!N6`!Lv?@Lv8RXZ8sHxo5ZM!>2!z>+Rc3|%8ADO)PdA-fw%r*0s zoTI`8`nEfq$UpIejLokUHHhPIPC8|drc25X`QyWczbOMgQhzQx}9Yb{Cq+Wb&U|DdFCGP76S>d*-d5bVoC7af&U|K5SuhSlp=kcndi3HB2vM zllWJ^6)mt7>jd&-k5=BA>u1+4Xg`@5p)Bf>Nnubl+=<{}HWd?|?4q{bX%`-M8SBMN zt^TrYQ827bIqQaC!%cdIwLT!oPhHtPTRfupubbk%{9iZaZhP8#S0>0={c?@70cs6v zC;s8(CvVg70`_2W&ifr%zPgB@w6Ej)`AVgqL+c706_R+Eh!@wRPX{Ze3|nifSYlG~ zaq`2^7!6c4KokU~!LF=+(3i}py3JqymTbd5)&=w5hZ`zM++E}K)MpT;Sfljv`xCYE zzm8KCd<~EG-6eX9Q%2az(KX|AJQ+#(h)YxkR9^_z&s*kR37r$0&K!NpD-j+k6*$Ti z?Pt`vEto@-lYES4o3nV5&f?fNY2?jBf?8ife9&~$&m?bFYh)Zz)|0l82PL8Z6buW^ zZ&|H0GHR*_uPlhsOJkfb3{Ynd7EGDU8uQzHYm(=;L*Qnr@>Yahv6FXvyp21FbdJ$s z!is)VhW*F=9~HSGxa6x57mfEb{IHX1)fF4tEH1rS&(aYj^5V>2+u*(Tudd>3J{rmw zs2{V{e$nbTEiNBydlA<-%U!Y4oNu>VdZ$Tc{aRcH8)0ao1zGSYWbbKe^W#B%dHhrF zRCxFS9M$>IaA87KAP?zn5q&2{A2d$MkCWu5Ltrcu@@Fe9G1-k>@j!%c} zwH_~Hicb5`Tnmt8zf&6CZXnymb9-IZ(LVM89($YZs$V%NzLBQdNY;pb0w zripGxjC^SpX{0-YpuFwd@}e$-Et^bZ^*0#^9u9sg1u8C9TvnG5NP(MIcErj0fh$*a z@4L;bCrk`EOKc%fw?-qS@RdEx>^VA8h#l23IHPD7nspZK0u;z0{jSB;_FcWMX3=vO zVy-H+su{n(KUtr6O98fvGYTqfHN`wF?^_-!?w!3*6jL)(z^YW9yk)Um{eo zsQBqM|Lq99XB03mU3pv^g>_f{>%I3R_|kAO79)p}ls&P+z{Za({c%U(nON%jM5*GI z-(jpbOniPv7Z?b!>95`PAQ`^T$5@az zC*fozs~S~pHKrqRH^&!qf`0)~(lpp1EU=-UNizH)TH*}az^^pDGSq0oNac?hYmVsYnx73!+SQ28gNzt<*iF@Y+=6fMOv}55 z73}Pkzx@|`JXtvD*;!VtX4c@tL(6PP!XN8DbiX2wX}f7Zp2JV@IVlvT#L-S9+=?eR zbYSMwc`ltoi<|b0=l*h0{wolpAbU@Hne0)-3%69=5~okyI6r9X%0|uCffU-Zivj9L zj8V?Qg`-~U@o)vanT-7%J+X^^tP46WSo;yiv9EQ-S*HCPrw;;x=hfCDHzGKrGNO97 z4KypToMM)Kjd6zI6T4mI%l$f>0_vi`NnbhiDe3J|ktUT%Y=+21;c2~-xu+=cT!XJK zM(rk>@aN@j8%Cwh7Ejal-r-bq3QW4U{_CECww~r^)DTI)v}$s=Qc25ky&xsR`265} z`x`t5 z#y431!0_Jb(AhGA6%zC}?|1)9#W99`REu^-MO9LHyK!3I6ftUQ8Te>|LSidaMO1^B z`j|Fj-i{_U*&MH=qLK*BV+svcng`c;ByZ)VNHTw3k-eu%$H$&5*m0i$ohnSs^zhMw zS$^9FOkBf{@ZLUIW$j$QvOe%N(s>lr3y6F#amN)r0KPAiK<2ibg!b=3wGcG0|ma*vKjRW?&*$h3P<)cZCN7 z;ltp>o|z3I!f_{W(-JvzmWGq^G+pd)V&OJv`r!B@_aWk?xPcL;jhS8SmaS__|4&x2 zaG!zC_S-x?%9MA#tk0?&xtzZI61Q{43(a{55Vw@HjP_MU_wNgTw`8;3Q*!PNGLT;u z;b05DW1q33=B-d0Pv+rzRH&DxpNO3c?ol~dB8yDp@MPq{_g811ScU0lV%7Mk|76Xt zC4c|=8+k0V^sB!9>Q8bL`WGfYvu{H!O;p6{;#eR_em_w*7Wk68>dR;Uo0&R$;Kl?XDle||?OSUUUUs38Z*JpVRxjqRTbbO0-#6#OSa zMIsC_JU$j^;pY&mQhV&6ZIGj3UzvP=vW}^QX))nyL7PAMgql+ZxyIJ7u`+oOzw~59 zq+qhIE|Zoq(mqpB)gTfne^mHXBr`e4eEPQSe$29IlM2_HUUMhU6PA9FJw@HQYbYj7 zOG7mMm1Du;+e#hSU@b+%3aNKe+XJ+wLu$J}_Wn3=tF&Us?H6A*l60qEEaeC0nkDgG zwcK|sLW)pUU6-R^Ws*cr$3-<^oeH>AdH@e=m0=-aJs>qzwQ2IViSmZ^sBmU%)=g

    z`k&@h-i1*`XqNT#mXP*yV8YmVx3u8p#x?DI(W7S88BB*p?RVIu#N8fo*AMHk86Ls@o6tH(NC{n%4v86jfM-<~%D}2c$ar4;Pz|<{4zMv_u~`#!O^-6d@l&-K^tajX>}?jbJSkW=VdMLVMCTnywJc1% zQt^*BW=YDF%*jp}rjx|kJTKTvoE0`GDF-#!(|eJFJ@Y_vBkPG8M=C(nA{o7Z-K=4! zupxnU8GDrjXCv3?X-XASFUdO-hADP8aATB0)sZ#6vgX#T5RZ!>>ioj72Y5MH`1+Zo zk)0){dt%Cbjj;vKyi-w}L7PX+T;TvODPzCeMR4TjoAK$Of zu;Y)I!45~A^8zq_VQsRquZLdp5>wE`UuL=F6(ugf*>%%5DXV{sBW&eVuu2xz$Q@T| z0=N&c7bKbCfjr0UDrLD`obPdo^~^LvN*z1PI_=$`vGQ{@L=0`hh$H8){o)o;XZfEL zR(%HcO}zSZwv|dwIiH58PU*g|9@g+CeME0$aN83Yd{2dpgoiwscxgeA49|s5U$@SW z34_ZluQ*cU_!4)?MSgPeh38+jwjeny#VDrR5BdL|slCFR_x}@8tSQ`y5yN+BVSR+- z{UuMg%o!(D_|#XYCU}Xd^!|}LJ4~aOaw0BS#Ze|~)}>0olRp_tk6ThSCOk*_aMTK>GN#=P#HP9gy}D3 z*$GNU2M1LAmFHvEh&Pw>K#|xwuN8gbCFaj6!pf*ZGEAf!9i(%kA99IP0t+j zwMADQC^x1xYls;x#F&jLjN^U41EMgI52ZdU*h^g^V|7O^Y}2{jB8v&aA4H=Fw_TAy zUDN*x#&!#3udz>@^gh{3tJ6Ab9wigu(Z0j(gbex&-Cr}3N;Z8TOD~*S)W#F8^J8^2#;qfADc#@->?ymIZ$mfdhPlTG7Q|%a zTKMK|2vZ=jIgHmEA$5UYE)C77>%xGA9!>?6RA`FeHOjuw1?)AoN{AiJ=P9a;17qGt z(Q!8!sF1K+9T)fOVFmib=Kv1$w~Lt{JMSyuC*hBQCcl5?8;Jw=w_N=%R%c^d#bsdL z$FZy9F?4Qpj*oBQQBdjxXj(=SP&O%k$Y4~r8mUxAD>~xxW+IqDDt8AEwVB^x31Wz3ms+uj}lo?%Xo1 zP*X^Mbgv!v7~@4PO5~qwuqw0`lvkA zIvfG1=3a_nD$gWR8l!th!c79|xRPLNWT(%^OkDR`(d9b}vF?FHA=!#kp?gv^$aRQA z!a*UWc$8E23_?w9aMAA*!S;Hw*?#?Wi7`+HhFiA&6*^yd$J1+ zUKSeKe)yp?$OmpStmic=hBY+VoVSmZm!0KI4c;Y6?RdE>N8O2_5Aj1xpI~>gdP$ve z{y*M(l=MVo3SYemd3fB3*fUCL#nBW#~yuLB2z%w1Ch`{?={ zIuFIGs8dK`f1SOdg040%@p8-l=IIMcfB%?YU|hU|EfmB^d~~y0P$uj1``e>cRYJLL zDenK>U)2cBfq-f=!*Hqo@1&89L?P64Shm#Cv7r24uoT811Ao`_vM(%5pb9IgcxmIk z{_h*frxm?*c!HAuh|%k)Szt?5u*L1hfDX;k&0{PvW^k}_(A*k)bjc!S7s!;c&%}Sc+KWMeX`e%IyD0cC{-6%*q z(02&hjsxOJc5#MN2Q`%e_R`>ouDSK~SnDF0gH9Fx68z|6Fm2${je(sHF-^n5SI1Pn zK?rP{j|e^5g;eE)<1r~>r2@CM33y<~FE&bPd)9@&q5EyjK2~Uhe=XGWJkL7(5H3|- zT+D+VgbO{V$xs_W#Y0DW1p~dB49fvvEMOmdb(UrWqSiOBbeiL}PJoZ&3V=sc0a7!7 z8|MX@{>11NX%%GM#1`y9PUd@9Y zP)vZIB}#4Ydm0qY`$pb^3E;|OylkF3`ntFa2ZRGm0x}(B6O9>eNBMp@l}q;WAl-ZwScZ6#_hWcJXUyw6c3ObeLQF2w$#g-}aQdB%DNk z+=goCU>qg+sd#k|MCm6)L8l(X&@S5T^UH%p-&x_1*gaXyb*s7B63No9&1CZ9vK6-w zM!R<>IUlyym3vd$wr3?-g)%xb{&22}6e&DmCn3>J4|R-KFzrh=qxd&mN0m(Qv(CsB zRFOH4^7kR+1u24tkCVDDhDpfGEV=O%4IQbsK&CLGj2YgBfFtvKfqktnK&jwuxLzAp z3NhCMsy%=>&jj!ieD(`}KIG3nU5<=#PpAWka=@)|dyyCf*zrsO%fl-f;q}x5 zz`Z}vDMbDQ@JB9yCDU!iC7Ib!ORG1DT3X#iGS+j~j`i1>Pq}hj+SdHe`pP#2FQt=csGkOr?joffSY;C1lN> zlpl2)?=3+YMb;%QAU zFjR&f2?X8MSAc`0&DB0GxMN5ki>WqT`=QrLxl{J^lVBkA{tF{XJe8=P7+Eq?JaR`) zI`SkR&M1b-d0yKB5aiRfbB_G+FK$395rEfgJB zWm=I@1Gwk_b&fJX7zeP@UfE9oUqBUjAs4_j2)v)kyW9vf<$J!GQF8-;TO7_C5^qD^ z1l(W!s~cr2YWdR944~wCTU@qY^{zl21CU#C0x)sle?Pwv30Ts&O#4s(c=W3S6L?#C zKs!gTqz6T|;~>H$XO1G@mz^Oc9%z=k5J$oC9I$Dc$cH@^NESwi_T9KQNMmT~CzD-0 zZKz6$&HEmA(qlwik9339N4-dl7iGRMFKyI$z=5WdE_V`d{M2ZDq}<_L$zz(Tqv%MZ zl|^E-g0Ix0>c*5$Xx-&x);KN-Tal^e5Qa-hS{>zAqw*B zo1N~5?Q(i6aP(MM$z4cq`PnUBx9?@OWF&|tPt#_L1O#{yF;53%Do%{BO zb3K3csT?Hz(itB##Y9mq@G#0;A7d0(o6sS~GFlLz#aD!cyj5AXwb*k~;uC>QNOKdu zZ?&l#-N5h$lss>9>cM}h>S+Hsda#V~M&9o9D{@*OsRK(17!~I#GT$pbRsW=G_I3m% zTM5X~eAz>^P-#TEOG~8&-Fy(x@0Woh(TLV!}-@P7Wqk1)#gx{9IYpnoP`3 zkRcFqkf@Y{@W}Ji`HD}y{lWrT4-ulZjr!QO%op2@g100AINffSrYDl!v`q4CJx=jKRQ~ zL&y_dw-6KIE$~~HqHgs;4*M$yT40$1LB4#Ood5RYkty+>7CUWO*hJNc_Zr7>$n)>*w0x6($=N=M$znRnB-Q+`+2Nk!aqrUYtL+ys_X(`rc9FEo-qi zDIy&eJ@k{3T!rMf(Yx3w(dhKjlh(zhFafRW{xuyL^7+_`Ceo?Ep_rS>5)_Ev6to=) zgm$EErGkkesBh{DuM;r&(ICrsrkOezb%3Vm`2)FyOuS zc|zdsR1`>IlJO4Jvp~I#u1nbdF+_JExn22$d?`q%f25_Lc0=m&BuIlM9`@LE1UjRW z+1z_F29;NOZ=JHy>70+fem(wCU(ATnrLu4eXQrnGjwh-7fs{e?HKzjA`RMd23rixiwS-mpyU#A`< zBqRVW=%bEg^v3wd4kH+<=2@ho1&?Bm04u zEVl6;XEXvqs3!YGDL{M+VDA85WiW7G<_0j5=)fZgc}`EMq0Q4<4`La{kU=XEu1WpH zj#U>~g3)Q5qF9`RqLQMPuqbQs$tr4G*pD#zSK|C zvu{DXG~PdxybIU}I*BLn1d==dfb0=Z`e3SJRH;xnvw6jk{$G2AQk|#X|{C-q1y_BKC{!8c~Jg&RbJ2`Ije=(Ctp; zx8_TKz+d$kg}y{~zhTsWU|}TF2;`e8VTCOOKN{6xD~cjUr?Po0$VGZpKEXU~etg=z z>2jz0^?)P8A(r7xJ?5SAKTLgfRFq%TH6S6KigXN(q%_h)DIp;Z(jnd5HT2NZQUcQ5 z4Kj2n-7s`XOMef)_kGv;{$QHV?53c-9#JmL+6E_Gub=29QQ2I z^vq}v@NYN*+*H2-&4dL(&YLe=Z-wGNm@b)!UZn_3haBNI%-2myM-)%;;ZC|B$C|vUT9nEnf^PUrtTo9< z@EI@+sluIqr(OJ!mW~=Y&wlLFi9`t`*?s;EzUhkvM^apO0Mc;BYC?=d66Wm?PflX|YG z+!Ff+1(@fN*eKAT2%(l(o#l=T0XcZNxb$P4R`HpU*vqBR_my;;dN&FG;-^D-lmpd* zy8)Ap+zpqjLuhVpewJPW2>MhE43q#|Ejn_#26YY~Zf}w4hzhXy0c3pK+{O?5MT!}} z03!e5iV6l+)>8Qlv4=fnuA|!8S`tAgx_p_KjhmhR3>!c*Lm`tXl;)Xo3D^k4YP_4@ zIgemKqvTolq^YS%p6W#)f~LOft7l8@@$TRC}} z$_PiN)fD7lZx#d96e)@JeTG1D-rgFXnCpk8W2skH3MGMF2n>3c^mXk1Zk4O^%TuQv z$22JLXA~7@aH*68&wwH>QLcyCml)-K;KlYYq^+Iu(Q3v}%8mHG8008xL%*>tjwn_D zggUa|*>T_ldpQTO$wO%d=SXzrZzb{!?@nzw0o$Zumb?HYt&*dcc@na-#{eQrqgGK6 zC_jRuPCvtg*7aniI!_izVsCEj{C-y7xt~=4krGfLS*&nB@COp#?_E*ECBSiDQZIi*mZrY@s{gNJbfBgtsh%Oigyp1DQyIa_PRuGsk!=2^D0a6yKM`0 zd>4PC-(jW2Kn~vrm^4FNvdw5$mX1;pUd1$gpvPe&e!=K5S4;Snw5!5H|D`}fwWdMH zrB2e0E6tU(BddJuD9nTQqcg)8BjjaP9C)1JV+d-*ANQ!kn0tk#8cdhCv?wB0n^@CL zGgzf+O^;-*i>g{;{A2?S`WSRy0ELY2}>N;0+><)S3H?>C3kz0Ju_Me-H2 z9T@fic}+SE+0L-5mNz#i{iU9WMIhj^;3ThL(hZ!<28Hi{&c2{e#37aq95o*y+_HDM zVNKawW2dE9)KhJS;B@KzSSR0VPwiV(rn?l-CB4UQN)wV%8?Vi#FLyFj&d;e<6CCn_ zljcZo^iM0v9M`*rx{(Da{L=RKWTt3C*YXmcwpTiJCVZ+%HDTLnoR#8Z`R4(E8W|g-@SXM7gqvi#nE5VSo_4q5 z@i|+hQA6N}g=5+drT4}}v9}c0w@%RN0rG6+%P7FQ!D?T4ufjm`?nLcv_`j>Uf5&XXP#cv-A;91J<%d%}fDlYGs1E8eQQi;qrEFxENI0`53;oF0K-l>= zhd7B1s=MUIIJLWd$HZIAdaQ<1-XWRClPJx9c%qHai174Lv*zXc_`MCVtf*8K)cHrKOj_wzN<%)juJZ~K%>Q3C4&(ntyzY;Ia6bk}U= zYz{K}huG>`_}SEY*JUzTG%SIaVW#ns57eySv#7m)M$80Tn+%6n{kl_5&NY;Kwe6P) zoS8F(;|EY<#dkook-TSc*3FYbl_E12tIB2*82)}b2l*zCEH7n)mnjf%=h}RWVK9llt`Xwf{`5;=QaC@8rg{R>S*|8C^$R+TGOLI9%>SvTu%;aK3MT)s#{H2Ys zc=KNt&~6xF34{*I)H2kX%{D(G?l&Hwv6d8bdfI&@XRFjGXBO9wXBY&dTjtCJd6#)( znjn0+I71F1X8Yq*-2z!usYNp?PDu6ca9cbNLdhS*FD-S45ej(pL3VXpIMm{3YwxHi zCtFETocS@MOkYj0OH`a&>n|Mr2y+p=c8#`oguWfyCdteXW`!PDaMwtGfQ}E2RTv>m zL`ZnV{q-Z8o7@ex;a9n1;Qs7XFwicW7{?MbM_VlD@IwE6q|@D~*sfM25_>K;I1c z{=NqE$@r!cI?#tlx3*2#uhX;hzy$+G%sOmrEV1+eAf=R*y zUWqoaBXSp`3ANUhN&A=*=8}1-OllL=WLWr6n$ZuaN+2fa8_5PqY7zdacPcR{6}2hM zG|s+qjegHEXqJ~RRtL!37%C?rWuE9eTT;h-CUPi=YhUf5C?M#Y|7uORvOEr&H)nGd zZA9LU{iEzh{>`R+dr@#-q7UR1B$Z)G_BIZ&BdFCbIZFPu6Q&XmdS1MpoCG+{XLo|8 zJK~r>aP`G%?W2Zkly$&Ig2j69x_kYj2vQo%p(W+{)G9# zV1(wlrHn37o;j?gmwHNbI*Zr$&Vt6QguZsKsaYH`20O(#kWr&Ra?*W928uI}QZVq0 zJEGjjkAHOtXvyn*@X}h9WVas(8(wJ#6#s3c-S9+RA)mm0wt*Ec$vWV4)O~ynqCF8* zskE5D63j>cD>#4?8*Ax3NKTXAM$}di+kRZ)f1`sb zKZ%RyY>UNY<5#n%R7{;h(>tZ7=0C8Joy!^S5tyXuAr24Y@TcYpb z(}$XpA4S#$dqwQN4xlLbT#|spdxGyiq6Auc0mw#-bQ{OCZb6_k;pI%&*ycI+nPUlN zH^auNpRY=oDHw}}zA&(^4jI%EEVp*n1es-jK`E6tWe+ZE@Xcpv!F0Tm=l?G{%5i^? zbhf=d9-NEGt^X$4Uhi$l`OkQ!O#69##@K127GE+>HP9M~Nz3HA=}8OJ6_;0`F*#}Z zlX9<#OmHtd(!CN88aqf6Af|oy28VbBm4QoBDmz;CmHu9@Oe_*HjSk2DY&JUVWL_Ua zX^CEuGnuU5<|V31Uj$X;1>xy)it<7(yFJzf#|JEj%w4!$Z%=t&5p7id)IsM>`8S8w zXn%{cMl2eOFE8p;>CiI9zF}^+&Tf|vQJORRo&kDG9vBtxY3{H|I~F)&ub$q�Uniq-cmO)yce$j5bU2 zO6dCY6*29vlL#-*39kJ?Ch-rVCzNwYfq%e2HP9{lwH%gyOUY_Z^ zS2){JGt+NeMicufP1}I<5N|obi(~tS3lT;i28cR z-N&Z1J1!s!f7F0}SDmIvUBv0`n&Q<1>KPW%O$TOq*42ySi`Gp}=YUI??bQHGnP&>c z408hUUuPdKeWW`nROahfq{*e;fN`kWdxOr`pa>i^D1yx@9B<5HF&h^9oQO~0{I6rt z6_rLsjJN8X?po5=Q}o%U0gavXX z)nxT&Uha}K$Ws+9q1M4%-d@sAs>Nu8y_5iv`T8R}ct;WhubkyrP&f8s+Zz6$aMAR{ z4%GO$us_9V#bj>GaN<~KfArspXDytm!SU$7y+*RujzH#M++YFV5i+8))H|i;Y2`8L zn{?|B1GzPJ{o)VE$vUne~Qg8C_f05+mX1 zMTP9KRTR1ID*{?DhLN(Bz8f_EbNHG(-BQz^awGBe3?V*EM#k=5j}MXPly* zdgY)Jf~ptq7HG%*yNd|_Z$dIm4(IkSyu6N!pUmkq3a&F#}t{cFCw-GqE!Ot~+6 zWd^w}(pPn{Pf+V(B`K4X$&Rl_Xpt!cJd1s7RT-h10Lwc!EL4_e=njvm4Pz84#n9yE zFd@}(_Qidwwa*0KRqb})nBza&(zCRC#uD-oRGQnW`D#m z>etJza;6pb22$C9eijeDqUfZ`{PZE;if6ULhv*x+R(%d!uQ>)$l8s(b<7ut?^9MWR z4F41l`ZjPY7Ol|dB4JLLchvnqH&~PZNz7-<#8GcoUyRAfC_ULsQ}#OrU49W!t$*34 zR1l~YchJx!N~b!eRPg4*l&U|WISKd81jj~wU|o5!M{w@t8#GgAJpbHOlK`LFztZ`q zVIsVcf!Z&XfyORWiXI=faDfbLf)nC&5oKK6hb=Hy@@39<736A(whkaa4|u)W841J;wjG5PZ}C?} zJ?M=c<8d^W6>~;p$CNKc%&Eu4<=2?NCJ$m@)5iwI)>kmSzk`5j2qNuy2N8-{?IwrI z$?hPniBlC+qH*yVK3fWe!AkN%4Uo+>EwAm&AjIsrjTFrBAFFtX5S?K7#aOCwdb`oD zKK-Y!?9SoFX`5a5SN4bNbs6W=ds(V#hs&?~WC;TK_MCMpK#{m7&hG-$al2nSb36pp zN==De#JImNN!Mbt_^O44yrQ7XbXtyT&@A|rtMJynPg^rOT4@m=p2hQq+VmLYP`@~D zm=X)lbsa>FH5POzh$}w`yD0!@y5i6lRO)7g=5?ic}^9{4JK?B`9F=;Dl$yQV9p2lL`_1D}v5RG{ihu4q?@kO9X4 zsEqP~+{&lCCC4M?Vy&66F1ffn4g5c?dogzN9hX4=cnXdG6)=_G#=K?%zni|ahauMN z!HQyJoy=*@L=-2NI%%T{bhHE7`Wpi(%h}t_e^(6Y#MWq6juM!*lwhbBCGz0=Q=DmC zLO-^Sm$^kWwITe?t{=JR#59w7Y?E1hPe3%DoE7CQs0bWHPIA9D);K^gWAFqtnSgwH z6P`#oX2Iit!wnl{u$mMfl@yskBv~)~%@_GFuOjbrK9r+9T&Y{dVdo?DJI~B2MC228 zSZ@aTn#?h{BHkdhg{{knbi(ty#$+`sh3@=0wjF*0HCLr9Lj7UCH{9Xd@*y=^qsPvC zQ+QoVH4Q3Po+UtnDIz*Y!UbGpf>yG2ltZZf4#H$U z#rlM!&-p1fqzG|+DV3k-2a9x?#T)j^KY#f;sRTO$&jIK0(=)~#=y9hZeiW2UE+@Jh!43OM_}z(`zV0w@Q4UU*CNNmB{BV6fI+kT>Vd}6qSFPu?VCBM^ z1c`mM>eDM#YjJ+OqiSh=|99QTeuyaSVjrce>cl^1BM51XR3v@BMJPLqKkgG#Uwu)| zn17aInDy#-(}P=z?UJ0WuSg}EfdVyeaw((o_D}@j;P9B8%{5^3T<-JSL#!;{)OChF zCo-r^)mxiT$y^)_GY6xcPybN7zpEYJoi4-_6S}iuNKH{~FhTS8-=Q$jZi2Rip~_&t z>AD_&pST(OKEaTwucch~W=l=E+Vn_g3JLM7rdIIo-{wvC#h&8r-vLd7^-Jlfmtm56 ze0JoTis@i;FJ0zXGfui+fK2XllZ?vu0)O@4*j=|(_$Wlk^wZ(%j^F8RQ3Xh=Vd_KL zYfEjP(Gdp*JbjrqT=y&Gw9czYNKh}nB%m=h8CUZZ^84*v3RYJ}h2h;1`ubdV$%N3NgH2kB%tu}Ttr}_}I7{Ne4Tz|++FX?j=%3ctKoJ#Ssg!mx@Q~!j?U2C zu}S~x<1ez#dwSm%H+m4;dyBt416046`BU93#^6-^%Y9Gnr>JJa8=lFeSmBg_F4A*L zRQR|lcw?hMtN8fS7AoET;o!_MVgbhFJPC;&mm_TnGcy)2 zJb@09`8(t9ax%r~Hpe+8xQ^UH{Mre;Go~lx_Ez^=?lhqgn9XqL?~5RE*%gli1_IaM ziOeITX2;x~azhHrMHRV$INI9xe-CR1$6(aZ^bZ;`VMkn`K?P+-Hr{0MuPkYMd!}Zl z(ASpfPT%5FeiZ;B4lQnlz!}Zt@!-sGJGQCu`||nK04`~tAY-PujE>Hx|3QPT$wPzf z^Fx`3hVz*?;@-)|7<;1);nVDVo=HfpN#M%-ZWoD%fHV#D7 z2!nzjms_~(<~T+FO%Y{t*Wo?_%8H3OIpfmA`hOPmtt>|Jj_#0BK|y81C~(^(sf1Rf z!NO;_2L?_*lx=-2*PyKkR_beoA`;ausyZ!i4!$x7_kDmmtkC7!#IDZRe2IBl$c|B` z?mW^lMKbX(oSyJM9QQr%@=;QO zj&n4{49`%$^+2r6qRAJO)|QG`LzrkwzJ&_@w8mstSgC=T= zi%;u=a42>)wBCTI8Kd&OuYWlEHGTCQ$Ry{Jkp`u@9DR7QTb5I_()pfywkENn)%H!g zv={dWU{4oyJY(d%k$~5*YyD?z=ey4w+wth7s-{LV-zi3%?SzpUN2N^tnUY!=81}h< zT+a%M>-`#(3}W5Q|7fe#2520^q1|GBOh_LE+sKek7p^%p%xbqg_wbH@hdBlo-YLKE&~1 zsc)8jt{EDdEIMPr$psHs{(enESH|ydx~yVtr{6t-?-%jSayL7nNGbTCL#l_t9bYOi z-ps>%)+Ebq)$xXz<+{Icgg_^L7sdizl)a$O5LHhCqxzYM^8jk^@(GQ0s{o7myU*yi z^|Vf>RNYkliZJD$l=$YZ4vq6OaQ}eP_>(`CvaQlWXO};|t1>T@$OHxX$`UgMO2Cwl zzN89j}ReTMb<1XLA5fUr*&C@*LH(~;zTf&5QA{fTbT54lnruczzl70U#l zlfu$kU+I1QyX!hJ!sJK6|Ag4!fH=r{c@F zqb%k8KT%p+?v425cnP;mro+q;1qNU?z!uP){F{)_w1{&&9kt_s^^P=1qTz65^f|>} zTeMeOotW4yT;^g7PhyH+G_>Ss1LjT?AD?IN1TX)nk?>dW=B#0dStgbLNrO}^2Fy9v zeHMmvv^fe*{vmKr0vre`bjv4#8IGru+M8on!MCEU|MjNB=nZ8VI+{kHA#4 zpzs$VlDDTdlZU?)B~?G@MVy$(h5Yp9>~~Y&>z{^5&b)dUcM=+^qeIiTRrB;Zc#Rib zKz7Dv<7mT6ZXX}2P)W$rE$GpW?4JGnt84gM1BgJQrVpG=obeClQ{ye zIBE@`s&o2+!>cU7{$v&qedZA@7da6@a1tBY=|`+`+2SQ2Lo-yX(LCKUaC4i*iNM@~ zdA4#WFAePPhJl?}hP-ik-wGs9Dd@Tr z;IExO&^wla<9GX)sT&s$cSXgPrzfD3XTc=M%FJ|GR&0QQO;7Ilk)$ZyW~wLgguRZK zChqhpjcmEE;5xzqTyoe!6tVMTmirU{PnZN~5pA9x6)_O)7Hh+)M$)CdbV%=TDdF($ zU@}Z>%EeAGURT$p%O1>;bdii$K|vtMb=9l=a0q$z*>_>w?-#J-@`{RP$2DdnE$gTQ zOh+E%?(ld8Dv|W_leR>_?O_PHti@^S7q&lyy00pJR>Z~~%^tn{{o_>ZchT?e$cf|C zaxx%K?X!Qn_^E|y9F z%F3vCb|H!tCY2Q@dJ6#rXsQ5-VPHD;7uNuJFPVMY$-tZCuR?7+Hq+5-KO1@ijo-D+j^IYif>(N8I?zrj=MxIt#VL^bH?K z+QP!r{-%_u1cc-s8xo$8G;i*RFng_Ed9uo@7wp(Vn4Z|guhYJRs?eb)JKQeAMJT6? zHKk?J-eMa_@T?G%CHL=Y(W)@<=0LQ``faTctUDLRkIIc#2F3F$p?InYCz>cEhJr%2n2iIzCW4Po>KqS1Y`eASF_=)Q{G6;T?|h>v!_1o zr2)sfzRvsoSJOs0S@Ql@^(%Wk%7vSPb$&H|8eT@B6;so8`%vV<`)1i>Sft{F2qV;VU#Sf~X zuW)M@H0KW?A{3`lZXh(3phQkb?PwQOICu`%kB?V0j zmD2~WburlZz=?9kSHt8SY@ilTBg$gLh9aMQi`>lK_-$MYStOoh%Q;?_5Crzl>!;0o zW%oF06^NiOv@m{D1mI#8Ts;cEG}=|)y@)(BQA2X(em6L%pd+gF+vG>V1PyB`m#Wap z?R_TsnQw>ke-~rq+Oj7i+vyakQvubNtP*hw!MRygSsvWF3|=?M8J`SJ?O*sy%I;`K zc1D{0%#N(x;gqX_?wS(#kz#oAdVU^XGb5r_EqnK2>?p>+R>mUL#Eb!-{h^4XbLgcj zF(+|Zxf7I{#oax$^7J~J546$v&|sl83?ltfBJ<^9Wx45OOYT#O@KA#B_ie5*$-Yy% zB@Un{)F@)tNQUn9WDoDNv(+pagT?s-$Jx$;##pZk%cCBxe9kr=8CVWd)M408~~YUnX1Y3Ki+|U3dt;$FGl9Y7v$o7d}WCwTC;ntkvhtB}USJT*!EmvC7XcE8iIPVQR_l#?qm2 zIZd#RwZGq3&HYp{U_ud`V0}4+$kM!U;2reW;_xs=FU;rHla)_@6m3afbU#QZEn^pj z-SyX(`Ubro(aBT6Upiqin77oA=tA&(pXM*%F^tCA&vW6Aa)P+LlL?%upf9Jbq7BQ@ z5FCRScNxKskll6n4tl~j32n!g=OOiNgPU%ZG)1RB;BEte?p7pxrA{5m3>_q zClv81eCfC9%hlO^sJw7H5&aAKNJw@)uY5lhR(Wrk_Ob1Aof-Jt0y@hT51+0+`p;#D zSk!XR!jnt*fy!r|3ltBvEp?+lmH~|q(OA}Qi>G#$izH@4a@=H0EiNa$}|;;D1bF zfh&lRFv@(}PgZdUCVmhe9jlamla5M+j|6jzETJ=4+zy&J$7RUVnUV zrx~b#6fL#=Jm8gEuX29s2|M~rO+ZmD9G8Lhp?ott>Vr~3U;PS9#G2rd!2tIi!Rx&7 z_va&~7roEdk^g!x_(|l~z+OJgIPr{q?iV6tHaU@!HSr=u&lS`tjWfb1FRaZPh?wDi zD+iD?^v_5*T98p&B}yzEdQMx^jSV=euVx<6PN@{$5DgjT;~o#KH9@YXS}>L&y90r% zmi0Ct#Fl>0Hw@HyptKJ;{8UX$67(Vd7E#fm9h^N4W1?#tY0u1OwEz{}ulm^eaOonj~hT@R&7GD=>GCSk}r8}NBd)z<(6?? zevk9Sku4*IY*z7 zmCuqpyWbkBZRi)^d?9_ct%*htJJKj@;>cU%0~&ka18>aotxNVh&B;?^_Po5+ORpxZ z_Q41|S}p(WnTf2&-5J~HalTSvgB_#s&h%dw>_3Yn z*T{^`BG-$7j3{ya7}{U2|E0;7TiW=U=IbAx@|hkb7rmHqI-QCYai%0C-*&rKIT15w zga}t!{{3Y3yj#|7QL}iDSeaQ!@1R;MoOfk~v2l(sCMV%{6Kr??2+o*YCcjb~tI@|7 zzS^vgvP=!LfOf<>&OZrQYvZ5#FV_SuqqpV@Poh)uCH_@ zKMU0rd6{paqqp`nlAZ}eZ|f|g@&2211^kad*-L_ycNuv-lv!;q98x_zjl3OaBrTVJ z9%pq{eoX81_2Tb_sM>*A{%zcelVW4Hh)(uHh=ab7xk>VXubskg{tZWc1_|vzhq1es z7%G{hUQq~oBInVCX@@PlQ;iB0#2GMPk4b}<=D5Gb!;x}+wcRow$DeHVMNzN5TI9s3 zKUNH=>Zuy2PG;?tT~RtDyOiNoCI4B!8>`1jP`!n~{CanwMg)IM(r?PIa|ovk3U>vZ z?Y}(`Tq;_tnWb|a(1Skl|__))!Z z(Ni6-eO~(+u`NrH3WNNHjJN~wK7W=96eJxGih#kkV`oHVX(eQ@+R&E@s-G+ys1vH3 zySpDDZzyEa-tB{p-06f2nnEnC7Gkj>eFv0;lrn=?x)i#u$g#1Wm!Lk%EuzEDlXdXG z89%k-6mHAa(JQ#H8@m{D{=?TLOotS-lPxOEp0L^dSqts;EuIgrv!ES! z4=mO%HQjjM01?HKPKEj9`#>UPTY0~TB}*k4JM1U$_EZtA^BFVjeoL~If-aD2#_<;( zEBJ}zwD*Zr0JRYzF-%QE>S7TxtUE6Tr8%al-E zh$WTjVKdY5LPVEBstIz$qk3DKE&N51RU^(F>p)6(G+nZX8|f43Bj(QTwH;WNFMMKJ zAX$1C+{FxK!nI%7;B%1$rV~*Qh5qE5#IN`e(NKBjQBK;^W{;jAYSJ0`x9k>v?c1@Y zBbWlx1xj~n{vHI*;1uFKG*H^BsPayG*$T{5ni8$$0C}EDJpE{eV(F*}YIdC*1V$uW zP@ao(?sjJux2cVafkb8u}jg(6D}S2MxbTtIBP zrgYt4zp8b~!D<^Jmo8BfA{ck}sD+xlZMJRB3bs3wEf1k1C0iqstUS}j{;Qa%`FdTN zZxyW7HEq;7-LX{tS>zPShM#7=$fD(9Cy}8t#DOmX{k(A6E97JAoR;kucw!S9njC49 zv&ir^eX^yLy}wWN%l*xO;lwI2id#Yvi|rUwAAcad<_dx-9+)4jK27%woXD2d{&tTa z{G|$SP@Nj_eG}qLJ1;MXl;{Tz5Hr{M$k>|C5q~H1Q7e?Z=YQrOp53{_+yokl*nAu) zNbU{1(`JTBs!n1p3i3uDuhJ9i+>wx_mx*Q}?Jf9GZvj3XBMym-bUfvYkg}(Pv-p@! z430ca>EQf%A4`kb2wNn?r#MRf#+$s$Y~u+g^Dfxvw>1=A84>IZUA&$qmY3Hjt=)FE z-g9XKK`52_6N>(C7Ql)MJo|9-xuPB2w+ z$ip5qw1URV$LqJ(O5Ml!VJQdz4+Mq?O?jO5I&hoYGk^C0=rg~EWv7Eq^*rBh@-%oO zt{q_zFHa@^xq=~*Q?F}{uuf1PPUfFzUn{i#e+?Y+>g(bN4Q$G@zSfGy?8>cFK;VLU zrD)Q-JGOQMquYo*-Exzc&Z=s|#g((=(3DkE-2LL?gl4BjQKfT%NM5jv;eZJbZPh^R zO#|Ne5^V}aZi8olM$^7=p6wk&iCv6JPJ=1 z>WjI2P#02-4)JA_5_3nP9uMN@V7c@jB@R3EwKG9p zPCh`XVj?(s$YT%1!E+dJfYl6>vh_{ck;_kPa-^}D#pOgfz6Gfn^Xpw39$;e0XRuJ8 zWK`JkY8Cci*#5Eg8Ynv$?l-!*>Oz&dav(=cS2i$~lrb|>So2{g zF2VXTkJCa%MFRmq&>LGg7peR25MQHm!-6E$go?gGy{TW(puFefnj;Bqzi|KYPJGqv zx8RZ4zOWi^3$YbH?m;>-e4@;^_3br;b6I^4^NuvM>2$`{H3ay%7pfu&12?eoH6L*K zoGIH8#{y8tDkL^?XK&OQ8rA4W^; z?4&89QCsVDW0qv%tbTRWz4-s)q0O66WO^aYa?C2t&MAn7`?l7{_O;%dnKP!ChIah! znY0K951H@%#RX#kQBe2qdau`&1kgm?hN?cD6e~)p_`r-9X?C|UByUI^encGU248Yb zGHNkn#&~VRZpE~Yskz1K!6@vek@k22@5(4A5ws9O5_#7oFv1G+^z9h+x-4lcX&-3H zG-kVFY#^g{b1S50mgrl;mS3{a%nV*hl=g@3xLP3HeT#yej;0+`#^un~vU2G9UrYK4 zwCglcp-Sme$NVjKioI++Ub4(nkSSv_7p!9zrxfS;#LK8Y7L%e;N>IPzYIV&uHM@Ol zb75bXfS*+0gn9G|1g7eF50rH8cV)#kW_0asuS|Raeu{el>Ah3w|G-+RIgk?Vm=B=+ zo&oe!)Q!MLImE62keop1oSYkDwKo*kF=c6&T$9Ec+_w&mF`a-Od^z(x0?#ZrMJ z^i!8eA1=ya3_K=$J`DM2Z;$SS4%@V4Mo{cvX^n**!KIg13%mw3xTU#m{gdJYll}CR z^*0TAqc8A(rpAoN99`|;g2)g%QVE|foqZI~WAU*!`n3ZDOVMIqn@g}hDOETa?nhtPqQk>*gA{FlqHu?Kxf$IhdLoXFNprkw5O8=6}@a~PB+DJ2Df zujBIFReN3RN~E&uYc)I3ulk(F+@Y!z6c#!Hf)0S-C#vX!dMEOEi|fI^f17dh&F}n- z%|HIV*~xha$hhnu9O#zg{?ElRK?-*%GeROvKD5u>H@4mzAtH2|?CGs6azBnvxoaCV zP6{sFdMnudJp(G#qw}ldi$1@#qu7-srJbb9Yq!l+9y;WY1Ieu==wXotvt-IY-}Sc} z7JQ1x;5zfLCh64rfx#NZ_@pep0Tcatwr}l$pEpab+P177oiK12EVH2+b$|C?M`;F5G37{kxJo<087zlF= z{SdxQ_F6V+C)Uk~E?4l*zI|Pam)EE+?4@)OWR1_o%bWcQQHq2_S6<#RaU~g1_7HOZ zayCEs+UfGczlPOT?qWy|;q^-beWfP-#pvUK6KcqzB$Z}DE)cTidv8MTT zaJm(mF#NnlW&nV=lkFWVpUA-F@z+o$hO{3rV%SQ1LR&L{=zRpN`dL5-6_;}4?|N_Z zR*LRFfLe^~y4tuO!>;XACJdKq44``$0079$9PX7_6~*P{TY+elYjY-XW`OFVLXKz_ zKwQOB0o3v+_?KM>L9(&%;{4d>hQu>&f9Qkf#@#xuKMdFJ?+f$M^nTBstbr<{-X>sl zV7^Hu%o{*8!sBHrjfRq#u}HW>a;3tZda?PdZ02izZTkQ1M$2@a(Z(Vd0JuWJI2|{@ z&wX9B&!17c0D6a}>lJUot2q-A0S9We9}4U3*DKbCn*fo-kiGw%E~W2<%JbKK{$~J8 zy`*HahICpiJpE$8%U4le`ttMD21DNot*~k7+>l&?&|8cc`(;!^vvxR< zgXfWh?eaBVSx#IC+EZ1NoSn`GH6pox{ntFvAWd`Du@cehhC{n8tP)V1t0>kP+vQfr z#ukquFEn|eUtZ`8zCawPx2M_BZ`*u@UpbT&8FpNj)vOr?Lp+7mUKKyJQKe3XJQx#f zNtyO7kVZrxUIeeZ?gj7gxP7^h%1a~6B^RV<_sC}mYFS#4rVx#rOOI~U28QhTg+S+R z@$_#}Xj1poHtgcx+cl;%Hr3s|@hlel-4Wq5`z>@NZkn0|;6BjeA_6r!Er;BGT^g4C zXN2eE{pan_%MivhEJrR$7vU{nx@mLXB4-QW-Y}i7F?;UzwE=tc92gFlTT=nFa;)gB zC8gg#BY>F*cvD+%gYBZn z>^_jSvMs?P+cT^m=<3`ZHU4gGB+4l%EzK_|2w8o4y!HX)aD0HHLG=3d8Q?Pk739|) z|28lw{qG&0LC}Ew=3tH4aMMZ0-7_x;Kt2L+7@SQ=;c|Ij*{t}SD?Y#ZnFGo1UoTaS zLoQbIitn|)-&tag1MuKyxBHBs=bhC9`UoGtwURvN&W3Ufdk~f2R@LV4kF4_UG1+v3fqM-4r3+~t7mw--{O)Ng4Qb)7GI z%4aD8hV^Eo>S)tL<$i(kG8StnMby5$%CO<62*&C->{Q_$iYekGmuedq7}dFS_d zk+Kr!xEKkwabb0DsqNNLQl5HrAqnw08f=(^oD3%D{V6nwH(?d|38DJFN?uI0MbCGz zLxVBH47r54>*lGUO0ja2H(N=cb;8Q?1Q|`oB)Iug*8Q;cLf%h}Kss-|VdIww4lg)S zn;R>oK)Vh0VXz1;GaalX>}? zl?F?0i?+{1KLCvcfbr~w4<_y{HgY_Zv6!1XZA37t>a*?neN1JiC&F+9mKT`GPzI<9 z{xe%1xym_30N4yb(K$Px9!{9q*`J%IfUX&*o!*?t>27}9c3JHhEeA(jyZ5!KmKF?n zx^}gsvDeh^-}1`9unAjCbTk&g@FEBNLN9GB*5ZCL_V094@OC%91b|rs51X1&b#iiI zVokK_ZD|n#m|+H1+P%>M1`@!f04RHapr-rr;m#8{&o|2_ezJ{r%dnv#nhet3VV=HbDM(`T4%CcUKFn!p z*d%9Y#Xpspn}dI*uiX}M=M3ToqYF$IX5ETrNd?CJDmng*3K!Yx*KWl9N4Nc%-rwD3 z0=r!Z>25Dn{o<#jpaVNW`A*rufm-Z{ZWBruV@7HG{V8{27^UZm4xhzoKN?hXR4Fbbrd@Jftu9rx4Y;rw`#=gRZn*Q|iImbt|rBta1B6CIR2%7?MbYvvN7Pq4h zUS9upM1X(;s8<0y@uRIR^O-6NU^Pqr#01vRc)i$YzXMM+ds**(Vj!7|x7>R7&J+_h zI4L=q%cIJdeKri6tm$$_SG&!F>*nSLc<3`>6`*EU7hCOpZI|tLYnAPDCXYk;UJgJN z&$WB=2cu#epTP&ookzHyd5Bt1Ix=+a+mn};^pxJ8f;-N$PB;Mqv;F;jtri#Noh)~Q zk&bXItHHC0|H-a&g5H%Cwwh`N%J~d{+aKA$boa_5uP;3!(3J-CBUDePg~@e4gW_e} z94k;z&gbf_v1nv{Rnk~cGuqOFE7rqi^QL}Q<+jt6W*eG}G7(J++^O|Sa@@kVn62Bui4_SkW3;fs1Ets0&*WihoC-z-(KAe0m@ceg7;Iiu4G_4&ag;v+KufY3F^6!;$Ee?QsF&&`sXDwPFnbJWZcUc+PD z1MCSK6q_HP=7moly|go!@PW0F0A|Ny6Blc6=$bwat&)owrxiR!_WF zIR2gxrLxBGT%msW6fKY>Hp5O-{=oa!0i)v%fv4KxVCsT|#-tvl>kZM$631>WInM$X ziYSKra%|u0KTDx^?`0J&#Qnm zqiR6U?`De}h!P`N!m0DM7VoTQ-ab=qoSkK^fB-`VoPm$|B|wO$S^3Qm;MCBnGDLjN zA%F_uGvMl(;_BjfnGB(Fc31@%00G+X-RZp69tY)(0v8ifp1Zl>-}r1vwY9YYj)w4X zD!*?)tU|l@20Yxs|D)+Ffa2)7ZjHMQ8raCdhnxFom*cMTRGK!UqN za2Q-~^ZxgvYM>~pIWX0|<($2qHI|s0s|&DN-I_)qR)O40rL~E3||Sx}rjF8zMv9 zbrRpwyWRxXQi11VCDbaor2Z6cyjvswWZt??o6hm^A3~@vVCm?VA76|8+%2IV-@rU0 z07^IvvXkpK=R@~ncqn?{D(;*9(IFs4yywSWv_J3>=G2LZO20?tm^mKD1ph5=_ zIfpA)`MU169*lQu#Z!s5%4qv`-216;-Oq?T6`|1~Vx~sy$Q~2h>b?I~-~GBkPug0( zC?@_a(jR@QO_boYlVrn78D(dU@}pq!n(y+6frm_Wpm1v+9zc6NF(vHa}> zu{>lPx;pEWRN>`j`|Wt4QO`LOJx1+ zhvNp%x2e^Xr-|-(^q>8@7SOpNYeJb$-iIH|Kw~plt0etg3Y+CRPI->}B6fzk#A9fc zm>7*|Ix+fw$F}MpK(S5WFj6Cjtf15V_BuHYiu!Jv@%^MYs!D4ALrldN+2Wd$dM4jr zA1Y-q*#AOtI`>_!n~&QLbePi88#1rdbQ4pCBzH@k8Hb&E!pxD-j*QV>V#bn+CF(K9 zm>7gOR6T;je01E5>(7$J(vv&I#o5|#xYo!c_Pm3JkK5VQ16iBsuU;E=UQ5Udx=8uE=7Ii=l7&H+MP)3mS1G6!2?7-XgfPiPK zH@U>%;9!pL;K&|Is2~kcm_)s8q)U@ppbsDk15$Ea#FaRNfDhB`Sl5Oqo5HaAL zbG}L9xe@dhD&AJy*%v}>FzWJl23Gk3#0f6oS39)-qeDPX4&4Cwg%&{BljGEn{MO~X zQO$n+`tWe2j(GsN&lK@_FGuQz3#72EL@A8TPRQ?KAi(8#Zbk9fFQo$8Ejd8p(y;FT z$Z0Wx6^=pr3%J(~YoVQh8rTJ(=yCeqIlVP-Z;jpe3?ribPl|8R1_(JKA!~crVm?i{ zkN96A2S+^xgX;TXq-VmkVw>sGc{g3;?MX-V`YZgX^<8uziB3Eg{@uL1v5il9N(|p` z-K7^~nZCo4$KNaP%wXALcF$@>tY=$!)P{AafP1#NT;G!G)ZjL`XhM5EkQ!n-%OP2i?d0dUwUK=lO0j;6=*IO8^fKZ)bmh`x@bMRVKePRZ~+FP%8bfooCD9 zb5z+L`W^h;3$piiE3SASRokt!CIJyNiLl??@fZ+;_+8IxXlU@XV*W44)SAH-H8R~f z@3>Y-yF6nC8JBE4$YG&QUhtZ^$WomA_9_egD@C>%sWTUv#sHZ>+6dwpcIB&0;tpFp zLwgVUF*3dqH{5`eUn{g}PmK`ad&_FV<0Q%_pZ z?9gmS@gG^+$QcE8k!@~7@jl)?8>_@#{!2Og$tt+4xmnr|C&LUh8>B}>CoP;KAHPyF zMTWfkn!I31w1KA47a=Fap}3WMU9#8f5_D&_p(0 zso&!bG>xkhA&^6elS7-qE3M8WkBM)YB57z6@pWgIGeekcS_v?VPbJ|YU(2|F+49w+ zzT{3fEOgkU#orEc#3JVX_4JC{$mC74GwtA!iaOcGKlFi)djF^{{PQLYOMQLwCSk{x5uxB9zK|+Ln^`;Z3a3LeT1tIkz5f#9!MMO8)yIu@!n|xaV%L&li2{ z6TU^lFBZcQ82mn7)iwgKqhR9xbQ_OQFINhG@m;j{+pJWZcCHayYq_*qRTh)>&JK!~ zxPyg&<41SxsHDKTH+HSIlqX`2#U>msZLH|Luy)tvl%diZglhge`2E z=!4O2R@`=SbtkE$G7H3yAqE<?Auz$c9OGR%}a}gnGr<@6vH%diR7r6_NE8M`n_# z@Yg%AIh7pQvUAt=&~#EQef*yEm5^B+g+B1gyZYM?j(*K%9GkPQ=kG}jc75p=iDhyq z69pEPBZKylSEy#;9yqM)OY`6+J-j^#Nh64lC#!>{TuoZ4=iG#cPOqq6iRL}p580c6 zFR6^RMDSv#(yA0(1Nx^~k!v=;ym8MHy=uwz@VoafiA>cLdFa31srTmTkJr-Oe*g#A z_4$2@!lNy#py4*v<}IfbeKy_pX)xp8hlM!8J3NQ@6J;hKjJr%tX(;fNQg5Q;vIquF z2{;AB2(B`#tNaa-B5B~8!a?)tSk3S z`qqiiTp{%D-k80->ErWk?0%_s>Wke8L)&gw{*QcjrlnpJ(vWQ*wVJ{ePxQh6FOTJ^zk9-5;ItInuSoc`@H-cCZ%GRCVEG-pj7S+o7^>>@9P~6; zx%jt*5r8B1?jwqL_mOFoVtB=w&3@eLCoGhi2f9r3OjT$&&AdNttw(9>Um@Jg+=ZjZ zL<<8yNfpb!Uo`z@%S%TRq7$S)5RM|f&@ShqdRN*K;p z$T}nBN6d(Ho!?=S_PM@N6uzwRp~MwSg_Dx7R)w2Co!ZLQR10Za!L zMvfA<6N*yo)a*h22Del`fx?oGhXUl8;NM?kl5O@tjOp~>yd|AcD+1PwB`7to&)xbh zCYBW$B-|b%7=~vH6q@3y5PVeJB;726?_ZNlYh1{pSG%$HT=+(M74(8)e?%iYI@@z* z6nvd32M50J>})2f2Q|Zn%P*LATv53y>a}(4U4Rpx-AHz!(c7k5(w>hKab+5n$uj;6 zGH;(iu>;djuCZQSnKLJADtL2+Zb6ez#Bp|lH!`UOUadX%11LE%eKso$2DdD~kd?qG zGNE>d$OY&>E)_)^1tFW?vQW|WOMSMqTAOeVfTx&c<(<4V_w75CFpy9f@#?C@- zQd}Yg)tcc!k_7r6$HmA$N*hNkgq~lykxtp(Ixskmp`_t3+}p?KB#i7PM01(l;=9G{ zM!suEKPi`Htk5g(SNgc`;rHIA@r>poOZ21SH=QrXqx_Tk_BHC_{ij@yEcnF^8xB{( z6;3OGUjj3xhSGg`?#Lq$zV996>CorpMzWA#8ica^)870>lL?L&LvX_>R`Vg=)K34( zA0^B#C4KRt@c2FGj`pGJy|W<#(Jv}TQRj&4DJ*?xlDLPARKGLzn6d))1QO}iTK_pwlFq0vv1ES0Q} z$L?seW=LYWgH+5DObBg6C!FZAMIt9(>>W)QsGR)3hIOb(UCfDo>)r2By`ih=gS)DH zHg=pB=QkvF>un3td$$?1|CrJwEdQdITkYbFtYem9k@Fmo9Sdk(r_7Vvd48qe2#>zr zn7b9sQMV{>lRWV2AO=@FBr15hvS9VcvQ!a5+0tIn41ahBc6YCwzlAZ-F_Z{&-Rv`q5%=Q=*x0wv4n+#V6A&d4yhKCmq5t4f)=5)v=i?%SMIGkkmWg!C>lqVrzgJS+}7avmsj6{dI=eTg0v${l>3zlJUi5;F>tAfA1$Cx zc~92BvdOLn?fzcc{`O-zLoHT=fgQffIGn#|A-VB8naFggD@px#xYcb1Fl(}1<=jFW z204ZwsXyLDvzOt?LpyU+=V4`U+@^!5Log~HTqYla35z#O;cjGZV32xk0%O=%Y1&_% zoygY@-~2Wx=Y~1CN^rbu-Kl9NP)JXiXtc(bFXTTH#fy*xe<1c6C0)h^{IIX+Ag|i} zWV+~{hWajnFf4JwFFh#>T!ZkY0UCs#n%WJbB8Q--F_d7k5{dd}`yVJu`{xScb#`B- zIT1m*)G5A(sET<##QXOF{ZY`@@vbH?{Fvyl*-kj*N^HM5*6&5k{`^Y1^y8$8a!E96 z{q@BB^Pe!cI-Q}d^D7$BpZcUPGeddN)|uxQ>N!>~qGo6T<~4>9FiZ_yOWQxn=oYf(In*RLSe&>9-Ch5taT2d<#KWywYT+tU0ku`uNkZAIJ-$tO>KK zP7zf2@^hoYpVJOra!l7+V7(Dtjs1F!lZZq?3zRkm-3|ojUt|7?@(j-jjgm;3wIPTW z_i60FMBJ?9g(;cww|p$_D!Z`wdFU8(+lmfWG*@Br1PSr9UJKPEK~G zdbsF!2w5fYgF~Hys|gfW?a4=KE_PGXZ(Qbvt&Tf2TfbuVC#eomkva;L1^eAVEz#bK z#&ghr;cDs%(F!e1$&<7c^R=?r-OCHTM#JpRfJ{qnCe!$-`nuV3=`E7R-q0DpyBWC# zpX@AoB+5u@VR@85j}jFH=*YWXlngh-pa1n&GztHWrV%p6ntHEDu}mxVNfYXR_ZNO6 z6zd;Bc(UXuVsb0Y!qLr?30p;vUFR@^{zt}Cth@t{bJ}LdJ3*~ZcW{XZ3sCI9ZaMuezXP^X>-q1WT5O4TvJgX+S zo8*AwDmAXv z$q#{#fySBZ54rcGw*?O(i#ZTcBAPrIxNGJTUk7=MSHa}4$QMcJB{I|}=yJ^dL3|(V zRRU(Cg@RrY&b(V=>E0LeUpKzo7CZfT+t8R6ZV@XVz*<4!KA0$5JhI5r*kPnEKL2ib zhH`fwt@aj%3SyTMGr?dy6s>nv(vVxT96uT3A|_wAZ%3{&x7;Z|Tb$SsmU*l$0HXGN;KrGUuLo}#F9OX)w-R|$yjl23?@Jplw+G_qk-s|D1s>dI z`*vgZA7x?EB;PD}GszBmTz#E!pbO(12K^%%V;|=7ALNzd_@HueszbSem6$^l zCM18wQ>%j0O9#jj0;6KerY=e7NrZ#dL@Y0nhC6k`YJ$4#y3-v!)w^m{&$^T;@0qr_ z4ZAB{hu`-eaGMeA4ZFc^>U zEy3v1go8xc1JL>X0c(GFyW%J-5r`})XD`?`+>vGs%eTSxawI{aGNWLub`Flk9f;o4CXllGttPL;4*on;LPb z?{otp=VTGtQSGjh>tL%~;DbNZI$0szr6*LODE-XJZnJocJFS&*Z<9H>F56SCYtMSd zW|ZTKK|@9opJGM-ZkEQevt9_cHAnBS*v;+p2`27ycwgv+6@#psYkT9Uvoe zzPR_QpBT#m-AIey=HWX+lg^5G(N`fNrC&misa0na?hI$^^WLKG)^pk!^#;Y3De&s#U>SQ4( zo{`pxdK7DhPmE~q4uUn>Nre6jR!u+OTC@fF588$?sGE<3?5DajpA-&EWh(+>{__RV zVZAT7KP9eRG25<)c3Sg7S)Blk*wUi@AxMT_fx^D=lH@1RgVTtSqFQ?sv~vvQK?|az zo^#BX0=ylKK3IZ&1Dr;1Ge$+0_?n8&I?-yS7+rC%KZDeDaY}dyDgWF{QXOhFyk6j; z!xfUN1zw8vyQtf0@7yckR1ivZy8y{R1W%Km` z0kCFXkS~QePO;s$_Cn9qo!|#)J1hR(=_EU)y&VP zm1?9FTJIxNMY<&$oU%opynm*A|JCsa)BUe3jp%`VV>~NhFCx}^keUGugJFrjF6iZu zzDAi5>m7xw@@2lWBXwdw)sJHu9pzz3vnRa&7#*}d?nHD)jHZPxB9=1@ffY5*=g6PK zVk;*Hle&wi9&r3Zq~kVPWdY`e8!^fpoMfD#OhYuPQ8~HNdO`>N#Ak#~dq5O(c><6~E|uo=?7> z=#WIHhbScSQXBN6ok*mmsYF;=GG`gNoRUi&iiW_g=>^5Yw%9l(9Nas+EuWu2TyW^*U5__SQQvIIO5^+aZAP_a7bKCGlZ@c5}B9K zo^d~4Pc( z{QT$IQWRxLI+_qznndyhV$^0?Dva8`2R|-KHl8?Q{gPjWolqG{^lTI&OWm+|{|I-I zycT~`ZWvmesuwsDcH(4_A%=aNkfS2C816sWZDr4izYblf5!0(^ndkP%mZL zgr+2&!>hmG9;>p_DfF_i5aa2c^`2Ek5Q#F2fGKp#jSo<)N%u5h z^>s9nnNx{jUYNBXpPBuaHhiXDCRKjxhlM%?IK&}^d$UL>E^Ksk!$mNHBZapVg4@t9 zzih<8Qf#BT;YI}GWJT9JFU4j5Ozt}f7JNPTByMHEr)noZ-^DB&&WuMWhKoFyj%-wR zL(pS4!}%E19a*rXbhnZ^DoLlpLP1z3-S`+=etLnAQgTCkKixS&lW--5nB+O3-V|^7 z+m+(ur&k0SwwP(UNT8wjk0F%jH@Q&F$tgmeCMl2z6_iDTR&9#F@Dr@-qzY1IgbgE9wgGnBCI195gYPY|wT@ zwCA(kr`QWdAJ+eM)zAXn@(lWI4~zMNBKi)Y$A{+kk=%e@L3WCApE8b4)E+0Qs(6S+ z=MCEnKP(YzSj^HtPO&I{!vNw2uEs{pP0x~QZ_S_FCVai~;xA?+>&TNN`J<^3dKa@5 znz+Rd-|;nz5j6ei^rUl@gp(lOOf!DCj)GA&6=;h7&XN2VA~&7r^sW}#%h8JKrdepm_Hh-Fj3C4GU;*>+>7n5FRXgGWbKf56g1p5_7a=UZZgnUx7M-xG=}%dxJAWeqThC6POWi-x@9Kscfg24LHIP2 z^zAUi^!K->@r)FS;>Q+73EZ`W{L+w?NME$(2qam39w>vLynhBf1n4c_S7VZYJtNTW zb|Ag`ck87+vhuYG4cP|@FA{D-%I#-_RGu#PitsmYfAaF*a#XV}r1AS-E!oa!-1Bdm zM(E&q5WEs6UOx50Nrx{RaPpRr#2`(iW5`Nun99#(Tm8PKxOO9OS(`ra%0KZq-3H(N zlf1KtkXR5js~k#c3T=^h4k<0zQM@~f%OcRA5Yaqi-yHjR@WN`q@pb23649JHv6Mei z|FM$GB!ys(B>Cr;s)!=ib3ZXM~>p z=#;EzvYaR;--;mFV7M+Nr?liKkO!k1m}rfpN7m2;*8S+O@&?$y-suuAn1qD+St(M} zJ7iQ}f87j?{>8&iD72^y3&$Xb$nD?is2-V?yg>HyTddqyOwv zluWJr^z-9##p#lRCzaEK>w+Fq<+2U@J?OLVkEDMGB60*p^y#sPU4cbeM1m2JC^i}M ziT77Z_0U7bYLg@*`Is>;R9p;sZOU}#-X!~jD7OCV+*|4w+u8>&8YzNBL*xySxUkWr zi{QK|3Y`?V&e-I;1=V$cU2ex~MvS4v|Ed;H(OgW;w@BV{4zgPSf+!CCgylIIidd3egRAb2en4#I_0 zSUl3)pj{dg`XNq!Nb-YkrwmwShi=r>I{r2m;j_7_%n44G--PVo1a zY9=k#_)1yyFPE*b44|H6gq}MMHX98IlB(ebqUtXJI2wU45ctjSY+gyCB1nw#(5KDB z2IyUnEHU+6uXeKqz~06Hks4v7I(rkCHi<$?(lXm^3ccF(gwNH=U=K7 zl)DXx4Xo9PWsQ6|s7$Klg$c|t0#KZ=gpDgicP$!K1@TEDm?D>vbf^|gj8qk;ujdP) zDQ1yDtV@DwuLQ;60q=>9DzMaj zQ4dQoBqq&?E39l2SAXvFn}5?^2rO7Fa1zv$TA-M`-n%B{$!{LMPxQSO$X&k*(eN4g zhV?3bJL_%hXZPX=dr>(hEF5!(0}1P22A2t8>bmoAtzXdRJQCYJ-l2Nu^%*U(7YOc2 z9Vw^@S%>;I=ofEZJ02|7N<&AwgO7O>=v&t7b4f$o4;J9wm$-5n|IH4kI-3W*`iC%{ z0=~xA-?j*QQC$!j_O|ggb)81C;g*=`0%gS^6X*Y43Nv)^Q>KdT>qblX+D(y*NGq_7 zi^O~de%E}TpIWKLcmC})f^lxUQHKmR$c-RdFj|W05~~|5 znKp-M%aK1g`GJH}aZ2)B=$qb$JuQ(K7+f@@EH8Iy;R&XUj0@G{Rk)o|pNjk5kflgW ztND)I$gR~SUr>C1fc!uLA{E9Kd`8AHFnFuoRWQr0?1idM;ozLJ8w0Cl0#Xq8q_X9e zFaBg-ArqgW6g+k&dvfEAE05f4exaSyTp4KS^^sGn0FmE`VI#;i!G?0{RhS8+aD%v^ zD5vm}`~2i8NyQB@!dP7h8Nfh*uT)ttu4)^}E<#a2X zQps`(0C`__JO9KV)NK@L(YU;5-WL=(qsY^jO6(iyFITZ=95U^)_DO)cULM#tz;>C? z2|;$aVEf2UpVB8t8W(4}q__eOqkDG`7R`(}>_)uS4v=|HL4RkN>GEa5R)|KI>w*%b zb=EfGPR(@oNqxCCqET_IqcrDG_?JD&nei3*8Yk=U_wV1d`lQEokC-zgb7XNtv)SXs zeY%6HCJCOz@Bh`V{P8eCmLiisZTc(i3LI}-Kn5vt?7P$75d}6+$;CX_Q}foB_`x$z z^*?Kx5YOPxC;woUO7Rvlt&%j|ivl;B;-NDuM3<&BdnRS=YDjP0J&sPmViXjzOA~Gx zJw+W{|4eCP5+$)T;*LDtzT^6Rqt>BmFQW1%&5tCaDF4nkb^AlmtjzfcN~8F{V4Wfd zu=`Cd4PF^+a$u|!YOq|QbYG0dxOShvNAE1oDo&fFs`wcCp{%?4uO&2A2S4z|1?!To zGn03o5Qq|g5)QBzRhy9LrZ8$Wc^2F7D$6aa83T5eWE(z{T!5+?P<#|qJ9uvtVSY<$ zJ}e>)+YOBNr6GB5)ql+>+{az3mV8zuqz{Vzu#_Jp< zOzple;W=KRA)T&xhhmW6yVuU8!0UI_5{Cwr@ebb{JW=a*w84d|f6jEa`_)s7Lu$Wc zF0I>(8lV$4o!?M28eBuqQvJx2pmAhhf$yxEIdDu@V#BPDZ(@>Q5s%O%DVf;y`xbrhk;xd_Pib0G=i;?f@ zBS<47Q*Xd40f->BAD$ff!H3JSU_?6Prf+Oc#}c7WdHp_nyt-PB?hc7euZ2CupR>pB z&!98{l5?Rz7HHXFzfNS_t`MY?Ul6Y;2M_r0sBE*0Y5sN0Qwb%kmKmi{Q~g=GUMF+4 zgGV=W`MT@#yYpCHWBeP&>#Ml`Xy0n`$v_+x|8aAh#r86mC3280GUqj#n-L)jjc}yH zn#GKm;gN?Dfh#7{bgv6mR+(;}%6kik@o(o{{h>G+OM%bcRQpsqK^5l0ocMeUdYHD$ zgLJ1g@a^pJyu-4d!jX{&6-8wcmptC7&_ZYKo5#HhP%>cod!j?Xz4@M=ZvT0QQxM14 z)vFu7OEL?2qb>^KvKQD%$%g2+27MUA5xb?=tgI*dpB#RSx5-H4p*Z5qvr0;x!i!Pkym3WdWabd*Xr@ z%=wpGIaQ2jUJQM$Q=YudaFTuOH-?7TUS>VL*Q23`;GaMzfp;Q@@&Zw7;$lM6HSVJ5 zx!y2N6ngNy5*BAzG~^Xj6cQ8#?ki~J8}t-hyCmm#6l0flx#PB|J&-E1HaO5~?i^Fr zg`w&-;!z;)Nx{D4yKbeGnhA&eFkIfRWiNYu&72(jV21oq{GOYRqrl>V!xl~7`?U;> zCpGAl>U<5wvN5Qve(Mu8+RT!IEy6o{RjBx&@0;=p>{PR37m$W>>H_W;@_2gZuH4ze zJ>HRX^9YDmxT?&`B4HeDwbS7t(@a|x*DVKPrqB2La}640SR?Pj3(D0@u zXG05<5DFe3srU0pCyk?$E`>Hc@p_ZVP2kdLM+09kJ_FAj8c>Y)=wrIHwQtaU5BrnM& zR+L8UHeUyE+`m3>4AQT^>Qla${et0f3n|9loQE|jJE%D<1_{DG+Bknq%PDJQA@ew) zhX0!d_>mXd>>x~l9y6gvTp@1fWLrSc$Y3v#VT+S+x>IOc%8c$cW@1O>WRt9fo8A|V z(W-r%hai+KK7U4x60j|SY?HA{AmzrUK0MO|UgDd|Gl+QlS-ejk9}T)I|NG3!dMo9w zbJn|=U%|{W;5@0fh>Y<{Qj$TKuqXBWyK6`(!VV)|qmWxEA89$OuZg{l;9sjuR^&^P z$-z`1i*a{Oo6Eke*n-LZ<*qNF+O0A^8#>`~2gc1Wf#GpZmp!ug=StLZ76t5P;&a<& zjp;?|D-)r231BF&+@;T67y7Hj1Pj~In2R{>4%silRxTl8z+rg)R*v z>}(E$sJ#6U;5-`&UOwtCfwJUSWR3(i$(qz=_zps%Bd><}e#fc-@;`6Dp@I4L&DfITRgcj+? z4%dDKalEJ4jH0j)2tUdnYPfdoL+KinogxLu)eze>f6xZ3hK2K8UdeO=Q3{vaA)mT!FQU=ysCdB6rlO zd-+CDOSg?|-)N_x`4!z;r&?RWt2=pvRq`bzJEpJ!1X7}!qBE)YGDNoM4b|VQqF3)a zFGQMhhlsp}R|IHmUU;2*`8u7`@0nUj{5?6}Vm#m4-V5f%ApC5psT?%FF+NK-f=zP# zNK)I!J;K)(~e%wx6%TuXWK?`Be{ZPY!m#d6?n+QKt)x7$SDM? zEk{`@<>~^=vK0G?-MBwVx*7Tulg$pRv+Q)xbZi<2efc%g-Gn16rJd9oo`%obh=)ab zk^;GB7}e&r90TQ;&P%^PU&@Ug&juWmptdXmQXqexMu*ROIe7VERZ#Mb8@<~}cn`=I zMfOvs@35@}deGve_&V4>71d3&W_58i8N7Q=RFh9Ho{-P!Zi9`^ST^XfN1Bn8mZsCg zaiHjIQmq@Y7D1*TXy7N5Gfz@*_1T_Ra{icf+qC^rXPIci#ea7z)bNAG!r|l2Lfy5* zz(S0!+CFVX+7yrLx_97^UN!*n+nJ#~4Ey=l8QcBy#?Du8>G%E!el1cVNWnbJ?8Kki z!t#7D%|4gh9T&&weH=>Qme2HxJMu9YAw-Ohw%Z+0eaHnTQOo`LKBl^eNC60nIMxO! zzto76+R^hcy8T^T3L6mQvALmV!}}{5XGfwn2AkJTu|0AGa{d95xpM)vIdaQ%Xr|Ex zi-N@+mCUG@P_BfslG^vdv)yDnu-fvzF|`d?0?83{ygtN=ATMVT=+W?cMU!8&((!XG zaP^x3^ic%GoO?{+$B$R{ zQ3fOSLafA7PWWvyh!dIUJgNV(_4GK(h&oPlpeF^-A$exspI#jJ&q5P!ajhTkZ+Z9r z9`L9?%+qXKu;5D5zW39K|Gbm%^_JbuV**M^0&bogPNkEZ(u#ItHh9g---yQ7N=2DR z&Po6T0BCIdIvxO#{EE!ARlKQ%Va;VH1G5=Z( zwC9S!h@I6tU6@^?oUT3px?NJO*QUV2&4|LsRifecpCLm$PN_2l6kp7lsK!2w`!poB z92CE4{@fyx`YB9gV3^c~^$lsSU~0%6`v^bW4L;-98D>P71h<2E5! zOnrCWGX%p0ix0#$6(QrcN)><3)Lwl(8)0u*P9+T=Wp8psyr~$(2g;_oc;w-6(2aWL z`JCL#eQjTwvj@bVQ!A}!=gaIh03ieKxyN(JfkLI21hpaoenCZ+i4>Rk<0B+quDWIFW^lc;J#?7 zlqdX^8}MTQS@x|Ac6B4;?XcK#j@BVg<2*B3aUq% zIG)?M%Phe@aT+O*#;H=44V7a`-qy8~;(mdn=i`xM4i_mDObEp$>4+sF!QMq^y$0P4 z1Rzgxk;!!>d$@2m8UbFm21promWV&*E3=)Nchd{o%|yn@#VZLhS44>L8^c%g3%t){ zo`I`Yj9w8_cgkQfOfPI1D@yNGk;v(IM(q@Kh-N&bxu+2nyegfmgk>rJ{p=ElC%Gg5 zTbCd?cH}Hpces%Xg`b(E=*n1GY|;#~h%?tWOxcO*1pPzkk-S|xwXK$7Cdbrh3h_XQ z5z38nZ;~C*hP#mBM2NkS`eq&?Y`3f~_8AWnr>t8Y5kW9~MvQABguF^nDg1^sM20(Z}6zO{zZ?T@~(~{G3{-r=dko zqJb}@a)+qBpbUjWhCMM3FDdQUBW;d6^||Rjnq4gb6kX*#SWCjnCmxS@^Qt9%*j`ZU zIh=ZJU{XeAs^gJ!Q|9o*HWR_DRt!h@>oe%%oI4B3pRevyGj)V<-bJ~ryWpzEXIXTN zhyVt?-er-lS^h=&qj4(&3f*ke)^$;oxu#o%QCC#&CO8l19~0`ousXJ7ppyb31RQ8k z=I)Yw;la1T6Y$#h{#(Kpa$PuXKF#T_94)43*b#EdPMYz8Ar^~LIt!wfm~^(5p!R@b z?2d7ctISH2!u5HZAzFF3e2c!EhYpKT_2t5coUDlsMhTypU7g+Yype_sn}zb7&lX;t zwc9i^)#(NP!l8Hp(kyb5=O1SrE+?A4IIrj(8&Hy88>)A}E2{o%_{)i0=Y^#T!$#d+ z@bYPf&qG;4x26lVUH^4!Ks^9dF?n9(?2cQ9%H%;$Kco}+nW{mn&@BX&`xp?bmSndvT*+Xy2K9MPwS|{kVhr-Rl&zj1cd~l}xQyT#0@VcJW)@=lX0QiG( z;5-C~1tWg9tHTRF%)g2Sh`woZ-*6+l8O8`ZjL-S6PZ6l>or!OXTR_owo)GX9Qe!x~ z>I<3Rdy8R!*ShG_xzw8HHu@z5a(~@X`k1duDf?51f00A~U&tKTG|4+qq;3GQdd5WrHM!|T#QHi2vcAX)qdmhA;7J(+xt zM$gyeo*U3_dO`Yp-+n-9t_azi_zI}PL`>f}`F|_5**}kG0*W5!hR+jbd*ffix|1SQ~wN130A!wdnwo zxZAwpa5NtCTNu5E?=KkVnq z{z*)bHF+I%#LzQY#~*O}yfLojkJiuv=11jE>5Zk`b2Lt8Kei5(HLy)@fv;v03KbJ( zT!<{*P;?bKT;0=Ch-aHG=F8fBN!yWE@i#f69~UN?P2o<$Ze?_$bmI1P3Z+c=(Kf8=g|Sm4lD7iGITyST9$KppGEGHB3vzg!88*J2Us<+4 zO-YNa{fDgAS|xJ=CaA&pH&oX|$J!$c8G>2%2#D}+poO(XHb{CH7cifA&G>5mK8ow!MV?5P3bK9Y0 zEnlpv$Cf&W6p6B@5&00yyC8n|dMZNH!YDsDp<9i(Yu_(tC!%1v2}NOvuGo8)2;RZY za7^NZuOid(#pyejZp`=iM?XFWbF=ArM*8uMZXe{$Qv4CZ{e^sqq|IWALY3Aq-b0|y z{m&-)3se33IvH4H%2Vk9sZ#k}Z)lO>V)J`WHj|K?e46|A>AINE#f(A*@D(W8PguRF_x*1Ve*)% zhk4G&Xa~EmUaNRp8|Kd8e+0wIQj)}f5VsRt4;NJ4SUL+uD&%AoL?;f-N=5s4fV{7kX0Pg1VQXxkV zVinVLJ=?-8v#vbO^dkeEQf9BA$Er-F7MIQOQWG<^oFI1l8|4PDb&mv)C5eEn@Ac)m z?dp%>QCjQb;^NNEPU6?E3JwlzMztBo$9BSG%D1Ag25lOXVz0g^C@A2+CFpN*&#Pjzg7iQfNxRQ|M>ylV0|B=uB$sbSFOL;WJ>`2l*E0(6pbXaLb%bICKh%Y zjSJOF5rKNHZ=dp8^b1@P-(x=-D@ZurT+SrBq0M-aI7Iszq!#`ecT6E`SPSY@qB8h~ zAN5jgk{iEDj(f@_5r*aK9W-dgD7ocqT1B|%*YL;4ZBW|_f*H{l5bP$7z?>`U?=_Ft zu6~c~*LkYJW85--xzW+A3jiKF@R0?nJS=(I1a!5BWh z!l2ju_j1hJYF^QbQ!G97Gq_*nKQ+i$jV(eIdf+A?0Gg-3R6?(h@g2BR#_eoKYRyv zlz$nDwRgZ*0|NYg2ugy50HXlxbbTp|`@iP?a|xPld*4^moH=Lww{O-x9a41I z*JfT@z$*+a)z1p(jzi-lxq4-n=^aF(u3`pi%9r1Vg8CfYXBfj|}tD-x;_x({Lb7NEFqP&8ILYr`kDSoX@nHVz&39d#~l1 z>#iQ8BLCM;Cq*e#p-;1w zQYEPsjnPf{5rSCR$D1jcK@xei5>E^m>|hOjH@tAM@_OdF6SnN-4Bs(*uFvErsW&O+nhl_@9j$taBU9 zpzWzYf63)a@o_~x?*d~4!7O@L-?X5Wj%}q==RGOXYt$8F#Uq6RunfRnrtPwzdVjVQ zce&9%*Wu+h7)L^)uZ0F@Vq(G%Adv_?_7fhCvK;u zWf3L*YJn)tpjJQh#2iIiy)Zry_DI=3=wal8`{GY4()Q`h-f#TORpTQr+vE1Fiz_9g zo}3cx8KQ#X=}Y-?vA}P3ISECFzfM1~^X6z6rP582cSE)k?9{RuOhcU}#zBwAYfn<%^ zWsdlF%k+O)oDo|I;lFjG)My2tox>6-Y&C)n7xqx3AI<(Gd?Yb*qN&hi6u9@uBq7pQ zFPd}B8}FWLJWNl&UqNJObY8&L8;HQI`_UucoQu>S!8>2!@5Mehm&u&P5bnNM!`_Y= zyfUkA5pKGU2zo#9Y3N#Cma*Q^u=D8#UCuNIH=H!$f_n>sVSC3w{8vA7igYj~(Rf&u2%uq;Sg$Id=QocCqDDX)vc1rhPty$;lgJ+t!ERxnAB;L#8l?FLK$@V&9tS zOxXg**S`uiRN<1N!d-8J*Amf@S_%({f8uK*1o_|xGGdwaG)#1l@`^$5N+hN^mz9VE zZq^LdgQaN1nBP2L8pF{8r3)X9xoEsPIleSb30&N~B3WuVZ1e1Y)D;%4tSEtZVDt8R zC?xt2*!=hGv|FgEQE&glVy`FnGAtx1@AZm^TNJ{oPL7<%F~$ zfD!XjWXhJtvx-xaKN756SCX8=oUecgY(j?Q=kApZwI&*0#2N|c5GpeO;#%I>&ktdSK#u+!A77tTn z_1~3()PG3rT->9ds=~1-hfjeXK0A>-o?VWx4O-AylSoy#*a*|kAB&R0OpS#UGlV?F z@UDw=6(3(Fe=~(@SFr%*zpMOzO-s32CHzb3&|a=;x!St>UJL+P!TC4a00g9Z;}P`3 zNf$Mr)YQ~xZ^6@3_I7~VXEZ}znUcn7GkOBVivpxrHNOu)V44D`fvteN1V&3stADY2 zUCtXfB9~-c6aFlg*Cnq!c#C)@W9tc2TEG$euPSn-0dJB?F zr19uB{_C}l!d$CIhKIk9wgruCHQ8uU|I8Q$^B%zOVKo{3UD72K(-Ev_4(?8lv`h|smboH1ItGRVfI?^5ACC4< zO&g4Xgj?ntH@OrgoCwL0Xix42847U{2JbbWn>o$A>X_etPh_T%=+>JSii$+*dk;fW+gaG`j+97d@`wF9z^3n)Pxmo)tNov z!B05`rHthWkcRt}=NCE%DYD&G5^}C94jhuO{G^zBt>|V#4R+E{J8|BX z%dMVuvT0Aq08YAGdqR8uXYcE?Fu9yO^p$i(De)}THE{*+OQ;WDf%D^_;e#Y|2S>)V zce{K8)^e$Yi*XnyQ01XpNLCg&K8)`jDtoOmj@DE;923W$qzc@mc&0pZtc;7XHMC=A zxM#|B2Aw>XLNn26oqJJSw02}t6EGprvT+* z+EonPk{^8BeHa|c=}RZ(F7BQz%4sORv|tw4M=WvQ;Wi4xsC`p`F*=9x7FRd5dmCDX zC2Y*5F#WXpzJ#Li_Tp;t30}Q+TT<0!r-9cS;o-`bc}nfF=>036#SO%lYa?sVOs}pM-ZzDP^ZrkDzBV zR8-jdA1x!dF8IhN*yU;5McTeAwOQNSD*dU(s?v17(xEr7j~!OBouE!v$zJs#yC2IM` z+A|H>#eJ~?6)((|VR1gp)wI1wNlWy#59*x4NI4_$v^0J|wvM21%M+wFPlFqtFy|s) zPRp?nCR*KYAObCJ^Ut~EBe5=&2n+;$vTfD>yO|@$;29hU#G*~gu2|0>%BORsj(lK4 zF}qBJ&Nyfho_SA1ZW;s=n*NI=m5>dikXcg>D(!?gHk zraHi*9ZO~^23Vwk!m~(odIpHQczAe!uX_>Bm&x49|H(%H#J1MEwSb|+^I`WN0CkB` zMhO7t4E&~3etxx*`^Lt`_D>TANTQ4YfJX%=N&v{|dR8{q^aF{-abJ4V>q@|MDoaP+ zR6dLr?Xr1ZubP8ELD>L zycxrb)kc6%mkv;H7uRb2Db)C(<)klRhRWID5GaJ}D{#p(WCA$s8otQ{{rdcZqfKa* z>5Db-94ph}jQrjH@%eRH;1jn>JjhX0J!*LLhqy5%#h5%nM&+!>Drd`olr~}@vD`0je^C9z-a%#5>vQm#uJJqKeI zp;-zk7WnsnUI4b4eF2>1TgIORRiw;ON*v_vl_tR`b&F;_Lv=&LP#P@bY)6`Z&b<54 zT_g(JX{n8H4RIo8I+|FANY~bd@_;0&tCX#bfDvR2@J}(vQBB-eH1C;U;fJewUq752 zSX4v&+rh-^5wa4&CeerKrYqeNq7X5Z2KZ*;RkX*W)wRW*uZ77w!xg?V!4==vzc6uu za&+uIAzY4{_xcekdZ&VjhhkDPqO#FiC)&Eb1KXVDIGIWnxSlBSEs-U~&i~NGrC>{SuU!UQ%T^ucS=cck zK}R?kP?u#pFb-HpGmi1EkGFMGI&davr^pF=5hmxDs>O~jU?((jc2!TXXa+&hdO?Uy zcQ|IJjs#Rff@bP#K0m=+GF7=14%{AXE8BR&*?eU&rVmD+N?Bsnoc$Ce+>Xp%5ARaZH$rZ5*18=5D=nZBA%qe zq`|*afACz9Om(!fjognTw($uG-r=zVbe}1K2c9X9tSt<8ZfC~BH~(-XnDoU$@DpP3 zqL>ZOEVX@|7&pzZaFpDNPFPYWN&YY@KT+`(jQCoc@t9_b78*26ii>(S&0f?Recm?? z92)({#28X6%VAIAe%#%!``Zti{mRZ5hW)H^r@tUCttIiID-}>R)bQ$TeM2*hGo*o+ zv)5Ypv2<3FLypkwlA&$lfb;;KNI2w|FNoyzgH5D*WSf@A2-nreaon)WieHxaA^1?h zy#(IPGPJc8^tem7s3Vdnv5hfjx)lD=y&7!Rk_3HTnSt8#4{PczIJdLA8}(0ZX3=)v z2|*;_j0X6&Y?|O|B+As0pb9%ot#WW$utZSe*cxbV)NPrP;Kyd94XB*U9f@ThvcDNsU{gqI068pWw$zg z{t;UTu+_B*@usxGeqS;{!0)A!dMX2aJvb zqkq1g0Q*KUfi0lto}8Q5~5E2vy@(vR?!WML@xo-m&6JprFBl3|H^KD21e#n{pCGq-ibWn5qyvU+)f%oBb^Am<$y-u2ta6I!h~ zoq)i*%grP+l9c}eeRJ3SVnx=jJvramqhi@8(bkt8pOT6~I@g)LZP^Ki<`RiUWgsP< zDgdMC{qk_MQL**u1<-s()^7d9c%`>%v;u@k?;I$t8pytLgnz}}zILgpUFOffihlW| z@AwNHKIS4|*ouo3hfe+;ih!3fgN)YK&0SGG-#S}=Htyb}|Mfq7txe*fX{rK(m+;xT zFBWr-1%I(YZWPwR>CfDrNZb)Zf5(}B6kdb+3xX{Dp%W#?Baa~NFahwm{_%Y*rFfS{WZilypG8kZjWdlcfUirb+0Q8jUF3X01%dWL6W{)q*fP?(gJ%_=03!Lf4@9k?_ z8gD_u44s|8rH~IsYyD$P(#K&(yaFtMu={UDbLS@>9UVPhZ)L-d^03u!)NH+MJ8L;i zv!Z2UDz2%Cuc)Y?CLA=&_Tl^|sk^wi7@L_T{-H9B1)levzA!eUK|}z-c>UsyiHQj% zum`vZ4uG71ysE0$va+wM0MR};Y~{q66thL|tIC7ZeIZ{wm6al8y*49>}t8II3?z4(|TrOL}x2G$qId(wa58SL}Np><~ zFB%5s+wGk&65HoB(|VwUyV(P9&^n_b&>(x7Rz~BAh1Bf$43CD zx8`Y*z@Tlrk|2ZB@!POE|q4tf4*SXuaSy@j{ek_UM zWWE$5lh3UP_^^PAmK#tusHq$zJ2$KtSq+r#S8x7&i@%@_=+6Y-1|0A}NUF4X z7CVC6I%Pf!$uYN_o<7=JDUWx9~c{Wk^U48>--+eY-5!Gr&+n6x1PlP zi*lOzpf1$B>)99b!2fM>C~cLAF94!&xl}@pr>(8!dIu88dX4`1#t8g%?P5Qa)=V%L zi&^K-E_ZfZvgkBa>#x=u;zPL-ABcp^%$N;Z8a}@EfW;C2s~;rKJx;B#daxv#9idG> zDAv-5Fo#dwbeTAt(|M3#TV46GUZF2i?wxVX53d_xZpL*+Y( z-0}EbQ687hdtUIV*TB1YEG@a!=7wWt_y!wiLaGx{vLGfZa~1ZRrfmMRqirZD&E>t; zcs=YaYAZ5mw(c1Hsw<=x0y5%jDz+h9Jykfj#hZ(Ra9f3g7K~$) zEcuhGep0*n%m~&a&UZ`mI9kYAC>zlQXI_NrIqZ2vfW5g#bAw|fq{w@p*nbrX`yCRb zzNGGOICzqL%>=?IlzUuUWW6N*cK4YD{j)?MAA5~nE764pm)O#3OreZTf#6NOsx&ul z;d>R^eLJoZFAWWiw6A09$o)V`TUfYoNnPK+#jQ|DfMt(AIyXiH;L6RLfD z;@o}Snh&S09rn*+=yHyCr%VnGZ?qyIPMpm}-Sw8zG4MD@Yo^s}&>-wW4nMqgPHRI! zr3TDoRV9^tsp-_5$g}9@By`+T6!dThOH(TaqkFeoF3M6mBVm`5{+9j_sDYq*VQe}? zjqv%Ik|ykrCyCW%ejF^a18=QnC4XZ2*hFJv-o667+?@S*y|Pe2R)z?Vxz!%;qm{6P z4THq@8DJ9@b$aTaFFjK<$S>YNK9?r);EP+d@T5nNP3SB1ON0KtQN88sx2O{i4)bnT zxxQkR=~fd?({4$MPXypGdj`34g;z9IPaFH)n&TrEnkOWR*;3&3;m*-$Rw6|*r2l%( zMR-buxfw*X>2I%`WxxGxm{DZ#E7IxQ)v;2|_Q{=lNsOh5|oMmw34RA zVcv&MK;d(C*0Z8%#ri#?_jTXwmX8#DCPdwgl@%q2ahyuL25 zYVE=m2vh(xel8tb2huPhZ2h9S5gM{xD)4nxy{Rxxf^-J#a}Ev_O?u2{kct&Pqkh}O zA~VpUTh)G(z@Gj-cl~W)I{9z6efghD4Gja6tt)Lt&lm5EbLTqdA0E3s>utRBzCyYn z0k>7_jEW`Yy(|Ty>kZiF(xxP2VcVa`T~4h)nWnE-Z<#;YCys;VCwA4SJco{bdU0p` zkMIlq^-Ig_fu;SU=e+4&q@<1Mwq-NH!Ncw%d&YOgDvQ4c^$rzNL;79WW*jjnPLAr@ zTC(kt@Qf$R2^?^b7kBHn*1Al0qT@I-3Ma0KS2iCX;5qGMAwx&`qa{OAxgVvT6>Jsm zAG=XeFx8t(!D=n^TF-ZiIaVi0bQxk(QZS z&023V55+9t|8BQ*2Y|4g>~z-}lX^+OF===+$8Alw9v0>mENiblTwN8i;kk;yc|g(i zc!zBp-hA_8H4^%*G89(_8PxPHA85YXY&!RKquy38BfUp^n0}s$EKlqT#b+%4xmoQq z#@bx{M*KGq*e_qWMn?5zD{IhWBlA$Q*2}A@sRco_v9QY_>}nyq2mntd`9g4!1)y(o z;wk)lG1SzQZfP4$nnn$X0$p!<0UPil4Z>V6^#ehMv#Ro68O6T;xIY@T5;jBm-Ecy?f_xGRL8Dg&OQa-gdV2zuPvs1 z&AdjVMqf7ayYlxQ?V(yD3}$L1#-GNI-0a?C|3Z53`)tfTGx)-PHMrlYq~*(J*|D~E zPfcD)=*pK#rwlwzTChI(8{$TEJ?Eh#`8*my-)!gVXxh_@G;PI(7y`o zwa56=_+0=*Hs<>TiK74TlEUFi9~H;{pQ4_3Pw3^w%Az@AYBEP$2rtQL_(fSj^Ud!( za%x=%i9~*mLifwE@?{N`{%MIQ?w3UQ8W{I}eqFsOBd$$plkRnp;!)gl&nKiAzaLCk zwGCksudnrKTZEYFVU6=N%xmSjR1_pb%V*Y`g#Vnw^J^cE-{Xs^H7ik9DjO^|L*Cv1 z4qI*hrj#4FU*JWxEln3|Hnvm)^Mp2e&d^_vW$ZNVI$%kU%zIq!TbI^6=@)fD)I3+# zfYs>HNZ9nj%$VV8kmwj9*6jCz5jTb7^%*_L2CE|Qh`Zv-hf&?m=xL}gbAfKU>Jn-R zYus9I$QXCg`Brj17ZzcbiFN<>8&a8jTB)Sjn!>uJ($+T36XWI2izwR6m(!0op5h#T zo!rsC8iFWWAI!c{B%0|?=SjN^f5*puS1|5O%Z0J-?~;*?tvI~7zB6@=Kjw<@fci0b zbefZVx4BTZiO3d(n?$vyy@WJwDKB}sY#tkWG7koq7;wg>gq+^wxOR{nNc)_hO`o~E z4?hv@N|QxoVQcr|iL5XF{<%EcSu=qC(QzYb${eI@mK|whXxYEr`*w8{{qD{ADRV_1 zcZQS4eiDhb#o}b@^;5uwQHl_)1BCE+6;`TDcfJ%CVI~<{1?`9j5O9j<{rq9w{m-rHTSr_lP_jNr)8zIR7kvD&GCV*J8R%i?jKszQH&7a0 zPrJ?P<`>SlgR|Hf6O5AYK2TCjKj^uo#-xZv78Y)79auC93oG~tUq8&Dz1`1UGl)^r zigGpRTQYv00}W3#PNBu`V_icXkZ;>7C?l#$e35R+j)@+Z0oc=m(V#jn>!5^pT=8Em@*%vY`SbSIlq*-9C| z_SPB0Js`t+sC|>-&iwIrCp6_w=ql4Kr$Hslr1?%c+Nk-nK!$L5YRGpR412>|U+L+R z(BW}KZWjA|Yf4VJ*fDBrN?yQoTc<0FWGFfpRGfXQECa{pyt3(jTfeYy|8^r4tJ@O4 zo`%m}DC`%iI){7ubf>ICpICzKj>O5IX-$_8Qi=nVk4kz_;6)HWZj|Ze{Ms* zemqmOTUnW0-q@Q5Iz81+@r(J`FdWIHpgwijm`)AWTjRNbPUKtCc>G9MOyJd; z`P`9Kkq9BH>~ww*bKn)y{mk_F8kCHPy_C!XHN!QjRU7E=`GUgqa5a^|a&yNU`>~7g z{OG-JRymfslLC&fUc-ExCz3Jyh^hS($AoAsC5tWdykgPa=8v{#FWfyI zx@J-gG*Ppil-B{)BQn8Y|6ZItclN)*VKN8sXg^sB2|XxOxU`jwTnu*&#TD1(_&-hg zCad~<2M<|*J?c~zk8@e7sb52v^nLK77qle7?h4&7I$B+-rt&j~;Pt4W zt^ETh^V`PZL!Q6YT0;P*jXq$cByoVs_6BkEnVy?0staKYJy!^FI&YEEbos{McyfTb~ZOZ65R3iNwM6TvQL z8%T>=if`@kk8YGninscG z!3b;pga#TLy>XAgCx2!8gv??t@_rlZ)EI2bUUC>gXORIpeSZAV>_~G>=j5>X6gS}8 zl6){&kh|rp{Y%)Tq#nSDfK!*#mgd#@{@)B>V;!N8+`fJ*U4*`$os+F?q1S$=UKfxF ze({V7aj|t%=v=a0U(T`bJX|p&psyBQ1?w)uOjAPieNeqTwF+Hvq<7o)+nVx|{0O7S zMk1oV8aWs{QTa90V$j#yS-oI6;1U=WlFVq_zjQrepW=4Q-`2U@*n>H~+qk`ak@GN7 zsiCmZkj11)1!Xk1R2k%Q)+_i8`}fiUv?4liR?sP<<@{O0XOjJ=wsB5PL7};UvFfoa zzbUD5Wku$U4J>(a$w^vO_1uHepOaxtVWBzlb@9Rdy5HHZ+%wmncCE2o=Cut@bXmW& zdHcbuc41llRRq!i9x%e0r!5LwxLCMyzMY*>2tJiSODTHF(|Ji=?btQH$6%jnDzF!S znW)@JJ=^JyhNLIG2mP{L4PH1q0BkftSq}GHQuVI^3o6KE{YJ@8x{v3qmTe0;=kROb z1Uiff6aA5^56-_LZ&TSc&@NGZz)SY9F6p@t;y6)QCOxH$Vg`DFUG%V4{Ln9NtVem_th?N1n$@4q2+cQ!`8;(gI#LP;FqMat z(P>NKN@3oFLRe1pe02lx1F130RxVmHCkrMy0*+hVm^zeFg#1DHd<)PEe^+l*fr(aw zufFDVGol`cx_J^v!>CcG2g37azi}nsJzW;AT2c)i;m4Qd3;XG&PU5a2gFDZa zJ^Sq@%@g%sH2kG$p%Qdu)||J0b+gWALxgOWg|W9E+=m}L9kl3|*<%*5B5g9$lyWqD z1gSqR>@qx~ThWtRHtruiN7ib{@6>6oC}_#D z#2>gS+tmuYaAZEhr;2~9w}KfjEjTQJo}7Az6SP|`Fw*|xzZ3jONzLTr8s>Oo+K6k< z2d2Dj&xE{p{}$M@QWog6(Asw277 zUJjPw!9CaWoF#c7MYBdFllmFf{&!8ldIe}e930dkvl3cO`ZsSHyY@9zEh$3QtHCh$ zI*pMaJ~u}@nTQ4^a*Dsr>Z0ku7vou}0es=^22;euJg2lH%>C^?P~(-QJ-biJJNDCq z4ACI?n&ZU}9X+p@qjp!MwrVGvN~qC!_E7In0VXg0ifH|7Y-EJaSNOOA(WFk(4Zq`D z{u)mX&aUiYx69znT9zxu;julo?cwUK!IQfiBVFCOrfB7#9g90TgQodGV*_8ix@3GI z7psSglx?gLeltL3DVsL3$|WC-)zw>^xhgAZj((sB>RX7s_oKR9ZB7V=QRKFEnQ7oj zdGMbD`GHp$?yjVlWuBZ^AvM%8=HCX`FUM-{wEm-_8xUh;xj(o*G?5c#Gf zz6+hBy_kmg>w}5sW|T12aTk`qCiJO%&SlIEPZ#uoxLuehCTRR`7BX<4kW(hodf%BV z>;pXtX~|35DXB;RQ_D zsJs_E;6~)J?^|CDH=%KGH#_u0S>A4mDybdwWaxBFXm&1a7dH1EHBW15{kQrDmQH%nG{DeU2K+V4Gcqzv1F?}W70|lvm`}NQ4D+UE_G$j zZf(%Hs{sZE6(BJhGbdJRap+Hq6)8N2LtRB>#D4X?_j`^YVT7edi03Q*JpQ=L>%`no z<*PW7>dry!E(BpBg7`R$)UAxyEn)?%9Ko5nt}m8gCHePmC6FA@PMKTCmg}%3RcDG; z4_l)ml_<2?G}|5o4A_Ojsur4JsmLHam-AxNEU){k0q`jgT#e-S;nf|K7PV3#qvnq{ z6!t$75Nj<9=*F9I3SAQ6{1)#QQu|q~pwB5idYhJ(>~|fU>%Tm&Pw=2k6VLWH)YNYY zk6B=4U0Go?q4!58CeLEQ?9iTRI^q15^CyKY`+C*I9gqnGJ}ExK&xp9p!hqci_SS_b z^nYFe&|_0p6ZdvAgQqTI2l3g%Ru{Z^m&U8tRd{V@)5#MfoOyC)3hR@sXIoXyXp0Nvlkg#-AP<_7efz26JvFQRmpwhNIg z!VV@>E7GK)3g8o)qJdM^=MaTqy=Z4Wnh1h8=%l$+NVVy);(2M~N&Om6(2L|XA;oe8nzN}2nYmO@ z9oWG%vU;5OWL91=UH7^C5cw55K3u;eF1i90v#uHyI^_WdWzLLX$K+ywxWo$q`g4AJ zfe`#N7droF)vqn`;LQcNd$Cn#&s~I9gmojE6-VeEG~z!WZo;idYbl%J0SFP|YLqXr z_A(^je=%Q^u+aThj_8Yb$iz?I(N|CS8iO>Jpix1?x(BsumKS5*hioA~J|&Bo?*DU* zH2lEQ>om*li)r_yN_V-}1_m-I}%KL4idT^&!1;RkDq?qPR1P*l>u^L zk;hQ1>-mGp)=)UTh3|(FIWOD$JT=%St;oT3bKv7Mb1ovMk7JS^>*&{RG?bHlEYgG{ zPt0PPn#_>cx)Jve-*cAmQ=HK6=R+W94p*IF$q!XYojzbXGV6cmi2`Cnz!bUTAFQ2W zo0#wf(7jn_@HCTow;$?Fovxn{MZBgSWlm8~Mqxa^jb|HILP}q~X)h#*vdbeFdF6$Z z`8!iHS~D*Jo|_GL+~jLYH9@m&KcW&R3?7rD{nXyQr)J1-bTS5usWk?7fE05wZsAcY zX|F&s2B94%=GOoM|AFBjPaz+~abQeg(t6SNOyyZm?Zce~eB^u|p~H^$;Imu|P*HrK zfYxr*@s)*gp(C)mD|G_0Ern-%G^thC_a=-44E}B~@xi|&39@Sx59eaWw|5DG&-~~q z7?if&?5_3c_x$v)e7I-6hQ281eHUy6*@D0IiF2nR;8@mi;ZwsTC0d2zQ%>cI6TPe~ zak0&&d(Yy1jrvt(pkxzX?wi?lD))Mrjs5PO*>0KR<>pf6YID9sEa7l`ontL<%B&JP zx6&uO4)`nPWb-G6hs)&5o`SvRA_n{noR%RWt|;f)!@O|zSCad*^}~Qgaps^!G1aW< zzs>(a@{6-2Gu^aTNiKG1-hXL1BG1i=q2-Vazg_yG^seK7 zjIRZbgA%%gO*U&5zVWLyi?IkbVhHAa%LGQWT58b*f&H2cStJ-Kq+%zN!uZY27{e95 zJ1hr;c4`mS6WPDyZ*_mmlQ1#=lETYS zm~26qSK^DHEc3=kIW@){vhBuo+`Fs(JW>3g6ms3naix$E3%R?T1ZP(E@sphpAtAB7 znMg88fnb*;XV5RQ@6#ROVB8{IW^ktBw^x1hXT{P&EyQSLcH()#cR5)zWOV^nrO8zC zex{kaxfhr}gZBnOcdeVz5F>`}2Dk2>h2%;88l8Z_?F zAGGo1E;+72lc)3`nB5JsXloRJS6(2*Ul=CSz6EPv11%hzmK8xfkC+J zF9lb!OSaZ$eM02cePDj5A?H*r=~pT82$GM7;oW*mRHe9 zSQ~a6HmnTxtywgdfbj|rv^d&oM#?z&8*6HSKZ6rF2?cEJUdD02HsQ?`!+W`rV*7It zpG#Z*iAEfa=xnF&+iNpfyCy2$*Z;_0r3;9#rAFQ&{6FnPkf&G4@*a|7W(DI))m2me zj>l239?OVl1vZh_Nf=3JP}!4+mV(zH@t`VpYxGwK!|-H)DGIuQS>D?rrRJkhxVsAJ zb(zv`6AMqy$AmM$C)|WVCWOnpl-a@88*u!imq2qkbvXhv3ZDlb(GQPHyABqfe%uv$f>DgJ;a#h^7kFf*_#3vN`hbzzvlQ&ixl{# z9PVsuZrsYVzI)Cz2eT^Lp5B5&|0cHWkg+< zn+~R;S$ST+g8!2#nIh`EHh74kd*q9r<&uknI#TRbcPB&(>zsDcq&D)}!f?lZ5Gnua)zsS?&kWyl;t&#iI za~{=ETv7I2u?}{1#q}I&vx?9aRpgP}eHrTv)@DV2PlG|OlOGF|6|Y6o6>ujsxsYOS z)NaER=!~&cDuAUhsEuzqV|{}~C{ofDGp_y>AM?28>7$Nj0s#A!%}@%d;0pt`;5#?2 zr)?B&iBQGHQ=L%Bm{Z{kVrCL4gA1j#3VZ*vqf@$?Ld6WCvM3RGy};?O>3LWAjLob3 zi+wW3f-v>x)l7~)B>v?%(LCZ(?2uec3rqyNEHq1SQ?4*q`1{ge4i(GS`*gUy92O$% znTHhk-^a|)&0-q{6ls-CoUHOg_Kyqn&X8?(64XNs!zU+0Xm%FZkBRGIZG+DmM|1Oe z1y-Dh42*^`&EN@MvjL9c25th|m0=uh8o3V3>`;neQt-dDgJ=md!f_kHmS>S9&%$&` zjA9v#e8OF9VnbutRoQ*PGJy0B>y%SHCzMk^Gdv^plG_7f63J+378V{ihp<6CpiJcp}-7Ra%ChXuXN5G(nTyN3Fm3Y~uYxCRWDfI)bK8|!F)wv0gdNojqo~sD zIWp}Apt)=y1)01y_Y7u4ouH`)Sbz|fvMb>P-90ouH}Z$ryRxcQop`1 z;i*Sgs4^CG`4j4Lhx@vt!IwKZjflRQ&>u(LTf`hz{?UpL3PGDemlT1UXr|<>N$Ou@ z=@S(wyDO@FVZZKt(d!E@<*~;&w@6caSLJu;7<#Y!GaaueZWb>B^I52Vo%yA7PspDJ z(Ft8A_lCYG{#=aT2@%t7r8kw$)c%9OE=MkVa#^E(c(XAIA!4dmPAvE&IU(dF@Ic?8 z`$lirB?R}YqY!z=g=j$}axjOTb%1rGwq)uS6rp}L1mM%#eKR<;vj&Tvh9n^)h{(C7 ze*#Mm8h}@eYYA(Tq=%iFP4tFEJX!ri;^=ry@n{X15YmKGR|;Nx`l9Q%`7P!9v=^Fz z<2d2+8hj{IFpm81r{iF2{w$H7IY@2;cc?v842LiW8CAQIpiLh8QETOH4zZRmx+0j) z@I1Lsr0}!+#>(3ZV|r4;%)&o#$oeuLn8o3?JifKahvn%Qiev|=b4vA^ZuiaT-v#Cq zOZt#Kn5e^Nly{XwuW08i9Tm{Nz!*Y1zE;O0^&xK8Es<6et37gIx$1&4Ezx?8mHHbW z$qRgaqy;X%1yg*-s@D55%D|yqq~DLjd`D}j#Ob=2{iH*9g@*JXGd|XhHViJxF^fGS znX|C>VxUYFYhAEWEGhe?2u5FH-jXok4)fT6dXExt`R}$OmYt|eBPn)_`a%s!%41Hx&CDh5HH7bNQWh8af+l` zw(Ogj|E|X}f$1^OuhPT7Gm*`i;u+5H61fXVT+Mk0Y13(7i_U%v_Ta4;oM&b2{5&Zb2N+_+nPayAu zH&Dw@h;r||uu^MC#P0*3yKfzH;Qy{LU*Mw!u7^KFK`Vb2kOj7|><|RHqfOJHWH25p zz-UF~s>BK6T2k1HB{QnC;51*|^M6);er|;y>TCFt(Z4u)xSgp=kx|I^vi+?m!B#Hg%NcQHN#ADwETk8R0tk98%|_h3Y;v&d5~f%})xP*)cnNO6xof+A zRt0oU^fL<0PwEB)n=r^)muel;3AhcWa^7JOPy}fe^0#R&VhSwYch6k_!?8bl9=E6#MT|5 ziWbZ{d6VBxgb_;CnOL=`b~QIx`ayI9U&YG_AsG9Gb8bW=sScmFqAQSOkO|PyT@Dn| zDI(27=1mAdFQFmD2EB}+HwF+N$;^pQ#P9)f|LR)z!mw|5H&j6f1WF=8yhBRZ zFgpWFWsTp+7nP!RG%K$lR|hqSm&(zJ0jYCI`9biX#BeNg&^vSme!9!i{O6RCGU)Jj z6h_CZ=5UY-(bMz;#yaK?-MldOVm`S0oxq{-98-*kUpia5X+V#=>RjA`vxskRO=faUm`bU5O)0*)cEnrA zu&kdMA=NCDnq}%_*xv6CE@TAA-=ed*=){EPW@=<0B{JTbRHKJCKetv@%paSXRz)~G@MzlO74q3SSb@{Uxq=G$C-FGY@E!we0V?j zK?a^@&(8Z^_u6aeF}YYMKp5#9*adP%7ZVyXqk6v%)dt352KCFyKD!~SRu^foK88ch z0u6fSs!|HISa>wl{$vYq%j}q8v%OYwmo_(f2P- zSK018A^N>cckgW#OY=kOjQ6JpD4sv9JVKv_zE8D38m- zKWpi7Eb1$9*N;Z~G)w*T4KL`=iygzTkGYGq(kHaNdP$k<<*=8&WzBvt)1V?GDaV&0 z{87+GW{^(S+4tAINykL{qDnGK!w4KaBcWh;IPy1^qm_X#dsdXw-%3 zTeV_nPIpi!O$UY%`iKv%-@#T#p`);~jOQUwk6S7pX2*Ql$)ZL}+E^>DH=n$9K zJ@tHWWABs#S7CO)e%|5aWlKqof|vx$yGPG;noDg(6_?gZf<~EKgs3r7$i`TCF;GX$6LHp@DrU;f zYWfEKHhv7LTP(O=z~@itYlE4$dUDUrFrDbw2)ehqmV=6bfvy@j2&yTH}ZgPxr!>FLqR9aBX3TF{iYh8$CS7hz$29_sKuOl*tT5 z_-6znQXec`$glT4E6s{PllBZrAs?kH=vWnmRbi^?Lpn^TbE`6b*OVG3;_tYAq2di- z%N2;n$gxVmmrpIYZClQ@4ioBTz49c$WVJia(rvA+Y($CjA$eQ>FHwd^r@4BG!}S5S zxufyJQ|zKjYPqJiK@$Z5slQ%M5Qv?05Os|}@)TTazYL!I0_$p|-kG8LQmxzK2VZ~U z_VQ^GosJ2k6T(P1l;J4?Mb1Zpi?Z@ssq{B^N6*J0gy=+UEol zcX8CIZ3@ilpSXzdyW8So&QNnMVJ33=>EvEv@YzSla}lTNDpV-1rw=zRj!pdtwg`*{ zWyy{d04JbBPdNSbkRLu85xZ7a^6*c(F)E$yq+Vfa9wlUP5yQ916qA)sV%@HKb7dM1 zai<*%i}5z2E6#iILhv0+goX`|$=nHag`S4M6XHHGwNxz1!Roy8MKTCvj;gL8snQbOmwbEa8no%MwejmR1xMYlS3T zickoabC^N*eCKkO?c8s{?tixlsw-?`C7D>QvhYT7TOtfsmZ!3^?>CvBGAevMR9LF} zOc%PjY88VKh_-t@!It`PXEAXOLp-seP^oa%Q|f8AMouSwm`pUhP>@!d;m?UuXE3*R zMhxDF8HQdl1i|0jYimt zSE8FBd-G_Gi1$Fn<`+31dd!==KLpnQ+?;2q5HH59Myqlql^#1XjJf&4_OgRY4LhLo ztLzGWt8$?`J7*h|Mc8-a}}cUw951kriT1YE8sv-iP#FqNna})%V9<1lSK0^db}`suD&SB6ME1P#(yBh!FpUu8t?;At8&+nCn+^ zSC&Y}6Am+S;+}hc;X)&VGfKISv3oE0I(1m#EPdHaA$G}o+bXL&?yhRZtMlb8eg160 zuCGz}T~jU0F(>o?O;BP{B(kR zUe)bnox;)XM>7CM`@CH^Co!5jiiq5FD#=Kw@ z`-}c4)Qf&QOg>K6KiBKLG3qF3ii=e&wJu$Pv_0%2NJ^|#3s|+odVy}ralMI zMi3g_5tS(=tMv3U99gDUf5+8{2vKlN(mtxmy2~DYj6pFWXm`zEC#~CB z9LHMxTV*7X8~DN_?G40Um+lGEnCGriR+uL@bolH;djKV>eL}3Mn30{2sqn-Nby_|8 z+hYEz8SSE^adGMeoY6{3ju#!S9#eMMM|y0*+VI?^&$;21dZqO6({)irb-dZ4D5Y#_ zZx)vRL<`sx)k!lWqlZtu9sQaWelc{Z6I`#j|_EIvH zhupaDLc=n}NJy(cMep|}sC1685Mku^^!k$)1}&8h^;(L!d_H^Tiu)TYImDHdjX~|DR0+I9Iojg>+?T^<^b%)UKX11-Ue&$6J)gl12y?q`%w@e{Y^O+% z+H-s)yCK-A`8}obJ2SSa;8TY}`4?1Z5eYPMHP6ySxjSpg6^+zo%N-m(_jWrGeX0rx zicj=-k$-phCh>nzMe2M~%mmdA*{el^su}D8)7aVI_OJ_xRL=c<_SFG}3TaPj5F?S& z?eosfZ6k~=>XOve5vKB3h1{Q0{{)IzCR83I3)Fht(L=hZ8y^u>w}fCbo2YT5&aXl} zH)Cbzgxk5>aq%p77ppp9c04A|qqZ>&imv#W-7Iw?e5(<1^^!(<{nh~sV9nEK0iE{NAaqJgGM0*( z<3mfbBwkvasT?>dwo@xV-sk}|_rAT#VP4Fk`O<=b4lb>N*9ugE(uC}34E;{Y8PqEm zr@_5Wgt#Y<^qtqQ6@ANuwtEIPrbYu<<`m_!F;cja`x6t2dTOe$!5g8qi?c@<_qMIt z=?u5xiTdIQi2=+G8*!4aiS%BdAHQeJZ}L~caQh&nhrR0FSp)qT_8PUYT>_^n{aF|h zr!Lp6IQ_%jqwb`q5G!?sl^6bLb1R)OX>gP8q7z-r|0L*?9>22F3HDO&DVef~|3@ia z%s*Bl_m6k9z7Bu)SAAZwFuMH9A`fCsK}M-D%Tvn-MltchMGyHo+W+*1^7HTL|L7G+ zC)i_lzex#FoD?r}7a4OANd&S5nC~O=h)znG(e9L-4yPW~uuEDTjT-4t^)x=&?QT11 z9)o8G@6}y-Mzf^KDX>1b1wm1Ze3J_FdNHlH-MPUraL*o3dALr!~m zp~T+pxdB2ZK13|IuREp6{G&=ETONcL8InGY+A81R;A zLeUw2x>5ZH@=VvvP}W1Om$H{vJVVgZ=vMkNA`3!Q2Q^}Op+_BUp&bZ zq}UO|os6_R#5zhNY=R>P>Nt#k0(4O|;~xYhxF9LxzW9nS($nYYx%beAqxk*abmFfY z8POi~P><61A*&4dI^pm=c4pT-EHhR=)s`$}-3^~x-J{Y-dqAfDU`QwPy#mOUOyUxY zUW5nkibrm9KXuR|y(arZ`gqd$F-K1T|9`z5PC(yZZ9ZT%&c^pX)?vQk2*?Y&wqZ~v zBqx*Kh9h}|rwB|5^<(Vjc4IM!?r-Ljoz+%!Yab7RrnutzpA@ge-V)*GQeta){ZitP zHR5!6Cq>1l>BQ^?2`^l>WKkaDZR6fFxV^5CZ#iHtw_^8y?wWQ0k!VEl{5ds8d3RzKojpKESDt)lPWY}~!C$~y6Zp@BGB!}=&4 zN>D^_B|iplOytObmnIT86zlx@Z~>X6codsJ@a^v97n|;H!V2miK=~%Ro+L4k;Tc&a z4HWeVt&y*53-j%vv!8JlOw1wK*NRli!=DEZUKOW^xnfA?^$pwq1ZW z@DwY)IW z(c@=ZKu~@_Q(dwPUwBRiNFLU&eR!eMB;vuY9^cb}l!r#@^GttZ2O`f9pn#9mpGP+W zi$MheMRGlnvd~D)=x-xZFWhTGWv-A)&PWk#aE;w-yCBsI=x0!gdvM1~p6Lvl*8_d} zAL}V^MOI_@sh~zEZw$Q6iT(igJ2`l?1(5gu`0=CDaUVOs=ij;TU2tLio#(te_}MS; z7Nn5=knrLl*biyPkOKSQYQ*R_OLe3M2(tZIk}IBu`uamit?jMRJY<{wuKq0pxfJt- zCU3qL*@yRe^*E7Ii3AcMr7M!e1#7&IIeUu`{dys6?G^WnIKFOB9CGGrqHjSHy@`Hr zJO3R&4=%_LiM@oIdAsE;ev2H)DEs(}4F3`qOP(yi5o*pxL*HTPGn1-ekbCiq&IfLq z;EG@-%V9U_7yiM00h!AA(HfTD<{5;;UO}J)&ov5s;nd=ZAxp5xsz!(gihhMeGq~3f@Y)&Cbb-}iV5u;=&f<%hMdsgG`eM^Ucw_iT2S*6 zmNPgV*81RhZvwqH3XErNLvezV@H%C=Jh3o^g>Eazslnb&1@y`p`7MX@YihPBoF>cl zk(!!T>D_M~e|F6}whWc(e$)Bs<1U+iwAyph&sFiO(bJKW>yrauVDAf-H(%M@U5*4C z14Wjjo0AbB_M3nh5C&3F1_8J3Qg;`oK%K<9I`?E9E5a-1vpq>I{&ZWI?BO3*&1}1<9_|E@w-ENLbeEtSZ=H9-(_sBBEQz*r~=~=5Vb-%1cEZ33SOil6<|Q)FTtbh zL62C^H@Htd1!wQG4z{J{5Pdk22sUu2F;b@5W^q@2U`tHkKqTi#Tpj5f^4oT4MNYJh zExfCD8D_kv%gt2d@ z@)C1ed58rVC9>ePRDVEerwHx-8DiYxN6ej>IL)4ouA;&|FZ^qv#{$U^`R7mwBA>%;-% zbKI6?hQijOW6>A7`=MTr+<>;q*?r<|febbFRdCx$^^*`8B_%(Q^wBPbj^qJV2Z9Ln z62X7es@mEVLZ9#(=i|n=JC~h|syY`~vjXnC8NAnsXX+f|yG(K%7n_l~6fDAT=yILVsPpMvy6*d z|LSkwkb2jBBb0CRJQw{^!Bpor>BIux3sBwH2?H+B7X$7kQIsD8L5=IP{k-qrDH`X8 zfn5ji0C5^T0LLUXisz%YJ3Okt)h%XCp^7q?L|xtlEptx;!b>kwnJqA)iME{`@;?Pv zk-mD2alAmm^!}HYbBADf6-0g|q>;utrMQ?^ZB8egy5}i_LGSYqrB2Q5M|Z36Ipa#^kIU9 zXkU?V#Di-^m`?S|!o8Enk(JjXOTh8UEg-0BUifh!E}kR5d@Irx>SEe0~hh_N*kqw6A0~A7LKi7*pQR zcrk^I49U|)62>N2)ZAsN>F%{)fK8=>N;VuXM-G>N%?b4Ub3Lgd9H8}74Nx7=`=MKov8a*uLd?GrYDJdz*26jg<_`qjo^nj4K+U`UdHJ{0Y`->jwFU7^r z9?R+KQhP3VvjZ`uT!nZB;F=OL>(Cf`Z+S4hn#VbE7aw53mXuui;Q7?EiAqi)vsV=4 z#kg`+oZ5ah?$3UIr+6ZzUhMvC=I-N6u3rsWd3^4Y9&wrN6C+?3tplxwVO6tMllEp^ z-a3z%G0mE7WQZoMUHkv^qPG|pJ%9I&MbtHO_uV&~M(4uYPLko4&xZ5K%ql4!Y@P zx*MV+1p09QpQ?`A^SUq2gu9nF_x*v*UsC-HDfE{H0(FWl= zBFn1&?&LH>G_{n1B9j&S-gU;*rFShXiSjG4%bEP*7#mhK9@xz-iIupAv1Fb95j*9(Waxh za^EEt64~}ymmCqikFR&9g=pM5-o?KT?-PL8Lc}mhO+SD1BE-+?I^b7%{d}D>lHqQB z*BFDcsgVy`gpvI6UK2y?r-(uEn~>)!uRUeix%c2dR8D>iEhfHHIV7FT0Gd;^C2y9B ztAl!O<7ewq>}N(3!igp>3Er#I)$^5UOIIE7sl8U=ND3%4;&BQyYW8@b<^%hBeu!Hn zQJz`7v&dqHamPhV>)-y_SdD}=;O}=6DMZe{h=zxnmG=QD@?=>ulCOwJDXvKT5}zcO z_PHV$cf&I-;ZgilkkNgE!R=WJt>2rlc8$UKE!Jmt*XSzA)$`<|pZI!)oe>T)jg|LQ z0i@(|c?R{baWc>RE2iJfp3QxsZ*+`A`I70Hh z$K_fG*z^aprL#w*g-?Ph$;n6S91TrORaJkb3)*@CpOt~Sx^^Ik1TLN80_DlvT*yR) z;RyIl1bBm5{rO6c+)RLHiey1S!8-YHywnv35Wz)Xie%4v#Ltg3hXTjWi1%h@4~TR{ zJ@%+jDD~Zl83S(kb|))}zI?&T9_ayriPnOtPgfMV?_nDzov2Ib+L{?MjRD)fk_uj} zZYDh8#ae$)sSB!wM(fh1UTl*-qUGuUMc?Z1l_o`Dd6moZG{^nZ53U4$VM_fIXFuym zM`xMVTlg6FJ+V1QP!K6}4n|CgnO~qrwE@&B*;_)eJEI${4Z49&y@~A3K???J%*s0Q zjxL0^2J>Z_PSEAFZM_U>@>L_pL%p+^c|-9>sIKjgNbDV(;jN~=d(w9`-?Dve2M;P7 z?R;ZC)3-H6=BNMCWcC8XA@LY{m zSemKc^<5BYmPg$fj&IK)$&ctaXQl?|z);Rom9p54y_)p9upplr=A+tAg0>VDEq7uO z1oWJa*kCtrGt8)R+t$ePJyt@F!}0pSB?#lZ{*6X)D}f6@2oYyUz}0v*m6#jHGzlG8-52o= zLr1o`RWe5%0}U@ylYfRP70QqQ80>~cZgB`XE=T~6o;Rxvz)@7Y(Gge!y>8g%IDk=NInAq2mrTJ8Q%1IJ62(8$Qh!A$YgYanc&kwGWswk4yY(xqTC zmal}2=;!9%nV6bdgJqrEM`RfAbH(Ius$sd6*3}^Y$Zu*{FxIQxv8LeJZu>LIAjC^Z zOnhc+%mg%KJJt{4H(h>g0mn3?lr9Da2AzagLL9xgwzZ`T&?)=x-|?Cf&}CFtR>mpQ ztL0?uSUox%&%XP(ThWqr&~l#z);9?WN&jR#qjVOC05!F=IzhJU47UFK{Eu&fq7~s8 z9Jh8mLgCUd28-aYfd-*^Ow?JYi0zR=G)L`*0IWir*+`rzqj~%}mHDJ>tuxa>&s)XX zMv*@@gMW74ps4?@(*OJjR429}Mm!tGf2xxIN_Vultu#$Uw^l&+Z9Qh7cLc$XX(q`F zh^$$BO5gz>)TEvN)&Be{wap-hD5}+#VsFG(4HQEr#0wf$$z?~=(uRXo zCaAEqDTRF6oYBH?j@%;&e7<)Vbx>@hgnjv4_=P?+6 ze85aL?$;{Xx`!pnfLLApgIGyS-_TL*zPW_|ZsJglB^eE#-0j*u)oyID9N95+HZd_# zR8=ke9sn-&+0eHfn+4&&*2FtHI;yeL_deJ5&cZC@n|7( zQsfclIBSu*K2EyX6o#m+Q`6c3N@4Rb9jWv(Sy$0q*2XgCR7MdfN9qdVl^ zO}Cq1myygVi{6O@tHJ}~t>+krETiSpe+cuj(>h|LXx?&mG$UNqF~1nF+NDZg-itED zeU&3XowueNr66R+f%&=nvvA zh`G^7gYP_pk?EsTC*FI3Km7u2k7=A5hT{49T4J;kcN(xH3_i0e=W>EABP26ix{o zHf2poQ9`t;ZLfm4gw@+Gr3s8otY|wu=K0J&{^4yWPvjWK<@fYmLR?iT@A7oe1t@fQ zS1KyzUL8#+5856EBoY?&Rjys@$;*e6cfi50kX=(2LZ0ID6Vpw-^?sAufmkT<;}eB1 zBT7PccTDM2rP@^}T84<~&@Tbn03N7`Y{7!za!Ja++9BPth zO!`DWJ73?>jDOk$TS)Ic5e75vR=nt{=3?|a!;ySNop@3HiOhx(wNBH!1iM(+O9)9E zGeTRJXK*p8|0H0K{b|yHd^BOu<79^()4TFiw0JR+SK~w;5TE0BgkLbl3X;9Z)L1yF@Gfava|4ciT@Q{}| z8P3z5Ay7HM3ezQ7F>e#7&X;;__VTA_$zoxhaN4~H-`m4tDYWvg zjGQlA#F^ou;`LG_&mtA;CrslsB@wO$-=Hlf5k`74f|U2D<()Ns;-nX}8;(o78F*i@ zU)mB76BA=Af5z{5f|xEr&2r~R2{0njPEN{uPanlf7R?tq=3iSH-y_jurT84(4pr}W zbvbXLesNL~XK-3?cSu^B#4p>a;wUTV>paUTfwOa%)X{x$fVCysjXMu-~Fc{3C9JG6at$rB;XPu+?(=v&eyki`YfOC}kGKp-R^ z(FR$)>G{ZudNS}M3J?dalSUtSQ^jf3LLRVPU6B{I=T_tLjj(g&693sJ9SpiCt_l|A zi0@FbSfsuhG<#52O zi}WZ`0&QElu3d)57>JTx_Nfah1IXeT6NQ!I>cu6@!$heu+82}LG6}<7EV#Iue!TV8 zC2)Qsg7iBt^!By?yOW&{F(e#8^%o*u!XJYEFfoc$WZ9!7|DxTUQ-KWp(6j&Gr9q-%}RW{`zoAQ=xc-9rvd(%Ki`I4 ziv)narmDMCMd@%e5}g=6Jr zfLxl7S`m9qyV3ME88Xjj$dI?3uSwoxeSsHi4<$vH zXBI9r_Q8MG^RE6RuQbJu9$FrEDhut~kyc=%Bd!{zM5I_Ii%y>nDjgVYys%bF5}aY( zg9)_$+a52Yl85C#qu_bB<%R`;7^h*r!yLr;+rv`2z#_Ks`Kuiz+cT-kaChm}W`o|? zX{J5v%U=&&y|*SoBeVCXKGmpV2u+LltKP+KdoNPH|FBdA^FZr1Z>67doi4$3)!rLz?}*|5nP#ajhfL=fLz;SI=V{ zzOuJ*Gf)pdACy&lx)$5sP8i7iG4b8?cXe0NOLS(oWh=pS2F|DGl$4Oq_#a_x? z4LsZ%$9COdrcv#=;S(vj`dU4nTPfHhq+*ykBjt9g-#qodTmWmtou)D@T0rdnm>2yd z6t-KTYW?mboC2&Z=a)~NO78C&ay?hNBA`FAS~6S$-b3CVP3y4yZc$R?`N#WyR={81 zcS`(KCatD3xl;CJs>f?l_l}!6nDSDU*bMY6?athiwwqvp@n)dmtBX2$v?T9`*B+Xy zdzH;p*-9D;N%IK8g)O~_y7LOha$s31V3KXZh9P}ArOrYJS_QgDnoj$)!Ed`1Ye6s_u$J*on^b}*q&Sz;WWi{3B@kbzt^kz z&35S9Fb(zKx_9}6ZyK?VRp|MvIMw!dm)yUsQ*_c#byxF$>4cSNlOPOgnNsZ;1z+u5 zLLz^QUFO1JEw+J+BJ`mGkN>A7u%HOI@7v&TJ$x24;cLfx#=={eYsRymQjFKB^xO=> zFaLSZtvH8N#YOcUmQrlV{^%(@vi(Mw)UjtXev#PRZyX)q{VTjG-b78_&%9&GSX^d& zhxC@Z(B`_~tLL@eHC)tAVLTgZW?GG7Iaz&2`$*Vj8H5XNnh-tYfr@iOGqvnSbc$Fp zydx~^9YSxylK86w8|5NR(yH}wX_3LjX6MX(QC0Co_K|VRB6zoEplI6D!R{Wo*={=8 zeao^?%znFy7I|`5CuSfi{+wkheUQ!?t_tMp2lD+F9D595LkSbFuDLBpq4*YZFmUuY zjLtT=b0PEFp7;oD%5MPCrT`K>UtgDS@Ra+!S^@TG-oQ$Ay5{lNN$OiJUfy^@sf$3M z8kUfqec&bnPMX*m?a%a3s`0P?L>2NP4Ki=?f0|cK+74GQ`mC07F|RdiTU8w&@@B zHYWhf^TFR$wz^P4BPO=4{s?ziBVd#o1c2^yV`D4JZuKmQK41cQ2~1%*xJtxM07E);!6V z+$nvyc!z(XcXh~6p5t9Jj+Scm&Y+{gWRL|Nbk39~_haIxpk4udO^A-~fQH%{K#0Bs zbjX(ita%Q2@t!(zfZqdPXQ2!L$?H0*VBgSG?z(nT2qm2zGzLf!XLuf4u}V|^*5eoM zkK400$+zCqZ=3wWN90%i(TMaVJor2xlO}g0#QD|LmPB#q3VsLsH+yHkgzol9x5jWR zYtG8H;ReTIEU;hFSP%U@pJnBY2=PZa9LD?_CT#M}a>U|rsV#=l@HTg(hv9t;s7oCe zN#8~yy;gwAHUl846EKt_8rEtj4OVlbc}#wPdDV1oa60}Qlv!EhrSC*qF1o-C9xv#m zVSuFVzjMq+QM~-pRju)s?t|R3#r*m!AJj1r}I(l&^|E6T?Lw z=;KDJ(gR{il+9zyXnVT%B83;OMX~X(D8<=u_Wv4A{4Q%%vu+ik?cSG@Tle`r9hTPi zt(mdjS7rQffCC@o21MnX+082H2ayPIVJqF6`Rp2uMI_Nw;E)EU=uOyHa ziC%zqo=zHWf(oeldVewsaA1uFg)EoL_0$u9nN@@0hC}`GLytYHDJ`{=%@Iq0toWYm zpIZANJuUz|fi$wOzd0VD1_ky>eNTGcrb9H8_ve4t!Ju9EHXr)|r2GQZKxxTB!0x5V zhpDOJg{S#|z4in(k|O?+{*W-b2T%J^k6SvvX^|;giyOp{9Mi4Jcur<x(yd9t;DoqsyI=ivG#>5)1&|Ir6fR`o=&>si2~Q z2OMQDF1)}Gof|{$djX^e_deMe&5^|fg*H&HSpkFw_Q!p`vB-KKaL{HF6-@&IvSYxt z5!g3svFb{JaTyj_#RK46*RLE|YAIi@5O#~0*x0V!vdhm;Ks&w-i$w#Yk%W&QJ3Avu zw@33Z7yYm8Ll|UXuzb;NCAr$7-+y1I)S+4_FYi6g3>O@;BR%VJ*9gJOn9cTtm3V? zsu?tccp#8qADFN;KqhNIaq`APSy?$YdBkJ-hbuc!!QyS9r=;xR4Y(ZO+zkM*Lof}(LPfXke^TF-A5mYpXTF`@G`utS`_cT8uKh>JxpWW9MHxk}r$e3b zUc*NdoLB0YLV5xg=>b3fj9@T{I(PBnS+ zcXf3kS1a%#K3Pv~8?uxF`esNYEU8N)04#z9xOp-%#AFAYh(RToRcPX!M7_ljje+0k zpX2?!Hsrnr?94ehpp?-(y49gzZtCeJKLJOEs^(*hES{1FIJjjFjYOq%_tnk0<1gJ% zK~&}djk2dX=e|F#R9&59`;{`;e~{- zDpnzRkNMr~KB{U7GXzou;sRnM1`lx7WiaVMupLp9<@5E~H80q@K-uCW*!#nfZtwuk z*3w-p)?`Pz2!d0X8UXP87K5$pE_}`_ou9i~fL9I`SXrQ0yPV-VYTN3dG{nMz}kJa zR)*YJ4a`fqJZqRlk zQ~W6h4$pWlnM(^QNgI5Q3r#eWLz&`rGk$>0QtI-4rp6j@Jj#Z9sQ4}LnB`+0NlP=v z_h=T_cV~#YeziY1^%-Di0uZIy-?<-iV8;hO*Pu5sO-wkYT!3%13BaU*;y4K{?F&Fe zC{YQ&xZ15qy}w7+s_ySWAy?B957eGxXocg5ndMOqfqT)!)eTyiEV4!vj=%AI5}T9_ zYTW(+1?<{hSKCF%IupP^ckq$(UBCU#3{|{(OY0=%;nUJn`>h^PT7X%PIwQ<1qXiIb9H<_%jFLKQAya&^D zB(soPh@U;QO#iLv5X?8|xq1=XDf)PN+s=zS#kvR`dyGIO+e&!CA4?9Fuk;e4 z_uON@c2bP~xmM>R&=DF*GR-Bl6Kl;g8BfbeJ&f!ZZK1b0sMR2%*U2{dFp5DDKZ~ZB zw)fGwRhA-_9QS56x5`eCAnE1?RggXRB=WfWub#>|?`}GrPmj#hqF;jGW_}q!U@SXd z6p%SS9FCuIm8yLjxe({N&xIBhG|tU%!ePN6R75fwB)atQtwcHP=0++P`qf(z0}^1b zXJ3UoPH3r&zgvz@5@=5x`{nZTQ^2&9lmLKjlv1={mS$!;d@;xeD<-|dqeHnuqvfXJ zrLfeK)HuPZ=czOtOfGc{N4!-6#U=cQ;_cMDWBtG#u@9ma+g@MgCsTbK~Xd(vYoK>{7i(|=huC` z2SGomF@j#lI1cH+#zu5DkU!BvJE%<}`Ijwn`(y&0aasv7M^iTC zn?wv#_ha639jJCE-NOd0hIyJz%PTU_FxK4vx^M48ygTOHlOO}oq&U^qXShAzTuNV_ zcFjzF7c7j8(ma@yhW^YH*Mm-|-H#RT{7vBQ{ugp*c)t%*0p?R63D=q`6HVbYbdaNi zK=8jiEk93rqM0WRzPN#S5IRN7_>A;$5k(An`9ZOs9ZfmQ(wDH+uob~2w^D0!R0{_Q z!UW4Uot&v{Lp79*aM1~(`?0=>$M_!7g$n=vw00oUXzN6&6Tol;%1P!Hsb@QMLBVUP z!E1_SiHM1dHEBP8!dU%>K7-oGO~v(YTjwMLZ5Y+$2^}vP_8lPVCS$D9cd+c0QE_Sg zKnQUz(^$7r#Z7@o4G?kkw~V+!kD`4MjQDTF?cW7X20LF}rrJLNk5YizvzL;DocQIc zU!@l53K;M{B2U8eh{C0^Y7^;_iNsii&5@|+UQHt?S07t;fUfx8F10&({L-jRr1);V z4*A7db&}o@iagl+?$q?MX+ORrs`E+fk2~{bxz#WTg=QjSd1k98MGUDkp++ssd_Q3s zXiF&UKk$&4_|qB+J2zDknFv8?ol&XN=^^hpH_b?F8p^1WA*ypL;S(C(m&^NRT;wHJ z4%vh(Zw0hFV>_Ct&0F;%O#e@d_QuG!K&u;}eXS7OZk#ut51b66yQ6zlbhc_bWZp-2 z<7D_cxdgWa7!7T9MW2*uwjX2I3^0KO&H6u33vrba4;wX=!>QBfuJ&bUPgT40?Tb{o z)dEz>Cp27im{o+9?L8$fmY1O(;Ztdm?R-vR61NMwcqA_`Fo5T(Nf)On44PCam3 zGn^?pO_KFn{Xd7ut^TMgkA;bBn9gM9zlCa}4YTJG>In>6%jC$J0`N-lq!3o)ba7}b zb-6~0gDWfEDdBz00y62f#)Ia(($XC!&;Ofh%YFd49Z11Mot6Sk`M^6BPsk1o39wx= zWD3fY${5gaph{b=yFiB6Lq|mWiwX3}^KP&xJP}HF8Dxm5rx`XkQZjsn)rMfDv%Evn z0ETISryi}49hUcfmgM{6PEvIpszl_2$B7hSgm|uWTvsY@&7%XhYmHUd%R060JiZ%o z^A4+NVQpN_p|XVYb%!A~kF!{bkzdBO2@A?5mn3Q6(Wp;A9Mc$p><>< zw=Dhw#_CeaTL)y_{LjSt#>O$Aqaxk8DuKbDT82m)$Qeff!v1*^ zezO6~Y3Z9~LL|KsX-ozJIHU?@e990X zF*T(l!Jr;{-P6@YOiCIuxyuTM1N?CA?~;@UDDopS#+JL&3h=iC!08cq(<1N5!~=WA zOAn+wHjpxH-}e}A2?zibQGx}4Qygz@p85b50+WzX3P?Rc8+cM*pEMz{&fiZ6w#YZA zSP^TEHB&KZmC$$ke94VDs%iE=JG5#vv3r!3NO8Nddr}eDq;JDT?BP8O&VKC zqQ4*e=HcaMbbX=HsLZXe?p=y7Om%bcwrDq~=AjkpHW$mG=3E;C3!_&;r5)6v*}X_; z7#oC9J0CML-r3f=LP4qw3hsc@gaSsj(eq#fu(r!A)vac~Kk12QWCtX-8!5nN0*iDD z%-*u=eXyK7_Bn0BK`kH2irG9teW|V84FDqg9ZeGObnAp+1O?eL6>7c?QS@sMQ`Ptu znSqFTiWu`SvvzgZ`5|wnzgo~(BA;=LGhz#&sDV8FAF}3lY5)HbyEXu0yVP?L^ae6l zK)TWaRy9Zzk^Brm9&rJ|V2WcM$T^P9P5~Fl3qVVvfW_56c@B)q^&35qd`~0~dsF(p z583{JYB2pEf?n~5vyxtcH$HVy8D)X-QGE|(|4g^Uq?{4H56Xr1aCH9rX+Y{Pl0rq) z-E1BD<`pvN)&Nw(p*cWkM`i?oy_Bn-EhTaKTN8gKV0*0KozHeb({Vr7AYgEc|EUYf?B@eaDY_yFCPo7#!Qm^IkWi{GGs=Cj{Y#({1Sa8-uAfO-8iXfklDy?%eT zr@P;bKu~FDmZ%+&0Ne=NQLv?#2J83Z#|ClsZm=~_Qc{|AB40moL6)RQAlOE2RR*0+ zcjB(XokGu#5LMgaPn=p^L~tIA2gNeQy?XG`XeL#}p1zPo8eg+(fe1HHXGvNclNCH+ z2mk~tU;2M$$&P|}jHV*j8j-dR!~$PBt&9XG_5 z41KkIDge{zcdkym`-3EvW~?t#_}=p*fwCzIEZ~7dx+3h?{{`ACSebz-On+z7w^Xpo z(LO-^LS>z~3Y8^hd@!;e{X54|;Yzl;`cRu4etrz9r{#4b$hTWB58YIxj(>CL{Z-2lTY2kFDlFH6W6HHm?ix^)&{C|ag2{@MP z`|XD!B|}tZW!_2%MM~yUh>E1ll0=y+8B&UjMMWf2QKpa~Weg$7oFW-Yrie_*bk@`U z?SA`z&UMcDu6^w(zVCaV_j&Gn-D|D;ekV*Sx0}VvEN!j*1?E!i0mt78k6MLw(L$}R zI}=}-AZwy_T)wkvsy&TU`pOE6ShE!WdIs|@r9Srr*B;*y@oq`$gEeN$bs{}%J%6uj z(ACZ`dvp*QRBYsLGF!ENixoUA2!W#mii6G@`$gzlm{=?oeeYeJ7;+E)PAq{o$pN|_K0?IH zd%$Pwn~Jb9&ehycMYze@ziNpB395$cULLt_T|d5|N#v)d#wa#Bx_M?ps!5yfVkxEg zR;r_4D8d|_y2<9nW;|Kj?qz-}-x;x=D>Ibq=j;3bV*v%JLz>5GRMxwx}ye=e^`iCs8x4&f8HD~v#DemtS3)bOo#7eJWtd7bS8*a@jh?|m}g{AK+~quqAL^J zNujcl(;HXM(swd`k#&gOJ8o_=lPa|<_DbX1l6nLFrF)oPtbOX#U!c|=J1)?bZtJ$z z>bTiHNvlD{N0TKt^GQ(XZpb?koqGyy=qEOU!|ikB7>9{!??%p zR#+H>w2f%KbKb$0rKh4oO;1nnGQ2KbTG?NpdUvzVqH*9ltli#lHf_zEqzyMp8;09+ zW<3<~lv$W?0^)mgAi{Q z&{qg+_%?B)oJ@X~Q@tq3M_pEE?}IOR@7}#;aChtY@o(FwrS-sjX_3@o0P_kwIt9S~ zT$k2vG8j17!H;^Y^7HtOyBz7O`Jys}O2xXFCF!4)gxE9Dh)e00A5uA=1`Ft~>5=`` z*1}+67|eaUcU~Rzj#)LIMKxCxd_g>6Jo%TX!}c+jvZ`~Nthc`2Bek~jrVPx+$fq^0 zQwpT^?i>?L3VywmYI*N*WQ_<_MtOne`WG&PmpewRk+vAsDTutUhNm=IyJ7&Vn^U)n zT5$a11vnzH&AwgD+&o8T>MsM*E-B~nQxamp?XGp9@I%Af0FcR2oGqReeqhTD4Cq5cXIS9$kntIb zdwLUQ?RII@qco$HIX*uxuI|VyZ@xp}wl9MD&7}Qn8!cWi^6VHxo5YSU3%hukScSE^ zq44EOijhoHtq>wlk*LT?lB@Oh*4F$OdFW2#8^6b&7!7u7z06DB)#EF!dqr+F`znus z!S9~i8fXs1E6(2XWHfI#@mPD8nahr@A^yJobBp_`UG90Tct`rH2z^<2!Vq~TJ9-2) z(96m$Ys-cUwx0b(^in*aJtF$d^XoxD3>u-lbzwsLt7~g%x-nI$=iRZhClF1KySC~x z@a~K}`qVlL8$>L0;xpe;BpBVXh?4n-Mhu6Nb^0LI^2qGkna@xQPA>ck zcuT7I?Swps@|u#jRCr+m(_920=Vkmj3nj6yV;=9-jpjnZUAqXYJ`T|kU1^J%rXY|Y zcK=$@?6*BG-}|mnd7jVf_E(bWb(&hI86OoG{XFa`S>#`mFP<)l8mjJIJ}zRn_?v_W~Jsi+Y3Fo0Y(2C0*h8HGWF zu^R`T@oe|0@Gflju{d-$!3d=1f7*BaI5)XSxZOX)X8i@IwI5uzHN*fstlGjN#Vc*` zS6fN8S=nXIj&oKgPBcPLxW>To@`=~fCSH#*<>}GRS~QF5E2@qGau%RhvH<&A56I=X z?yJf3AXO8JU>t&fa}Y zt5=?ny}P8|@3HlFf6Zq{bl#inSO2ktGd8ZO&_f5>6Cta!d zK6|xgW#x)4&U_{1^z6cSZ`0z=2b$r;Nsa=v*mKSaEk+aQ0;TRo;Rt2%^Efj=C<*|R zC+j0pZAHon8m<|;-`I_Z=A7x3rs4 z&|Fw(r?PrB>joOpsil&np$;2ohURJWjm)c#U)5}}rasq_>3K13ZKkx!_|=5%V>^U( z)(caOP`#cX)`?k^l1gZlJ-*U4|3CrDMBi9vwJ+oX{<<4DM31rcZ$?J$MORen$K4)3 z$99D0kWOlJ;%09SQCg#b@Qv$Z;o@2qsdhnfv}DPPg8#1EHS@82es+QgOHxu&=)i!# zz8-%1w*sL%4;CLl=biYmZ4UzD_v)k4pF}~20E@n?V<(K^<;S9L*Tza3(PA{)$7LzRv;1Zo5D3A zV^RMZ)Wh#cnek$@7bKg=mMtMLSGbLSq%Vc~e)NT#c&zuLJes?(RY-?8`g3FaD@C>U zBRLLs# zL@os@DVWhZY)oo;_Eg%Ow$Jg+#UF>vvX+VuzNw)O^){9fX+ll&VEoYO5bJOC-iy-2 zfd%Hq<@=|Yw6x6`Mbk#sZ|@x~)`oW};7N_$|vd-b*YO6Ub z&`)27a7b5by7*%~X-}T{bP+TpquH9F-HYR)RFPXxtel;l{ph{4F#mOXNjx@>*TS#c z2Mk5Ek2q!T;*s4G#I6k08fFJ^JR<%Q!mwexH>T)sBJdO}bxm#Urn7yGhLsf+ z-EJ?qrkrp5s;r7;GqkX9aoZ6b7}$KWfgi^pv?{T!*_`iZL``W*xQP6V9JciiAN%+} z^e49T@fWBE-l$@l-z)-~!ua`@A^BVQ)~$CwrA!4AN1>)>VaNrO+DobzE(p$g=qsKb zeW}vEZms&lNe3F;s0hERe#?^w*Q9<-3K8L`R=5yW(R5JbV$m(UK~rCEl<%@IdoMWB z++KjOdpt3?XzzmI21ZoBiv=&RfH2OyaM`=}>Asx_aK z*|?EPa(A=Oooh`p1;@95OE~PgSmEwdkU6Qioe4s$`xC0R{G%P7LPA2fZrwR(bWjDY zpg^%~5w~;?9*2ISGM!-zM}0v%aSEOMH95%WyT#xyF)<6sr!F9jUPs)*bVff|9h^U$ zh`>ODedsMc9V3&OnRx@vrjUJYJ6~y@IB|kdUB0*$VEHpN{Eb3jiBOE_zwk!IxcT_A zhC5YSnwlHo-fL+&eDKhrS>TJ>HbCMK+|n%fDcd!ytb?c#@I|3f6Z*y=&5*@q$(iMG zCi+|{#F&K%7y}M6{L`}*3+~4i`J#{In3$&&tDoYFh@maZ<$!4B_OmjuklKTfE0-t4XeSLfjV`aq+U4vIYrFHD%dhY?nb~_cw zxeVN}lw#o6x-7rLxX2p#Lyz{m#Pt?} z+=XYzr2kh`JM-anAa-uk4^Z+u(s_&Ow5+X@>@8s;A`soq&hB>AAj~FUs4Ngkkuw2$ z%b&Xr@72`o36g$mhC_!jBJbBl#5{KyQ~}Dtfg?~lAT+c;r&&ipLE%L^H+AC%5s|8Q zu_Ip}9Lqlgz~lA}Hc!!mHQOQr-<5{Ud(cukn0N&z3`S{VB-A~@ zVtV`yOGIsBe-p-=tX#F~L(#=^MIC3{3gn8?f)2)cs!;dE28p^$>~J0O?HFMkntlK9 zbXx}S!=qn8!XhHg5BIOnJKLq>=$O^q;~z}sqabIz&p#X69Pb~D>U8h^{edZ6(iWiz z&(34r%1+L$%l5+%ppQa{Fv3!L4j1n4RlORfw*SBZ;{R(MmDs%b3y|%ml9BQAqGDnR zkO^LYMr)q`I&q_h#63)?zzlP3*Mj=w-R16pY#nm-rj~;dBA8;VgjjgEMbXQbFCTe4 z2@DKO+?w&~QCb>9MD4>i>DRZGmWzq^$(ZeNl=8i4xAOQPo`l*xaIuK(JlnIRXOZfa zmGjii+ua4?7m7l1+LL;`I3oQ9H!k>;dkc6f@}UY;t{kJ;z}1{Qr+ce-5ycFqzV0z? z#xZ&{w~NE3N>5i;$=p1?ywN|#L(w$%J7?46vUZsP&ojJ}()Oa|qPf2Y4|os3e$Fxl zB=s9j6)qvSp#(_8q8846jYfBABc4f&)jq7~lLQ(;GU{NuJEOxIc4{lLum*}|h`LoU z_ZzEgQl-(1RZYzDhqVI!0%(F0Krlgi>((^5+y#d!QMTvVAA=}G+EIBF+>j&%K#LwS zG_1xgB4cTY5Ya!;n0{4@9!J6YC9>{%N+bvQ`v)Exub3|cXuw$1&!Bpn=5jI7xyR7@ax)c4_%i&qb>OHdn1s-W(k$K86IlXBg@{C;AKDe=Z($iM z^(Z-%5Hqpsgxh;?!BK(d63m2nf@+c=&w@-g+z*6w9;rx%*Ug1`I$xCT} zG7X9w7M4B#=+0^t2FWyFs99L5d}I7giaiR}I^ui0e|dG)(LB4m&F185k=Nc`n;-k% zSM+>N8ntAq@#is&%49Lf>v9|~>74n`%K~k8ziG$ce^z1eANJ_)_euYcs7pSQh2_{^ zEQI_2&nxdB|8tJ_e@xYUOsDXm)0wAcWz>MP>Hw*?U5SLUFw=DsoPvR`*gwC>uYCjJ zK`ENfVTnB;x_L9hsU_6%*^ZwzP&p~!kffy5*43S;i;_i+bd)9K@9%=Y%P14Mbo&1y zm;U`@G9ob4^}={ohlX?xG&<-07C%w(_Z{&5#mXw8V+Cg~(dm#&GCiWva2Oo8<+(o@ zri1BD`dpt;Wquj2;_F{u@^d*V(68W3P6BW$SDl0W@B_W@F{`#by98)Dv3qG^H+;O; zZf`n5O@tpZ@agCHXE=WQN&N@a^fT-yeU@p4S(gc)3g8!_A;oj>5!bI#eL+XR^ z&fr)?baX8SCZNl9GYoXZ-wdnx56GPnX9<-@#>CJvu$Mv^N(mnSznO0(#tezb+aK$# z2n*gxikRe(@)ilU!VZRi7U_ zE`cC}CO76@gc6Yz|FeTbE9v_@1Q)l`H(F{))egHXD|gTe_i-m~L^OgPgF7j9)ggdaZDmcer@&n|2HE|Fe; zzhwB}=XM4J&oxk>D<5(D>{K8sF1}og`T}PAuwirrO!TzDeNF`_AI~5G0yN*-d0`C- zyJ9c=07#PF@$+bD76Sajo;a+jK}WWX$HG(_5tmVPP{yz$vu#^bj6OsD>c>&ZvG2%J z9{=+V_SS((f7w**c@aDdspOtLi+uA&%LLlk58k>SpdE8q3^1(Cy9d+@T{lh_w0Cc_ z-iqsjA|lSrBaAIs#VP-6GlKlM=W$FBaI1~u6kE|(>YdNN+wZ<)=Y5O%wdc=ytml&s3 z@Hs>wCGC65og*bz-!vH!vd!KoCRED$ z4Z8-494{|LY<{fN4_9cNkMm%1Jb|flm@@IOkk1v!@I$eu0!3g?$QR73quBsXoRDNt zo{@-EZEbCD*R1b6vmL?ybHJvIZiHV!K|#314}W?k0M>2~pXV+3PFAj5Nd`>e4D0s} zw&!kwl(*sYQvSLAGQCgzJf$Vy=SCkE9ckKUZM zw;J{r2A#_~1cSq6WaS*cwVV>3exJ*(aApI?khCs$TkfFQ)({%8_v}7O>z^~_JU1{( zH+V5uyrB9m(7?#Yih0LRFKd~Lg{d>1ZV$Ugi|gkK>(AD4E~BQxsnxMzRr#F;$=^(Q zSsPu9ZE}rla@*-=s)kt88*RE>b|e=qRtBy=@ccMi<)(~gyKQ^4U$YO-SWZR$))GmM zOE_JnCR6taJG;(p#gRU@7d;Mg)(Q;&q`!paf!A%G5AH$+ddh=VpTA#?m)(rlG~UBQ z=>EKfo$Ia-z>IL~&K;9b!$1Gq--c?kHJYjVeo9a2QBQuNku?rXE8F_cgb(sGK75J@2{o~I3oD=|KuU!VJYBJ(| zeSQD>mfBRuod5Yz{BV#3f7Cy3?eA~R#@hI2_0(h%|DWHg&W=vWB|U_9R{-{t+4=MA zDEP`@N)XwZ^x_2<^6C;zVx#|y(dVn&i%g8&x=X1re~w>7q+jEj_CFuu(rl(KQ+E*& z(XiM<9uq3AfmW&Tcr!L8nUa#Cd+b=CgB*A6H<*2FPMs=Xi6@SX->=SFhAi3>pTJ>v zJIE0lS(7h3Dk=aLiO$kTe=bP$^4i8#hDVO9CmbCBGhnDCw8)>M=Sl(>7riJ-s;V@_ zGezIyA3RuwSO}xla1oJH9 z+WEPXB?VeKy5uP%GHDg@?L5pM!kZ_~?<8X*Gc77tf<|IP3)=>Q0$%aR?ioFO{i|IIqvy_pbsdL;YU7qIjNom4 z!q1>(nImYuL?lz}9r=`T`&;<*-i9{in5x@aRlxdXy{+Xiy+Pbd8EuwXr>z_@n z#>RC~O~Q;cBNb1?e2;tfjJ?N!9l!At(m@D5X>XWsQj##a`dE)2^jgBKGMuZUqN5!# zUyGWOot>=<91<19DI+V}gGr(|0is*BTr+vH$JCS$fGZH}*MZKY1W`$L2IT6PgF&lT zuND;*)jc~r(p%g8_xo;V z6;4<$8Bu!`Bs4W;$BrGOnXB7$vCov5fp#3TR4x18#yrE=(lHDZE$eZhP`rMG$8O+e zOdTd|BVJRfres^}3E@`8WQi!bJgf|=3L->3>l~F>YiVmM#>vH%7}jWc`}S>fK$r7q z@iN~QO+{InuU|^bTYr}x=k3asE08ZEv+V!Gr%tW+QI=G50Mi-MwmO=cWf-$V?$-VL zyp+=F>J@+jtp+?0j!VI{1{W7Ay7J)kT`Myyh}FyT|a3R7bXv_xO@qR ziF`*At1dOxtehF?@cZ$@30V{eSvjdd=x((B@LUC|Pho|_t8OzV)tFlR~ zZ~u;}{^j>mxkktpy-+578f_|2nFsSN4D1>B_Dv0qQ7sQH6AGG?V8;v3v+RgrG)R@T zU7$F0dCv5p{Cv?n><9?28BsL;itEM+4s5Fx%c%EiY58tgapXAPpHQRC!`ir=D!j(` z-o1O85h8dPNAs`c%9rY_0}D29+I0G*CucCNPO|inV!FY_O0gk;s?!1EwrYAo`W@XE8Q13czfxVU|_@ z{c&+6yShJ>zM7hJz;&Dd{#KNpmfD|B|3A`qi|he|^SJh57CM&3oZAr*p8?^X^85*} z#+7Ijp)$kN&NfR~HMQo0CMK|F{&Ujwy?S1(_t#x4I;o%tWAb1>tE28F^m ztEr}Z*x&yv129kqzq~vL_Bu(FBtlhasf7jw#T6Ix*45ShOfC79`bcdOoP@a~d!&ET zg^l36F#}f(Io|g4>DDUJK^CpIJy}bTSNmAKAD=DGKE$-C#pV_(0tMcx|9pEI4^HdN^VwWUPdx-OiWCJ zjSNO38Wx_HQi*5Q(9qbhg4)Q)sNv(sH&VMoAlGvz}*cg|ceUPUaCdulzZ#6bB zD~YmQ-mt>P#zyJbF)pj4_eYYI4uRnH1r3HHtSkB;WbpOteUwDY_CXho;4WQJ-(SDn zC#RxcJEP5mq)XHFcFy z`Z_=>a6}ai4a{unJ_(|7=SI2R-Q5$sPR3jEM-7O9mqIDhD*!Iofjy7a2kvBfLGVX-u@~QDl`t9zJ?DU=u=x)CO2Q7 zo_1?#ZQaPW(j1CLbzNO0Knv53Hv+(?lF@aKQc^B=ecuD4{Er_$8rs`emUJ-z;l6uk zfM0rCk|??o%M~6Lb{V7tSy*v#@rFSck~eSMzaR4Utq$-9wn0u_UIP9!Ab|h_Tpr?+ zmhM}D{dYF|wAxl;NGEMc7xp!Sm6cW8)2FP8u}om%aHst_o3l5=pj>CsGI>HsSQt>6 z4ugd8hs?{Uh<%F*`0dpz4H+33r7*!XquiBvb5&JUJYha0LKIZS zNo~W89UX!Ag{fj3i1_&U4=ZjL3*yG&_R*^w-TZzG>U*Z)=0~Zis+N`lE<1P-e3@5X zbwCLnJ@mbfxAEx%+~1il@7>UI39PmIu+?McMVEf)d082m?u%V>y!Z_?3WQ?+bi+X+ z^y}9zj2a#XXV?o;EA-b(f?r{KV#Pz|;@vMIgOFk$6GX3_^&CDX2e<1j%gulNRR*RY zloS%)@Q{ojSeiUwn16-`mB&i6$yN0jgiLC1esnYv6b-H-k+z|V&pYU>$7e3X=PrLi zV-JM?g@JVcQz%gIo)k@Ujy@mWLIAe9y82H)@1JzJm+2_QOAFtBLml9D0>FtM*;cmn zFi9joQO`J|1+o{tpknvEew`{r_dDeh!Ex=mtH2qnqV|RnD+D*ttz9!0d58(K9m+!S zo#|_l6k!Gk1>-0nA;AQ31s_|P^X`C5GguCy?8?Qwja<79Bcie8VYSsbbcprZwQGQ1 zs627wwylB*THnynUq98rIIGvy#%4vBV43yPGBZh%Kbcp2EEOFzs;sI?OiZN7&CMMc z9o0Z!c>dyrxeO;&(CE*A1b@T>*wr3c?g%SQnk~258lRoLCOtiUU~o|R^yy8AS7!Mg ztyK)GS1TtrmLeTLX-h0A;S&%Lc*-uT9nol`hD|_1RA*-}&I!~ZKmx=X$c(-!8^MMr zq^GY2iYqf?23v+u+hpf=pcz+y!r)=ZAbth2rD0>EV&8S+%gkJStF8Id4{@!wJyY&1 z474ZZoualNE@A+AVo?!KXJ_ZoIcYsMzzE;?_>JgMrRCw_Vdv$21=NQT1K91mYi~BY z_$T;-k=dxI$g8cbJvO(XS9{{3hs z2N8vz+J|zvEY6+wbDdR_TF!Ixjfy$23d;oe^x8nShb@nhoCkmJ^Ha@vZiomT*#aP$eyRf>7X zl&2qp2$486Fne1q>>VW0_c^Cn7r)gnGT`6IKvyctlfoY>31?Y|;RbTfUm3^@iEpUF zFr3$~zQ4RNagUyfNl3}!aLFr@WC3mCaN~)c;8LT+Q35I3ycdq(rt|{lT`TV?B{4M) zH;AHpJy8sB;&@B8t8euii4;nT@RSOh`c&N3Iwr(h6mq3)TZOK|-%rd4taG;z;1sIYNl{C9iT3Xtc&lX~aBxf)RK>xtNawMs1etu*Y0?0YC zBG`?3>Bj3Xr}l*(W!bf#KlyJpq3b|hBmz1_Btj#WI5o;;zW zzz)ZO=%}x+57b;#RD>rG=pMMe`~Ou)?+f!S`59QEgxELfzKdWh3^HwLX;IQ+Bi$oE z%b2{#mqNjd)gf~nh*PGqtBU~tZW2k)lq|U6juYnj?9%jE6nD!g08yl507{YCxsySU zjnF0R!5S!sso3oU9pOMLx7${3n`;4{l8CX4+;Wl+`$^AvFKNv{QMfUHA1R5PX%6AASW8Nh6V;omlnE~V3AxUmHI_ZPi+J9B|%NYY%BV2ZVDtQe)`0iZm>%4OI3}B zqxVSv}-T{ch z-8>P5R(EU%z^vLn72FgALG0T2=D|48mDs@q1pw9tYg|E;0veRMD^-twY-C*dKif)e!%xl4S5UC$T|hFfYSKTX8wgV86yY=kZ>3q&TP&s$qgt=K=x(8k(9egXBXhBOApa zRo~d;cl~ydl6dx6$->B4Vpu|!L!mr5Ik^Fu9s)=RM|i8Px`hS*+t}T^ANB){GUa#h zto>Zhv^&k@ti63@z1Orfx1t9-3R(Pxj7;oih^P|CzyjjptI@X>3rA2 z(0#C=fl3UWsODLQ7*QHN=|6STBfXoPm0P!U^Rut-_X&qDx!8dtQL9Of;@Ecb8~xOv9sO8 z_@phhI5sq9=l!pF)h8Xle4_jzNTvK->>TI zJn`V^%H3$*+q-YyOAN5`M`=gA=9S3)iit&&m&-OFngD7N*01dtYDX|h&4X&r&eGr= z&9~k~?(LbFm2;klh;iZ!f%Sud;Il$TX1p@Wc9(m@z$_lJ0`8a0E<5K2AIDBU@MF1#`unH2jxyKP)*diNSaZ+*=}GDTDX3y(4@J}HT|%uH8Y z7?ni;XY)fKjlD_Ul*uue=#C5QqEk9Y4vJHt$JzXSyr)VI$GMe=E0VC=MhqM*_OAqwnBsk zeWWJIemrx+P3z9dbs~6R$!M~~ceG&^w5Q4o2`$G#Cx-=PEhT7r?c29+4bG8PWgnu% z+rApE)@#}R={yb2BkZ0-jMj+xYI+q=Die9dpFDb03TJhKwdF!K0zPR7MXY<&s*l=@ z5QUj=Re+C%@=gziwG5nN>mgleKK^hvP_t{>0rjV9cA<_dM8wl;mB%s0`QFK6-- zH@7$U-DJ+GiHUy5VBnnGsH zjl-bQjrn(f;a+T&mL9+T#6u{B-{^l($jJt(G-N^|^NM9-(0vjL3%NlVxV_+kz4*vQ zHse&j#W6o(DJC7^(0WOU082qx7tl_*_0yiyrgNOAUERKa3g(;drb9kPa4SUsq^A&w z237wAv`v-N)|a5FWM%b7Hm(j5F7cX(?lOa)0Fhtvt`>P@2uj?jzbc8aWPx=ghvN8_ z_26bm={sN7HNTqD9o;oA48m8Qcv6Tgg}4S44Z3uz>pY5?^(G$U>fF1%xWOlpI>+Qf z-|a^u#PTbLPALQcz^n0*v))|!oo-y08WTH7R|P4Xu)s*kM131_N+@_a=#s+PrIx~f z+SZm5#LEU|@JfxVEC^u$ZpYiM zWXVhb!(fP+#xH}Bj@GI*ttk|ic4_WPZ&O%WI^F&Ym=x{qi8 zg3#er$FOW00{9W9p^KRzbY~el^t@c2+q$NX35nk}@OE|N>Z>Y4+&fS)W5S*l+ye_%;Ax(*~EY7v_=XH0ZWubrjcWRP~L#_C|I&~jxZ zFcn~cP$=94S9kL!ORoDmc5T~icc(=xuQEa^(h{OQcvPr(Ju`EpN<&-*%k0%P3i^ng zk9}hv*&u2C6CMeho>YBc_!X(7D82&{E`dWTDwm@o?M|Oo-Lr?_2JojXv#$InkLTs& zWV$=u55Nd+YiSVA;5L9%3HL_Py{NwG@+HvkxKxY_-uVDj5z42is1zOQE<|YnaU=#r zX*?bac?$oD<8nWKTRk`-`~kcmDRW!w?d=KGySbLAS%{NrdN>Y#8&(Vq3@DvGJ$(68 z-FTVz()Jvq)j3AuGMxBpu*r3`U@$GG=4C<6ERjuzSv@1Re%KsvU;gHY8zNw*&ub5_ zUq-bpTKsFaq4cKHGK9H1Wv`mrYLfNZ=s$*%)O0D~xdlT__YKp|%<57p2^{R5v&9F4 zZYl;yt1~Y{c@U|U#L>yvm<#ZJFxA3xd~N|`=Vn1oaQadwJ(CI~*cnos=_(Q+3Jedo zYG#0)doOXG*VfLi(00=nKxYt8Q%dIqH8m${370gOUF}l|$r!9SzDi2?K*M}9)(CJJ zyUDk_hu-qt@Ki!ZhEB|zAWL^I;I@NZ(L$P0l0J3_0kaeRIBju_HgZY*1!ZMrnq5^F zFJ5eX|NarLNAJDO6GtT3)eaqM_Puf%&N6lmjxzWKTBJ&J!@{<69lfImmj>t?&6#+_ zk;bN`1g{W@94YY?5kG2fzV6oytKrO*;Z!+HKlOfpUcX`FD+7jl{WJN;MlSNydYore zTebR}-C4%$&CdPP!evsP&fSqF?EDi+$LX2aBp9+7w`rY}7w6_~-cA=Xc-362E1&;l zmblE3*MF^g=5bLabYQ%M`Lujv@Q<-_JmYPJ%z=l=$@u50eUN&Y=n$o^sL3wK< z6D2=YV3}nI&M_3Fuz~g#hnwqccW$yb4-5@O>)ZT2_t^NmEa2ajnb)~Qzf0{46Udjf z{Qj(|{lzaQ1oI>XR~@sGb1QA=mhPVBE8IaGdY%jq4dP zjW#GZJa(;@Lre;+yquSpC+~WP#@HLd*{j4`Irx+w+sUa}wXgdk_dj{udB(5CN(F@S zv60OV@Olo6jKmyT@^)ERex*!)Mp0E-04&vd36tXu-opbG6JJ7EBzCh~3X2qeEWfhr zU*;vzJB9^cs=r(vQoBZ}$kO~8`LOxla;6@GrE_(7Zl8Ztn#0SWYY|>JuGyEOPyI{q zj1UOmhXi}qm-nLay|lG^9vIX8+s~x8Im@Xg%c;&{@`^-+-kz-=5;my7Vf0^7Gg#pG z>y4r5LA+flG?5JgoVIIzIc;^H4Etjl^0!ILlK+xb(3hpXZJ9EATa=|%jmzP!MrQx^ zNhPSK#3zO|uo@|?YEaYO_eeBxH}giZ0QXqY*H0Hb{`FoV*AJ_vrpv!Nyf-waLYKx& z#m(JLKPN#Ht_%v?i19}~$-J2VykySp4P%RO3DH}r(MSCACTeOjPg@?0Mb^^q{%o{uf0Iqv z(J(=1jvJkfZ*9jV46x3%~>36|{?rsru5 zQ)RXk$*-FB=j{kkWmBhYWm8{P@m|v+x57wUWlu_c<^G6+F0wMh25NgG|D`9(NLvUc z2t=?RJGH^~hw{{(u$JreRl@PDRyhvxjy$rC=4om!U#M6T=`H@UzLdRr19$P{#q6C% z^5UVV>ZDE`3&|S(mwk?_&naZ)$4DfP^cH>jD%)nM;*o2j`&dQ9xlLI-bAze2QU;x@ zKJ!Y{Qd=n>?r>CF({yBbRo%ZVca6boQxCX&aZ-u3$fodz?#2Oo=S2h>&oCY0P zSsNQ$8!TDt?mZ$i_5OYhyo$1W`LcQ{Qhdj&13N?mm^W;A_rTXOyrHpXpwZrjpG)^v zt$kdTNa9*`j_{y$8&*Vwy}i8RC`S>m=3dkE?UO%$w~PM0*IYga9Z(4^2}-dEv2F9A zuj#K5OBQHt7_z#0bG1MJmfV5ThaJ7XDPPGq^Gx7Z%k9yP(`sjpT8RJe5}hgBG=2S5 t#r;O=Ek|Uk?r+yE>>b&=KcsqOiH`A*z5Uct8)^z(n(8`g87gL%{};xPG;#m{ literal 0 HcmV?d00001 diff --git a/docker/b_image/Dockerfile b/docker/b_image/Dockerfile new file mode 100644 index 0000000..3fe3c06 --- /dev/null +++ b/docker/b_image/Dockerfile @@ -0,0 +1,3 @@ +FROM ubuntu:18.04 + +RUN apt-get update && DEBIAN_FRONTEND=noninteractive apt-get install -y cmake git libtbb-dev libeigen3-dev libglew-dev ccache libjpeg-dev libpng-dev openssh-client liblz4-dev libbz2-dev libboost-regex-dev libboost-filesystem-dev libboost-date-time-dev libboost-program-options-dev libopencv-dev libpython2.7-dev libgtest-dev lsb-core gcovr ggcov lcov diff --git a/docker/b_image_xenial/Dockerfile b/docker/b_image_xenial/Dockerfile new file mode 100644 index 0000000..38ceeec --- /dev/null +++ b/docker/b_image_xenial/Dockerfile @@ -0,0 +1,17 @@ +FROM ubuntu:16.04 + +RUN apt-get update && apt-get install -y cmake git libtbb-dev libeigen3-dev libglew-dev ccache libjpeg-dev libpng12-dev openssh-client liblz4-dev libbz2-dev libboost-regex-dev libboost-filesystem-dev libboost-date-time-dev libboost-program-options-dev libopencv-dev libpython2.7-dev wget libgtest-dev software-properties-common + +RUN wget https://cmake.org/files/v3.13/cmake-3.13.4-Linux-x86_64.sh +RUN chmod +x cmake-3.13.4-Linux-x86_64.sh +RUN ./cmake-3.13.4-Linux-x86_64.sh --skip-license --prefix=/usr/local +RUN update-alternatives --install /usr/bin/cmake cmake /usr/local/bin/cmake 1 --force +RUN cmake --version + + +RUN add-apt-repository ppa:ubuntu-toolchain-r/test +RUN apt update && apt-get install -y g++-7 +RUN update-alternatives --install /usr/bin/gcc gcc /usr/bin/gcc-7 60 \ + --slave /usr/bin/g++ g++ /usr/bin/g++-7 +RUN gcc --version +RUN g++ --version diff --git a/include/basalt/calibration/aprilgrid.h b/include/basalt/calibration/aprilgrid.h new file mode 100644 index 0000000..cf1c79e --- /dev/null +++ b/include/basalt/calibration/aprilgrid.h @@ -0,0 +1,137 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +namespace basalt { + +struct AprilGrid { + AprilGrid() { + const int tagCols = 6; // number of apriltags + const int tagRows = 6; // number of apriltags + const double tagSize = 0.088; // size of apriltag, edge to edge [m] + const double tagSpacing = 0.3; // ratio of space between tags to tagSize + + double x_corner_offsets[4] = {0, tagSize, tagSize, 0}; + double y_corner_offsets[4] = {0, 0, tagSize, tagSize}; + + aprilgrid_corner_pos_3d.resize(tagCols * tagRows * 4); + + for (int y = 0; y < tagCols; y++) { + for (int x = 0; x < tagRows; x++) { + int tag_id = tagRows * y + x; + double x_offset = x * tagSize * (1 + tagSpacing); + double y_offset = y * tagSize * (1 + tagSpacing); + + for (int i = 0; i < 4; i++) { + int corner_id = (tag_id << 2) + i; + + Eigen::Vector4d &pos_3d = aprilgrid_corner_pos_3d[corner_id]; + + pos_3d[0] = x_offset + x_corner_offsets[i]; + pos_3d[1] = y_offset + y_corner_offsets[i]; + pos_3d[2] = 0; + pos_3d[3] = 1; + } + } + } + + size_t num_vign_points = 5; + size_t num_blocks = tagCols * tagRows * 2; + + aprilgrid_vignette_pos_3d.resize((num_blocks + tagCols + tagRows) * + num_vign_points); + + for (size_t k = 0; k < num_vign_points; k++) { + for (size_t i = 0; i < tagCols * tagRows; i++) { + // const Eigen::Vector3d p0 = aprilgrid_corner_pos_3d[4 * i + 0]; + const Eigen::Vector4d p1 = aprilgrid_corner_pos_3d[4 * i + 1]; + const Eigen::Vector4d p2 = aprilgrid_corner_pos_3d[4 * i + 2]; + const Eigen::Vector4d p3 = aprilgrid_corner_pos_3d[4 * i + 3]; + + double coeff = double(k + 1) / double(num_vign_points + 1); + + aprilgrid_vignette_pos_3d[k * num_blocks + 2 * i + 0] = + (p1 + coeff * (p2 - p1)); + aprilgrid_vignette_pos_3d[k * num_blocks + 2 * i + 1] = + (p2 + coeff * (p3 - p2)); + + aprilgrid_vignette_pos_3d[k * num_blocks + 2 * i + 0][0] += + tagSize * tagSpacing / 2; + aprilgrid_vignette_pos_3d[k * num_blocks + 2 * i + 1][1] += + tagSize * tagSpacing / 2; + } + } + + size_t curr_idx = num_blocks * num_vign_points; + + for (size_t k = 0; k < num_vign_points; k++) { + for (size_t i = 0; i < tagCols; i++) { + const Eigen::Vector4d p0 = aprilgrid_corner_pos_3d[4 * i + 0]; + const Eigen::Vector4d p1 = aprilgrid_corner_pos_3d[4 * i + 1]; + + double coeff = double(k + 1) / double(num_vign_points + 1); + + aprilgrid_vignette_pos_3d[curr_idx + k * tagCols + i] = + (p0 + coeff * (p1 - p0)); + + aprilgrid_vignette_pos_3d[curr_idx + k * tagCols + i][1] -= + tagSize * tagSpacing / 2; + } + } + + curr_idx += tagCols * num_vign_points; + + for (size_t k = 0; k < num_vign_points; k++) { + for (size_t i = 0; i < tagRows; i++) { + const Eigen::Vector4d p0 = aprilgrid_corner_pos_3d[4 * i * tagCols + 0]; + const Eigen::Vector4d p3 = aprilgrid_corner_pos_3d[4 * i * tagCols + 3]; + + double coeff = double(k + 1) / double(num_vign_points + 1); + + aprilgrid_vignette_pos_3d[curr_idx + k * tagCols + i] = + (p0 + coeff * (p3 - p0)); + + aprilgrid_vignette_pos_3d[curr_idx + k * tagCols + i][0] -= + tagSize * tagSpacing / 2; + } + } + } + + Eigen::vector aprilgrid_corner_pos_3d; + Eigen::vector aprilgrid_vignette_pos_3d; +}; +} // namespace basalt diff --git a/include/basalt/calibration/calibration_helper.h b/include/basalt/calibration/calibration_helper.h new file mode 100644 index 0000000..558ee5c --- /dev/null +++ b/include/basalt/calibration/calibration_helper.h @@ -0,0 +1,116 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include + +#include +#include + +namespace basalt { + +struct CalibCornerData { + Eigen::vector corners; + std::vector corner_ids; + std::vector radii; //!< threshold used for maximum displacement + //! during sub-pix refinement; Search region is + //! slightly larger. + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +struct CalibInitPoseData { + Sophus::SE3d T_a_c; + size_t num_inliers; + + Eigen::vector reprojected_corners; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +class CalibHelper { + public: + static void detectCorners( + const VioDatasetPtr& vio_data, + tbb::concurrent_unordered_map& calib_corners, + tbb::concurrent_unordered_map& + calib_corners_rejected); + + static void initCamPoses( + const Calibration::Ptr& calib, const VioDatasetPtr& vio_data, + const Eigen::vector& aprilgrid_corner_pos_3d, + tbb::concurrent_unordered_map& calib_corners, + tbb::concurrent_unordered_map& + calib_init_poses); + + static bool initializeIntrinsics( + const Eigen::vector& corners, + const std::vector& corner_ids, + const Eigen::vector& aprilgrid_corner_pos_3d, int cols, + int rows, Eigen::Vector4d& init_intr); + + private: + inline static double square(double x) { return x * x; } + + inline static double hypot(double a, double b) { + return sqrt(square(a) + square(b)); + } + + static void computeInitialPose( + const Calibration::Ptr& calib, size_t cam_id, + const Eigen::vector& aprilgrid_corner_pos_3d, + const basalt::CalibCornerData& cd, basalt::CalibInitPoseData& cp); + + static size_t computeReprojectionError( + const UnifiedCamera& cam_calib, + const Eigen::vector& corners, + const std::vector& corner_ids, + const Eigen::vector& aprilgrid_corner_pos_3d, + const Sophus::SE3d& T_target_camera, double& error); +}; + +} // namespace basalt + +namespace cereal { +template +void serialize(Archive& ar, basalt::CalibCornerData& c) { + ar(c.corners, c.corner_ids, c.radii); +} + +template +void serialize(Archive& ar, basalt::CalibInitPoseData& c) { + ar(c.T_a_c, c.num_inliers, c.reprojected_corners); +} +} // namespace cereal diff --git a/include/basalt/calibration/cam_calib.h b/include/basalt/calibration/cam_calib.h new file mode 100644 index 0000000..aef7bd2 --- /dev/null +++ b/include/basalt/calibration/cam_calib.h @@ -0,0 +1,165 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace basalt { + +class PosesOptimization; + +class CamCalib { + public: + CamCalib(const std::string &dataset_path, const std::string &dataset_type, + const std::string &cache_path, const std::string &cache_dataset_name, + int skip_images, const std::vector &cam_types, + bool show_gui = true); + + ~CamCalib(); + + void initGui(); + + void computeVign(); + + void setNumCameras(size_t n); + + void renderingLoop(); + + void computeProjections(); + + void detectCorners(); + + void initCamIntrinsics(); + + void initCamPoses(); + + void initCamExtrinsics(); + + void initOptimization(); + + void loadDataset(); + + void optimize(); + + void optimizeWithParam(bool print_info, + std::map *stats = nullptr); + + void saveCalib(); + + void drawImageOverlay(pangolin::View &v, size_t cam_id); + + bool hasCorners() const; + + void setOptIntrinsics(bool opt) { opt_intr = opt; } + + private: + static constexpr int UI_WIDTH = 300; + + static constexpr size_t RANSAC_THRESHOLD = 10; + + // typedef Calibration::Ptr CalibrationPtr; + + AprilGrid april_grid; + + VioDatasetPtr vio_dataset; + // CalibrationPtr calib; + + tbb::concurrent_unordered_map calib_corners; + tbb::concurrent_unordered_map + calib_corners_rejected; + tbb::concurrent_unordered_map calib_init_poses; + + std::shared_ptr processing_thread; + + std::shared_ptr calib_opt; + + std::map> reprojected_corners; + std::map> reprojected_vignette; + std::map> reprojected_vignette_error; + + std::string dataset_path; + std::string dataset_type; + std::string cache_path; + std::string cache_dataset_name; + + int skip_images; + + std::vector cam_types; + + bool show_gui; + + const size_t MIN_CORNERS = 15; + + ////////////////////// + + pangolin::Var show_frame; + + pangolin::Var show_corners; + pangolin::Var show_corners_rejected; + pangolin::Var show_init_reproj; + pangolin::Var show_opt; + pangolin::Var show_vign; + pangolin::Var show_ids; + + pangolin::Var huber_thresh; + + pangolin::Var opt_intr; + + std::shared_ptr vign_plotter; + pangolin::View *img_view_display; + + std::vector> img_view; + + pangolin::DataLog vign_data_log; +}; + +} // namespace basalt diff --git a/include/basalt/calibration/cam_imu_calib.h b/include/basalt/calibration/cam_imu_calib.h new file mode 100644 index 0000000..d616d34 --- /dev/null +++ b/include/basalt/calibration/cam_imu_calib.h @@ -0,0 +1,180 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace basalt { + +template +class SplineOptimization; + +class CamImuCalib { + public: + CamImuCalib(const std::string &dataset_path, const std::string &dataset_type, + const std::string &cache_path, + const std::string &cache_dataset_name, int skip_images, + const std::vector &imu_noise, bool show_gui = true); + + ~CamImuCalib(); + + void initGui(); + + void setNumCameras(size_t n); + + void renderingLoop(); + + void computeProjections(); + + void detectCorners(); + + void initCamPoses(); + + void initCamImuTransform(); + + void initOptimization(); + + void initMocap(); + + void loadDataset(); + + void optimize(); + + void optimizeWithParam(bool print_info, + std::map *stats = nullptr); + + void saveCalib(); + + void saveMocapCalib(); + + void drawImageOverlay(pangolin::View &v, size_t cam_id); + + void recomputeDataLog(); + + void drawPlots(); + + bool hasCorners() const; + + void setOptIntrinsics(bool opt) { opt_intr = opt; } + + private: + static constexpr int UI_WIDTH = 300; + + AprilGrid april_grid; + + VioDatasetPtr vio_dataset; + + tbb::concurrent_unordered_map calib_corners; + tbb::concurrent_unordered_map + calib_corners_rejected; + tbb::concurrent_unordered_map calib_init_poses; + + std::shared_ptr processing_thread; + + std::shared_ptr> calib_opt; + + std::map> reprojected_corners; + + std::string dataset_path; + std::string dataset_type; + std::string cache_path; + std::string cache_dataset_name; + + int skip_images; + + bool show_gui; + + const size_t MIN_CORNERS = 15; + + std::vector imu_noise; + + ////////////////////// + + pangolin::Var show_frame; + + pangolin::Var show_corners; + pangolin::Var show_corners_rejected; + pangolin::Var show_init_reproj; + pangolin::Var show_opt; + pangolin::Var show_ids; + + pangolin::Var show_accel; + pangolin::Var show_gyro; + pangolin::Var show_pos; + pangolin::Var show_rot_error; + + pangolin::Var show_mocap; + pangolin::Var show_mocap_rot_error; + pangolin::Var show_mocap_rot_vel; + + pangolin::Var show_spline; + pangolin::Var show_data; + + pangolin::Var opt_intr; + pangolin::Var opt_poses; + pangolin::Var opt_corners; + pangolin::Var opt_cam_time_offset; + pangolin::Var opt_imu_scale; + + pangolin::Var opt_mocap; + + pangolin::Var huber_thresh; + + pangolin::Plotter *plotter; + pangolin::View *img_view_display; + + std::vector> img_view; + + pangolin::DataLog imu_data_log, pose_data_log, mocap_data_log, vign_data_log; +}; + +} // namespace basalt diff --git a/include/basalt/calibration/vignette.h b/include/basalt/calibration/vignette.h new file mode 100644 index 0000000..15b7fb2 --- /dev/null +++ b/include/basalt/calibration/vignette.h @@ -0,0 +1,87 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include + +#include + +#include + +namespace basalt { + +class VignetteEstimator { + public: + static const int SPLINE_N = 4; + static const int64_t knot_spacing = 1e10; + static const int border_size = 2; + + VignetteEstimator(const VioDatasetPtr &vio_dataset, + const Eigen::vector &optical_centers, + const std::map> + &reprojected_vignette, + const AprilGrid &april_grid); + + void compute_error(std::map> + *reprojected_vignette_error = nullptr); + + void opt_irradience(); + + void opt_vign(); + + void optimize(); + + void compute_data_log(pangolin::DataLog &vign_data_log); + + void save_vign_png(const std::string &path); + + inline const std::vector> &get_vign_param() { + return vign_param; + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + private: + const VioDatasetPtr vio_dataset; + Eigen::vector optical_centers; + std::map> reprojected_vignette; + const AprilGrid &april_grid; + + size_t vign_size; + std::vector irradiance; + std::vector> vign_param; +}; +} diff --git a/include/basalt/io/dataset_io.h b/include/basalt/io/dataset_io.h new file mode 100644 index 0000000..6909019 --- /dev/null +++ b/include/basalt/io/dataset_io.h @@ -0,0 +1,247 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ +#ifndef DATASET_IO_H +#define DATASET_IO_H + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +#include +#include + +#include +#include + +#include + +namespace basalt { + +inline bool file_exists(const std::string &name) { + std::ifstream f(name.c_str()); + return f.good(); +} + +typedef std::pair TimeCamId; + +struct ImageData { + ImageData() : exposure(0) {} + + ManagedImage::Ptr img; + double exposure; +}; + +struct Observations { + Eigen::vector pos; + std::vector id; +}; + +struct GyroData { + int64_t timestamp_ns; + Eigen::Vector3d data; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +struct AccelData { + int64_t timestamp_ns; + Eigen::Vector3d data; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +struct PoseData { + int64_t timestamp_ns; + Sophus::SE3d data; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +struct MocapPoseData { + int64_t timestamp_ns; + Sophus::SE3d data; + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +struct AprilgridCornersData { + int64_t timestamp_ns; + int cam_id; + + Eigen::vector corner_pos; + std::vector corner_id; +}; + +class VioDataset { + public: + virtual ~VioDataset(){}; + + virtual size_t get_num_cams() const = 0; + + virtual std::vector &get_image_timestamps() = 0; + + virtual const Eigen::vector &get_accel_data() const = 0; + virtual const Eigen::vector &get_gyro_data() const = 0; + virtual const std::vector &get_gt_timestamps() const = 0; + virtual const Eigen::vector &get_gt_pose_data() const = 0; + virtual int64_t get_mocap_to_imu_offset_ns() const = 0; + virtual std::vector get_image_data(int64_t t_ns) = 0; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +typedef std::shared_ptr VioDatasetPtr; + +class DatasetIoInterface { + public: + virtual void read(const std::string &path) = 0; + virtual void reset() = 0; + virtual VioDatasetPtr get_data() = 0; + + virtual ~DatasetIoInterface(){}; +}; + +typedef std::shared_ptr DatasetIoInterfacePtr; + +class DatasetIoFactory { + public: + static DatasetIoInterfacePtr getDatasetIo(const std::string &dataset_type, + bool with_images = true); +}; + +} // namespace basalt + +namespace cereal { + +template +inline + typename std::enable_if<_Rows == Eigen::Dynamic || _Cols == Eigen::Dynamic, + void>::type + save(Archive &ar, const Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, + _MaxRows, _MaxCols> &matrix) { + const std::int32_t rows = static_cast(matrix.rows()); + const std::int32_t cols = static_cast(matrix.cols()); + ar(rows); + ar(cols); + ar(binary_data(matrix.data(), rows * cols * sizeof(_Scalar))); +}; + +template +inline + typename std::enable_if<_Rows == Eigen::Dynamic || _Cols == Eigen::Dynamic, + void>::type + load(Archive &ar, Eigen::Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, + _MaxCols> &matrix) { + std::int32_t rows; + std::int32_t cols; + ar(rows); + ar(cols); + + matrix.resize(rows, cols); + + ar(binary_data(matrix.data(), + static_cast(rows * cols * sizeof(_Scalar)))); +}; + +template +void serialize(Archive &archive, basalt::ManagedImage &m) { + archive(m.w); + archive(m.h); + + m.Reinitialise(m.w, m.h); + + archive(binary_data(m.ptr, m.size())); +} + +template +void serialize(Archive &ar, basalt::GyroData &c) { + ar(c.timestamp_ns, c.data); +} + +template +void serialize(Archive &ar, basalt::AccelData &c) { + ar(c.timestamp_ns, c.data); +} + +} // namespace cereal + +namespace std { + +inline void hash_combine(std::size_t &seed, std::size_t value) { + seed ^= value + 0x9e3779b9 + (seed << 6) + (seed >> 2); +} + +template <> +struct hash { + size_t operator()(const basalt::TimeCamId &x) const { + size_t seed = 0; + hash_combine(seed, std::hash()(x.first)); + hash_combine(seed, std::hash()(x.second)); + return seed; + } +}; + +template <> +struct hash> { + size_t operator()( + const std::pair &x) const { + size_t seed = 0; + hash_combine(seed, std::hash()(x.first.first)); + hash_combine(seed, std::hash()(x.first.second)); + hash_combine(seed, std::hash()(x.second.first)); + hash_combine(seed, std::hash()(x.second.second)); + return seed; + } +}; +} // namespace std + +#endif // DATASET_IO_H diff --git a/include/basalt/io/dataset_io_euroc.h b/include/basalt/io/dataset_io_euroc.h new file mode 100644 index 0000000..5ca5a8c --- /dev/null +++ b/include/basalt/io/dataset_io_euroc.h @@ -0,0 +1,248 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ +#ifndef DATASET_IO_EUROC_H +#define DATASET_IO_EUROC_H + +#include + +namespace basalt { + +class EurocVioDataset : public VioDataset { + size_t num_cams; + + std::string path; + + std::vector image_timestamps; + std::unordered_map image_path; + + // vector of images for every timestamp + // assumes vectors size is num_cams for every timestamp with null pointers for + // missing frames + // std::unordered_map> image_data; + + Eigen::vector accel_data; + Eigen::vector gyro_data; + + std::vector gt_timestamps; // ordered gt timestamps + Eigen::vector gt_pose_data; // TODO: change to eigen aligned + + int64_t mocap_to_imu_offset_ns; + + public: + ~EurocVioDataset(){}; + + size_t get_num_cams() const { return num_cams; } + + std::vector &get_image_timestamps() { return image_timestamps; } + + const Eigen::vector &get_accel_data() const { return accel_data; } + const Eigen::vector &get_gyro_data() const { return gyro_data; } + const std::vector &get_gt_timestamps() const { + return gt_timestamps; + } + const Eigen::vector &get_gt_pose_data() const { + return gt_pose_data; + } + int64_t get_mocap_to_imu_offset_ns() const { return mocap_to_imu_offset_ns; } + + std::vector get_image_data(int64_t t_ns) { + std::vector res(num_cams); + + const std::vector folder = {"/mav0/cam0/", "/mav0/cam1/"}; + + for (size_t i = 0; i < num_cams; i++) { + std::string full_image_path = + path + folder[i] + "data/" + image_path[t_ns]; + + if (file_exists(full_image_path)) { + pangolin::TypedImage img = pangolin::LoadImage(full_image_path); + + if (img.fmt.bpp == 8) { + res[i].img.reset(new ManagedImage(img.w, img.h)); + + const uint8_t *data_in = img.ptr; + uint16_t *data_out = res[i].img->ptr; + + for (size_t i = 0; i < img.size(); i++) { + int val = data_in[i]; + val = val << 8; + data_out[i] = val; + } + } else if (img.fmt.bpp == 16) { + res[i].img.reset(new ManagedImage(img.w, img.h)); + std::memcpy(res[i].img->ptr, img.ptr, img.size() * sizeof(uint16_t)); + + } else { + std::cerr << "img.fmt.bpp " << img.fmt.bpp << std::endl; + std::abort(); + } + } + } + + return res; + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + friend class EurocIO; +}; + +class EurocIO : public DatasetIoInterface { + public: + EurocIO() {} + + void read(const std::string &path) { + data.reset(new EurocVioDataset); + + data->num_cams = 2; + data->path = path; + + read_image_timestamps(path + "/mav0/cam0/"); + + read_imu_data(path + "/mav0/imu0/"); + + if (file_exists(path + "/mav0/state_groundtruth_estimate0/data.csv")) { + read_gt_data_state(path + "/mav0/state_groundtruth_estimate0/"); + } else if (file_exists(path + "/mav0/mocap0/data.csv")) { + read_gt_data_pose(path + "/mav0/mocap0/"); + } + } + + void reset() { data.reset(); } + + VioDatasetPtr get_data() { return data; } + + private: + void read_image_timestamps(const std::string &path) { + std::ifstream f(path + "data.csv"); + std::string line; + while (std::getline(f, line)) { + if (line[0] == '#') continue; + std::stringstream ss(line); + char tmp; + int64_t t_ns; + std::string path; + ss >> t_ns >> tmp >> path; + + data->image_timestamps.emplace_back(t_ns); + data->image_path[t_ns] = path; + } + } + + void read_imu_data(const std::string &path) { + data->accel_data.clear(); + data->gyro_data.clear(); + + std::ifstream f(path + "data.csv"); + std::string line; + while (std::getline(f, line)) { + if (line[0] == '#') continue; + + std::stringstream ss(line); + + char tmp; + uint64_t timestamp; + Eigen::Vector3d gyro, accel; + + ss >> timestamp >> tmp >> gyro[0] >> tmp >> gyro[1] >> tmp >> gyro[2] >> + tmp >> accel[0] >> tmp >> accel[1] >> tmp >> accel[2]; + + data->accel_data.emplace_back(); + data->accel_data.back().timestamp_ns = timestamp; + data->accel_data.back().data = accel; + + data->gyro_data.emplace_back(); + data->gyro_data.back().timestamp_ns = timestamp; + data->gyro_data.back().data = gyro; + } + } + + void read_gt_data_state(const std::string &path) { + data->gt_timestamps.clear(); + data->gt_pose_data.clear(); + + std::ifstream f(path + "data.csv"); + std::string line; + while (std::getline(f, line)) { + if (line[0] == '#') continue; + + std::stringstream ss(line); + + char tmp; + uint64_t timestamp; + Eigen::Quaterniond q; + Eigen::Vector3d pos, vel, accel_bias, gyro_bias; + + ss >> timestamp >> tmp >> pos[0] >> tmp >> pos[1] >> tmp >> pos[2] >> + tmp >> q.w() >> tmp >> q.x() >> tmp >> q.y() >> tmp >> q.z() >> tmp >> + vel[0] >> tmp >> vel[1] >> tmp >> vel[2] >> tmp >> accel_bias[0] >> + tmp >> accel_bias[1] >> tmp >> accel_bias[2] >> tmp >> gyro_bias[0] >> + tmp >> gyro_bias[1] >> tmp >> gyro_bias[2]; + + data->gt_timestamps.emplace_back(timestamp); + data->gt_pose_data.emplace_back(q, pos); + } + } + + void read_gt_data_pose(const std::string &path) { + data->gt_timestamps.clear(); + data->gt_pose_data.clear(); + + std::ifstream f(path + "data.csv"); + std::string line; + while (std::getline(f, line)) { + if (line[0] == '#') continue; + + std::stringstream ss(line); + + char tmp; + uint64_t timestamp; + Eigen::Quaterniond q; + Eigen::Vector3d pos; + + ss >> timestamp >> tmp >> pos[0] >> tmp >> pos[1] >> tmp >> pos[2] >> + tmp >> q.w() >> tmp >> q.x() >> tmp >> q.y() >> tmp >> q.z(); + + data->gt_timestamps.emplace_back(timestamp); + data->gt_pose_data.emplace_back(q, pos); + } + } + + std::shared_ptr data; +}; + +} // namespace basalt + +#endif // DATASET_IO_H diff --git a/include/basalt/io/dataset_io_rosbag.h b/include/basalt/io/dataset_io_rosbag.h new file mode 100644 index 0000000..01f6919 --- /dev/null +++ b/include/basalt/io/dataset_io_rosbag.h @@ -0,0 +1,375 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ +#ifndef DATASET_IO_ROSBAG_H +#define DATASET_IO_ROSBAG_H + +#include +#include + +#include + +// Hack to access private functions +#define private public +#include +#include +#undef private + +#include +#include +#include +#include + +namespace basalt { + +class RosbagVioDataset : public VioDataset { + std::shared_ptr bag; + std::mutex m; + + size_t num_cams; + + std::vector image_timestamps; + + // vector of images for every timestamp + // assumes vectors size is num_cams for every timestamp with null pointers for + // missing frames + std::unordered_map>> + image_data_idx; + + Eigen::vector accel_data; + Eigen::vector gyro_data; + + std::vector gt_timestamps; // ordered gt timestamps + Eigen::vector gt_pose_data; // TODO: change to eigen aligned + + int64_t mocap_to_imu_offset_ns; + + public: + ~RosbagVioDataset() {} + + size_t get_num_cams() const { return num_cams; } + + std::vector &get_image_timestamps() { return image_timestamps; } + + const Eigen::vector &get_accel_data() const { return accel_data; } + const Eigen::vector &get_gyro_data() const { return gyro_data; } + const std::vector &get_gt_timestamps() const { + return gt_timestamps; + } + const Eigen::vector &get_gt_pose_data() const { + return gt_pose_data; + } + int64_t get_mocap_to_imu_offset_ns() const { return mocap_to_imu_offset_ns; } + + std::vector get_image_data(int64_t t_ns) { + std::vector res(num_cams); + + auto it = image_data_idx.find(t_ns); + + if (it != image_data_idx.end()) + for (size_t i = 0; i < num_cams; i++) { + ImageData &id = res[i]; + + if (!it->second[i].has_value()) continue; + + m.lock(); + sensor_msgs::ImageConstPtr img_msg = + bag->instantiateBuffer(*it->second[i]); + m.unlock(); + + // std::cerr << "img_msg->width " << img_msg->width << " + // img_msg->height " + // << img_msg->height << std::endl; + + id.img.reset( + new ManagedImage(img_msg->width, img_msg->height)); + + if (!img_msg->header.frame_id.empty() && + std::isdigit(img_msg->header.frame_id[0])) { + id.exposure = std::stol(img_msg->header.frame_id) * 1e-9; + } else { + id.exposure = -1; + } + + if (img_msg->encoding == "mono8") { + const uint8_t *data_in = img_msg->data.data(); + uint16_t *data_out = id.img->ptr; + + for (size_t i = 0; i < img_msg->data.size(); i++) { + int val = data_in[i]; + val = val << 8; + data_out[i] = val; + } + + } else if (img_msg->encoding == "mono16") { + std::memcpy(id.img->ptr, img_msg->data.data(), img_msg->data.size()); + } else { + std::cerr << "Encoding " << img_msg->encoding << " is not supported." + << std::endl; + std::abort(); + } + } + + return res; + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + friend class RosbagIO; +}; + +class RosbagIO : public DatasetIoInterface { + public: + RosbagIO(bool with_images) : with_images(with_images) {} + + void read(const std::string &path) { + data.reset(new RosbagVioDataset); + + data->bag.reset(new rosbag::Bag); + data->bag->open(path, rosbag::bagmode::Read); + + rosbag::View view(*data->bag, [this](const rosbag::ConnectionInfo *ci) { + if (this->with_images) + return true; + else + return ci->datatype == std::string("sensor_msgs/Imu") || + ci->datatype == std::string("geometry_msgs/TransformStamped"); + }); + + // get topics + std::vector connection_infos = + view.getConnections(); + + std::set cam_topics; + std::string imu_topic; + std::string mocap_topic; + std::string point_topic; + + for (const rosbag::ConnectionInfo *info : connection_infos) { + // if (info->topic.substr(0, 4) == std::string("/cam")) { + // cam_topics.insert(info->topic); + // } else if (info->topic.substr(0, 4) == std::string("/imu")) { + // imu_topic = info->topic; + // } else if (info->topic.substr(0, 5) == std::string("/vrpn") || + // info->topic.substr(0, 6) == std::string("/vicon")) { + // mocap_topic = info->topic; + // } + + if (info->datatype == std::string("sensor_msgs/Image")) { + cam_topics.insert(info->topic); + } else if (info->datatype == std::string("sensor_msgs/Imu")) { + imu_topic = info->topic; + } else if (info->datatype == + std::string("geometry_msgs/TransformStamped")) { + mocap_topic = info->topic; + } else if (info->datatype == std::string("geometry_msgs/PointStamped")) { + point_topic = info->topic; + } + } + + std::cout << "imu_topic: " << imu_topic << std::endl; + std::cout << "mocap_topic: " << mocap_topic << std::endl; + std::cout << "cam_topics: "; + for (const std::string &s : cam_topics) std::cout << s << " "; + std::cout << std::endl; + + std::map topic_to_id; + int idx = 0; + for (const std::string &s : cam_topics) { + topic_to_id[s] = idx; + idx++; + } + + data->num_cams = cam_topics.size(); + + int num_msgs = 0; + + int64_t min_time = std::numeric_limits::max(); + int64_t max_time = std::numeric_limits::min(); + + std::vector mocap_msgs; + std::vector point_msgs; + + std::vector + system_to_imu_offset_vec; // t_imu = t_system + system_to_imu_offset + std::vector system_to_mocap_offset_vec; // t_mocap = t_system + + // system_to_mocap_offset + + std::set image_timestamps; + + for (rosbag::MessageInstance const m : view) { + const std::string &topic = m.getTopic(); + + if (cam_topics.find(topic) != cam_topics.end()) { + sensor_msgs::ImageConstPtr img_msg = + m.instantiate(); + int64_t timestamp_ns = img_msg->header.stamp.toNSec(); + + auto &img_vec = data->image_data_idx[timestamp_ns]; + if (img_vec.size() == 0) img_vec.resize(data->num_cams); + + img_vec[topic_to_id.at(topic)] = m.index_entry_; + image_timestamps.insert(timestamp_ns); + + min_time = std::min(min_time, timestamp_ns); + max_time = std::max(max_time, timestamp_ns); + } + + if (imu_topic == topic) { + sensor_msgs::ImuConstPtr imu_msg = m.instantiate(); + int64_t time = imu_msg->header.stamp.toNSec(); + + data->accel_data.emplace_back(); + data->accel_data.back().timestamp_ns = time; + data->accel_data.back().data = Eigen::Vector3d( + imu_msg->linear_acceleration.x, imu_msg->linear_acceleration.y, + imu_msg->linear_acceleration.z); + + data->gyro_data.emplace_back(); + data->gyro_data.back().timestamp_ns = time; + data->gyro_data.back().data = Eigen::Vector3d( + imu_msg->angular_velocity.x, imu_msg->angular_velocity.y, + imu_msg->angular_velocity.z); + + min_time = std::min(min_time, time); + max_time = std::max(max_time, time); + + int64_t msg_arrival_time = m.getTime().toNSec(); + system_to_imu_offset_vec.push_back(time - msg_arrival_time); + } + + if (mocap_topic == topic) { + geometry_msgs::TransformStampedConstPtr mocap_msg = + m.instantiate(); + int64_t time = mocap_msg->header.stamp.toNSec(); + + mocap_msgs.push_back(mocap_msg); + + int64_t msg_arrival_time = m.getTime().toNSec(); + system_to_mocap_offset_vec.push_back(time - msg_arrival_time); + } + + if (point_topic == topic) { + geometry_msgs::PointStampedConstPtr mocap_msg = + m.instantiate(); + int64_t time = mocap_msg->header.stamp.toNSec(); + + point_msgs.push_back(mocap_msg); + + int64_t msg_arrival_time = m.getTime().toNSec(); + system_to_mocap_offset_vec.push_back(time - msg_arrival_time); + } + + num_msgs++; + } + + data->image_timestamps.clear(); + data->image_timestamps.insert(data->image_timestamps.begin(), + image_timestamps.begin(), + image_timestamps.end()); + + if (system_to_mocap_offset_vec.size() > 0) { + int64_t system_to_imu_offset = + system_to_imu_offset_vec[system_to_imu_offset_vec.size() / 2]; + + int64_t system_to_mocap_offset = + system_to_mocap_offset_vec[system_to_mocap_offset_vec.size() / 2]; + + data->mocap_to_imu_offset_ns = + system_to_imu_offset - system_to_mocap_offset; + } + + data->gt_pose_data.clear(); + data->gt_timestamps.clear(); + + if (!mocap_msgs.empty()) + for (size_t i = 0; i < mocap_msgs.size() - 1; i++) { + auto mocap_msg = mocap_msgs[i]; + + int64_t time = mocap_msg->header.stamp.toNSec(); + + Eigen::Quaterniond q( + mocap_msg->transform.rotation.w, mocap_msg->transform.rotation.x, + mocap_msg->transform.rotation.y, mocap_msg->transform.rotation.z); + + Eigen::Vector3d t(mocap_msg->transform.translation.x, + mocap_msg->transform.translation.y, + mocap_msg->transform.translation.z); + + int64_t timestamp_ns = time + data->mocap_to_imu_offset_ns; + data->gt_timestamps.emplace_back(timestamp_ns); + data->gt_pose_data.emplace_back(q, t); + } + + if (!point_msgs.empty()) + for (size_t i = 0; i < point_msgs.size() - 1; i++) { + auto point_msg = point_msgs[i]; + + int64_t time = point_msg->header.stamp.toNSec(); + + Eigen::Vector3d t(point_msg->point.x, point_msg->point.y, + point_msg->point.z); + + int64_t timestamp_ns = time; // + data->mocap_to_imu_offset_ns; + data->gt_timestamps.emplace_back(timestamp_ns); + data->gt_pose_data.emplace_back(Sophus::SO3d(), t); + } + + std::cout << "Total number of messages: " << num_msgs << std::endl; + std::cout << "Image size: " << data->image_data_idx.size() << std::endl; + + std::cout << "Min time: " << min_time << " max time: " << max_time + << " mocap to imu offset: " << data->mocap_to_imu_offset_ns + << std::endl; + + std::cout << "Number of mocap poses: " << data->gt_timestamps.size() + << std::endl; + } + + void reset() { data.reset(); } + + VioDatasetPtr get_data() { + // return std::dynamic_pointer_cast(data); + return data; + } + + private: + std::shared_ptr data; + + bool with_images; +}; + +} // namespace basalt + +#endif // DATASET_IO_ROSBAG_H diff --git a/include/basalt/io/marg_data_io.h b/include/basalt/io/marg_data_io.h new file mode 100644 index 0000000..2be5058 --- /dev/null +++ b/include/basalt/io/marg_data_io.h @@ -0,0 +1,76 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include + +#include + +namespace basalt { + +class MargDataSaver { + public: + using Ptr = std::shared_ptr; + + MargDataSaver(const std::string& path); + ~MargDataSaver() { + saving_thread->join(); + saving_img_thread->join(); + } + tbb::concurrent_bounded_queue in_marg_queue; + + private: + std::shared_ptr saving_thread; + std::shared_ptr saving_img_thread; + + tbb::concurrent_bounded_queue save_image_queue; +}; + +class MargDataLoader { + public: + using Ptr = std::shared_ptr; + + MargDataLoader(); + + void start(const std::string& path); + ~MargDataLoader() { processing_thread->join(); } + + tbb::concurrent_bounded_queue* out_marg_queue; + + private: + std::shared_ptr processing_thread; +}; +} // namespace basalt diff --git a/include/basalt/optical_flow/frame_to_frame_optical_flow.h b/include/basalt/optical_flow/frame_to_frame_optical_flow.h new file mode 100644 index 0000000..5d36243 --- /dev/null +++ b/include/basalt/optical_flow/frame_to_frame_optical_flow.h @@ -0,0 +1,382 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +#include +#include +#include + +#include +#include + +#include + +#include + +namespace basalt { + +template typename Pattern> +class FrameToFrameOpticalFlow : public OpticalFlowBase { + public: + typedef OpticalFlowPatch> PatchT; + + typedef Eigen::Matrix Vector2; + typedef Eigen::Matrix Matrix2; + + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Matrix3; + + typedef Eigen::Matrix Vector4; + typedef Eigen::Matrix Matrix4; + + typedef Sophus::SE2 SE2; + + FrameToFrameOpticalFlow(const VioConfig& config, + const basalt::Calibration& calib) + : t_ns(-1), last_keypoint_id(0), config(config) { + input_queue.set_capacity(10); + + this->calib = calib.cast(); + + patch_coord = PatchT::pattern2.template cast(); + + if (calib.intrinsics.size() > 1) { + Eigen::Matrix4d Ed; + Sophus::SE3d T_i_j = calib.T_i_c[0].inverse() * calib.T_i_c[1]; + computeEssential(T_i_j, Ed); + E = Ed.cast(); + } + + processing_thread.reset( + new std::thread(&FrameToFrameOpticalFlow::processingLoop, this)); + } + + ~FrameToFrameOpticalFlow() { processing_thread->join(); } + + void processingLoop() { + OpticalFlowInput::Ptr input_ptr; + + while (true) { + input_queue.pop(input_ptr); + + if (!input_ptr.get()) { + if (output_queue) output_queue->push(nullptr); + break; + } + + processFrame(input_ptr->t_ns, input_ptr); + } + } + + void processFrame(int64_t curr_t_ns, OpticalFlowInput::Ptr& new_img_vec) { + for (const auto& v : new_img_vec->img_data) { + if (!v.img.get()) return; + } + + if (t_ns < 0) { + t_ns = curr_t_ns; + + transforms.reset(new OpticalFlowResult); + transforms->observations.resize(calib.intrinsics.size()); + transforms->t_ns = t_ns; + + pyramid.reset(new std::vector>); + pyramid->resize(calib.intrinsics.size()); + + tbb::parallel_for(tbb::blocked_range(0, calib.intrinsics.size()), + [&](const tbb::blocked_range& r) { + for (size_t i = r.begin(); i != r.end(); ++i) { + pyramid->at(i).setFromImage( + *new_img_vec->img_data[i].img, + config.optical_flow_levels); + } + }); + + transforms->input_images = new_img_vec; + + addPoints(); + filterPoints(); + + } else { + t_ns = curr_t_ns; + + old_pyramid = pyramid; + + pyramid.reset(new std::vector>); + pyramid->resize(calib.intrinsics.size()); + tbb::parallel_for(tbb::blocked_range(0, calib.intrinsics.size()), + [&](const tbb::blocked_range& r) { + for (size_t i = r.begin(); i != r.end(); ++i) { + pyramid->at(i).setFromImage( + *new_img_vec->img_data[i].img, + config.optical_flow_levels); + } + }); + + OpticalFlowResult::Ptr new_transforms; + new_transforms.reset(new OpticalFlowResult); + new_transforms->observations.resize(calib.intrinsics.size()); + new_transforms->t_ns = t_ns; + + for (size_t i = 0; i < calib.intrinsics.size(); i++) { + trackPoints(old_pyramid->at(i), pyramid->at(i), + transforms->observations[i], + new_transforms->observations[i]); + } + + transforms = new_transforms; + transforms->input_images = new_img_vec; + + addPoints(); + filterPoints(); + } + + if (output_queue) { + output_queue->push(transforms); + } + } + + void trackPoints( + const basalt::ManagedImagePyr& pyr_1, + const basalt::ManagedImagePyr& pyr_2, + const Eigen::map& transform_map_1, + Eigen::map& transform_map_2) const { + size_t num_points = transform_map_1.size(); + + std::vector ids; + Eigen::vector init_vec; + + ids.reserve(num_points); + init_vec.reserve(num_points); + + for (const auto& kv : transform_map_1) { + ids.push_back(kv.first); + init_vec.push_back(kv.second); + } + + tbb::concurrent_unordered_map result; + + auto compute_func = [&](const tbb::blocked_range& range) { + for (size_t r = range.begin(); r != range.end(); ++r) { + const KeypointId id = ids[r]; + + const Eigen::AffineCompact2f& transform_1 = init_vec[r]; + Eigen::AffineCompact2f transform_2 = transform_1; + + bool valid = trackPoint(pyr_1, pyr_2, transform_1, transform_2); + + if (valid) { + Eigen::AffineCompact2f transform_1_recovered = transform_2; + + valid = trackPoint(pyr_2, pyr_1, transform_2, transform_1_recovered); + + if (valid) { + Scalar dist2 = (transform_1.translation() - + transform_1_recovered.translation()) + .squaredNorm(); + + if (dist2 < config.optical_flow_max_recovered_dist2) { + result[id] = transform_2; + } + } + } + } + }; + + tbb::blocked_range range(0, num_points); + + tbb::parallel_for(range, compute_func); + // compute_func(range); + + transform_map_2.clear(); + transform_map_2.insert(result.begin(), result.end()); + } + + inline bool trackPoint(const basalt::ManagedImagePyr& old_pyr, + const basalt::ManagedImagePyr& pyr, + const Eigen::AffineCompact2f& old_transform, + Eigen::AffineCompact2f& transform) const { + bool patch_valid = true; + + transform.linear().setIdentity(); + + for (int level = config.optical_flow_levels; level >= 0 && patch_valid; + level--) { + const Scalar scale = 1 << level; + + transform.translation() /= scale; + + PatchT p(old_pyr.lvl(level), old_transform.translation() / scale); + + // Perform tracking on current level + patch_valid &= trackPointAtLevel(pyr.lvl(level), p, transform); + + transform.translation() *= scale; + } + + transform.linear() = old_transform.linear() * transform.linear(); + + return patch_valid; + } + + inline bool trackPointAtLevel(const Image& img_2, + const PatchT& dp, + Eigen::AffineCompact2f& transform) const { + bool patch_valid = true; + + for (int iteration = 0; + patch_valid && iteration < config.optical_flow_max_iterations; + iteration++) { + typename PatchT::VectorP res; + + typename PatchT::Matrix2P transformed_pat = + transform.linear().matrix() * PatchT::pattern2; + transformed_pat.colwise() += transform.translation(); + + bool valid = dp.residual(img_2, transformed_pat, res); + + if (valid) { + Vector3 inc = -dp.H_se2_inv_J_se2_T * res; + transform *= SE2::exp(inc).matrix(); + + const int filter_margin = 2; + + if (!img_2.InBounds(transform.translation(), filter_margin)) + patch_valid = false; + } else { + patch_valid = false; + } + } + + return patch_valid; + } + + void addPoints() { + Eigen::vector pts0; + + for (const auto& kv : transforms->observations.at(0)) { + pts0.emplace_back(kv.second.translation().cast()); + } + + KeypointsData kd; + + detectKeypoints(pyramid->at(0).lvl(0), kd, + config.optical_flow_detection_grid_size, 1, pts0); + + Eigen::map new_poses0, new_poses1; + + for (size_t i = 0; i < kd.corners.size(); i++) { + Eigen::AffineCompact2f transform; + transform.setIdentity(); + transform.translation() = kd.corners[i].cast(); + + transforms->observations.at(0)[last_keypoint_id] = transform; + new_poses0[last_keypoint_id] = transform; + + last_keypoint_id++; + } + + if (calib.intrinsics.size() > 1) { + trackPoints(pyramid->at(0), pyramid->at(1), new_poses0, new_poses1); + + for (const auto& kv : new_poses1) { + transforms->observations.at(1).emplace(kv); + } + } + } + + void filterPoints() { + if (calib.intrinsics.size() < 2) return; + + std::set lm_to_remove; + + std::vector kpid; + Eigen::vector proj0, proj1; + + for (const auto& kv : transforms->observations.at(1)) { + auto it = transforms->observations.at(0).find(kv.first); + + if (it != transforms->observations.at(0).end()) { + proj0.emplace_back(it->second.translation()); + proj1.emplace_back(kv.second.translation()); + kpid.emplace_back(kv.first); + } + } + + Eigen::vector p3d0, p3d1; + std::vector p3d0_success, p3d1_success; + + calib.intrinsics[0].unproject(proj0, p3d0, p3d0_success); + calib.intrinsics[1].unproject(proj1, p3d1, p3d1_success); + + for (size_t i = 0; i < p3d0_success.size(); i++) { + if (p3d0_success[i] && p3d1_success[i]) { + const double epipolar_error = + std::abs(p3d0[i].transpose() * E * p3d1[i]); + + if (epipolar_error > config.optical_flow_epipolar_error) { + lm_to_remove.emplace(kpid[i]); + } + } else { + lm_to_remove.emplace(kpid[i]); + } + } + + for (int id : lm_to_remove) { + transforms->observations.at(1).erase(id); + } + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + private: + int64_t t_ns; + + KeypointId last_keypoint_id; + + VioConfig config; + basalt::Calibration calib; + + OpticalFlowResult::Ptr transforms; + std::shared_ptr>> old_pyramid, + pyramid; + + Matrix4 E; + + std::shared_ptr processing_thread; +}; + +} // namespace basalt diff --git a/include/basalt/optical_flow/optical_flow.h b/include/basalt/optical_flow/optical_flow.h new file mode 100644 index 0000000..929298c --- /dev/null +++ b/include/basalt/optical_flow/optical_flow.h @@ -0,0 +1,85 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +#include + +#include + +#include +#include +#include +#include + +#include + +namespace basalt { + +using KeypointId = uint32_t; + +struct OpticalFlowInput { + using Ptr = std::shared_ptr; + + int64_t t_ns; + std::vector img_data; +}; + +struct OpticalFlowResult { + using Ptr = std::shared_ptr; + + int64_t t_ns; + std::vector> observations; + + OpticalFlowInput::Ptr input_images; +}; + +class OpticalFlowBase { + public: + using Ptr = std::shared_ptr; + + tbb::concurrent_bounded_queue input_queue; + tbb::concurrent_bounded_queue* output_queue = nullptr; + + Eigen::MatrixXf patch_coord; +}; + +class OpticalFlowFactory { + public: + static OpticalFlowBase::Ptr getOpticalFlow(const VioConfig& config, + const Calibration& cam); +}; +} // namespace basalt diff --git a/include/basalt/optical_flow/patch.h b/include/basalt/optical_flow/patch.h new file mode 100644 index 0000000..11eff68 --- /dev/null +++ b/include/basalt/optical_flow/patch.h @@ -0,0 +1,177 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +#include +#include + +namespace basalt { + +template +struct OpticalFlowPatch { + static constexpr int PATTERN_SIZE = Pattern::PATTERN_SIZE; + + typedef Eigen::Matrix Vector2i; + + typedef Eigen::Matrix Vector2; + typedef Eigen::Matrix Vector2T; + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Matrix3; + typedef Eigen::Matrix Matrix4; + typedef Eigen::Matrix VectorP; + + typedef Eigen::Matrix Matrix2P; + typedef Eigen::Matrix MatrixP2; + typedef Eigen::Matrix MatrixP3; + typedef Eigen::Matrix Matrix3P; + typedef Eigen::Matrix MatrixP4; + typedef Eigen::Matrix Matrix2Pi; + + static const Matrix2P pattern2; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + OpticalFlowPatch() { mean = 0; } + + OpticalFlowPatch(const Image &img, const Vector2 &pos) { + setFromImage(img, pos); + } + + void setFromImage(const Image &img, const Vector2 &pos) { + this->pos = pos; + + int num_valid_points = 0; + Scalar sum = 0; + Vector2 grad_sum(0, 0); + + MatrixP2 grad; + + for (int i = 0; i < PATTERN_SIZE; i++) { + Vector2 p = pos + pattern2.col(i); + if (img.InBounds(p, 2)) { + Vector3 valGrad = img.interpGrad(p); + data[i] = valGrad[0]; + sum += valGrad[0]; + grad.row(i) = valGrad.template tail<2>(); + grad_sum += valGrad.template tail<2>(); + num_valid_points++; + } else { + data[i] = -1; + } + } + + mean = sum / num_valid_points; + + Scalar mean_inv = num_valid_points / sum; + + Eigen::Matrix Jw_se2; + Jw_se2.template topLeftCorner<2, 2>().setIdentity(); + + MatrixP3 J_se2; + + for (int i = 0; i < PATTERN_SIZE; i++) { + if (data[i] >= 0) { + data[i] *= mean_inv; + Vector2 grad_i = grad.row(i); + grad.row(i) = num_valid_points * (grad_i * sum - grad_sum * data[i]) / + (sum * sum); + } else { + grad.row(i).setZero(); + } + + // Fill jacobians with respect to SE2 warp + Jw_se2(0, 2) = -pattern2(1, i); + Jw_se2(1, 2) = pattern2(0, i); + J_se2.row(i) = grad.row(i) * Jw_se2; + } + + Matrix3 H_se2 = J_se2.transpose() * J_se2; + Matrix3 H_se2_inv; + H_se2_inv.setIdentity(); + H_se2.ldlt().solveInPlace(H_se2_inv); + + H_se2_inv_J_se2_T = H_se2_inv * J_se2.transpose(); + } + + inline bool residual(const Image &img, + const Matrix2P &transformed_pattern, + VectorP &residual) const { + Scalar sum = 0; + Vector2 grad_sum(0, 0); + int num_valid_points = 0; + + for (int i = 0; i < PATTERN_SIZE; i++) { + if (img.InBounds(transformed_pattern.col(i), 2)) { + residual[i] = img.interp(transformed_pattern.col(i)); + sum += residual[i]; + num_valid_points++; + } else { + residual[i] = -1; + } + } + + int num_residuals = 0; + + for (int i = 0; i < PATTERN_SIZE; i++) { + if (residual[i] >= 0 && data[i] >= 0) { + Scalar val = residual[i]; + residual[i] = num_valid_points * val / sum - data[i]; + num_residuals++; + + } else { + residual[i] = 0; + } + } + + return num_residuals > PATTERN_SIZE / 2; + } + + Vector2 pos; + VectorP data; // negative if the point is not valid + + // MatrixP3 J_se2; // total jacobian with respect to se2 warp + // Matrix3 H_se2_inv; + Matrix3P H_se2_inv_J_se2_T; + + Scalar mean; +}; + +template +const typename OpticalFlowPatch::Matrix2P + OpticalFlowPatch::pattern2 = Pattern::pattern2; + +} // namespace basalt diff --git a/include/basalt/optical_flow/patch_optical_flow.h b/include/basalt/optical_flow/patch_optical_flow.h new file mode 100644 index 0000000..ac6c99d --- /dev/null +++ b/include/basalt/optical_flow/patch_optical_flow.h @@ -0,0 +1,376 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +#include +#include +#include + +#include +#include + +#include + +namespace basalt { + +template typename Pattern> +class PatchOpticalFlow : public OpticalFlowBase { + public: + typedef OpticalFlowPatch> PatchT; + + typedef Eigen::Matrix Vector2; + typedef Eigen::Matrix Matrix2; + + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Matrix3; + + typedef Eigen::Matrix Vector4; + typedef Eigen::Matrix Matrix4; + + typedef Sophus::SE2 SE2; + + PatchOpticalFlow(const VioConfig& config, + const basalt::Calibration& calib) + : t_ns(-1), last_keypoint_id(0), config(config), calib(calib) { + patches.reserve(3000); + input_queue.set_capacity(10); + + patch_coord = PatchT::pattern2.template cast(); + + if (calib.intrinsics.size() > 1) { + Sophus::SE3d T_i_j = calib.T_i_c[0].inverse() * calib.T_i_c[1]; + computeEssential(T_i_j, E); + } + + processing_thread.reset( + new std::thread(&PatchOpticalFlow::processingLoop, this)); + } + + ~PatchOpticalFlow() { processing_thread->join(); } + + void processingLoop() { + OpticalFlowInput::Ptr input_ptr; + + while (true) { + input_queue.pop(input_ptr); + + if (!input_ptr.get()) { + output_queue->push(nullptr); + break; + } + + processFrame(input_ptr->t_ns, input_ptr); + } + } + + void processFrame(int64_t curr_t_ns, OpticalFlowInput::Ptr& new_img_vec) { + for (const auto& v : new_img_vec->img_data) { + if (!v.img.get()) return; + } + + if (t_ns < 0) { + t_ns = curr_t_ns; + + transforms.reset(new OpticalFlowResult); + transforms->observations.resize(calib.intrinsics.size()); + transforms->t_ns = t_ns; + + pyramid.reset(new std::vector>); + pyramid->resize(calib.intrinsics.size()); + for (size_t i = 0; i < calib.intrinsics.size(); i++) { + pyramid->at(i).setFromImage(*new_img_vec->img_data[i].img, + config.optical_flow_levels); + } + + transforms->input_images = new_img_vec; + + addPoints(); + filterPoints(); + + } else { + t_ns = curr_t_ns; + + old_pyramid = pyramid; + + pyramid.reset(new std::vector>); + pyramid->resize(calib.intrinsics.size()); + for (size_t i = 0; i < calib.intrinsics.size(); i++) { + pyramid->at(i).setFromImage(*new_img_vec->img_data[i].img, + config.optical_flow_levels); + } + + OpticalFlowResult::Ptr new_transforms; + new_transforms.reset(new OpticalFlowResult); + new_transforms->observations.resize(new_img_vec->img_data.size()); + new_transforms->t_ns = t_ns; + + for (size_t i = 0; i < calib.intrinsics.size(); i++) { + trackPoints(old_pyramid->at(i), pyramid->at(i), + transforms->observations[i], + new_transforms->observations[i]); + } + + transforms = new_transforms; + transforms->input_images = new_img_vec; + + addPoints(); + filterPoints(); + } + + if (output_queue) { + output_queue->push(transforms); + } + } + + void trackPoints( + const basalt::ManagedImagePyr& pyr_1, + const basalt::ManagedImagePyr& pyr_2, + const Eigen::map& transform_map_1, + Eigen::map& transform_map_2) const { + size_t num_points = transform_map_1.size(); + + std::vector ids; + Eigen::vector init_vec; + + ids.reserve(num_points); + init_vec.reserve(num_points); + + for (const auto& kv : transform_map_1) { + ids.push_back(kv.first); + init_vec.push_back(kv.second); + } + + tbb::concurrent_unordered_map result; + + auto compute_func = [&](const tbb::blocked_range& range) { + for (size_t r = range.begin(); r != range.end(); ++r) { + const KeypointId id = ids[r]; + + const Eigen::AffineCompact2f& transform_1 = init_vec[r]; + Eigen::AffineCompact2f transform_2 = transform_1; + + const Eigen::vector& patch_vec = patches.at(id); + + bool valid = trackPoint(pyr_2, patch_vec, transform_2); + + if (valid) { + Eigen::AffineCompact2f transform_1_recovered = transform_2; + + valid = trackPoint(pyr_1, patch_vec, transform_1_recovered); + + if (valid) { + Scalar dist2 = (transform_1.translation() - + transform_1_recovered.translation()) + .squaredNorm(); + + if (dist2 < config.optical_flow_max_recovered_dist2) { + result[id] = transform_2; + } + } + } + } + }; + + tbb::blocked_range range(0, num_points); + + tbb::parallel_for(range, compute_func); + // compute_func(range); + + transform_map_2.clear(); + transform_map_2.insert(result.begin(), result.end()); + } + + inline bool trackPoint(const basalt::ManagedImagePyr& pyr, + const Eigen::vector& patch_vec, + Eigen::AffineCompact2f& transform) const { + bool patch_valid = true; + + for (int level = config.optical_flow_levels; level >= 0 && patch_valid; + level--) { + const Scalar scale = 1 << level; + + transform.translation() /= scale; + + // Perform tracking on current level + patch_valid &= + trackPointAtLevel(pyr.lvl(level), patch_vec[level], transform); + + transform.translation() *= scale; + } + + return patch_valid; + } + + inline bool trackPointAtLevel(const Image& img_2, + const PatchT& dp, + Eigen::AffineCompact2f& transform) const { + bool patch_valid = true; + + for (int iteration = 0; + patch_valid && iteration < config.optical_flow_max_iterations; + iteration++) { + typename PatchT::VectorP res; + + typename PatchT::Matrix2P transformed_pat = + transform.linear().matrix() * PatchT::pattern2; + transformed_pat.colwise() += transform.translation(); + + bool valid = dp.residual(img_2, transformed_pat, res); + + if (valid) { + Vector3 inc = -dp.H_se2_inv_J_se2_T * res; + transform *= SE2::exp(inc).matrix(); + + const int filter_margin = 2; + + if (!img_2.InBounds(transform.translation(), filter_margin)) + patch_valid = false; + } else { + patch_valid = false; + } + } + + return patch_valid; + } + + void addPoints() { + Eigen::vector pts0; + + for (const auto& kv : transforms->observations.at(0)) { + pts0.emplace_back(kv.second.translation().cast()); + } + + KeypointsData kd; + + detectKeypoints(pyramid->at(0).lvl(0), kd, + config.optical_flow_detection_grid_size, 1, pts0); + + Eigen::map new_poses0, new_poses1; + + for (size_t i = 0; i < kd.corners.size(); i++) { + Eigen::vector& p = patches[last_keypoint_id]; + + Vector2 pos = kd.corners[i].cast(); + + for (int l = 0; l < 4; l++) { + Scalar scale = 1 << l; + Vector2 pos_scaled = pos / scale; + p.emplace_back(pyramid->at(0).lvl(l), pos_scaled); + } + + Eigen::AffineCompact2f transform; + transform.setIdentity(); + transform.translation() = kd.corners[i].cast(); + + transforms->observations.at(0)[last_keypoint_id] = transform; + new_poses0[last_keypoint_id] = transform; + + last_keypoint_id++; + } + + if (calib.intrinsics.size() > 1) { + trackPoints(pyramid->at(0), pyramid->at(1), new_poses0, new_poses1); + + for (const auto& kv : new_poses1) { + transforms->observations.at(1).emplace(kv); + } + } + } + + void filterPoints() { + if (calib.intrinsics.size() < 2) return; + + std::set lm_to_remove; + + std::vector kpid; + Eigen::vector proj0, proj1; + + for (const auto& kv : transforms->observations.at(1)) { + auto it = transforms->observations.at(0).find(kv.first); + + if (it != transforms->observations.at(0).end()) { + proj0.emplace_back(it->second.translation().cast()); + proj1.emplace_back(kv.second.translation().cast()); + kpid.emplace_back(kv.first); + } + } + + Eigen::vector p3d0, p3d1; + std::vector p3d0_success, p3d1_success; + + calib.intrinsics[0].unproject(proj0, p3d0, p3d0_success); + calib.intrinsics[1].unproject(proj1, p3d1, p3d1_success); + + for (size_t i = 0; i < p3d0_success.size(); i++) { + if (p3d0_success[i] && p3d1_success[i]) { + const double epipolar_error = + std::abs(p3d0[i].transpose() * E * p3d1[i]); + + if (epipolar_error > config.optical_flow_epipolar_error) { + lm_to_remove.emplace(kpid[i]); + } + } else { + lm_to_remove.emplace(kpid[i]); + } + } + + for (int id : lm_to_remove) { + transforms->observations.at(1).erase(id); + } + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + private: + int64_t t_ns; + + KeypointId last_keypoint_id; + + VioConfig config; + basalt::Calibration calib; + + Eigen::unordered_map> patches; + + OpticalFlowResult::Ptr transforms; + std::shared_ptr>> old_pyramid, + pyramid; + + Eigen::Matrix4d E; + + std::shared_ptr processing_thread; +}; + +} // namespace basalt diff --git a/include/basalt/optical_flow/patterns.h b/include/basalt/optical_flow/patterns.h new file mode 100644 index 0000000..0b05102 --- /dev/null +++ b/include/basalt/optical_flow/patterns.h @@ -0,0 +1,171 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +namespace basalt { + +template +struct Pattern24 { + // 00 01 + // + // 02 03 04 05 + // + // 06 07 08 09 10 11 + // + // 12 13 14 15 16 17 + // + // 18 19 20 21 + // + // 22 23 + // + // -----> x + // | + // | + // y + + static constexpr Scalar pattern_raw[][2] = { + {-1, 5}, {1, 5}, + + {-3, 3}, {-1, 3}, {1, 3}, {3, 3}, + + {-5, 1}, {-3, 1}, {-1, 1}, {1, 1}, {3, 1}, {5, 1}, + + {-5, -1}, {-3, -1}, {-1, -1}, {1, -1}, {3, -1}, {5, -1}, + + {-3, -3}, {-1, -3}, {1, -3}, {3, -3}, + + {-1, -5}, {1, -5} + + }; + + static constexpr int PATTERN_SIZE = + sizeof(pattern_raw) / (2 * sizeof(Scalar)); + + typedef Eigen::Matrix Matrix2P; + static const Matrix2P pattern2; +}; + +template +const typename Pattern24::Matrix2P Pattern24::pattern2 = + Eigen::Map::Matrix2P>((Scalar *) + Pattern24::pattern_raw); + +template +struct Pattern52 { + // 00 01 02 03 + // + // 04 05 06 07 08 09 + // + // 10 11 12 13 14 15 16 17 + // + // 18 19 20 21 22 23 24 25 + // + // 26 27 28 29 30 31 32 33 + // + // 34 35 36 37 38 39 40 41 + // + // 42 43 44 45 46 47 + // + // 48 49 50 51 + // + // -----> x + // | + // | + // y + + static constexpr Scalar pattern_raw[][2] = { + {-3, 7}, {-1, 7}, {1, 7}, {3, 7}, + + {-5, 5}, {-3, 5}, {-1, 5}, {1, 5}, {3, 5}, {5, 5}, + + {-7, 3}, {-5, 3}, {-3, 3}, {-1, 3}, {1, 3}, {3, 3}, + {5, 3}, {7, 3}, + + {-7, 1}, {-5, 1}, {-3, 1}, {-1, 1}, {1, 1}, {3, 1}, + {5, 1}, {7, 1}, + + {-7, -1}, {-5, -1}, {-3, -1}, {-1, -1}, {1, -1}, {3, -1}, + {5, -1}, {7, -1}, + + {-7, -3}, {-5, -3}, {-3, -3}, {-1, -3}, {1, -3}, {3, -3}, + {5, -3}, {7, -3}, + + {-5, -5}, {-3, -5}, {-1, -5}, {1, -5}, {3, -5}, {5, -5}, + + {-3, -7}, {-1, -7}, {1, -7}, {3, -7} + + }; + + static constexpr int PATTERN_SIZE = + sizeof(pattern_raw) / (2 * sizeof(Scalar)); + + typedef Eigen::Matrix Matrix2P; + static const Matrix2P pattern2; +}; + +template +const typename Pattern52::Matrix2P Pattern52::pattern2 = + Eigen::Map::Matrix2P>((Scalar *) + Pattern52::pattern_raw); + +// Same as Pattern52 but twice smaller +template +struct Pattern51 { + static constexpr int PATTERN_SIZE = Pattern52::PATTERN_SIZE; + + typedef Eigen::Matrix Matrix2P; + static const Matrix2P pattern2; +}; + +template +const typename Pattern51::Matrix2P Pattern51::pattern2 = + 0.5 * Pattern52::pattern2; + +// Same as Pattern52 but 0.75 smaller +template +struct Pattern50 { + static constexpr int PATTERN_SIZE = Pattern52::PATTERN_SIZE; + + typedef Eigen::Matrix Matrix2P; + static const Matrix2P pattern2; +}; + +template +const typename Pattern50::Matrix2P Pattern50::pattern2 = + 0.75 * Pattern52::pattern2; + +} // namespace basalt diff --git a/include/basalt/optimization/accumulator.h b/include/basalt/optimization/accumulator.h new file mode 100644 index 0000000..2e12356 --- /dev/null +++ b/include/basalt/optimization/accumulator.h @@ -0,0 +1,336 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ + +#ifndef BASALT_ACCUMULATOR_H +#define BASALT_ACCUMULATOR_H + +#include +#include + +#include +#include +#include + +#include + +namespace basalt { + +template +class DenseAccumulator { + public: + typedef Eigen::Matrix VectorX; + typedef Eigen::Matrix MatrixX; + + template + inline void addH(int i, int j, const Eigen::MatrixBase& data) { + BASALT_ASSERT_STREAM(i >= 0, "i " << i); + BASALT_ASSERT_STREAM(j >= 0, "j " << j); + + BASALT_ASSERT_STREAM(i + ROWS <= H.cols(), "i " << i << " ROWS " << ROWS + << " H.rows() " + << H.rows()); + BASALT_ASSERT_STREAM(j + COLS <= H.rows(), "j " << j << " COLS " << COLS + << " H.cols() " + << H.cols()); + + H.template block(i, j) += data; + } + + template + inline void addB(int i, const Eigen::MatrixBase& data) { + BASALT_ASSERT_STREAM(i >= 0, "i " << i); + + BASALT_ASSERT_STREAM(i + ROWS <= H.cols(), "i " << i << " ROWS " << ROWS + << " H.rows() " + << H.rows()); + + b.template segment(i) += data; + } + + inline VectorX solve() const { return H.ldlt().solve(b); } + + inline VectorX solveWithPrior(const MatrixX& H_prior, const VectorX& b_prior, + size_t pos) const { + const int prior_size = b_prior.rows(); + + BASALT_ASSERT_STREAM( + H_prior.cols() == prior_size, + "H_prior.cols() " << H_prior.cols() << " prior_size " << prior_size); + BASALT_ASSERT_STREAM( + H_prior.rows() == prior_size, + "H_prior.rows() " << H_prior.rows() << " prior_size " << prior_size); + + MatrixX H_new = H; + VectorX b_new = b; + + H_new.block(pos, pos, prior_size, prior_size) += H_prior; + b_new.segment(pos, prior_size) += b_prior; + + return H_new.ldlt().solve(-b_new); + } + + inline void reset(int opt_size) { + H.setZero(opt_size, opt_size); + b.setZero(opt_size); + } + + inline void join(const DenseAccumulator& other) { + H += other.H; + b += other.b; + } + + inline void print() { + Eigen::IOFormat CleanFmt(2); + std::cerr << "H\n" << H.format(CleanFmt) << std::endl; + std::cerr << "b\n" << b.transpose().format(CleanFmt) << std::endl; + } + + inline const MatrixX& getH() const { return H; } + inline const VectorX& getB() const { return b; } + + inline MatrixX& getH() { return H; } + inline VectorX& getB() { return b; } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + private: + MatrixX H; + VectorX b; +}; + +template +class SparseAccumulator { + public: + typedef Eigen::Matrix VectorX; + typedef Eigen::Triplet T; + typedef Eigen::SparseMatrix SparseMatrix; + + template + inline void addH(int si, int sj, const Eigen::MatrixBase& data) { + EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived, ROWS, COLS); + + for (int i = 0; i < ROWS; i++) { + for (int j = 0; j < COLS; j++) { + triplets.emplace_back(si + i, sj + j, data(i, j)); + } + } + } + + template + inline void addB(int i, const Eigen::MatrixBase& data) { + b.template segment(i) += data; + } + + inline VectorX solve() const { + SparseMatrix sm(b.rows(), b.rows()); + + auto triplets_copy = triplets; + for (int i = 0; i < b.rows(); i++) { + triplets_copy.emplace_back(i, i, 0.000001); + } + + sm.setFromTriplets(triplets_copy.begin(), triplets_copy.end()); + + // Eigen::IOFormat CleanFmt(2); + // std::cerr << "sm\n" << sm.toDense().format(CleanFmt) << std::endl; + + Eigen::SimplicialLDLT chol(sm); + return chol.solve(-b); + // return sm.toDense().ldlt().solve(-b); + } + + inline void reset(int opt_size) { + triplets.clear(); + b.setZero(opt_size); + } + + inline void join(const SparseAccumulator& other) { + triplets.reserve(triplets.size() + other.triplets.size()); + triplets.insert(triplets.end(), other.triplets.begin(), + other.triplets.end()); + b += other.b; + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + private: + std::vector triplets; + VectorX b; +}; + +template +class SparseHashAccumulator { + public: + typedef Eigen::Matrix VectorX; + typedef Eigen::Matrix MatrixX; + typedef Eigen::Triplet T; + typedef Eigen::SparseMatrix SparseMatrix; + + template + inline void addH(int si, int sj, const Eigen::MatrixBase& data) { + EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived, ROWS, COLS); + + KeyT id; + id[0] = si; + id[1] = sj; + id[2] = ROWS; + id[3] = COLS; + + auto it = hash_map.find(id); + + if (it == hash_map.end()) { + hash_map.emplace(id, data); + } else { + it->second += data; + } + } + + template + inline void addB(int i, const Eigen::MatrixBase& data) { + b.template segment(i) += data; + } + + inline VectorX solve() const { + SparseMatrix sm(b.rows(), b.rows()); + + auto t1 = std::chrono::high_resolution_clock::now(); + std::vector triplets; + triplets.reserve(hash_map.size() * 36 + b.rows()); + + for (int i = 0; i < b.rows(); i++) { + triplets.emplace_back(i, i, 0.000001); + } + + for (const auto& kv : hash_map) { + // if (kv.first[2] != kv.second.rows()) std::cerr << "rows mismatch" << + // std::endl; + // if (kv.first[3] != kv.second.cols()) std::cerr << "cols mismatch" << + // std::endl; + + for (int i = 0; i < kv.second.rows(); i++) { + for (int j = 0; j < kv.second.cols(); j++) { + triplets.emplace_back(kv.first[0] + i, kv.first[1] + j, + kv.second(i, j)); + } + } + } + + sm.setFromTriplets(triplets.begin(), triplets.end()); + + auto t2 = std::chrono::high_resolution_clock::now(); + + // sm.diagonal() *= 1.01; + + // Eigen::IOFormat CleanFmt(2); + // std::cerr << "sm\n" << sm.toDense().format(CleanFmt) << std::endl; + + VectorX res; + + if (iterative_solver) { + Eigen::ConjugateGradient, + Eigen::Lower | Eigen::Upper> + cg; + + cg.setTolerance(tolerance); + cg.compute(sm); + res = cg.solve(b); + } else { + Eigen::SimplicialLDLT chol(sm); + res = chol.solve(b); + } + + auto t3 = std::chrono::high_resolution_clock::now(); + + auto elapsed1 = + std::chrono::duration_cast(t2 - t1); + auto elapsed2 = + std::chrono::duration_cast(t3 - t2); + + if (print_info) { + std::cout << "Forming matrix: " << elapsed1.count() * 1e-6 + << "s. Solving linear system: " << elapsed2.count() * 1e-6 + << "s." << std::endl; + } + + return res; + } + + inline void reset(int opt_size) { + hash_map.clear(); + b.setZero(opt_size); + } + + inline void join(const SparseHashAccumulator& other) { + for (const auto& kv : other.hash_map) { + auto it = hash_map.find(kv.first); + + if (it == hash_map.end()) { + hash_map.emplace(kv.first, kv.second); + } else { + it->second += kv.second; + } + } + + b += other.b; + } + + double tolerance = 1e-4; + bool iterative_solver = false; + bool print_info = false; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + private: + using KeyT = std::array; + + struct KeyHash { + inline size_t operator()(const KeyT& c) const { + size_t seed = 0; + for (int i = 0; i < 4; i++) { + hash_combine(seed, std::hash()(c[i])); + } + return seed; + } + + inline void hash_combine(std::size_t& seed, std::size_t value) const { + seed ^= value + 0x9e3779b9 + (seed << 6) + (seed >> 2); + } + }; + + std::unordered_map hash_map; + + VectorX b; +}; + +} // namespace basalt + +#endif diff --git a/include/basalt/optimization/linearize.h b/include/basalt/optimization/linearize.h new file mode 100644 index 0000000..2927966 --- /dev/null +++ b/include/basalt/optimization/linearize.h @@ -0,0 +1,187 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ +#ifndef BASALT_LINEARIZE_H +#define BASALT_LINEARIZE_H + +#include +#include +#include +#include + +#include + +#include + +namespace basalt { + +template +struct LinearizeBase { + static const int POSE_SIZE = 6; + + static const int POS_SIZE = 3; + static const int POS_OFFSET = 0; + static const int ROT_SIZE = 3; + static const int ROT_OFFSET = 3; + static const int ACCEL_BIAS_SIZE = 9; + static const int GYRO_BIAS_SIZE = 12; + static const int G_SIZE = 3; + + static const int TIME_SIZE = 1; + + static const int ACCEL_BIAS_OFFSET = 0; + static const int GYRO_BIAS_OFFSET = ACCEL_BIAS_SIZE; + static const int G_OFFSET = GYRO_BIAS_OFFSET + GYRO_BIAS_SIZE; + + typedef Sophus::SE3 SE3; + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Vector6; + + typedef Eigen::Matrix Matrix3; + typedef Eigen::Matrix Matrix6; + + typedef Eigen::Matrix VectorX; + typedef Eigen::Matrix MatrixX; + + typedef typename Eigen::vector::const_iterator PoseDataIter; + typedef typename Eigen::vector::const_iterator GyroDataIter; + typedef typename Eigen::vector::const_iterator AccelDataIter; + typedef typename Eigen::vector::const_iterator + AprilgridCornersDataIter; + + template + struct PoseCalibH { + Sophus::Matrix6d H_pose_accum; + Sophus::Vector6d b_pose_accum; + Eigen::Matrix H_intr_pose_accum; + Eigen::Matrix H_intr_accum; + Eigen::Matrix b_intr_accum; + + PoseCalibH() { + H_pose_accum.setZero(); + b_pose_accum.setZero(); + H_intr_pose_accum.setZero(); + H_intr_accum.setZero(); + b_intr_accum.setZero(); + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + struct CalibCommonData { + const Calibration* calibration = nullptr; + const MocapCalibration* mocap_calibration = nullptr; + const Eigen::vector* aprilgrid_corner_pos_3d = nullptr; + + // Calib data + const std::vector* offset_T_i_c = nullptr; + const std::vector* offset_intrinsics = nullptr; + + // Cam data + size_t mocap_block_offset; + size_t bias_block_offset; + const std::unordered_map* offset_poses = nullptr; + + // Cam-IMU data + const Vector3* g = nullptr; + + bool opt_intrinsics; + + // Cam-IMU options + bool opt_cam_time_offset; + bool opt_g; + bool opt_imu_scale; + + Scalar pose_var_inv; + Scalar gyro_var_inv; + Scalar accel_var_inv; + Scalar mocap_var_inv; + + Scalar huber_thresh; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + template + inline void linearize_point(const Eigen::Vector2d& corner_pos, int corner_id, + const Eigen::Matrix4d& T_c_w, const CamT& cam, + PoseCalibH& cph, double& error, + int& num_points, double& reproj_err) const { + Eigen::Matrix d_r_d_p; + Eigen::Matrix d_r_d_param; + Eigen::Matrix d_point_d_xi; + + BASALT_ASSERT_STREAM( + corner_id < int(common_data.aprilgrid_corner_pos_3d->size()), + "corner_id " << corner_id); + + Eigen::Vector4d point3d = + T_c_w * common_data.aprilgrid_corner_pos_3d->at(corner_id); + + d_point_d_xi.topLeftCorner<3, 3>().setIdentity(); + d_point_d_xi.topRightCorner<3, 3>() = -Sophus::SO3d::hat(point3d.head<3>()); + d_point_d_xi.row(3).setZero(); + + Eigen::Vector2d proj; + bool valid = cam.project(point3d, proj, &d_r_d_p, &d_r_d_param); + + if (!valid) return; + + Eigen::Matrix d_r_d_xi = d_r_d_p * d_point_d_xi; + Eigen::Vector2d residual = proj - corner_pos; + + double e = residual.norm(); + double huber_weight = + e < common_data.huber_thresh ? 1.0 : common_data.huber_thresh / e; + + cph.H_pose_accum += huber_weight * d_r_d_xi.transpose() * d_r_d_xi; + cph.b_pose_accum += huber_weight * d_r_d_xi.transpose() * residual; + + cph.H_intr_pose_accum += huber_weight * d_r_d_param.transpose() * d_r_d_xi; + cph.H_intr_accum += huber_weight * d_r_d_param.transpose() * d_r_d_param; + cph.b_intr_accum += huber_weight * d_r_d_param.transpose() * residual; + + error += huber_weight * e * e * (2 - huber_weight); + reproj_err += e; + num_points++; + } + + CalibCommonData common_data; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace basalt + +#endif diff --git a/include/basalt/optimization/poses_linearize.h b/include/basalt/optimization/poses_linearize.h new file mode 100644 index 0000000..510f229 --- /dev/null +++ b/include/basalt/optimization/poses_linearize.h @@ -0,0 +1,180 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ +#ifndef BASALT_POSES_LINEARIZE_H +#define BASALT_POSES_LINEARIZE_H + +#include +#include +#include + +#include + +#include + +#include + +namespace basalt { + +template +struct LinearizePosesOpt : public LinearizeBase { + static const int POSE_SIZE = LinearizeBase::POSE_SIZE; + + typedef Sophus::SE3 SE3; + typedef Eigen::Matrix Vector2; + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Vector4; + typedef Eigen::Matrix Vector6; + + typedef Eigen::Matrix Matrix3; + typedef Eigen::Matrix Matrix6; + + typedef Eigen::Matrix VectorX; + typedef Eigen::Matrix MatrixX; + + typedef typename Eigen::vector::const_iterator + AprilgridCornersDataIter; + + typedef typename LinearizeBase::CalibCommonData CalibCommonData; + + AccumT accum; + Scalar error; + Scalar reprojection_error; + int num_points; + + size_t opt_size; + + const Eigen::unordered_map& timestam_to_pose; + + LinearizePosesOpt(size_t opt_size, + const Eigen::unordered_map& timestam_to_pose, + const CalibCommonData& common_data) + : opt_size(opt_size), timestam_to_pose(timestam_to_pose) { + this->common_data = common_data; + accum.reset(opt_size); + error = 0; + reprojection_error = 0; + num_points = 0; + } + LinearizePosesOpt(const LinearizePosesOpt& other, tbb::split) + : opt_size(other.opt_size), timestam_to_pose(other.timestam_to_pose) { + this->common_data = other.common_data; + accum.reset(opt_size); + error = 0; + reprojection_error = 0; + num_points = 0; + } + + void operator()(const tbb::blocked_range& r) { + for (const AprilgridCornersData& acd : r) { + std::visit( + [&](const auto& cam) { + constexpr int INTRINSICS_SIZE = + std::remove_reference::type::N; + typename LinearizeBase::template PoseCalibH + cph; + + SE3 T_w_i = timestam_to_pose.at(acd.timestamp_ns); + SE3 T_w_c = + T_w_i * this->common_data.calibration->T_i_c[acd.cam_id]; + SE3 T_c_w = T_w_c.inverse(); + Eigen::Matrix4d T_c_w_m = T_c_w.matrix(); + + double err = 0; + double reproj_err = 0; + int num_inliers = 0; + + for (size_t i = 0; i < acd.corner_pos.size(); i++) { + this->linearize_point(acd.corner_pos[i], acd.corner_id[i], + T_c_w_m, cam, cph, err, num_inliers, + reproj_err); + } + + error += err; + reprojection_error += reproj_err; + num_points += num_inliers; + + const Matrix6 Adj = + -this->common_data.calibration->T_i_c[acd.cam_id] + .inverse() + .Adj(); + + const size_t po = + this->common_data.offset_poses->at(acd.timestamp_ns); + const size_t co = this->common_data.offset_T_i_c->at(acd.cam_id); + const size_t io = + this->common_data.offset_intrinsics->at(acd.cam_id); + + accum.template addH( + po, po, Adj.transpose() * cph.H_pose_accum * Adj); + accum.template addB(po, + Adj.transpose() * cph.b_pose_accum); + + if (acd.cam_id > 0) { + accum.template addH( + co, po, -cph.H_pose_accum * Adj); + accum.template addH(co, co, + cph.H_pose_accum); + + accum.template addB(co, -cph.b_pose_accum); + } + + if (this->common_data.opt_intrinsics) { + accum.template addH( + io, po, cph.H_intr_pose_accum * Adj); + + if (acd.cam_id > 0) + accum.template addH( + io, co, -cph.H_intr_pose_accum); + + accum.template addH( + io, io, cph.H_intr_accum); + accum.template addB(io, cph.b_intr_accum); + } + }, + this->common_data.calibration->intrinsics[acd.cam_id].variant); + } + } + + void join(LinearizePosesOpt& rhs) { + accum.join(rhs.accum); + error += rhs.error; + reprojection_error += rhs.reprojection_error; + num_points += rhs.num_points; + } +}; + +} // namespace basalt + +#endif diff --git a/include/basalt/optimization/poses_optimize.h b/include/basalt/optimization/poses_optimize.h new file mode 100644 index 0000000..d0ad7a3 --- /dev/null +++ b/include/basalt/optimization/poses_optimize.h @@ -0,0 +1,259 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include + +#include + +#include + +namespace basalt { + +class PosesOptimization { + static constexpr size_t POSE_SIZE = 6; + + using Scalar = double; + + typedef LinearizePosesOpt> LinearizeT; + + using SE3 = typename LinearizeT::SE3; + using Vector2 = typename LinearizeT::Vector2; + using Vector3 = typename LinearizeT::Vector3; + using Vector4 = typename LinearizeT::Vector4; + using VectorX = typename LinearizeT::VectorX; + + using AprilgridCornersDataIter = + typename Eigen::vector::const_iterator; + + public: + PosesOptimization() {} + + bool initializeIntrinsics( + size_t cam_id, const Eigen::vector &corners, + const std::vector &corner_ids, + const Eigen::vector &aprilgrid_corner_pos_3d, int cols, + int rows) { + Eigen::Vector4d init_intr; + + bool val = CalibHelper::initializeIntrinsics( + corners, corner_ids, aprilgrid_corner_pos_3d, cols, rows, init_intr); + + calib->intrinsics[cam_id].setFromInit(init_intr); + + return val; + } + + Vector2 getOpticalCenter(size_t i) { + return calib->intrinsics[i].getParam().template segment<2>(2); + } + + void resetCalib(size_t num_cams, const std::vector &cam_types) { + BASALT_ASSERT(cam_types.size() == num_cams); + + calib.reset(new Calibration); + + for (size_t i = 0; i < cam_types.size(); i++) { + calib->intrinsics.emplace_back( + GenericCamera::fromString(cam_types[i])); + + if (calib->intrinsics.back().getName() != cam_types[i]) { + std::cerr << "Unknown camera type " << cam_types[i] << " default to " + << calib->intrinsics.back().getName() << std::endl; + } + } + calib->T_i_c.resize(num_cams); + } + + void loadCalib(const std::string &p) { + std::string path = p + "calibration.json"; + + std::ifstream is(path); + + if (is.good()) { + cereal::JSONInputArchive archive(is); + calib.reset(new Calibration); + archive(*calib); + std::cout << "Loaded calibration from: " << path << std::endl; + } else { + std::cout << "No calibration found" << std::endl; + } + } + + void saveCalib(const std::string &path, + int64_t mocap_to_imu_offset_ns = 0) const { + if (calib) { + std::ofstream os(path + "calibration.json"); + cereal::JSONOutputArchive archive(os); + + archive(*calib); + } + } + + bool calibInitialized() const { return calib != nullptr; } + bool initialized() const { return true; } + + void optimize(bool opt_intrinsics, double huber_thresh, double &error, + int &num_points, double &reprojection_error) { + error = 0; + num_points = 0; + + ccd.opt_intrinsics = opt_intrinsics; + ccd.huber_thresh = huber_thresh; + + LinearizePosesOpt> lopt( + problem_size, timestam_to_pose, ccd); + + tbb::blocked_range april_range( + aprilgrid_corners_measurements.begin(), + aprilgrid_corners_measurements.end()); + tbb::parallel_reduce(april_range, lopt); + + error = lopt.error; + num_points = lopt.num_points; + reprojection_error = lopt.reprojection_error; + + Eigen::VectorXd inc = -lopt.accum.solve(); + + for (auto &kv : timestam_to_pose) { + kv.second *= Sophus::expd(inc.segment(offset_poses[kv.first])); + } + + for (size_t i = 0; i < calib->T_i_c.size(); i++) { + calib->T_i_c[i] *= Sophus::expd(inc.segment(offset_T_i_c[i])); + } + + for (size_t i = 0; i < calib->intrinsics.size(); i++) { + auto &c = calib->intrinsics[i]; + c.applyInc(inc.segment(offset_cam_intrinsics[i], c.getN())); + } + } + + void recompute_size() { + offset_poses.clear(); + offset_T_i_c.clear(); + offset_cam_intrinsics.clear(); + + size_t curr_offset = 0; + + for (const auto &kv : timestam_to_pose) { + offset_poses[kv.first] = curr_offset; + curr_offset += POSE_SIZE; + } + + offset_T_i_c.emplace_back(curr_offset); + for (size_t i = 0; i < calib->T_i_c.size(); i++) + offset_T_i_c.emplace_back(offset_T_i_c.back() + POSE_SIZE); + + offset_cam_intrinsics.emplace_back(offset_T_i_c.back()); + for (size_t i = 0; i < calib->intrinsics.size(); i++) + offset_cam_intrinsics.emplace_back(offset_cam_intrinsics.back() + + calib->intrinsics[i].getN()); + + problem_size = offset_cam_intrinsics.back(); + } + + Sophus::SE3d getT_w_i(int64_t i) { + auto it = timestam_to_pose.find(i); + + if (it == timestam_to_pose.end()) + return Sophus::SE3d(); + else + return it->second; + } + + void setAprilgridCorners3d(const Eigen::vector &v) { + aprilgrid_corner_pos_3d = v; + } + + void init() { + recompute_size(); + + ccd.calibration = calib.get(); + ccd.aprilgrid_corner_pos_3d = &aprilgrid_corner_pos_3d; + ccd.offset_poses = &offset_poses; + ccd.offset_T_i_c = &offset_T_i_c; + ccd.offset_intrinsics = &offset_cam_intrinsics; + } + + void addAprilgridMeasurement( + int64_t t_ns, int cam_id, + const Eigen::vector &corners_pos, + const std::vector &corner_id) { + aprilgrid_corners_measurements.emplace_back(); + + aprilgrid_corners_measurements.back().timestamp_ns = t_ns; + aprilgrid_corners_measurements.back().cam_id = cam_id; + aprilgrid_corners_measurements.back().corner_pos = corners_pos; + aprilgrid_corners_measurements.back().corner_id = corner_id; + } + + void addPoseMeasurement(int64_t t_ns, const Sophus::SE3d &pose) { + timestam_to_pose[t_ns] = pose; + } + + void setVignette(const std::vector> &vign) { + calib->vignette = vign; + } + + void setResolution(const Eigen::vector &resolution) { + calib->resolution = resolution; + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + std::shared_ptr> calib; + + private: + typename LinearizePosesOpt< + Scalar, SparseHashAccumulator>::CalibCommonData ccd; + + size_t problem_size; + + std::unordered_map offset_poses; + std::vector offset_cam_intrinsics; + std::vector offset_T_i_c; + + // frame poses + Eigen::unordered_map timestam_to_pose; + + Eigen::vector aprilgrid_corners_measurements; + + Eigen::vector aprilgrid_corner_pos_3d; + +}; // namespace basalt + +} // namespace basalt diff --git a/include/basalt/optimization/spline_linearize.h b/include/basalt/optimization/spline_linearize.h new file mode 100644 index 0000000..cf0eb7d --- /dev/null +++ b/include/basalt/optimization/spline_linearize.h @@ -0,0 +1,635 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ +#ifndef BASALT_SPLINE_LINEARIZE_H +#define BASALT_SPLINE_LINEARIZE_H + +#include +#include +#include +#include + +#include + +#include + +#include + +namespace basalt { + +template +struct LinearizeSplineOpt : public LinearizeBase { + static const int POSE_SIZE = LinearizeBase::POSE_SIZE; + static const int POS_SIZE = LinearizeBase::POS_SIZE; + static const int POS_OFFSET = LinearizeBase::POS_OFFSET; + static const int ROT_SIZE = LinearizeBase::ROT_SIZE; + static const int ROT_OFFSET = LinearizeBase::ROT_OFFSET; + static const int ACCEL_BIAS_SIZE = LinearizeBase::ACCEL_BIAS_SIZE; + static const int GYRO_BIAS_SIZE = LinearizeBase::GYRO_BIAS_SIZE; + static const int G_SIZE = LinearizeBase::G_SIZE; + static const int TIME_SIZE = LinearizeBase::TIME_SIZE; + static const int ACCEL_BIAS_OFFSET = LinearizeBase::ACCEL_BIAS_OFFSET; + static const int GYRO_BIAS_OFFSET = LinearizeBase::GYRO_BIAS_OFFSET; + static const int G_OFFSET = LinearizeBase::G_OFFSET; + + typedef Sophus::SE3 SE3; + + typedef Eigen::Matrix Vector2; + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Vector4; + typedef Eigen::Matrix Vector6; + + typedef Eigen::Matrix Matrix3; + typedef Eigen::Matrix Matrix6; + + typedef Eigen::Matrix Matrix24; + + typedef Eigen::Matrix VectorX; + typedef Eigen::Matrix MatrixX; + + typedef Se3Spline SplineT; + + typedef typename Eigen::deque::const_iterator PoseDataIter; + typedef typename Eigen::deque::const_iterator GyroDataIter; + typedef typename Eigen::deque::const_iterator AccelDataIter; + typedef typename Eigen::deque::const_iterator + AprilgridCornersDataIter; + typedef + typename Eigen::deque::const_iterator MocapPoseDataIter; + + // typedef typename LinearizeBase::PoseCalibH PoseCalibH; + typedef typename LinearizeBase::CalibCommonData CalibCommonData; + + AccumT accum; + Scalar error; + Scalar reprojection_error; + int num_points; + + size_t opt_size; + + const SplineT* spline; + + LinearizeSplineOpt(size_t opt_size, const SplineT* spl, + const CalibCommonData& common_data, + const SplineT* spl_lin = nullptr) + : opt_size(opt_size), spline(spl) { + this->common_data = common_data; + + accum.reset(opt_size); + error = 0; + reprojection_error = 0; + num_points = 0; + + BASALT_ASSERT(spline); + } + + LinearizeSplineOpt(const LinearizeSplineOpt& other, tbb::split) + : opt_size(other.opt_size), spline(other.spline) { + this->common_data = other.common_data; + accum.reset(opt_size); + error = 0; + reprojection_error = 0; + num_points = 0; + } + + void operator()(const tbb::blocked_range& r) { + for (const PoseData& pm : r) { + int64_t start_idx; + + typename SplineT::SO3JacobianStruct J_rot; + typename SplineT::PosJacobianStruct J_pos; + + int64_t time_ns = pm.timestamp_ns; + + // std::cout << "time " << time << std::endl; + // std::cout << "sline.minTime() " << spline.minTime() << std::endl; + + BASALT_ASSERT_STREAM(time_ns >= spline->minTimeNs(), + "time " << time_ns << " spline.minTimeNs() " + << spline->minTimeNs()); + + // Residual from current value of spline + Vector3 residual_pos = + spline->positionResidual(time_ns, pm.data.translation(), &J_pos); + Vector3 residual_rot = + spline->orientationResidual(time_ns, pm.data.so3(), &J_rot); + + // std::cerr << "residual_pos " << residual_pos.transpose() << std::endl; + // std::cerr << "residual_rot " << residual_rot.transpose() << std::endl; + + BASALT_ASSERT(J_pos.start_idx == J_rot.start_idx); + + start_idx = J_pos.start_idx; + + // std::cout << "J_pos.start_idx " << J_pos.start_idx << std::endl; + + const Scalar& pose_var_inv = this->common_data.pose_var_inv; + + error += pose_var_inv * + (residual_pos.squaredNorm() + residual_rot.squaredNorm()); + + for (size_t i = 0; i < N; i++) { + size_t start_i = (start_idx + i) * POSE_SIZE; + + // std::cout << "start_idx " << start_idx << std::endl; + // std::cout << "start_i " << start_i << std::endl; + + BASALT_ASSERT(start_i < opt_size); + + for (size_t j = 0; j <= i; j++) { + size_t start_j = (start_idx + j) * POSE_SIZE; + + BASALT_ASSERT(start_j < opt_size); + + accum.template addH( + start_i + POS_OFFSET, start_j + POS_OFFSET, + this->common_data.pose_var_inv * J_pos.d_val_d_knot[i] * + J_pos.d_val_d_knot[j] * Matrix3::Identity()); + + accum.template addH( + start_i + ROT_OFFSET, start_j + ROT_OFFSET, + this->common_data.pose_var_inv * + J_rot.d_val_d_knot[i].transpose() * J_rot.d_val_d_knot[j]); + } + + accum.template addB( + start_i + POS_OFFSET, + pose_var_inv * J_pos.d_val_d_knot[i] * residual_pos); + accum.template addB( + start_i + ROT_OFFSET, + pose_var_inv * J_rot.d_val_d_knot[i].transpose() * residual_rot); + } + } + } + + void operator()(const tbb::blocked_range& r) { + // size_t num_knots = spline.numKnots(); + // size_t bias_block_offset = POSE_SIZE * num_knots; + + for (const AccelData& pm : r) { + typename SplineT::AccelPosSO3JacobianStruct J; + typename SplineT::Mat39 J_bias; + Matrix3 J_g; + + int64_t t = pm.timestamp_ns; + + // std::cout << "time " << t << std::endl; + // std::cout << "sline.minTime() " << spline.minTime() << std::endl; + + BASALT_ASSERT_STREAM(t >= spline->minTimeNs(), + "t " << t << " spline.minTime() " + << spline->minTimeNs()); + BASALT_ASSERT_STREAM(t <= spline->maxTimeNs(), + "t " << t << " spline.maxTime() " + << spline->maxTimeNs()); + + Vector3 residual = spline->accelResidual( + t, pm.data, this->common_data.calibration->calib_accel_bias, + *(this->common_data.g), &J, &J_bias, &J_g); + + if (!this->common_data.opt_imu_scale) { + J_bias.template block<3, 6>(0, 3).setZero(); + } + + // std::cerr << "================================" << std::endl; + // std::cerr << "accel res: " << residual.transpose() << std::endl; + // std::cerr << "accel_bias.transpose(): " + // << this->common_data.calibration->accel_bias.transpose() + // << std::endl; + // std::cerr << "*(this->common_data.g): " + // << this->common_data.g->transpose() << std::endl; + // std::cerr << "pm.data " << pm.data.transpose() << std::endl; + + // std::cerr << "time " << t << std::endl; + // std::cerr << "sline.minTime() " << spline.minTime() << std::endl; + // std::cerr << "sline.maxTime() " << spline.maxTime() << std::endl; + // std::cerr << "================================" << std::endl; + + const Scalar& accel_var_inv = this->common_data.accel_var_inv; + + error += accel_var_inv * residual.squaredNorm(); + + size_t start_bias = + this->common_data.bias_block_offset + ACCEL_BIAS_OFFSET; + size_t start_g = this->common_data.bias_block_offset + G_OFFSET; + + for (size_t i = 0; i < N; i++) { + size_t start_i = (J.start_idx + i) * POSE_SIZE; + + BASALT_ASSERT(start_i < opt_size); + + for (size_t j = 0; j <= i; j++) { + size_t start_j = (J.start_idx + j) * POSE_SIZE; + + BASALT_ASSERT(start_j < opt_size); + + accum.template addH( + start_i, start_j, accel_var_inv * J.d_val_d_knot[i].transpose() * + J.d_val_d_knot[j]); + } + accum.template addH( + start_bias, start_i, + accel_var_inv * J_bias.transpose() * J.d_val_d_knot[i]); + + if (this->common_data.opt_g) { + accum.template addH( + start_g, start_i, + accel_var_inv * J_g.transpose() * J.d_val_d_knot[i]); + } + + accum.template addB( + start_i, accel_var_inv * J.d_val_d_knot[i].transpose() * residual); + } + + accum.template addH( + start_bias, start_bias, accel_var_inv * J_bias.transpose() * J_bias); + + if (this->common_data.opt_g) { + accum.template addH( + start_g, start_bias, accel_var_inv * J_g.transpose() * J_bias); + accum.template addH( + start_g, start_g, accel_var_inv * J_g.transpose() * J_g); + } + + accum.template addB( + start_bias, accel_var_inv * J_bias.transpose() * residual); + + if (this->common_data.opt_g) { + accum.template addB(start_g, + accel_var_inv * J_g.transpose() * residual); + } + } + } + + void operator()(const tbb::blocked_range& r) { + // size_t num_knots = spline.numKnots(); + // size_t bias_block_offset = POSE_SIZE * num_knots; + + for (const GyroData& pm : r) { + typename SplineT::SO3JacobianStruct J; + typename SplineT::Mat312 J_bias; + + int64_t t_ns = pm.timestamp_ns; + + BASALT_ASSERT(t_ns >= spline->minTimeNs()); + BASALT_ASSERT(t_ns <= spline->maxTimeNs()); + + const Scalar& gyro_var_inv = this->common_data.gyro_var_inv; + + Vector3 residual = spline->gyroResidual( + t_ns, pm.data, this->common_data.calibration->calib_gyro_bias, &J, + &J_bias); + + if (!this->common_data.opt_imu_scale) { + J_bias.template block<3, 9>(0, 3).setZero(); + } + + // std::cerr << "==============================" << std::endl; + // std::cerr << "residual " << residual.transpose() << std::endl; + // std::cerr << "gyro_bias " + // << this->common_data.calibration->gyro_bias.transpose() + // << std::endl; + // std::cerr << "pm.data " << pm.data.transpose() << std::endl; + // std::cerr << "t_ns " << t_ns << std::endl; + + error += gyro_var_inv * residual.squaredNorm(); + + size_t start_bias = + this->common_data.bias_block_offset + GYRO_BIAS_OFFSET; + for (size_t i = 0; i < N; i++) { + size_t start_i = (J.start_idx + i) * POSE_SIZE + ROT_OFFSET; + + // std::cout << "start_idx " << J.start_idx << std::endl; + // std::cout << "start_i " << start_i << std::endl; + + BASALT_ASSERT(start_i < opt_size); + + for (size_t j = 0; j <= i; j++) { + size_t start_j = (J.start_idx + j) * POSE_SIZE + ROT_OFFSET; + + // std::cout << "start_j " << start_j << std::endl; + + BASALT_ASSERT(start_i < opt_size); + + accum.template addH( + start_i, start_j, + gyro_var_inv * J.d_val_d_knot[i].transpose() * J.d_val_d_knot[j]); + } + accum.template addH( + start_bias, start_i, + gyro_var_inv * J_bias.transpose() * J.d_val_d_knot[i]); + accum.template addB( + start_i, gyro_var_inv * J.d_val_d_knot[i].transpose() * residual); + } + + accum.template addH( + start_bias, start_bias, gyro_var_inv * J_bias.transpose() * J_bias); + accum.template addB( + start_bias, gyro_var_inv * J_bias.transpose() * residual); + } + } + + void operator()(const tbb::blocked_range& r) { + for (const AprilgridCornersData& acd : r) { + std::visit( + [&](const auto& cam) { + constexpr int INTRINSICS_SIZE = + std::remove_reference::type::N; + + typename SplineT::PosePosSO3JacobianStruct J; + + int64_t time_ns = acd.timestamp_ns + + this->common_data.calibration->cam_time_offset_ns; + + if (time_ns < spline->minTimeNs() || time_ns >= spline->maxTimeNs()) + return; + + SE3 T_w_i = spline->pose(time_ns, &J); + + Vector6 d_T_wi_d_time; + spline->d_pose_d_t(time_ns, d_T_wi_d_time); + + SE3 T_w_c = + T_w_i * this->common_data.calibration->T_i_c[acd.cam_id]; + SE3 T_c_w = T_w_c.inverse(); + Eigen::Matrix4d T_c_w_m = T_c_w.matrix(); + + typename LinearizeBase::template PoseCalibH + cph; + + double err = 0; + double reproj_err = 0; + int num_inliers = 0; + + for (size_t i = 0; i < acd.corner_pos.size(); i++) { + this->linearize_point(acd.corner_pos[i], acd.corner_id[i], + T_c_w_m, cam, cph, err, num_inliers, + reproj_err); + } + + error += err; + reprojection_error += reproj_err; + num_points += num_inliers; + + Matrix6 Adj = -this->common_data.calibration->T_i_c[acd.cam_id] + .inverse() + .Adj(); + Matrix6 A_H_p_A = Adj.transpose() * cph.H_pose_accum * Adj; + + size_t T_i_c_start = this->common_data.offset_T_i_c->at(acd.cam_id); + size_t calib_start = + this->common_data.offset_intrinsics->at(acd.cam_id); + size_t start_cam_time_offset = + this->common_data.mocap_block_offset + 2 * POSE_SIZE + 1; + + for (int i = 0; i < N; i++) { + int start_i = (J.start_idx + i) * POSE_SIZE; + + Matrix6 Ji_A_H_p_A = J.d_val_d_knot[i].transpose() * A_H_p_A; + + for (int j = 0; j <= i; j++) { + int start_j = (J.start_idx + j) * POSE_SIZE; + + accum.template addH( + start_i, start_j, Ji_A_H_p_A * J.d_val_d_knot[j]); + } + + accum.template addH( + T_i_c_start, start_i, + -cph.H_pose_accum * Adj * J.d_val_d_knot[i]); + + if (this->common_data.opt_intrinsics) + accum.template addH( + calib_start, start_i, + cph.H_intr_pose_accum * Adj * J.d_val_d_knot[i]); + + if (this->common_data.opt_cam_time_offset) + accum.template addH( + start_cam_time_offset, start_i, + d_T_wi_d_time.transpose() * A_H_p_A * J.d_val_d_knot[i]); + + accum.template addB( + start_i, J.d_val_d_knot[i].transpose() * Adj.transpose() * + cph.b_pose_accum); + } + + accum.template addH(T_i_c_start, T_i_c_start, + cph.H_pose_accum); + accum.template addB(T_i_c_start, -cph.b_pose_accum); + + if (this->common_data.opt_intrinsics) { + accum.template addH( + calib_start, T_i_c_start, -cph.H_intr_pose_accum); + accum.template addH( + calib_start, calib_start, cph.H_intr_accum); + accum.template addB(calib_start, + cph.b_intr_accum); + } + + if (this->common_data.opt_cam_time_offset) { + accum.template addH( + start_cam_time_offset, T_i_c_start, + -d_T_wi_d_time.transpose() * Adj.transpose() * + cph.H_pose_accum); + + if (this->common_data.opt_intrinsics) + accum.template addH( + start_cam_time_offset, calib_start, + d_T_wi_d_time.transpose() * Adj.transpose() * + cph.H_intr_pose_accum.transpose()); + + accum.template addH( + start_cam_time_offset, start_cam_time_offset, + d_T_wi_d_time.transpose() * A_H_p_A * d_T_wi_d_time); + + accum.template addB(start_cam_time_offset, + d_T_wi_d_time.transpose() * + Adj.transpose() * + cph.b_pose_accum); + } + }, + this->common_data.calibration->intrinsics[acd.cam_id].variant); + } + } + + void operator()(const tbb::blocked_range& r) { + for (const MocapPoseData& pm : r) { + typename SplineT::PosePosSO3JacobianStruct J_pose; + + int64_t time_ns = + pm.timestamp_ns + + this->common_data.mocap_calibration->mocap_time_offset_ns; + + // std::cout << "time " << time << std::endl; + // std::cout << "sline.minTime() " << spline.minTime() << std::endl; + + if (time_ns < spline->minTimeNs() || time_ns >= spline->maxTimeNs()) + continue; + + BASALT_ASSERT_STREAM(time_ns >= spline->minTimeNs(), + "time " << time_ns << " spline.minTimeNs() " + << spline->minTimeNs()); + + const SE3 T_moc_w = this->common_data.mocap_calibration->T_moc_w; + const SE3 T_i_mark = this->common_data.mocap_calibration->T_i_mark; + + const SE3 T_w_i = spline->pose(time_ns, &J_pose); + const SE3 T_moc_mark = T_moc_w * T_w_i * T_i_mark; + + const SE3 T_mark_moc_meas = pm.data.inverse(); + + Vector6 residual = Sophus::logd(T_mark_moc_meas * T_moc_mark); + + // TODO: check derivatives + Matrix6 d_res_d_T_i_mark; + Sophus::rightJacobianInvSE3Decoupled(residual, d_res_d_T_i_mark); + Matrix6 d_res_d_T_w_i = d_res_d_T_i_mark * T_i_mark.inverse().Adj(); + Matrix6 d_res_d_T_moc_w = + d_res_d_T_i_mark * (T_w_i * T_i_mark).inverse().Adj(); + + Vector6 d_T_wi_d_time; + spline->d_pose_d_t(time_ns, d_T_wi_d_time); + + Vector6 d_res_d_time = d_res_d_T_w_i * d_T_wi_d_time; + + size_t start_idx = J_pose.start_idx; + + size_t start_T_moc_w = this->common_data.mocap_block_offset; + size_t start_T_i_mark = this->common_data.mocap_block_offset + POSE_SIZE; + size_t start_mocap_time_offset = + this->common_data.mocap_block_offset + 2 * POSE_SIZE; + + // std::cout << "J_pos.start_idx " << J_pos.start_idx << std::endl; + + const Scalar& mocap_var_inv = this->common_data.mocap_var_inv; + + error += mocap_var_inv * residual.squaredNorm(); + + Matrix6 H_T_w_i = d_res_d_T_w_i.transpose() * d_res_d_T_w_i; + + for (size_t i = 0; i < N; i++) { + size_t start_i = (start_idx + i) * POSE_SIZE; + + // std::cout << "start_idx " << start_idx << std::endl; + // std::cout << "start_i " << start_i << std::endl; + + BASALT_ASSERT(start_i < opt_size); + + Matrix6 Ji_H_T_w_i = J_pose.d_val_d_knot[i].transpose() * H_T_w_i; + + for (size_t j = 0; j <= i; j++) { + size_t start_j = (start_idx + j) * POSE_SIZE; + + BASALT_ASSERT(start_j < opt_size); + + accum.template addH( + start_i, start_j, + mocap_var_inv * Ji_H_T_w_i * J_pose.d_val_d_knot[j]); + } + + accum.template addB( + start_i, mocap_var_inv * J_pose.d_val_d_knot[i].transpose() * + d_res_d_T_w_i.transpose() * residual); + + accum.template addH( + start_T_moc_w, start_i, mocap_var_inv * + d_res_d_T_moc_w.transpose() * + d_res_d_T_w_i * J_pose.d_val_d_knot[i]); + + accum.template addH( + start_T_i_mark, start_i, + mocap_var_inv * d_res_d_T_i_mark.transpose() * d_res_d_T_w_i * + J_pose.d_val_d_knot[i]); + + accum.template addH( + start_mocap_time_offset, start_i, + mocap_var_inv * d_res_d_time.transpose() * d_res_d_T_w_i * + J_pose.d_val_d_knot[i]); + } + + // start_T_moc_w + accum.template addH( + start_T_moc_w, start_T_moc_w, + mocap_var_inv * d_res_d_T_moc_w.transpose() * d_res_d_T_moc_w); + + // start_T_i_mark + accum.template addH( + start_T_i_mark, start_T_moc_w, + mocap_var_inv * d_res_d_T_i_mark.transpose() * d_res_d_T_moc_w); + + accum.template addH( + start_T_i_mark, start_T_i_mark, + mocap_var_inv * d_res_d_T_i_mark.transpose() * d_res_d_T_i_mark); + + // start_mocap_time_offset + accum.template addH( + start_mocap_time_offset, start_T_moc_w, + mocap_var_inv * d_res_d_time.transpose() * d_res_d_T_moc_w); + + accum.template addH( + start_mocap_time_offset, start_T_i_mark, + mocap_var_inv * d_res_d_time.transpose() * d_res_d_T_i_mark); + + accum.template addH( + start_mocap_time_offset, start_mocap_time_offset, + mocap_var_inv * d_res_d_time.transpose() * d_res_d_time); + + // B + accum.template addB( + start_T_moc_w, + mocap_var_inv * d_res_d_T_moc_w.transpose() * residual); + + accum.template addB( + start_T_i_mark, + mocap_var_inv * d_res_d_T_i_mark.transpose() * residual); + + accum.template addB( + start_mocap_time_offset, + mocap_var_inv * d_res_d_time.transpose() * residual); + } + } + + void join(LinearizeSplineOpt& rhs) { + accum.join(rhs.accum); + error += rhs.error; + reprojection_error += rhs.reprojection_error; + num_points += rhs.num_points; + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +} // namespace basalt + +#endif diff --git a/include/basalt/optimization/spline_optimize.h b/include/basalt/optimization/spline_optimize.h new file mode 100644 index 0000000..839991b --- /dev/null +++ b/include/basalt/optimization/spline_optimize.h @@ -0,0 +1,488 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include + +#include + +#include + +#include + +#include + +#include + +namespace basalt { + +template +class SplineOptimization { + public: + typedef LinearizeSplineOpt> + LinearizeT; + + typedef typename LinearizeT::SE3 SE3; + typedef typename LinearizeT::Vector2 Vector2; + typedef typename LinearizeT::Vector3 Vector3; + typedef typename LinearizeT::Vector4 Vector4; + typedef typename LinearizeT::VectorX VectorX; + typedef typename LinearizeT::Matrix24 Matrix24; + + static const int POSE_SIZE = LinearizeT::POSE_SIZE; + static const int POS_SIZE = LinearizeT::POS_SIZE; + static const int POS_OFFSET = LinearizeT::POS_OFFSET; + static const int ROT_SIZE = LinearizeT::ROT_SIZE; + static const int ROT_OFFSET = LinearizeT::ROT_OFFSET; + static const int ACCEL_BIAS_SIZE = LinearizeT::ACCEL_BIAS_SIZE; + static const int GYRO_BIAS_SIZE = LinearizeT::GYRO_BIAS_SIZE; + static const int G_SIZE = LinearizeT::G_SIZE; + + static const int ACCEL_BIAS_OFFSET = LinearizeT::ACCEL_BIAS_OFFSET; + static const int GYRO_BIAS_OFFSET = LinearizeT::GYRO_BIAS_OFFSET; + static const int G_OFFSET = LinearizeT::G_OFFSET; + + const Scalar pose_var; + + Scalar pose_var_inv; + + typedef Eigen::Matrix Matrix3; + + typedef Eigen::Matrix Vector6; + + typedef Eigen::Matrix MatrixX; + + typedef Se3Spline SplineT; + + SplineOptimization(int64_t dt_ns = 1e7) + : pose_var(1e-4), spline(dt_ns), dt_ns(dt_ns) { + pose_var_inv = 1.0 / pose_var; + + // reasonable default values + // calib.accelerometer_noise_var = 2e-2; + // calib.gyroscope_noise_var = 1e-4; + + g.setZero(); + + min_time_us = std::numeric_limits::max(); + max_time_us = std::numeric_limits::min(); + } + + int64_t getCamTimeOffsetNs() const { return calib->cam_time_offset_ns; } + int64_t getMocapTimeOffsetNs() const { + return mocap_calib->mocap_time_offset_ns; + } + + const SE3& getCamT_i_c(size_t i) const { return calib->T_i_c[i]; } + SE3& getCamT_i_c(size_t i) { return calib->T_i_c[i]; } + + VectorX getIntrinsics(size_t i) const { + return calib->intrinsics[i].getParam(); + } + + const CalibAccelBias& getAccelBias() const { + return calib->calib_accel_bias; + } + const CalibGyroBias& getGyroBias() const { + return calib->calib_gyro_bias; + } + + void resetCalib(size_t num_cams, const std::vector& cam_types) { + BASALT_ASSERT(cam_types.size() == num_cams); + + calib.reset(new Calibration); + + calib->intrinsics.resize(num_cams); + calib->T_i_c.resize(num_cams); + + mocap_calib.reset(new MocapCalibration); + } + + void resetMocapCalib() { mocap_calib.reset(new MocapCalibration); } + + void loadCalib(const std::string& p) { + std::string path = p + "calibration.json"; + + std::ifstream is(path); + + if (is.good()) { + cereal::JSONInputArchive archive(is); + calib.reset(new Calibration); + archive(*calib); + std::cout << "Loaded calibration from: " << path << std::endl; + } else { + std::cerr << "No calibration found. Run camera calibration first!!!" + << std::endl; + } + } + + void saveCalib(const std::string& path) const { + if (calib) { + std::ofstream os(path + "calibration.json"); + cereal::JSONOutputArchive archive(os); + + archive(*calib); + } + } + + void saveMocapCalib(const std::string& path, + int64_t mocap_to_imu_offset_ns = 0) const { + if (calib) { + std::ofstream os(path + "mocap_calibration.json"); + cereal::JSONOutputArchive archive(os); + + mocap_calib->mocap_to_imu_offset_ns = mocap_to_imu_offset_ns; + + archive(*mocap_calib); + } + } + + bool calibInitialized() const { return calib != nullptr; } + + bool initialized() const { return spline.numKnots() > 0; } + + void initSpline(const SE3& pose, int num_knots) { + spline.setKnots(pose, num_knots); + } + + void initSpline(const SplineT& other) { + spline.setKnots(other); + + // std::cerr << "spline.numKnots() " << spline.numKnots() << std::endl; + // std::cerr << "other.numKnots() " << other.numKnots() << std::endl; + + size_t num_knots = spline.numKnots(); + + for (size_t i = 0; i < num_knots; i++) { + Eigen::Vector3d rot_rand_inc = Eigen::Vector3d::Random() / 20; + Eigen::Vector3d trans_rand_inc = Eigen::Vector3d::Random(); + + // std::cerr << "rot_rand_inc " << rot_rand_inc.transpose() << std::endl; + // std::cerr << "trans_rand_inc " << trans_rand_inc.transpose() << + // std::endl; + + spline.getKnotSO3(i) *= Sophus::SO3d::exp(rot_rand_inc); + spline.getKnotPos(i) += trans_rand_inc; + } + } + + const SplineT& getSpline() const { return spline; } + + Vector3 getG() const { return g; } + + void setG(const Vector3& g_a) { g = g_a; } + + // const Calibration& getCalib() const { return calib; } + // void setCalib(const Calibration& c) { calib = c; } + + SE3 getT_w_moc() const { return mocap_calib->T_moc_w.inverse(); } + void setT_w_moc(const SE3& val) { mocap_calib->T_moc_w = val.inverse(); } + + SE3 getT_mark_i() const { return mocap_calib->T_i_mark.inverse(); } + void setT_mark_i(const SE3& val) { mocap_calib->T_i_mark = val.inverse(); } + + Eigen::Vector3d getTransAccelWorld(int64_t t_ns) const { + return spline.transAccelWorld(t_ns); + } + + Eigen::Vector3d getRotVelBody(int64_t t_ns) const { + return spline.rotVelBody(t_ns); + } + + SE3 getT_w_i(int64_t t_ns) { return spline.pose(t_ns); } + + void setAprilgridCorners3d(const Eigen::vector& v) { + aprilgrid_corner_pos_3d = v; + } + + void addPoseMeasurement(int64_t t_ns, const SE3& pose) { + min_time_us = std::min(min_time_us, t_ns); + max_time_us = std::max(max_time_us, t_ns); + + pose_measurements.emplace_back(); + pose_measurements.back().timestamp_ns = t_ns; + pose_measurements.back().data = pose; + } + + void addMocapMeasurement(int64_t t_ns, const SE3& pose) { + mocap_measurements.emplace_back(); + mocap_measurements.back().timestamp_ns = t_ns; + mocap_measurements.back().data = pose; + } + + void addAccelMeasurement(int64_t t_ns, const Vector3& meas) { + min_time_us = std::min(min_time_us, t_ns); + max_time_us = std::max(max_time_us, t_ns); + + accel_measurements.emplace_back(); + accel_measurements.back().timestamp_ns = t_ns; + accel_measurements.back().data = meas; + } + + void addGyroMeasurement(int64_t t_ns, const Vector3& meas) { + min_time_us = std::min(min_time_us, t_ns); + max_time_us = std::max(max_time_us, t_ns); + + gyro_measurements.emplace_back(); + gyro_measurements.back().timestamp_ns = t_ns; + gyro_measurements.back().data = meas; + } + + void addAprilgridMeasurement( + int64_t t_ns, int cam_id, + const Eigen::vector& corners_pos, + const std::vector& corner_id) { + min_time_us = std::min(min_time_us, t_ns); + max_time_us = std::max(max_time_us, t_ns); + + aprilgrid_corners_measurements.emplace_back(); + aprilgrid_corners_measurements.back().timestamp_ns = t_ns; + aprilgrid_corners_measurements.back().cam_id = cam_id; + aprilgrid_corners_measurements.back().corner_pos = corners_pos; + aprilgrid_corners_measurements.back().corner_id = corner_id; + } + + Scalar getMinTime() const { return min_time_us * 1e-9; } + Scalar getMaxTime() const { return max_time_us * 1e-9; } + + int64_t getMinTimeNs() const { return min_time_us; } + int64_t getMaxTimeNs() const { return max_time_us; } + + void init() { + int64_t time_interval_us = max_time_us - min_time_us; + + if (spline.numKnots() == 0) { + spline.setStartTimeNs(min_time_us); + spline.setKnots(pose_measurements.front().data, + time_interval_us / dt_ns + N + 1); + } + + recompute_size(); + + // std::cout << "spline.minTimeNs() " << spline.minTimeNs() << std::endl; + // std::cout << "spline.maxTimeNs() " << spline.maxTimeNs() << std::endl; + + ccd.calibration = calib.get(); + ccd.mocap_calibration = mocap_calib.get(); + ccd.aprilgrid_corner_pos_3d = &aprilgrid_corner_pos_3d; + ccd.g = &g; + ccd.offset_intrinsics = &offset_cam_intrinsics; + ccd.offset_T_i_c = &offset_T_i_c; + ccd.bias_block_offset = bias_block_offset; + ccd.mocap_block_offset = mocap_block_offset; + + ccd.opt_g = true; + + ccd.pose_var_inv = pose_var_inv; + ccd.gyro_var_inv = 1.0 / (calib->gyro_noise_std * calib->gyro_noise_std); + ccd.accel_var_inv = 1.0 / (calib->accel_noise_std * calib->accel_noise_std); + ccd.mocap_var_inv = pose_var_inv; + } + + void recompute_size() { + offset_cam_intrinsics.clear(); + + size_t num_knots = spline.numKnots(); + + bias_block_offset = POSE_SIZE * num_knots; + + size_t T_i_c_block_offset = + bias_block_offset + ACCEL_BIAS_SIZE + GYRO_BIAS_SIZE + G_SIZE; + + offset_T_i_c.emplace_back(T_i_c_block_offset); + for (size_t i = 0; i < calib->T_i_c.size(); i++) + offset_T_i_c.emplace_back(offset_T_i_c.back() + POSE_SIZE); + + offset_cam_intrinsics.emplace_back(offset_T_i_c.back()); + for (size_t i = 0; i < calib->intrinsics.size(); i++) + offset_cam_intrinsics.emplace_back(offset_cam_intrinsics.back() + + calib->intrinsics[i].getN()); + + mocap_block_offset = offset_cam_intrinsics.back(); + + opt_size = mocap_block_offset + 2 * POSE_SIZE + 2; + + // std::cerr << "bias_block_offset " << bias_block_offset << std::endl; + // std::cerr << "mocap_block_offset " << mocap_block_offset << std::endl; + // std::cerr << "opt_size " << opt_size << std::endl; + // std::cerr << "offset_T_i_c.back() " << offset_T_i_c.back() << + // std::endl; std::cerr << "offset_cam_intrinsics.back() " << + // offset_cam_intrinsics.back() + // << std::endl; + } + + void optimize(bool use_intr, bool use_poses, bool use_april_corners, + bool opt_cam_time_offset, bool opt_imu_scale, bool use_mocap, + double huber_thresh, double& error, int& num_points, + double& reprojection_error) { + // std::cerr << "optimize num_knots " << num_knots << std::endl; + + for (int i = 0; i < 1; i++) { + ccd.opt_intrinsics = use_intr; + ccd.opt_cam_time_offset = opt_cam_time_offset; + ccd.opt_imu_scale = opt_imu_scale; + ccd.huber_thresh = huber_thresh; + + LinearizeT lopt(opt_size, &spline, ccd); + + // auto t1 = std::chrono::high_resolution_clock::now(); + + if (use_poses) { + tbb::blocked_range pose_range(pose_measurements.begin(), + pose_measurements.end()); + + tbb::parallel_reduce(pose_range, lopt); + // lopt(pose_range); + } + + if (use_april_corners) { + tbb::blocked_range april_range( + aprilgrid_corners_measurements.begin(), + aprilgrid_corners_measurements.end()); + tbb::parallel_reduce(april_range, lopt); + // lopt(april_range); + } + + if (use_mocap) { + tbb::blocked_range mocap_pose_range( + mocap_measurements.begin(), mocap_measurements.end()); + tbb::parallel_reduce(mocap_pose_range, lopt); + // lopt(mocap_pose_range); + } + + tbb::blocked_range accel_range(accel_measurements.begin(), + accel_measurements.end()); + tbb::parallel_reduce(accel_range, lopt); + + tbb::blocked_range gyro_range(gyro_measurements.begin(), + gyro_measurements.end()); + + tbb::parallel_reduce(gyro_range, lopt); + + VectorX inc_full = -lopt.accum.solve(); + + applyInc(inc_full, offset_cam_intrinsics); + + error = lopt.error; + num_points = lopt.num_points; + reprojection_error = lopt.reprojection_error; + } + } + + typename Calibration::Ptr calib; + typename MocapCalibration::Ptr mocap_calib; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + private: + typedef typename Eigen::deque::const_iterator PoseDataIter; + typedef typename Eigen::deque::const_iterator GyroDataIter; + typedef typename Eigen::deque::const_iterator AccelDataIter; + typedef typename Eigen::deque::const_iterator + AprilgridCornersDataIter; + typedef + typename Eigen::deque::const_iterator MocapPoseDataIter; + + void applyInc(VectorX& inc_full, + const std::vector& offset_cam_intrinsics) { + size_t num_knots = spline.numKnots(); + + for (size_t i = 0; i < num_knots; i++) { + Vector6 inc = inc_full.template segment(POSE_SIZE * i); + + // std::cerr << "i: " << i << " inc: " << inc.transpose() << std::endl; + + spline.applyInc(i, inc); + } + + size_t bias_block_offset = POSE_SIZE * num_knots; + calib->calib_accel_bias += inc_full.template segment( + bias_block_offset + ACCEL_BIAS_OFFSET); + + calib->calib_gyro_bias += inc_full.template segment( + bias_block_offset + GYRO_BIAS_OFFSET); + g += inc_full.template segment(bias_block_offset + G_OFFSET); + + size_t T_i_c_block_offset = + bias_block_offset + ACCEL_BIAS_SIZE + GYRO_BIAS_SIZE + G_SIZE; + for (size_t i = 0; i < calib->T_i_c.size(); i++) { + calib->T_i_c[i] *= Sophus::expd(inc_full.template segment( + T_i_c_block_offset + i * POSE_SIZE)); + } + + for (size_t i = 0; i < calib->intrinsics.size(); i++) { + calib->intrinsics[i].applyInc(inc_full.segment( + offset_cam_intrinsics[i], calib->intrinsics[i].getN())); + } + + size_t mocap_block_offset = offset_cam_intrinsics.back(); + + mocap_calib->T_moc_w *= + Sophus::expd(inc_full.template segment(mocap_block_offset)); + mocap_calib->T_i_mark *= Sophus::expd( + inc_full.template segment(mocap_block_offset + POSE_SIZE)); + + mocap_calib->mocap_time_offset_ns += + 1e9 * inc_full[mocap_block_offset + 2 * POSE_SIZE]; + + calib->cam_time_offset_ns += + 1e9 * inc_full[mocap_block_offset + 2 * POSE_SIZE + 1]; + } + + int64_t min_time_us, max_time_us; + + Eigen::deque pose_measurements; + Eigen::deque gyro_measurements; + Eigen::deque accel_measurements; + Eigen::deque aprilgrid_corners_measurements; + Eigen::deque mocap_measurements; + + typename LinearizeT::CalibCommonData ccd; + + std::vector offset_cam_intrinsics; + std::vector offset_T_i_c; + size_t mocap_block_offset; + size_t bias_block_offset; + size_t opt_size; + + SplineT spline; + Vector3 g; + + Eigen::vector aprilgrid_corner_pos_3d; + + int64_t dt_ns; +}; // namespace basalt + +} // namespace basalt diff --git a/include/basalt/utils/common_types.h b/include/basalt/utils/common_types.h new file mode 100644 index 0000000..c9a543e --- /dev/null +++ b/include/basalt/utils/common_types.h @@ -0,0 +1,254 @@ +/** +BSD 3-Clause License + +Copyright (c) 2018, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include +#include +#include +#include + +#include + +#include +#include +#include + +#include + +namespace basalt { + +/// identifies a frame of multiple images (stereo pair) +using FrameId = int64_t; + +/// identifies the camera (left or right) +using CamId = std::size_t; + +/// pair of image timestamp and camera id identifies an image (imageId) +typedef std::pair TimeCamId; +inline std::ostream& operator<<(std::ostream& os, const TimeCamId& tcid) { + os << tcid.first << "_" << tcid.second; + return os; +} + +/// ids for 2D features detected in images +using FeatureId = int; + +/// keypoint positions and descriptors for an image +struct KeypointsData { + /// collection of 2d corner points (indexed by FeatureId) + std::vector> + corners; + /// collection of feature orientation (in radian) with same index as `corners` + /// (indexed by FeatureId) + std::vector corner_angles; + /// collection of feature descriptors with same index as `corners` (indexed by + /// FeatureId) + std::vector> corner_descriptors; + + Eigen::vector corners_3d; +}; + +/// feature corners is a collection of { imageId => KeypointsData } +using Corners = tbb::concurrent_unordered_map; + +/// feature matches for an image pair +struct MatchData { + /// estimated transformation (based on inliers or calibration) from the second + /// image's coordinate system to the first image's corrdinate system + Sophus::SE3d T_i_j; + /// collection of {featureId_i, featureId_j} pairs of all matches + std::vector> matches; + /// collection of {featureId_i, featureId_j} pairs of inlier matches + std::vector> inliers; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +/// feature matches is a collection of { (imageId, imageId) => MatchData } +using Matches = tbb::concurrent_unordered_map< + std::pair, MatchData, + tbb::tbb_hash>, + std::equal_to>, + Eigen::aligned_allocator< + std::pair, MatchData>>>; + +/// pair of image and feature indices +using ImageFeaturePair = std::pair; + +/// Feature tracks are collections of {ImageId => FeatureId}. +/// I.e. a collection of all images that observed this feature and the +/// corresponding feature index in that image. +using FeatureTrack = std::map; + +/// Ids for feature tracks; also used for landmarks created from (some of) the +/// tracks; +using TrackId = int64_t; + +/// FeatureTracks is a collection {TrackId => FeatureTrack} +using FeatureTracks = std::unordered_map; + +/// cameras in the map +struct Camera { + // camera pose (transforms from camera to world) + Sophus::SE3d T_w_c; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +/// landmarks in the map +struct Landmark { + /// 3d position in world coordinates + Eigen::Vector3d p; + + /// Inlier observations in the current map. + /// This is a subset of the original feature track. + FeatureTrack obs; + + /// Outlier observations in the current map. + /// This is a subset of the original feature track. + FeatureTrack outlier_obs; +}; + +/// collection {imageId => Camera} for all cameras in the map +using Cameras = + std::map, + Eigen::aligned_allocator>>; + +/// collection {trackId => Landmark} for all landmarks in the map. +/// trackIds correspond to feature_tracks +using Landmarks = std::unordered_map; + +/// camera candidate to be added to map +struct CameraCandidate { + TimeCamId tcid; + std::vector shared_tracks; + + // keep track of different stages of adding a set of candidate cameras and its + // landmarks to the map + bool tried = false; //!< tried to add to map + bool camera_added = false; //!< succeeded to add to map + bool landmarks_added = false; //!< added new landmarks to map +}; + +/// list of current candidates and some book keeping for the different stages +struct CameraCandidates { + enum Stage { + ComputeCandidates, + AddCameras, + AddLandmarks, + Optimize, + RemoveOutliers, + Done + }; + + std::vector cameras; + Stage current_stage = ComputeCandidates; + int min_localization_inliers = 0; + int max_cameras_to_add = 0; + + int num_cameras_added() { + int num_added = 0; + for (const auto& c : cameras) { + if (c.camera_added) { + ++num_added; + } + } + return num_added; + } + + int num_landmarks_added() { + int num_added = 0; + for (const auto& c : cameras) { + if (c.landmarks_added) { + ++num_added; + } + } + return num_added; + } +}; + +/// Flags for different landmark outlier criteria +enum OutlierFlags { + OutlierNone = 0, + // reprojection error much too large + OutlierReprojectionErrorHuge = 1 << 0, + // reprojection error too large + OutlierReprojectionErrorNormal = 1 << 1, + // distance to a camera too small + OutlierCameraDistance = 1 << 2, + // z-coord in some camera frame too small + OutlierZCoordinate = 1 << 3 +}; + +/// info on a single projected landmark +struct ProjectedLandmark { + Eigen::Vector2d point_measured; //!< detected feature location + Eigen::Vector2d point_reprojected; //!< landmark projected into image + Eigen::Vector3d point_3d_c; //!< 3d point in camera coordinates + TrackId track_id = -1; //!< corresponding track_id + double reprojection_error = 0; //!< current reprojection error + unsigned int outlier_flags = OutlierNone; //!< flags for outlier + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +using ProjectedLandmarkPtr = std::shared_ptr; +using ProjectedLandmarkConstPtr = std::shared_ptr; + +/// all landmark projections for inlier and outlier observations for a single +/// image +struct ImageProjection { + std::vector obs; + std::vector outlier_obs; +}; + +/// projections for all images +using ImageProjections = std::map; + +/// inlier projections indexed per track +using TrackProjections = + std::unordered_map>; +} + +namespace cereal { + +template +void serialize(Archive& ar, basalt::KeypointsData& c) { + ar(c.corners, c.corner_angles, c.corner_descriptors); +} + +template +void serialize(Archive& ar, basalt::MatchData& c) { + ar(c.T_i_j, c.matches, c.inliers); +} +} diff --git a/include/basalt/utils/image.h b/include/basalt/utils/image.h new file mode 100644 index 0000000..11c6a1f --- /dev/null +++ b/include/basalt/utils/image.h @@ -0,0 +1,711 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ + +// This file is adapted from Pangolin. Original license: + +/* This file is part of the Pangolin Project. + * http://github.com/stevenlovegrove/Pangolin + * + * Copyright (c) 2011 Steven Lovegrove + * + * Permission is hereby granted, free of charge, to any person + * obtaining a copy of this software and associated documentation + * files (the "Software"), to deal in the Software without + * restriction, including without limitation the rights to use, + * copy, modify, merge, publish, distribute, sublicense, and/or sell + * copies of the Software, and to permit persons to whom the + * Software is furnished to do so, subject to the following + * conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES + * OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT + * HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, + * WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING + * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR + * OTHER DEALINGS IN THE SOFTWARE. + */ + +#pragma once + +#include + +#include +#include +#include + +namespace basalt { + +inline void PitchedCopy(char* dst, unsigned int dst_pitch_bytes, + const char* src, unsigned int src_pitch_bytes, + unsigned int width_bytes, unsigned int height) { + if (dst_pitch_bytes == width_bytes && src_pitch_bytes == width_bytes) { + std::memcpy(dst, src, height * width_bytes); + } else { + for (unsigned int row = 0; row < height; ++row) { + std::memcpy(dst, src, width_bytes); + dst += dst_pitch_bytes; + src += src_pitch_bytes; + } + } +} + +template +struct Image { + inline Image() : pitch(0), ptr(0), w(0), h(0) {} + + inline Image(T* ptr, size_t w, size_t h, size_t pitch) + : pitch(pitch), ptr(ptr), w(w), h(h) {} + + PANGO_HOST_DEVICE inline size_t SizeBytes() const { return pitch * h; } + + PANGO_HOST_DEVICE inline size_t Area() const { return w * h; } + + PANGO_HOST_DEVICE inline bool IsValid() const { return ptr != 0; } + + PANGO_HOST_DEVICE inline bool IsContiguous() const { + return w * sizeof(T) == pitch; + } + + pangolin::Image toPangoImage() { + pangolin::Image img(ptr, w, h, pitch); + return img; + } + + ////////////////////////////////////////////////////// + // Iterators + ////////////////////////////////////////////////////// + + PANGO_HOST_DEVICE inline T* begin() { return ptr; } + + PANGO_HOST_DEVICE inline T* end() { return RowPtr(h - 1) + w; } + + PANGO_HOST_DEVICE inline const T* begin() const { return ptr; } + + PANGO_HOST_DEVICE inline const T* end() const { return RowPtr(h - 1) + w; } + + PANGO_HOST_DEVICE inline size_t size() const { return w * h; } + + ////////////////////////////////////////////////////// + // Image transforms + ////////////////////////////////////////////////////// + + template + PANGO_HOST_DEVICE inline void Transform(UnaryOperation unary_op) { + PANGO_ASSERT(IsValid()); + + for (size_t y = 0; y < h; ++y) { + T* el = RowPtr(y); + const T* el_end = el + w; + for (; el != el_end; ++el) { + *el = unary_op(*el); + } + } + } + + PANGO_HOST_DEVICE inline void Fill(const T& val) { + Transform([&](const T&) { return val; }); + } + + PANGO_HOST_DEVICE inline void Replace(const T& oldval, const T& newval) { + Transform([&](const T& val) { return (val == oldval) ? newval : val; }); + } + + inline void Memset(unsigned char v = 0) { + PANGO_ASSERT(IsValid()); + if (IsContiguous()) { + ::pangolin::Memset((char*)ptr, v, pitch * h); + } else { + for (size_t y = 0; y < h; ++y) { + ::pangolin::Memset((char*)RowPtr(y), v, pitch); + } + } + } + + inline void CopyFrom(const Image& img) { + if (IsValid() && img.IsValid()) { + PANGO_ASSERT(w >= img.w && h >= img.h); + PitchedCopy((char*)ptr, pitch, (char*)img.ptr, img.pitch, + std::min(img.w, w) * sizeof(T), std::min(img.h, h)); + } else if (img.IsValid() != IsValid()) { + PANGO_ASSERT(false && "Cannot copy from / to an unasigned image."); + } + } + + ////////////////////////////////////////////////////// + // Reductions + ////////////////////////////////////////////////////// + + template + PANGO_HOST_DEVICE inline T Accumulate(const T init, + BinaryOperation binary_op) { + PANGO_ASSERT(IsValid()); + + T val = init; + for (size_t y = 0; y < h; ++y) { + T* el = RowPtr(y); + const T* el_end = el + w; + for (; el != el_end; ++el) { + val = binary_op(val, *el); + } + } + return val; + } + + std::pair MinMax() const { + PANGO_ASSERT(IsValid()); + + std::pair minmax(std::numeric_limits::max(), + std::numeric_limits::lowest()); + for (size_t r = 0; r < h; ++r) { + const T* ptr = RowPtr(r); + const T* end = ptr + w; + while (ptr != end) { + minmax.first = std::min(*ptr, minmax.first); + minmax.second = std::max(*ptr, minmax.second); + ++ptr; + } + } + return minmax; + } + + template + Tout Sum() const { + return Accumulate((T)0, + [](const T& lhs, const T& rhs) { return lhs + rhs; }); + } + + template + Tout Mean() const { + return Sum() / Area(); + } + + ////////////////////////////////////////////////////// + // Direct Pixel Access + ////////////////////////////////////////////////////// + + PANGO_HOST_DEVICE inline T* RowPtr(size_t y) { + return (T*)((unsigned char*)(ptr) + y * pitch); + } + + PANGO_HOST_DEVICE inline const T* RowPtr(size_t y) const { + return (T*)((unsigned char*)(ptr) + y * pitch); + } + + PANGO_HOST_DEVICE inline T& operator()(size_t x, size_t y) { + PANGO_BOUNDS_ASSERT(InBounds(x, y)); + return RowPtr(y)[x]; + } + + PANGO_HOST_DEVICE inline const T& operator()(size_t x, size_t y) const { + PANGO_BOUNDS_ASSERT(InBounds(x, y)); + return RowPtr(y)[x]; + } + + template + PANGO_HOST_DEVICE inline T& operator()(const TVec& p) { + PANGO_BOUNDS_ASSERT(InBounds(p[0], p[1])); + return RowPtr(p[1])[p[0]]; + } + + template + PANGO_HOST_DEVICE inline const T& operator()(const TVec& p) const { + PANGO_BOUNDS_ASSERT(InBounds(p[0], p[1])); + return RowPtr(p[1])[p[0]]; + } + + PANGO_HOST_DEVICE inline T& operator[](size_t ix) { + PANGO_BOUNDS_ASSERT(InImage(ptr + ix)); + return ptr[ix]; + } + + PANGO_HOST_DEVICE inline const T& operator[](size_t ix) const { + PANGO_BOUNDS_ASSERT(InImage(ptr + ix)); + return ptr[ix]; + } + + ////////////////////////////////////////////////////// + // Interpolated Pixel Access + ////////////////////////////////////////////////////// + + template + inline S interp(const Eigen::Matrix& p) const { + return interp(p[0], p[1]); + } + + template + inline Eigen::Matrix interpGrad( + const Eigen::Matrix& p) const { + return interpGrad(p[0], p[1]); + } + + template + inline float interp(S x, S y) const { + int ix = x; + int iy = y; + + S dx = x - ix; + S dy = y - iy; + + S ddx = 1.0f - dx; + S ddy = 1.0f - dy; + + return ddx * ddy * (*this)(ix, iy) + ddx * dy * (*this)(ix, iy + 1) + + dx * ddy * (*this)(ix + 1, iy) + dx * dy * (*this)(ix + 1, iy + 1); + } + + template + inline Eigen::Matrix interpGrad(S x, S y) const { + int ix = x; + int iy = y; + + S dx = x - ix; + S dy = y - iy; + + S ddx = 1.0f - dx; + S ddy = 1.0f - dy; + + Eigen::Matrix res; + + const T& px0y0 = (*this)(ix, iy); + const T& px1y0 = (*this)(ix + 1, iy); + const T& px0y1 = (*this)(ix, iy + 1); + const T& px1y1 = (*this)(ix + 1, iy + 1); + + res[0] = ddx * ddy * px0y0 + ddx * dy * px0y1 + dx * ddy * px1y0 + + dx * dy * px1y1; + + const T& pxm1y0 = (*this)(ix - 1, iy); + const T& pxm1y1 = (*this)(ix - 1, iy + 1); + + S res_mx = ddx * ddy * pxm1y0 + ddx * dy * pxm1y1 + dx * ddy * px0y0 + + dx * dy * px0y1; + + const T& px2y0 = (*this)(ix + 2, iy); + const T& px2y1 = (*this)(ix + 2, iy + 1); + + S res_px = ddx * ddy * px1y0 + ddx * dy * px1y1 + dx * ddy * px2y0 + + dx * dy * px2y1; + + res[1] = 0.5 * (res_px - res_mx); + + const T& px0ym1 = (*this)(ix, iy - 1); + const T& px1ym1 = (*this)(ix + 1, iy - 1); + + S res_my = ddx * ddy * px0ym1 + ddx * dy * px0y0 + dx * ddy * px1ym1 + + dx * dy * px1y0; + + const T& px0y2 = (*this)(ix, iy + 2); + const T& px1y2 = (*this)(ix + 1, iy + 2); + + S res_py = ddx * ddy * px0y1 + ddx * dy * px0y2 + dx * ddy * px1y1 + + dx * dy * px1y2; + + res[2] = 0.5 * (res_py - res_my); + + return res; + } + + ////////////////////////////////////////////////////// + // Bounds Checking + ////////////////////////////////////////////////////// + + PANGO_HOST_DEVICE + bool InImage(const T* ptest) const { + return ptr <= ptest && ptest < RowPtr(h); + } + + PANGO_HOST_DEVICE inline bool InBounds(int x, int y) const { + return 0 <= x && x < (int)w && 0 <= y && y < (int)h; + } + + PANGO_HOST_DEVICE inline bool InBounds(float x, float y, float border) const { + return border <= x && x < (w - border) && border <= y && y < (h - border); + } + + template + PANGO_HOST_DEVICE inline bool InBounds( + const TVec& p, const TBorder border = (TBorder)0) const { + return border <= p[0] && p[0] < ((int)w - border) && border <= p[1] && + p[1] < ((int)h - border); + } + + ////////////////////////////////////////////////////// + // Obtain slices / subimages + ////////////////////////////////////////////////////// + + PANGO_HOST_DEVICE inline const Image SubImage(size_t x, size_t y, + size_t width, + size_t height) const { + PANGO_ASSERT((x + width) <= w && (y + height) <= h); + return Image(RowPtr(y) + x, width, height, pitch); + } + + PANGO_HOST_DEVICE inline Image SubImage(size_t x, size_t y, size_t width, + size_t height) { + PANGO_ASSERT((x + width) <= w && (y + height) <= h); + return Image(RowPtr(y) + x, width, height, pitch); + } + + PANGO_HOST_DEVICE inline Image Row(int y) const { + return SubImage(0, y, w, 1); + } + + PANGO_HOST_DEVICE inline Image Col(int x) const { + return SubImage(x, 0, 1, h); + } + + ////////////////////////////////////////////////////// + // Data mangling + ////////////////////////////////////////////////////// + + template + PANGO_HOST_DEVICE inline Image Reinterpret() const { + PANGO_ASSERT(sizeof(TRecast) == sizeof(T), + "sizeof(TRecast) must match sizeof(T): % != %", + sizeof(TRecast), sizeof(T)); + return UnsafeReinterpret(); + } + + template + PANGO_HOST_DEVICE inline Image UnsafeReinterpret() const { + return Image((TRecast*)ptr, w, h, pitch); + } + + ////////////////////////////////////////////////////// + // Deprecated methods + ////////////////////////////////////////////////////// + + // PANGOLIN_DEPRECATED inline + Image(size_t w, size_t h, size_t pitch, T* ptr) + : pitch(pitch), ptr(ptr), w(w), h(h) {} + + // Use RAII/move aware pangolin::ManagedImage instead + // PANGOLIN_DEPRECATED inline + void Dealloc() { + if (ptr) { + ::operator delete(ptr); + ptr = nullptr; + } + } + + // Use RAII/move aware pangolin::ManagedImage instead + // PANGOLIN_DEPRECATED inline + void Alloc(size_t w, size_t h, size_t pitch) { + Dealloc(); + this->w = w; + this->h = h; + this->pitch = pitch; + this->ptr = (T*)::operator new(h* pitch); + } + + ////////////////////////////////////////////////////// + // Data members + ////////////////////////////////////////////////////// + + size_t pitch; + T* ptr; + size_t w; + size_t h; + + PANGO_EXTENSION_IMAGE +}; + +template +using DefaultImageAllocator = std::allocator; + +// Image that manages it's own memory, storing a strong pointer to it's memory +template > +class ManagedImage : public Image { + public: + typedef std::shared_ptr> Ptr; + + // Destructor + inline ~ManagedImage() { Deallocate(); } + + // Null image + inline ManagedImage() {} + + // Row image + inline ManagedImage(size_t w) + : Image(Allocator().allocate(w), w, 1, w * sizeof(T)) {} + + inline ManagedImage(size_t w, size_t h) + : Image(Allocator().allocate(w * h), w, h, w * sizeof(T)) {} + + inline ManagedImage(size_t w, size_t h, size_t pitch_bytes) + : Image(Allocator().allocate((h * pitch_bytes) / sizeof(T) + 1), w, h, + pitch_bytes) {} + + // Not copy constructable + inline ManagedImage(const ManagedImage& other) = delete; + + // Move constructor + inline ManagedImage(ManagedImage&& img) { + *this = std::move(img); + } + + // Move asignment + inline void operator=(ManagedImage&& img) { + Deallocate(); + Image::pitch = img.pitch; + Image::ptr = img.ptr; + Image::w = img.w; + Image::h = img.h; + img.ptr = nullptr; + } + + // Move constructor + inline ManagedImage(pangolin::ManagedImage&& img) { + *this = std::move(img); + } + + // Move asignment + inline void operator=(pangolin::ManagedImage&& img) { + Deallocate(); + Image::pitch = img.pitch; + Image::ptr = img.ptr; + Image::w = img.w; + Image::h = img.h; + img.ptr = nullptr; + } + + // Explicit copy constructor + template + ManagedImage(const pangolin::CopyObject& other) { + CopyFrom(other.obj); + } + + // Explicit copy assignment + template + void operator=(const pangolin::CopyObject& other) { + CopyFrom(other.obj); + } + + inline void Swap(ManagedImage& img) { + std::swap(img.pitch, Image::pitch); + std::swap(img.ptr, Image::ptr); + std::swap(img.w, Image::w); + std::swap(img.h, Image::h); + } + + inline void CopyFrom(const Image& img) { + if (!Image::IsValid() || Image::w != img.w || Image::h != img.h) { + Reinitialise(img.w, img.h); + } + Image::CopyFrom(img); + } + + inline void Reinitialise(size_t w, size_t h) { + if (!Image::ptr || Image::w != w || Image::h != h) { + *this = ManagedImage(w, h); + } + } + + inline void Reinitialise(size_t w, size_t h, size_t pitch) { + if (!Image::ptr || Image::w != w || Image::h != h || + Image::pitch != pitch) { + *this = ManagedImage(w, h, pitch); + } + } + + inline void Deallocate() { + if (Image::ptr) { + Allocator().deallocate(Image::ptr, + (Image::h * Image::pitch) / sizeof(T)); + Image::ptr = nullptr; + } + } + + // Move asignment + template + inline void OwnAndReinterpret(ManagedImage&& img) { + Deallocate(); + Image::pitch = img.pitch; + Image::ptr = (T*)img.ptr; + Image::w = img.w; + Image::h = img.h; + img.ptr = nullptr; + } + + template + inline void ConvertFrom(const ManagedImage& img) { + Reinitialise(img.w, img.h); + + for (size_t j = 0; j < img.h; j++) { + T* this_row = this->RowPtr(j); + const T1* other_row = img.RowPtr(j); + for (size_t i = 0; i < img.w; i++) { + this_row[i] = T(other_row[i]); + } + } + } + + inline void operator-=(const ManagedImage& img) { + for (size_t j = 0; j < img.h; j++) { + T* this_row = this->RowPtr(j); + const T* other_row = img.RowPtr(j); + for (size_t i = 0; i < img.w; i++) { + this_row[i] -= other_row[i]; + } + } + } +}; + +template > +class ManagedImagePyr { + public: + inline ManagedImagePyr() {} + + inline ManagedImagePyr(ManagedImage& other, size_t num_levels) { + setFromImage(other, num_levels); + } + + inline void setFromImage(const ManagedImage& other, size_t num_levels) { + orig_w = other.w; + image.Reinitialise(other.w + other.w / 2, other.h); + image.Fill(0); + lvl_internal(0).CopyFrom(other); + + for (size_t i = 0; i < num_levels; i++) { + const Image l = lvl(i); + Image lp1 = lvl_internal(i + 1); + subsample(l, lp1); + } + } + + static inline int border101(int x, int h) { + return h - 1 - std::abs(h - 1 - x); + } + + static void subsample(const Image& img, Image& img_sub) { + static_assert(std::is_same::value || + std::is_same::value); + + constexpr int kernel[5] = {1, 4, 6, 4, 1}; + + // accumulator + ManagedImage tmp(img_sub.h, img.w); + + // Vertical convolution + { + for (int r = 0; r < int(img_sub.h); r++) { + const T* row_m2 = img.RowPtr(std::abs(2 * r - 2)); + const T* row_m1 = img.RowPtr(std::abs(2 * r - 1)); + const T* row = img.RowPtr(2 * r); + const T* row_p1 = img.RowPtr(border101(2 * r + 1, img.h)); + const T* row_p2 = img.RowPtr(border101(2 * r + 2, img.h)); + + for (int c = 0; c < int(img.w); c++) { + tmp(r, c) = kernel[0] * int(row_m2[c]) + kernel[1] * int(row_m1[c]) + + kernel[2] * int(row[c]) + kernel[3] * int(row_p1[c]) + + kernel[4] * int(row_p2[c]); + } + } + } + + // Horizontal convolution + { + for (int c = 0; c < int(img_sub.w); c++) { + const int* row_m2 = tmp.RowPtr(std::abs(2 * c - 2)); + const int* row_m1 = tmp.RowPtr(std::abs(2 * c - 1)); + const int* row = tmp.RowPtr(2 * c); + const int* row_p1 = tmp.RowPtr(border101(2 * c + 1, tmp.h)); + const int* row_p2 = tmp.RowPtr(border101(2 * c + 2, tmp.h)); + + for (int r = 0; r < int(tmp.w); r++) { + int val_int = kernel[0] * row_m2[r] + kernel[1] * row_m1[r] + + kernel[2] * row[r] + kernel[3] * row_p1[r] + + kernel[4] * row_p2[r]; + T val = ((val_int + (1 << 7)) >> 8); + img_sub(c, r) = val; + } + } + } + } + + inline const Image lvl(size_t lvl) const { + size_t x = (lvl == 0) ? 0 : orig_w; + size_t y = (lvl <= 1) ? 0 : (image.h - (image.h >> (lvl - 1))); + size_t width = (orig_w >> lvl); + size_t height = (image.h >> lvl); + + return image.SubImage(x, y, width, height); + } + + template + inline Eigen::Matrix lvl_offset(size_t lvl) { + size_t x = (lvl == 0) ? 0 : orig_w; + size_t y = (lvl <= 1) ? 0 : (image.h - (image.h >> (lvl - 1))); + + return Eigen::Matrix(x, y); + } + + inline pangolin::Image toPangoImage() { return image.toPangoImage(); } + + private: + inline Image lvl_internal(size_t lvl) { + size_t x = (lvl == 0) ? 0 : orig_w; + size_t y = (lvl <= 1) ? 0 : (image.h - (image.h >> (lvl - 1))); + size_t width = (orig_w >> lvl); + size_t height = (image.h >> lvl); + + return image.SubImage(x, y, width, height); + } + + size_t orig_w; + ManagedImage image; +}; + +inline void rgb_to_gray(const pangolin::TypedImage& rgb, + basalt::ManagedImage& gray) { + gray.Reinitialise(rgb.w, rgb.h); + + for (size_t x = 0; x < rgb.w; x++) { + for (size_t y = 0; y < rgb.h; y++) { + double val = 0.2989 * (double)rgb(3 * x + 0, y) + + 0.5870 * (double)rgb(3 * x + 1, y) + + 0.1140 * (double)rgb(3 * x + 2, y); + + gray(x, y) = val; + } + } +} + +} // namespace basalt diff --git a/include/basalt/utils/imu_types.h b/include/basalt/utils/imu_types.h new file mode 100644 index 0000000..c96b8f0 --- /dev/null +++ b/include/basalt/utils/imu_types.h @@ -0,0 +1,270 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include +#include +#include + +#include +#include + +#include +#include +#include + +#include + +namespace basalt { + +namespace constants { +static const Eigen::Vector3d g(0, 0, -9.81); +static const Eigen::Vector3d g_dir(0, 0, -1); +} // namespace constants + +struct PoseVelBiasStateWithLin : private PoseVelBiasState { + PoseVelBiasStateWithLin() { + linearized = false; + delta.setZero(); + }; + + PoseVelBiasStateWithLin(int64_t t_ns, const Sophus::SE3d& T_w_i, + const Eigen::Vector3d& vel_w_i, + const Eigen::Vector3d& bias_gyro, + const Eigen::Vector3d& bias_accel, bool linearized) + : PoseVelBiasState(t_ns, T_w_i, vel_w_i, bias_gyro, bias_accel), + linearized(linearized) { + delta.setZero(); + state_current = *this; + } + + PoseVelBiasStateWithLin(const PoseVelBiasState& other) + : PoseVelBiasState(other), linearized(false) { + delta.setZero(); + state_current = other; + } + + void setLinFalse() { + linearized = false; + delta.setZero(); + } + + void setLinTrue() { linearized = true; } + + void applyInc(const VecN& inc) { + if (!linearized) { + PoseVelBiasState::applyInc(inc); + } else { + delta += inc; + state_current = *this; + state_current.applyInc(delta); + } + } + + inline const PoseVelBiasState& getState() const { + if (!linearized) { + return *this; + } else { + return state_current; + } + } + + inline const PoseVelBiasState& getStateLin() const { return *this; } + + inline bool isLinearized() const { return linearized; } + inline const VecN& getDelta() const { return delta; } + inline int64_t getT_ns() const { return t_ns; } + + friend struct PoseStateWithLin; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + private: + bool linearized; + VecN delta; + + PoseVelBiasState state_current; + + friend class cereal::access; + + template + void serialize(Archive& ar) { + ar(T_w_i); + ar(vel_w_i); + ar(bias_gyro); + ar(bias_accel); + ar(state_current.T_w_i); + ar(state_current.vel_w_i); + ar(state_current.bias_gyro); + ar(state_current.bias_accel); + ar(delta); + ar(linearized); + ar(t_ns); + } +}; + +struct PoseStateWithLin : private PoseState { + PoseStateWithLin() { + linearized = false; + delta.setZero(); + }; + + PoseStateWithLin(int64_t t_ns, const Sophus::SE3d& T_w_i) + : PoseState(t_ns, T_w_i), linearized(false) { + delta.setZero(); + T_w_i_current = T_w_i; + } + + PoseStateWithLin(const PoseVelBiasStateWithLin& other) + : PoseState(other.t_ns, other.T_w_i), + linearized(other.linearized), + delta(other.delta.head<6>()) { + T_w_i_current = T_w_i; + incPose(delta, T_w_i_current); + } + + inline const Sophus::SE3d& getPose() const { + if (!linearized) { + return T_w_i; + } else { + return T_w_i_current; + } + } + + inline const Sophus::SE3d& getPoseLin() const { return T_w_i; } + + inline void applyInc(const VecN& inc) { + if (!linearized) { + incPose(inc, T_w_i); + } else { + delta += inc; + T_w_i_current = T_w_i; + incPose(delta, T_w_i_current); + } + } + + inline bool isLinearized() const { return linearized; } + inline const VecN& getDelta() const { return delta; } + inline int64_t getT_ns() const { return t_ns; } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + private: + bool linearized; + VecN delta; + + Sophus::SE3d T_w_i_current; + + friend class cereal::access; + + template + void serialize(Archive& ar) { + ar(T_w_i); + ar(T_w_i_current); + ar(delta); + ar(linearized); + ar(t_ns); + } +}; + +struct AbsOrderMap { + std::map> abs_order_map; + size_t items = 0; + size_t total_size = 0; + + void print_order() { + for (const auto& kv : abs_order_map) { + std::cout << kv.first << " (" << kv.second.first << "," + << kv.second.second << ")" << std::endl; + } + std::cout << std::endl; + } +}; + +struct MargData { + typedef std::shared_ptr Ptr; + + AbsOrderMap aom; + Eigen::MatrixXd abs_H; + Eigen::VectorXd abs_b; + Eigen::map frame_states; + Eigen::map frame_poses; + std::set kfs_all; + std::set kfs_to_marg; + + std::vector opt_flow_res; +}; + +struct RelPoseFactor { + int64_t t_i_ns, t_j_ns; + + Sophus::SE3d T_i_j; + Sophus::Matrix6d cov_inv; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +struct RollPitchFactor { + int64_t t_ns; + + Sophus::SO3d R_w_i_meas; + + Eigen::Matrix2d cov_inv; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; +} // namespace basalt + +namespace cereal { + +template +void serialize(Archive& ar, basalt::AbsOrderMap& a) { + ar(a.total_size); + ar(a.items); + ar(a.abs_order_map); +} + +template +void serialize(Archive& ar, basalt::MargData& m) { + ar(m.aom); + ar(m.abs_H); + ar(m.abs_b); + ar(m.frame_poses); + ar(m.frame_states); + ar(m.kfs_all); + ar(m.kfs_to_marg); +} + +} // namespace cereal diff --git a/include/basalt/utils/keypoints.h b/include/basalt/utils/keypoints.h new file mode 100644 index 0000000..c556477 --- /dev/null +++ b/include/basalt/utils/keypoints.h @@ -0,0 +1,111 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include + +#include +#include + +#include + +#include +#include + +#include +#include + +namespace basalt { + +typedef std::bitset<256> Descriptor; + +void detectKeypointsMapping(const basalt::Image& img_raw, + KeypointsData& kd, int num_features); + +void detectKeypoints(const basalt::Image& img_raw, + KeypointsData& kd, int PATCH_SIZE = 32, + int num_points_cell = 1, + const Eigen::vector& current_points = + Eigen::vector()); + +void computeAngles(const basalt::Image& img_raw, + KeypointsData& kd, bool rotate_features); + +void computeDescriptors(const basalt::Image& img_raw, + KeypointsData& kd); + +void matchFastHelper(const std::vector>& corner_descriptors_1, + const std::vector>& corner_descriptors_2, + std::map& matches, int threshold, + double test_dist); + +void matchDescriptors(const std::vector>& corner_descriptors_1, + const std::vector>& corner_descriptors_2, + std::vector>& matches, int threshold, + double dist_2_best); + +inline void computeEssential(const Sophus::SE3d& T_0_1, Eigen::Matrix4d& E) { + E.setZero(); + const Eigen::Vector3d t_0_1 = T_0_1.translation(); + const Eigen::Matrix3d R_0_1 = T_0_1.rotationMatrix(); + + E.topLeftCorner<3, 3>() = Sophus::SO3d::hat(t_0_1.normalized()) * R_0_1; +} + +inline void findInliersEssential(const KeypointsData& kd1, + const KeypointsData& kd2, + const Eigen::Matrix4d& E, + double epipolar_error_threshold, + MatchData& md) { + md.inliers.clear(); + + for (size_t j = 0; j < md.matches.size(); j++) { + const Eigen::Vector4d p0_3d = kd1.corners_3d[md.matches[j].first]; + const Eigen::Vector4d p1_3d = kd2.corners_3d[md.matches[j].second]; + + const double epipolar_error = std::abs(p0_3d.transpose() * E * p1_3d); + + if (epipolar_error < epipolar_error_threshold) { + md.inliers.push_back(md.matches[j]); + } + } +} + +void findInliersRansac(const KeypointsData& kd1, const KeypointsData& kd2, + const double ransac_thresh, const int ransac_min_inliers, + MatchData& md); + +} // namespace basalt diff --git a/include/basalt/utils/nfr.h b/include/basalt/utils/nfr.h new file mode 100644 index 0000000..24d9fab --- /dev/null +++ b/include/basalt/utils/nfr.h @@ -0,0 +1,120 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +#include + +namespace basalt { + +inline Sophus::Vector6d relPoseError( + const Sophus::SE3d& T_i_j, const Sophus::SE3d& T_w_i, + const Sophus::SE3d& T_w_j, Sophus::Matrix6d* d_res_d_T_w_i = nullptr, + Sophus::Matrix6d* d_res_d_T_w_j = nullptr) { + Sophus::SE3d T_j_i = T_w_j.inverse() * T_w_i; + Sophus::Vector6d res = Sophus::logd(T_i_j * T_j_i); + + if (d_res_d_T_w_i || d_res_d_T_w_j) { + Sophus::Matrix6d J; + Sophus::rightJacobianInvSE3Decoupled(res, J); + + Eigen::Matrix3d R = T_w_i.so3().inverse().matrix(); + + Sophus::Matrix6d Adj; + Adj.setZero(); + Adj.topLeftCorner<3, 3>() = R; + Adj.bottomRightCorner<3, 3>() = R; + + if (d_res_d_T_w_i) { + *d_res_d_T_w_i = J * Adj; + } + + if (d_res_d_T_w_j) { + Adj.topRightCorner<3, 3>() = + Sophus::SO3d::hat(T_j_i.inverse().translation()) * R; + *d_res_d_T_w_j = -J * Adj; + } + } + + return res; +} + +inline Sophus::Vector3d absPositionError( + const Sophus::SE3d& T_w_i, const Eigen::Vector3d pos, + Eigen::Matrix* d_res_d_T_w_i = nullptr) { + if (d_res_d_T_w_i) { + d_res_d_T_w_i->topLeftCorner<3, 3>().setIdentity(); + d_res_d_T_w_i->topRightCorner<3, 3>().setZero(); + } + + return T_w_i.translation() - pos; +} + +inline double yawError(const Sophus::SE3d& T_w_i, + const Eigen::Vector3d yaw_dir_body, + Eigen::Matrix* d_res_d_T_w_i = nullptr) { + Eigen::Matrix3d curr_R_w_i = T_w_i.so3().matrix(); + Eigen::Vector3d tmp = curr_R_w_i * yaw_dir_body; + double res_yaw = tmp[1]; + + if (d_res_d_T_w_i) { + d_res_d_T_w_i->setZero(); + (*d_res_d_T_w_i)[3] = -tmp[2]; + (*d_res_d_T_w_i)[5] = tmp[0]; + } + + return res_yaw; +} + +inline Sophus::Vector2d rollPitchError( + const Sophus::SE3d& T_w_i, const Sophus::SO3d& R_w_i_meas, + Eigen::Matrix* d_res_d_T_w_i = nullptr) { + // Assumes g direction is negative Z in world coordinate frame + + Eigen::Matrix3d R = (R_w_i_meas * T_w_i.so3().inverse()).matrix(); + Eigen::Vector3d res = R * (-Eigen::Vector3d::UnitZ()); + + if (d_res_d_T_w_i) { + d_res_d_T_w_i->setZero(); + (*d_res_d_T_w_i)(0, 3) = -R(0, 1); + (*d_res_d_T_w_i)(1, 3) = -R(1, 1); + (*d_res_d_T_w_i)(0, 4) = R(0, 0); + (*d_res_d_T_w_i)(1, 4) = R(1, 0); + } + + return res.head<2>(); +} +} diff --git a/include/basalt/utils/sim_utils.h b/include/basalt/utils/sim_utils.h new file mode 100644 index 0000000..dc7dc42 --- /dev/null +++ b/include/basalt/utils/sim_utils.h @@ -0,0 +1,55 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +namespace basalt { + +struct SimObservations { + Eigen::vector pos; + std::vector id; +}; + +} + +namespace cereal { +template +void serialize(Archive& ar, basalt::SimObservations& c) { + ar(c.pos, c.id); +} +} + + diff --git a/include/basalt/utils/system_utils.h b/include/basalt/utils/system_utils.h new file mode 100644 index 0000000..1693791 --- /dev/null +++ b/include/basalt/utils/system_utils.h @@ -0,0 +1,52 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ +#ifndef BASALT_SYSTEM_UTILS_H +#define BASALT_SYSTEM_UTILS_H + +#include + +namespace basalt { + +inline std::string ensure_trailing_slash(const std::string& path) { + if (!path.empty() && path[path.size() - 1] != '/') { + return path + "/"; + } else { + return path; + } +} + +} // namespace basalt + +#endif // include guard diff --git a/include/basalt/utils/test_utils.h b/include/basalt/utils/test_utils.h new file mode 100644 index 0000000..10a2d5f --- /dev/null +++ b/include/basalt/utils/test_utils.h @@ -0,0 +1,77 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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. +*/ +#ifndef BASALT_TEST_UTILS_H +#define BASALT_TEST_UTILS_H + +#include + +template +void test_jacobian_code(const std::string& name, + const Eigen::MatrixBase& Ja, F func, + const Eigen::MatrixBase& x0, + double eps = 1e-8, double max_norm = 1e-4) { + typedef typename Derived1::Scalar Scalar; + + Eigen::Matrix Jn = Ja; + Jn.setZero(); + + Eigen::Matrix inc = x0; + for (int i = 0; i < Jn.cols(); i++) { + inc.setZero(); + inc[i] += eps; + + Eigen::Matrix fpe = func(x0 + inc); + Eigen::Matrix fme = func(x0 - inc); + + Jn.col(i) = (fpe - fme) / (2 * eps); + } + + Scalar diff = (Ja - Jn).norm(); + + if (diff > max_norm || !Ja.allFinite()) { + std::cerr << name << std::endl; + std::cerr << "Numeric Jacobian is different from analytic. Norm difference " + << diff << std::endl; + std::cerr << "Ja\n" << Ja << std::endl; + std::cerr << "Jn\n" << Jn << std::endl; + } else { + // std::cout << name << std::endl; + // std::cout << "Success" << std::endl; + // std::cout << "Ja\n" << Ja << std::endl; + // std::cout << "Jn\n" << Jn << std::endl; + } +} + +#endif // BASALT_TEST_UTILS_H diff --git a/include/basalt/utils/tracks.h b/include/basalt/utils/tracks.h new file mode 100644 index 0000000..b6a4b83 --- /dev/null +++ b/include/basalt/utils/tracks.h @@ -0,0 +1,225 @@ +// Adapted from OpenMVG + +// Copyright (c) 2012, 2013 Pierre MOULON +// 2018 Nikolaus DEMMEL + +// This file was originally part of OpenMVG, an Open Multiple View Geometry C++ +// library. + +// This Source Code Form is subject to the terms of the Mozilla Public +// License, v. 2.0. If a copy of the MPL was not distributed with this +// file, You can obtain one at http://mozilla.org/MPL/2.0/. + +// Implementation of [1] an efficient algorithm to compute track from pairwise +// correspondences. +// +// [1] Pierre Moulon and Pascal Monasse, +// "Unordered feature tracking made fast and easy" CVMP 2012. +// +// It tracks the position of features along the series of image from pairwise +// correspondences. +// +// From map<[imageI,ImageJ], [indexed matches array] > it builds tracks. +// +// Usage : +// //--------------------------------------- +// // Compute tracks from matches +// //--------------------------------------- +// TrackBuilder trackBuilder; +// FeatureTracks tracks; +// trackBuilder.Build(matches); // Build: Efficient fusion of correspondences +// trackBuilder.Filter(); // Filter: Remove tracks that have conflict +// trackBuilder.Export(tracks); // Export tree to usable data structure + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include + + +namespace basalt { + + + +/// TrackBuild class creates feature tracks from matches +struct TrackBuilder { + std::map map_node_to_index; + UnionFind uf_tree; + + /// Build tracks for a given series of pairWise matches + void Build(const Matches& map_pair_wise_matches) { + // 1. We need to know how much single set we will have. + // i.e each set is made of a tuple : (imageIndex, featureIndex) + std::set allFeatures; + // For each couple of images list the used features + for (const auto& iter : map_pair_wise_matches) { + const auto I = iter.first.first; + const auto J = iter.first.second; + const MatchData& matchData = iter.second; + + // Retrieve all shared features and add them to a set + for (const auto& match : matchData.inliers) { + allFeatures.emplace(I, match.first); + allFeatures.emplace(J, match.second); + } + } + + // 2. Build the 'flat' representation where a tuple (the node) + // is attached to a unique index. + TrackId cpt = 0; + for (const auto& feat : allFeatures) { + map_node_to_index.emplace(feat, cpt); + ++cpt; + } + // Clean some memory + allFeatures.clear(); + + // 3. Add the node and the pairwise correpondences in the UF tree. + uf_tree.InitSets(map_node_to_index.size()); + + // 4. Union of the matched features corresponding UF tree sets + for (const auto& iter : map_pair_wise_matches) { + const auto I = iter.first.first; + const auto J = iter.first.second; + const MatchData& matchData = iter.second; + for (const auto& match : matchData.inliers) { + const ImageFeaturePair pairI(I, match.first); + const ImageFeaturePair pairJ(J, match.second); + // Link feature correspondences to the corresponding containing sets. + uf_tree.Union(map_node_to_index[pairI], map_node_to_index[pairJ]); + } + } + } + + /// Remove bad tracks (too short or track with ids collision) + bool Filter(size_t minimumTrackLength = 2) { + // Remove bad tracks: + // - track that are too short, + // - track with id conflicts: + // i.e. tracks that have many times the same image index + + // From the UF tree, create tracks of the image indexes. + // If an image index appears twice the track must disappear + // If a track is too short it has to be removed. + std::map> tracks; + + std::set problematic_track_id; + // Build tracks from the UF tree, track problematic ids. + for (const auto& iter : map_node_to_index) { + const TrackId track_id = uf_tree.Find(iter.second); + if (problematic_track_id.count(track_id) != 0) { + continue; // Track already marked + } + + const ImageFeaturePair& feat = iter.first; + + if (tracks[track_id].count(feat.first)) { + problematic_track_id.insert(track_id); + } else { + tracks[track_id].insert(feat.first); + } + } + + // - track that are too short, + for (const auto& val : tracks) { + if (val.second.size() < minimumTrackLength) { + problematic_track_id.insert(val.first); + } + } + + for (uint32_t& root_index : uf_tree.m_cc_parent) { + if (problematic_track_id.count(root_index) > 0) { + // reset selected root + uf_tree.m_cc_size[root_index] = 1; + root_index = UnionFind::InvalidIndex(); + } + } + return false; + } + + /// Return the number of connected set in the UnionFind structure (tree + /// forest) + size_t TrackCount() const { + std::set parent_id(uf_tree.m_cc_parent.begin(), + uf_tree.m_cc_parent.end()); + // Erase the "special marker" that depicted rejected tracks + parent_id.erase(UnionFind::InvalidIndex()); + return parent_id.size(); + } + + /// Export tracks as a map (each entry is a map of imageId and + /// featureIndex): + /// {TrackIndex => {imageIndex => featureIndex}} + void Export(FeatureTracks& tracks) { + tracks.clear(); + for (const auto& iter : map_node_to_index) { + const TrackId track_id = uf_tree.Find(iter.second); + const ImageFeaturePair& feat = iter.first; + // ensure never add rejected elements (track marked as invalid) + if (track_id != UnionFind::InvalidIndex()) { + tracks[track_id].emplace(feat); + } + } + } +}; + +/// Find common tracks between images. +bool GetTracksInImages(const std::set& image_ids, + const FeatureTracks& all_tracks, + std::vector& shared_track_ids) { + shared_track_ids.clear(); + + // Go along the tracks + for (const auto& kv_track : all_tracks) { + // Look if the track contains the provided view index & save the point ids + size_t observed_image_count = 0; + for (const auto& imageId : image_ids) { + if (kv_track.second.count(imageId) > 0) { + ++observed_image_count; + } else { + break; + } + } + + if (observed_image_count == image_ids.size()) { + shared_track_ids.push_back(kv_track.first); + } + } + return !shared_track_ids.empty(); +} + +/// Find all tracks in an image. +bool GetTracksInImage(const TimeCamId& image_id, + const FeatureTracks& all_tracks, + std::vector& track_ids) { + std::set image_set; + image_set.insert(image_id); + return GetTracksInImages(image_set, all_tracks, track_ids); +} + +/// Find shared tracks between map and image +bool GetSharedTracks(const TimeCamId& image_id, const FeatureTracks& all_tracks, + const Landmarks& landmarks, + std::vector& track_ids) { + track_ids.clear(); + for (const auto& kv : landmarks) { + const TrackId trackId = kv.first; + if (all_tracks.at(trackId).count(image_id) > 0) { + track_ids.push_back(trackId); + } + } + return !track_ids.empty(); +} + +} diff --git a/include/basalt/utils/union_find.h b/include/basalt/utils/union_find.h new file mode 100644 index 0000000..4f4a4c1 --- /dev/null +++ b/include/basalt/utils/union_find.h @@ -0,0 +1,94 @@ +// Adapted from OpenMVG + +// Copyright (c) 2016 Pierre MOULON +// 2018 Nikolaus DEMMEL + +// This file was originally part of OpenMVG, an Open Multiple View Geometry C++ +// library. + +// This Source Code Form is subject to the terms of the Mozilla Public +// License, v. 2.0. If a copy of the MPL was not distributed with this +// file, You can obtain one at http://mozilla.org/MPL/2.0/. + +#pragma once + +#include +#include +#include +#include + +// Union-Find/Disjoint-Set data structure +//-- +// A disjoint-set data structure also called a union–find data structure +// or merge–find set, is a data structure that keeps track of a set of elements +// partitioned into a number of disjoint (non-overlapping) subsets. +// It supports two operations: +// - Find: Determine which subset a particular element is in. +// - It returns an item from this set that serves as its "representative"; +// - Union: Join two subsets into a single subset. +// Sometime a Connected method is implemented: +// - Connected: +// - By comparing the result of two Find operations, one can determine whether +// two elements are in the same subset. +//-- +struct UnionFind { + using ValueType = uint32_t; + + // Special Value for invalid parent index + static ValueType InvalidIndex() { + return std::numeric_limits::max(); + } + + // Represent the DS/UF forest thanks to two array: + // A parent 'pointer tree' where each node holds a reference to its parent + // node + std::vector m_cc_parent; + // A rank array used for union by rank + std::vector m_cc_rank; + // A 'size array' to know the size of each connected component + std::vector m_cc_size; + + // Init the UF structure with num_cc nodes + void InitSets(const ValueType num_cc) { + // all set size are 1 (independent nodes) + m_cc_size.resize(num_cc, 1); + // Parents id have their own CC id {0,n} + m_cc_parent.resize(num_cc); + std::iota(m_cc_parent.begin(), m_cc_parent.end(), 0); + // Rank array (0) + m_cc_rank.resize(num_cc, 0); + } + + // Return the number of nodes that have been initialized in the UF tree + std::size_t GetNumNodes() const { return m_cc_size.size(); } + + // Return the representative set id of I nth component + ValueType Find(ValueType i) { + // Recursively set all branch as children of root (Path compression) + if (m_cc_parent[i] != i && m_cc_parent[i] != InvalidIndex()) + m_cc_parent[i] = Find(m_cc_parent[i]); + return m_cc_parent[i]; + } + + // Replace sets containing I and J with their union + void Union(ValueType i, ValueType j) { + i = Find(i); + j = Find(j); + if (i == j) { // Already in the same set. Nothing to do + return; + } + + // x and y are not already in same set. Merge them. + // Perform an union by rank: + // - always attach the smaller tree to the root of the larger tree + if (m_cc_rank[i] < m_cc_rank[j]) { + m_cc_parent[i] = j; + m_cc_size[j] += m_cc_size[i]; + + } else { + m_cc_parent[j] = i; + m_cc_size[i] += m_cc_size[j]; + if (m_cc_rank[i] == m_cc_rank[j]) ++m_cc_rank[i]; + } + } +}; diff --git a/include/basalt/utils/vio_config.h b/include/basalt/utils/vio_config.h new file mode 100644 index 0000000..abb8477 --- /dev/null +++ b/include/basalt/utils/vio_config.h @@ -0,0 +1,75 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +namespace basalt { + +struct VioConfig { + VioConfig(); + void load(const std::string& filename); + void save(const std::string& filename); + + std::string optical_flow_type; + int optical_flow_detection_grid_size; + float optical_flow_max_recovered_dist2; + int optical_flow_pattern; + int optical_flow_max_iterations; + int optical_flow_levels; + float optical_flow_epipolar_error; + + int vio_max_states; + int vio_max_kfs; + int vio_min_frames_after_kf; + float vio_new_kf_keypoints_thresh; + int vio_max_iterations; + bool vio_debug; + + double vio_obs_std_dev; + double vio_obs_huber_thresh; + + double mapper_obs_std_dev; + double mapper_obs_huber_thresh; + int mapper_detection_num_points; + double mapper_num_frames_to_match; + double mapper_frames_to_match_threshold; + double mapper_min_matches; + double mapper_ransac_threshold; + double mapper_min_track_length; + double mapper_max_hamming_distance; + double mapper_second_best_test_ratio; +}; +} // namespace basalt diff --git a/include/basalt/utils/vis_utils.h b/include/basalt/utils/vis_utils.h new file mode 100644 index 0000000..41c581e --- /dev/null +++ b/include/basalt/utils/vis_utils.h @@ -0,0 +1,106 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +#include + +#include + +const u_int8_t cam_color[3]{250, 0, 26}; +const u_int8_t state_color[3]{250, 0, 26}; +const u_int8_t pose_color[3]{0, 50, 255}; +const u_int8_t gt_color[3]{0, 171, 47}; + +inline void render_camera(const Eigen::Matrix4d& T_w_c, float lineWidth, + const u_int8_t* color, float sizeFactor) { + const float sz = sizeFactor; + const float width = 640, height = 480, fx = 500, fy = 500, cx = 320, cy = 240; + + const Eigen::vector lines = { + {0, 0, 0}, + {sz * (0 - cx) / fx, sz * (0 - cy) / fy, sz}, + {0, 0, 0}, + {sz * (0 - cx) / fx, sz * (height - 1 - cy) / fy, sz}, + {0, 0, 0}, + {sz * (width - 1 - cx) / fx, sz * (height - 1 - cy) / fy, sz}, + {0, 0, 0}, + {sz * (width - 1 - cx) / fx, sz * (0 - cy) / fy, sz}, + {sz * (width - 1 - cx) / fx, sz * (0 - cy) / fy, sz}, + {sz * (width - 1 - cx) / fx, sz * (height - 1 - cy) / fy, sz}, + {sz * (width - 1 - cx) / fx, sz * (height - 1 - cy) / fy, sz}, + {sz * (0 - cx) / fx, sz * (height - 1 - cy) / fy, sz}, + {sz * (0 - cx) / fx, sz * (height - 1 - cy) / fy, sz}, + {sz * (0 - cx) / fx, sz * (0 - cy) / fy, sz}, + {sz * (0 - cx) / fx, sz * (0 - cy) / fy, sz}, + {sz * (width - 1 - cx) / fx, sz * (0 - cy) / fy, sz}}; + + glPushMatrix(); + glMultMatrixd(T_w_c.data()); + glColor3ubv(color); + glLineWidth(lineWidth); + pangolin::glDrawLines(lines); + glPopMatrix(); +} + +inline void getcolor(float p, float np, float& r, float& g, float& b) { + float inc = 4.0 / np; + float x = p * inc; + r = 0.0f; + g = 0.0f; + b = 0.0f; + + if ((0 <= x && x <= 1) || (5 <= x && x <= 6)) + r = 1.0f; + else if (4 <= x && x <= 5) + r = x - 4; + else if (1 <= x && x <= 2) + r = 1.0f - (x - 1); + + if (1 <= x && x <= 3) + g = 1.0f; + else if (0 <= x && x <= 1) + g = x - 0; + else if (3 <= x && x <= 4) + g = 1.0f - (x - 3); + + if (3 <= x && x <= 5) + b = 1.0f; + else if (2 <= x && x <= 3) + b = x - 2; + else if (5 <= x && x <= 6) + b = 1.0f - (x - 5); +} diff --git a/include/basalt/vi_estimator/ba_base.h b/include/basalt/vi_estimator/ba_base.h new file mode 100644 index 0000000..829aca5 --- /dev/null +++ b/include/basalt/vi_estimator/ba_base.h @@ -0,0 +1,372 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +#include + +namespace basalt { + +class BundleAdjustmentBase { + public: + // keypoint position defined relative to some frame + struct KeypointPosition { + TimeCamId kf_id; + Eigen::Vector2d dir; + double id; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + struct KeypointObservation { + int kpt_id; + Eigen::Vector2d pos; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + struct RelLinDataBase { + std::vector> order; + + Eigen::vector d_rel_d_h; + Eigen::vector d_rel_d_t; + }; + + struct FrameRelLinData { + Sophus::Matrix6d Hpp; + Sophus::Vector6d bp; + + std::vector lm_id; + Eigen::vector> Hpl; + + FrameRelLinData() { + Hpp.setZero(); + bp.setZero(); + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + }; + + struct RelLinData : public RelLinDataBase { + RelLinData(size_t num_keypoints, size_t num_rel_poses) { + Hll.reserve(num_keypoints); + bl.reserve(num_keypoints); + lm_to_obs.reserve(num_keypoints); + + Hpppl.reserve(num_rel_poses); + order.reserve(num_rel_poses); + + d_rel_d_h.reserve(num_rel_poses); + d_rel_d_t.reserve(num_rel_poses); + + error = 0; + } + + void invert_keypoint_hessians() { + for (auto& kv : Hll) { + Eigen::Matrix3d Hll_inv; + Hll_inv.setIdentity(); + kv.second.ldlt().solveInPlace(Hll_inv); + kv.second = Hll_inv; + } + } + + Eigen::unordered_map Hll; + Eigen::unordered_map bl; + Eigen::unordered_map>> lm_to_obs; + + Eigen::vector Hpppl; + + double error; + }; + + void computeError(double& error) const; + + void linearizeHelper( + Eigen::vector& rld_vec, + const Eigen::map< + TimeCamId, Eigen::map>>& + obs_to_lin, + double& error) const; + + static void linearizeRel(const RelLinData& rld, Eigen::MatrixXd& H, + Eigen::VectorXd& b); + + template + static bool linearizePoint( + const KeypointObservation& kpt_obs, const KeypointPosition& kpt_pos, + const Eigen::Matrix4d& T_t_h, const CamT& cam, Eigen::Vector2d& res, + Eigen::Matrix* d_res_d_xi = nullptr, + Eigen::Matrix* d_res_d_p = nullptr, + Eigen::Vector4d* proj = nullptr) { + // Todo implement without jacobians + Eigen::Matrix Jup; + Eigen::Vector4d p_h_3d; + p_h_3d = StereographicParam::unproject(kpt_pos.dir, &Jup); + p_h_3d[3] = kpt_pos.id; + + Eigen::Vector4d p_t_3d = T_t_h * p_h_3d; + + Eigen::Matrix d_point_d_xi; + d_point_d_xi.topLeftCorner<3, 3>() = + Eigen::Matrix3d::Identity() * kpt_pos.id; + d_point_d_xi.topRightCorner<3, 3>() = -Sophus::SO3d::hat(p_t_3d.head<3>()); + d_point_d_xi.row(3).setZero(); + + Eigen::Matrix Jp; + bool valid = cam.project(p_t_3d, res, &Jp); + + if (!valid) { + // std::cerr << " Invalid projection! kpt_pos.dir " + // << kpt_pos.dir.transpose() << " kpt_pos.id " << + // kpt_pos.id + // << " idx " << kpt_obs.kpt_id << std::endl; + + // std::cerr << "T_t_h\n" << T_t_h << std::endl; + // std::cerr << "p_h_3d\n" << p_h_3d.transpose() << std::endl; + // std::cerr << "p_t_3d\n" << p_t_3d.transpose() << std::endl; + + return false; + } + + if (proj) { + proj->head<2>() = res; + (*proj)[2] = p_t_3d[3] / p_t_3d.head<3>().norm(); + } + res -= kpt_obs.pos; + + if (d_res_d_xi) { + *d_res_d_xi = Jp * d_point_d_xi; + } + + if (d_res_d_p) { + Eigen::Matrix Jpp; + Jpp.block<3, 2>(0, 0) = T_t_h.topLeftCorner<3, 4>() * Jup; + Jpp.col(2) = T_t_h.col(3); + + *d_res_d_p = Jp * Jpp; + } + + return true; + } + + template + inline static bool linearizePoint( + const KeypointObservation& kpt_obs, const KeypointPosition& kpt_pos, + const CamT& cam, Eigen::Vector2d& res, + Eigen::Matrix* d_res_d_p = nullptr, + Eigen::Vector4d* proj = nullptr) { + // Todo implement without jacobians + Eigen::Matrix Jup; + Eigen::Vector4d p_h_3d; + p_h_3d = StereographicParam::unproject(kpt_pos.dir, &Jup); + + Eigen::Matrix Jp; + bool valid = cam.project(p_h_3d, res, &Jp); + + if (!valid) { + // std::cerr << " Invalid projection! kpt_pos.dir " + // << kpt_pos.dir.transpose() << " kpt_pos.id " << + // kpt_pos.id + // << " idx " << kpt_obs.kpt_id << std::endl; + // std::cerr << "p_h_3d\n" << p_h_3d.transpose() << std::endl; + + return false; + } + + if (proj) { + proj->head<2>() = res; + (*proj)[2] = kpt_pos.id; + } + res -= kpt_obs.pos; + + if (d_res_d_p) { + Eigen::Matrix Jpp; + Jpp.block<4, 2>(0, 0) = Jup; + Jpp.col(2).setZero(); + + *d_res_d_p = Jp * Jpp; + } + + return true; + } + + void updatePoints(const AbsOrderMap& aom, const RelLinData& rld, + const Eigen::VectorXd& inc); + + static Sophus::SE3d computeRelPose(const Sophus::SE3d& T_w_i_h, + const Sophus::SE3d& T_w_i_t, + const Sophus::SE3d& T_i_c_h, + const Sophus::SE3d& T_i_c_t, + Sophus::Matrix6d* d_rel_d_h = nullptr, + Sophus::Matrix6d* d_rel_d_t = nullptr); + + void get_current_points(Eigen::vector& points, + std::vector& ids) const; + + // Modifies abs_H and abs_b as a side effect. + static void marginalizeHelper(Eigen::MatrixXd& abs_H, Eigen::VectorXd& abs_b, + const std::set& idx_to_keep, + const std::set& idx_to_marg, + Eigen::MatrixXd& marg_H, + Eigen::VectorXd& marg_b); + + static Eigen::Vector4d triangulate(const Eigen::Vector3d& p0_3d, + const Eigen::Vector3d& p1_3d, + const Sophus::SE3d& T_0_1); + + template + static void linearizeAbs(const Eigen::MatrixXd& rel_H, + const Eigen::VectorXd& rel_b, + const RelLinDataBase& rld, const AbsOrderMap& aom, + AccumT& accum) { + // int asize = aom.total_size; + + // BASALT_ASSERT(abs_H.cols() == asize); + // BASALT_ASSERT(abs_H.rows() == asize); + // BASALT_ASSERT(abs_b.rows() == asize); + + for (size_t i = 0; i < rld.order.size(); i++) { + const TimeCamId& tcid_h = rld.order[i].first; + const TimeCamId& tcid_ti = rld.order[i].second; + + int abs_h_idx = aom.abs_order_map.at(tcid_h.first).first; + int abs_ti_idx = aom.abs_order_map.at(tcid_ti.first).first; + + accum.template addB( + abs_h_idx, rld.d_rel_d_h[i].transpose() * + rel_b.segment(i * POSE_SIZE)); + accum.template addB( + abs_ti_idx, rld.d_rel_d_t[i].transpose() * + rel_b.segment(i * POSE_SIZE)); + + for (size_t j = 0; j < rld.order.size(); j++) { + BASALT_ASSERT(rld.order[i].first == rld.order[j].first); + + const TimeCamId& tcid_tj = rld.order[j].second; + + int abs_tj_idx = aom.abs_order_map.at(tcid_tj.first).first; + + if (tcid_h.first == tcid_ti.first || tcid_h.first == tcid_tj.first) + continue; + + accum.template addH( + abs_h_idx, abs_h_idx, rld.d_rel_d_h[i].transpose() * + rel_H.block( + POSE_SIZE * i, POSE_SIZE * j) * + rld.d_rel_d_h[j]); + + accum.template addH( + abs_ti_idx, abs_h_idx, rld.d_rel_d_t[i].transpose() * + rel_H.block( + POSE_SIZE * i, POSE_SIZE * j) * + rld.d_rel_d_h[j]); + + accum.template addH( + abs_h_idx, abs_tj_idx, rld.d_rel_d_h[i].transpose() * + rel_H.block( + POSE_SIZE * i, POSE_SIZE * j) * + rld.d_rel_d_t[j]); + + accum.template addH( + abs_ti_idx, abs_tj_idx, rld.d_rel_d_t[i].transpose() * + rel_H.block( + POSE_SIZE * i, POSE_SIZE * j) * + rld.d_rel_d_t[j]); + } + } + } + + template + struct LinearizeAbsReduce { + using RelLinDataIter = Eigen::vector::iterator; + + LinearizeAbsReduce(AbsOrderMap& aom) : aom(aom) { + accum.reset(aom.total_size); + } + + LinearizeAbsReduce(const LinearizeAbsReduce& other, tbb::split) + : aom(other.aom) { + accum.reset(aom.total_size); + } + + void operator()(const tbb::blocked_range& range) { + for (RelLinData& rld : range) { + rld.invert_keypoint_hessians(); + + Eigen::MatrixXd rel_H; + Eigen::VectorXd rel_b; + linearizeRel(rld, rel_H, rel_b); + + linearizeAbs(rel_H, rel_b, rld, aom, accum); + } + } + + void join(LinearizeAbsReduce& rhs) { accum.join(rhs.accum); } + + AbsOrderMap& aom; + AccumT accum; + }; + + // protected: + PoseStateWithLin getPoseStateWithLin(int64_t t_ns) const { + auto it = frame_poses.find(t_ns); + if (it != frame_poses.end()) return it->second; + + auto it2 = frame_states.find(t_ns); + if (it2 == frame_states.end()) { + std::cerr << "Could not find pose " << t_ns << std::endl; + std::abort(); + } + + return PoseStateWithLin(it2->second); + } + + Eigen::map frame_states; + Eigen::map frame_poses; + + // Point management + Eigen::unordered_map kpts; + Eigen::map>> + obs; + + double obs_std_dev; + double huber_thresh; + + basalt::Calibration calib; +}; +} diff --git a/include/basalt/vi_estimator/keypoint_vio.h b/include/basalt/vi_estimator/keypoint_vio.h new file mode 100644 index 0000000..ad6ee28 --- /dev/null +++ b/include/basalt/vi_estimator/keypoint_vio.h @@ -0,0 +1,229 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include +#include + +namespace basalt { + +class KeypointVioEstimator : public VioEstimatorBase, + public BundleAdjustmentBase { + public: + typedef std::shared_ptr Ptr; + + static const int N = 9; + typedef Eigen::Matrix VecN; + typedef Eigen::Matrix MatNN; + typedef Eigen::Matrix MatN3; + + static constexpr double prior_weight = 1e8; + + KeypointVioEstimator(int64_t t_ns, const Sophus::SE3d& T_w_i, + const Eigen::Vector3d& vel_w_i, + const Eigen::Vector3d& bg, const Eigen::Vector3d& ba, + double int_std_dev, const Eigen::Vector3d& g, + const basalt::Calibration& calib, + const VioConfig& config); + + ~KeypointVioEstimator() { processing_thread->join(); } + + void addIMUToQueue(const ImuData::Ptr& data); + void addVisionToQueue(const OpticalFlowResult::Ptr& data); + + bool measure(const OpticalFlowResult::Ptr& data, + const IntegratedImuMeasurement::Ptr& meas); + + static void linearizeAbsIMU( + const AbsOrderMap& aom, Eigen::MatrixXd& abs_H, Eigen::VectorXd& abs_b, + double& imu_error, double& bg_error, double& ba_error, + const Eigen::map& states, + const Eigen::map& imu_meas, + const Eigen::Vector3d& gyro_bias_weight, + const Eigen::Vector3d& accel_bias_weight, const Eigen::Vector3d& g); + + static void computeImuError( + const AbsOrderMap& aom, double& imu_error, double& bg_error, + double& ba_error, + const Eigen::map& states, + const Eigen::map& imu_meas, + const Eigen::Vector3d& gyro_bias_weight, + const Eigen::Vector3d& accel_bias_weight, const Eigen::Vector3d& g); + + void linearizeMargPrior(const AbsOrderMap& aom, Eigen::MatrixXd& abs_H, + Eigen::VectorXd& abs_b, + double& marg_prior_error) const; + + void computeMargPriorError(double& marg_prior_error) const; + + void computeDelta(const AbsOrderMap& marg_order, + Eigen::VectorXd& delta) const; + + // int64_t propagate(); + // void addNewState(int64_t data_t_ns); + + void marginalize(const std::map& num_points_connected); + + void optimize(); + + void checkMargNullspace() const; + static Eigen::VectorXd checkNullspace( + const Eigen::MatrixXd& marg_H, const Eigen::VectorXd& marg_b, + const AbsOrderMap& marg_order, + const Eigen::map& frame_states, + const Eigen::map& frame_poses); + + int64_t get_t_ns() const { + return frame_states.at(last_state_t_ns).getState().t_ns; + } + const Sophus::SE3d& get_T_w_i() const { + return frame_states.at(last_state_t_ns).getState().T_w_i; + } + const Eigen::Vector3d& get_vel_w_i() const { + return frame_states.at(last_state_t_ns).getState().vel_w_i; + } + + const PoseVelBiasState& get_state() const { + return frame_states.at(last_state_t_ns).getState(); + } + PoseVelBiasState get_state(int64_t t_ns) const { + PoseVelBiasState state; + + auto it = frame_states.find(t_ns); + + if (it != frame_states.end()) { + return it->second.getState(); + } + + auto it2 = frame_poses.find(t_ns); + if (it2 != frame_poses.end()) { + state.T_w_i = it2->second.getPose(); + } + + return state; + } + // const MatNN get_cov() const { return cov.bottomRightCorner(); } + + void computeProjections( + std::vector>& res) const; + + inline void setMaxStates(size_t val) { max_states = val; } + inline void setMaxKfs(size_t val) { max_kfs = val; } + + Eigen::vector getFrameStates() const { + Eigen::vector res; + + for (const auto& kv : frame_states) { + res.push_back(kv.second.getState().T_w_i); + } + + return res; + } + + Eigen::vector getFramePoses() const { + Eigen::vector res; + + for (const auto& kv : frame_poses) { + res.push_back(kv.second.getPose()); + } + + return res; + } + + Eigen::map getAllPosesMap() const { + Eigen::map res; + + for (const auto& kv : frame_poses) { + res[kv.first] = kv.second.getPose(); + } + + for (const auto& kv : frame_states) { + res[kv.first] = kv.second.getState().T_w_i; + } + + return res; + } + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + private: + bool take_kf; + int frames_after_kf; + std::set kf_ids; + + int64_t last_state_t_ns; + Eigen::map imu_meas; + + const Eigen::Vector3d g; + + // Input + + Eigen::map prev_opt_flow_res; + + std::map num_points_kf; + + // Marginalization + AbsOrderMap marg_order; + Eigen::MatrixXd marg_H; + Eigen::VectorXd marg_b; + + Eigen::Vector3d gyro_bias_weight, accel_bias_weight; + + size_t max_states; + size_t max_kfs; + + bool opt_started; + + VioConfig config; + + int64_t msckf_kf_id; + + std::shared_ptr processing_thread; +}; +} // namespace basalt diff --git a/include/basalt/vi_estimator/nfr_mapper.h b/include/basalt/vi_estimator/nfr_mapper.h new file mode 100644 index 0000000..d1710ab --- /dev/null +++ b/include/basalt/vi_estimator/nfr_mapper.h @@ -0,0 +1,218 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include + +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include + +#include + +namespace basalt { + +class NfrMapper : public BundleAdjustmentBase { + public: + using Ptr = std::shared_ptr; + using TimeCamId = std::pair; + using Matches = tbb::concurrent_unordered_map< + std::pair, MatchData, + tbb::tbb_hash>, + std::equal_to>, + Eigen::aligned_allocator< + std::pair, MatchData>>>; + + template + struct MapperLinearizeAbsReduce + : public BundleAdjustmentBase::LinearizeAbsReduce { + using RollPitchFactorConstIter = + Eigen::vector::const_iterator; + using RelPoseFactorConstIter = Eigen::vector::const_iterator; + using RelLinDataIter = Eigen::vector::iterator; + + MapperLinearizeAbsReduce( + AbsOrderMap& aom, + const Eigen::map* frame_poses) + : BundleAdjustmentBase::LinearizeAbsReduce(aom), + frame_poses(frame_poses) { + this->accum.reset(aom.total_size); + roll_pitch_error = 0; + rel_error = 0; + } + + MapperLinearizeAbsReduce(const MapperLinearizeAbsReduce& other, tbb::split) + : BundleAdjustmentBase::LinearizeAbsReduce(other.aom), + frame_poses(other.frame_poses) { + this->accum.reset(this->aom.total_size); + roll_pitch_error = 0; + rel_error = 0; + } + + void join(MapperLinearizeAbsReduce& rhs) { + this->accum.join(rhs.accum); + roll_pitch_error += rhs.roll_pitch_error; + rel_error += rhs.rel_error; + } + + void operator()(const tbb::blocked_range& range) { + for (RelLinData& rld : range) { + rld.invert_keypoint_hessians(); + + Eigen::MatrixXd rel_H; + Eigen::VectorXd rel_b; + linearizeRel(rld, rel_H, rel_b); + + linearizeAbs(rel_H, rel_b, rld, this->aom, this->accum); + } + } + + void operator()(const tbb::blocked_range& range) { + for (const RollPitchFactor& rpf : range) { + const Sophus::SE3d& pose = frame_poses->at(rpf.t_ns).getPose(); + + int idx = this->aom.abs_order_map.at(rpf.t_ns).first; + + Eigen::Matrix J; + Sophus::Vector2d res = basalt::rollPitchError(pose, rpf.R_w_i_meas, &J); + + this->accum.template addH( + idx, idx, J.transpose() * rpf.cov_inv * J); + this->accum.template addB(idx, + J.transpose() * rpf.cov_inv * res); + + roll_pitch_error += res.transpose() * rpf.cov_inv * res; + } + } + + void operator()(const tbb::blocked_range& range) { + for (const RelPoseFactor& rpf : range) { + const Sophus::SE3d& pose_i = frame_poses->at(rpf.t_i_ns).getPose(); + const Sophus::SE3d& pose_j = frame_poses->at(rpf.t_j_ns).getPose(); + + int idx_i = this->aom.abs_order_map.at(rpf.t_i_ns).first; + int idx_j = this->aom.abs_order_map.at(rpf.t_j_ns).first; + + Sophus::Matrix6d Ji, Jj; + Sophus::Vector6d res = + basalt::relPoseError(rpf.T_i_j, pose_i, pose_j, &Ji, &Jj); + + this->accum.template addH( + idx_i, idx_i, Ji.transpose() * rpf.cov_inv * Ji); + this->accum.template addH( + idx_i, idx_j, Ji.transpose() * rpf.cov_inv * Jj); + this->accum.template addH( + idx_j, idx_i, Jj.transpose() * rpf.cov_inv * Ji); + this->accum.template addH( + idx_j, idx_j, Jj.transpose() * rpf.cov_inv * Jj); + + this->accum.template addB( + idx_i, Ji.transpose() * rpf.cov_inv * res); + this->accum.template addB( + idx_j, Jj.transpose() * rpf.cov_inv * res); + + rel_error += res.transpose() * rpf.cov_inv * res; + } + } + + double roll_pitch_error; + double rel_error; + + const Eigen::map* frame_poses; + }; + + NfrMapper(const basalt::Calibration& calib, const VioConfig& config, + const std::string& vocabulary = ""); + + void addMargData(basalt::MargData::Ptr& data); + + void processMargData(basalt::MargData& m); + + void extractNonlinearFactors(basalt::MargData& m); + + void optimize(int num_iterations = 10); + + Eigen::map& getFramePoses(); + + void computeRelPose(double& rel_error); + + void computeRollPitch(double& roll_pitch_error); + + void detect_keypoints(); + + // Feature matching and inlier filtering for stereo pairs with known pose + void match_stereo(); + + void match_all(); + + void build_tracks(); + + void setup_opt(); + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + Eigen::vector roll_pitch_factors; + Eigen::vector rel_pose_factors; + + std::unordered_map img_data; + + tbb::concurrent_unordered_map< + TimeCamId, std::pair> + bow_data; + + Corners feature_corners; + + Matches feature_matches; + + FeatureTracks feature_tracks; + + DBoW3::Database bow_database; + + std::unordered_map bow_id_to_tcid; + + VioConfig config; +}; +} // namespace basalt diff --git a/include/basalt/vi_estimator/vio_estimator.h b/include/basalt/vi_estimator/vio_estimator.h new file mode 100644 index 0000000..13f4bd6 --- /dev/null +++ b/include/basalt/vi_estimator/vio_estimator.h @@ -0,0 +1,102 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +#include +#include + +namespace basalt { + +struct VioVisualizationData { + typedef std::shared_ptr Ptr; + + int64_t t_ns; + + Eigen::vector states; + Eigen::vector frames; + + Eigen::vector points; + std::vector point_ids; + + OpticalFlowResult::Ptr opt_flow_res; + + std::vector> projections; + + EIGEN_MAKE_ALIGNED_OPERATOR_NEW +}; + +class VioEstimatorBase { + public: + typedef std::shared_ptr Ptr; + + VioEstimatorBase() + : out_state_queue(nullptr), + out_marg_queue(nullptr), + out_vis_queue(nullptr) { + vision_data_queue.set_capacity(10); + imu_data_queue.set_capacity(300); + last_processed_t_ns = 0; + finished = false; + } + + std::atomic last_processed_t_ns; + std::atomic finished; + + tbb::concurrent_bounded_queue vision_data_queue; + tbb::concurrent_bounded_queue imu_data_queue; + + tbb::concurrent_bounded_queue* out_state_queue = + nullptr; + tbb::concurrent_bounded_queue* out_marg_queue = nullptr; + tbb::concurrent_bounded_queue* out_vis_queue = + nullptr; +}; + +class VioEstimatorFactory { + public: + static VioEstimatorBase::Ptr getVioEstimator( + const VioConfig& config, const Calibration& cam, int64_t t_ns, + const Sophus::SE3d& T_w_i, const Eigen::Vector3d& vel_w_i, + const Eigen::Vector3d& bg, const Eigen::Vector3d& ba, double int_std_dev, + const Eigen::Vector3d& g); +}; + +double alignSVD(const std::vector& filter_t_ns, + const Eigen::vector& filter_t_w_i, + const std::vector& gt_t_ns, + Eigen::vector& gt_t_w_i); +} // namespace basalt diff --git a/scripts/eval_full/gen_results.py b/scripts/eval_full/gen_results.py new file mode 100755 index 0000000..a1a551a --- /dev/null +++ b/scripts/eval_full/gen_results.py @@ -0,0 +1,39 @@ +#!/usr/bin/env python + +import os +import sys +import numpy as np + + +datasets = ['MH_01_easy', 'MH_02_easy', 'MH_03_medium', 'MH_04_difficult', +'MH_05_difficult', 'V1_01_easy', 'V1_02_medium', +'V1_03_difficult', 'V2_01_easy', 'V2_02_medium'] + + +# Other results. +results_vio = [] +results_mapping = [] + +out_dir = sys.argv[1] + + +for key in datasets: + fname = out_dir + '/vio_' + key + if os.path.isfile(fname): + res = round(float(np.loadtxt(fname)), 3) + results_vio.append(float(res)) + else: + results_vio.append(float('Inf')) + + fname = out_dir + '/mapper_' + key + if os.path.isfile(fname): + res = round(float(np.loadtxt(fname)), 3) + results_mapping.append(float(res)) + else: + results_mapping.append(float('Inf')) + +row_format ="{:>17}" * (len(datasets)) +print row_format.format(*datasets) +print row_format.format(*results_vio) +print row_format.format(*results_mapping) + diff --git a/scripts/eval_full/run_evaluations.sh b/scripts/eval_full/run_evaluations.sh new file mode 100755 index 0000000..8b4e5e5 --- /dev/null +++ b/scripts/eval_full/run_evaluations.sh @@ -0,0 +1,26 @@ +#!/bin/bash + +set -e +set -x + +DATASET_PATH=/data/euroc + +DATASETS=(MH_01_easy MH_02_easy MH_03_medium MH_04_difficult MH_05_difficult V1_01_easy V1_02_medium V1_03_difficult V2_01_easy V2_02_medium V2_03_difficult) + + +folder_name=eval_$(date +%Y%m%d_%H%M%S) +mkdir $folder_name + +cp ../../data/euroc_config.json $folder_name/config.json + + +for d in ${DATASETS[@]}; do + ../../build/basalt_vio --dataset-path $DATASET_PATH/$d --cam-calib ../../data/euroc_ds_calib.json \ + --dataset-type euroc --show-gui 0 --config-path $folder_name/config.json \ + --result-path $folder_name/vio_$d --marg-data $folder_name/marg_$d/ + + ../../build/basalt_mapper --show-gui 0 --cam-calib ../../data/euroc_ds_calib.json --marg-data $folder_name/marg_$d/ \ + --vocabulary ../../thirdparty/DBoW3/vocab/orbvoc.dbow3 --result-path $folder_name/mapper_$d +done + +./gen_results.py $folder_name diff --git a/scripts/install_deps.sh b/scripts/install_deps.sh new file mode 100755 index 0000000..b46f731 --- /dev/null +++ b/scripts/install_deps.sh @@ -0,0 +1,9 @@ +#!/bin/bash + +DIR="$( cd "$( dirname "${BASH_SOURCE[0]}" )" >/dev/null 2>&1 && pwd )" + +if [[ "$OSTYPE" == "darwin"* ]]; then +${DIR}/install_mac_os_deps.sh +else +${DIR}/install_ubuntu_deps.sh +fi diff --git a/scripts/install_mac_os_deps.sh b/scripts/install_mac_os_deps.sh new file mode 100755 index 0000000..237c253 --- /dev/null +++ b/scripts/install_mac_os_deps.sh @@ -0,0 +1,4 @@ +#!/bin/sh + +brew install clang-format tbb glew eigen ccache +brew install --with-toolchain llvm diff --git a/scripts/install_ubuntu_deps.sh b/scripts/install_ubuntu_deps.sh new file mode 100755 index 0000000..51521de --- /dev/null +++ b/scripts/install_ubuntu_deps.sh @@ -0,0 +1,4 @@ +#!/bin/sh + +sudo apt-get update +sudo apt-get install -y gcc g++ cmake git libtbb-dev libeigen3-dev libglew-dev ccache libjpeg-dev libpng-dev liblz4-dev libbz2-dev libboost-regex-dev libboost-filesystem-dev libboost-date-time-dev libboost-program-options-dev libgtest-dev libopencv-dev diff --git a/scripts/update_submodules.sh b/scripts/update_submodules.sh new file mode 100755 index 0000000..3d7d068 --- /dev/null +++ b/scripts/update_submodules.sh @@ -0,0 +1,7 @@ +#!/usr/bin/env bash + +set -x + +git submodule sync --recursive +git submodule update --init --recursive + diff --git a/src/calibrate.cpp b/src/calibrate.cpp new file mode 100644 index 0000000..8555328 --- /dev/null +++ b/src/calibrate.cpp @@ -0,0 +1,82 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +int main(int argc, char **argv) { + tbb::task_scheduler_init init( + tbb::task_scheduler_init::default_num_threads()); + + std::string dataset_path; + std::string dataset_type; + std::string result_path; + std::vector cam_types; + std::string cache_dataset_name = "calib-cam"; + int skip_images = 1; + + CLI::App app{"Calibrate IMU"}; + + app.add_option("--dataset-path", dataset_path, "Path to dataset")->required(); + app.add_option("--result-path", result_path, "Path to result folder") + ->required(); + app.add_option("--dataset-type", dataset_type, "Dataset type (euroc, bag)") + ->required(); + + app.add_option("--cache-name", cache_dataset_name, + "Name to save cached files"); + + app.add_option("--skip-images", skip_images, "Number of images to skip"); + app.add_option("--cam-types", cam_types, + "Type of cameras (eucm, ds, kb4, pinhole)") + ->required(); + + try { + app.parse(argc, argv); + } catch (const CLI::ParseError &e) { + return app.exit(e); + } + + basalt::CamCalib cv(dataset_path, dataset_type, result_path, + cache_dataset_name, skip_images, cam_types); + + cv.renderingLoop(); + + return 0; +} diff --git a/src/calibrate_imu.cpp b/src/calibrate_imu.cpp new file mode 100644 index 0000000..f5add27 --- /dev/null +++ b/src/calibrate_imu.cpp @@ -0,0 +1,94 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +int main(int argc, char **argv) { + tbb::task_scheduler_init init( + tbb::task_scheduler_init::default_num_threads()); + + std::string dataset_path; + std::string dataset_type; + std::string result_path; + std::string cache_dataset_name = "calib-cam-imu"; + int skip_images = 1; + + double accel_noise_std = 0.016; + double gyro_noise_std = 0.000282; + double accel_bias_std = 0.001; + double gyro_bias_std = 0.0001; + + CLI::App app{"Calibrate IMU"}; + + app.add_option("--dataset-path", dataset_path, "Path to dataset")->required(); + app.add_option("--result-path", result_path, "Path to result folder") + ->required(); + app.add_option("--dataset-type", dataset_type, "Dataset type (euroc, bag)") + ->required(); + + app.add_option("--gyro-noise-std", gyro_noise_std, "Gyroscope noise std"); + app.add_option("--accel-noise-std", accel_noise_std, + "Accelerometer noise std"); + + app.add_option("--gyro-bias-std", accel_bias_std, + "Gyroscope bias random walk std"); + app.add_option("--accel-bias-std", gyro_bias_std, + "Accelerometer bias random walk std"); + + app.add_option("--cache-name", cache_dataset_name, + "Name to save cached files"); + + app.add_option("--skip-images", skip_images, "Number of images to skip"); + + try { + app.parse(argc, argv); + } catch (const CLI::ParseError &e) { + return app.exit(e); + } + + basalt::CamImuCalib cv( + dataset_path, dataset_type, result_path, cache_dataset_name, skip_images, + {accel_noise_std, gyro_noise_std, accel_bias_std, gyro_bias_std}); + + cv.renderingLoop(); + + return 0; +} diff --git a/src/calibration/calibraiton_helper.cpp b/src/calibration/calibraiton_helper.cpp new file mode 100644 index 0000000..0a72e5e --- /dev/null +++ b/src/calibration/calibraiton_helper.cpp @@ -0,0 +1,361 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 +#include + +#include +#include + +#include +#include +#include + +namespace basalt { + +template +bool estimateTransformation( + const CamT &cam_calib, const Eigen::vector &corners, + const std::vector &corner_ids, + const Eigen::vector &aprilgrid_corner_pos_3d, + Sophus::SE3d &T_target_camera, size_t &num_inliers) { + opengv::bearingVectors_t bearingVectors; + opengv::points_t points; + + for (size_t i = 0; i < corners.size(); i++) { + Eigen::Vector4d tmp; + cam_calib.unproject(corners[i], tmp); + Eigen::Vector3d bearing = tmp.head<3>(); + Eigen::Vector3d point = aprilgrid_corner_pos_3d[corner_ids[i]].head<3>(); + bearing.normalize(); + + bearingVectors.push_back(bearing); + points.push_back(point); + } + + opengv::absolute_pose::CentralAbsoluteAdapter adapter(bearingVectors, points); + + opengv::sac::Ransac< + opengv::sac_problems::absolute_pose::AbsolutePoseSacProblem> + ransac; + std::shared_ptr + absposeproblem_ptr( + new opengv::sac_problems::absolute_pose::AbsolutePoseSacProblem( + adapter, opengv::sac_problems::absolute_pose:: + AbsolutePoseSacProblem::KNEIP)); + ransac.sac_model_ = absposeproblem_ptr; + ransac.threshold_ = 1.0 - cos(atan(sqrt(2.0) * 1 / cam_calib.getParam()[0])); + ransac.max_iterations_ = 50; + + ransac.computeModel(); + + T_target_camera = + Sophus::SE3d(ransac.model_coefficients_.topLeftCorner<3, 3>(), + ransac.model_coefficients_.topRightCorner<3, 1>()); + + num_inliers = ransac.inliers_.size(); + + return ransac.inliers_.size() > 8; +} + +void CalibHelper::detectCorners( + const VioDatasetPtr &vio_data, + tbb::concurrent_unordered_map &calib_corners, + tbb::concurrent_unordered_map + &calib_corners_rejected) { + calib_corners.clear(); + calib_corners_rejected.clear(); + + tbb::parallel_for( + tbb::blocked_range(0, vio_data->get_image_timestamps().size()), + [&](const tbb::blocked_range &r) { + ApriltagDetector ad; + + for (size_t j = r.begin(); j != r.end(); ++j) { + int64_t timestamp_ns = vio_data->get_image_timestamps()[j]; + const std::vector &img_vec = + vio_data->get_image_data(timestamp_ns); + + for (size_t i = 0; i < img_vec.size(); i++) { + if (img_vec[i].img.get()) { + CalibCornerData ccd_good; + CalibCornerData ccd_bad; + ad.detectTags(*img_vec[i].img, ccd_good.corners, + ccd_good.corner_ids, ccd_good.radii, + ccd_bad.corners, ccd_bad.corner_ids, ccd_bad.radii); + + // std::cout << "image (" << timestamp_ns << "," + // << i + // << ") detected " << + // ccd_good.corners.size() + // << "corners (" << + // ccd_bad.corners.size() + // << " rejected)" << std::endl; + + TimeCamId tcid = std::make_pair(timestamp_ns, i); + + calib_corners.emplace(tcid, ccd_good); + calib_corners_rejected.emplace(tcid, ccd_bad); + } + } + } + }); +} + +void CalibHelper::initCamPoses( + const Calibration::Ptr &calib, const VioDatasetPtr &vio_data, + const Eigen::vector &aprilgrid_corner_pos_3d, + tbb::concurrent_unordered_map &calib_corners, + tbb::concurrent_unordered_map + &calib_init_poses) { + calib_init_poses.clear(); + + std::vector corners; + corners.reserve(calib_corners.size()); + for (const auto &kv : calib_corners) { + corners.emplace_back(kv.first); + } + + tbb::parallel_for(tbb::blocked_range(0, corners.size()), + [&](const tbb::blocked_range &r) { + for (size_t j = r.begin(); j != r.end(); ++j) { + TimeCamId tcid = corners[j]; + const CalibCornerData &ccd = calib_corners.at(tcid); + + CalibInitPoseData cp; + + computeInitialPose(calib, tcid.second, + aprilgrid_corner_pos_3d, ccd, cp); + + calib_init_poses.emplace(tcid, cp); + } + }); +} + +bool CalibHelper::initializeIntrinsics( + const Eigen::vector &corners, + const std::vector &corner_ids, + const Eigen::vector &aprilgrid_corner_pos_3d, int cols, + int rows, Eigen::Vector4d &init_intr) { + // First, initialize the image center at the center of the image. + + Eigen::map id_to_corner; + for (size_t i = 0; i < corner_ids.size(); i++) { + id_to_corner[corner_ids[i]] = corners[i]; + } + + double _xi = 1.0; + double _cu = cols / 2.0 - 0.5; + double _cv = rows / 2.0 - 0.5; + + /// Initialize some temporaries needed. + double gamma0 = 0.0; + double minReprojErr = std::numeric_limits::max(); + + // Now we try to find a non-radial line to initialize the focal length + const size_t target_cols = 6; + const size_t target_rows = 6; + + bool success = false; + for (int tag_corner_offset = 0; tag_corner_offset < 2; tag_corner_offset++) + for (size_t r = 0; r < target_rows; ++r) { + // cv::Mat P(target.cols(); 4, CV_64F); + + Eigen::vector P; + + for (size_t c = 0; c < target_cols; ++c) { + int tag_offset = (r * target_cols + c) << 2; + + for (int i = 0; i < 2; i++) { + int corner_id = tag_offset + i + tag_corner_offset * 2; + + // std::cerr << corner_id << " "; + + if (id_to_corner.find(corner_id) != id_to_corner.end()) { + const Eigen::Vector2d imagePoint = id_to_corner[corner_id]; + + double u = imagePoint[0] - _cu; + double v = imagePoint[1] - _cv; + + P.emplace_back(u, v, 0.5, -0.5 * (square(u) + square(v))); + } + } + } + + // std::cerr << std::endl; + + const int MIN_CORNERS = 8; + // MIN_CORNERS is an arbitrary threshold for the number of corners + if (P.size() > MIN_CORNERS) { + // Resize P to fit with the count of valid points. + + Eigen::Map P_mat((double *)P.data(), 4, P.size()); + + // std::cerr << "P_mat\n" << P_mat.transpose() << std::endl; + + Eigen::MatrixXd P_mat_t = P_mat.transpose(); + + Eigen::JacobiSVD svd( + P_mat_t, Eigen::ComputeThinU | Eigen::ComputeThinV); + + // std::cerr << "U\n" << svd.matrixU() << std::endl; + // std::cerr << "V\n" << svd.matrixV() << std::endl; + // std::cerr << "singularValues\n" << svd.singularValues() << + // std::endl; + + Eigen::Vector4d C = svd.matrixV().col(3); + // std::cerr << "C\n" << C.transpose() << std::endl; + // std::cerr << "P*res\n" << P_mat.transpose() * C << std::endl; + + double t = square(C(0)) + square(C(1)) + C(2) * C(3); + if (t < 0) { + continue; + } + + // check that line image is not radial + double d = sqrt(1.0 / t); + double nx = C(0) * d; + double ny = C(1) * d; + if (hypot(nx, ny) > 0.95) { + // std::cerr << "hypot(nx, ny) " << hypot(nx, ny) << std::endl; + continue; + } + + double nz = sqrt(1.0 - square(nx) - square(ny)); + double gamma = fabs(C(2) * d / nz); + + Eigen::Matrix calib; + calib << 0.5 * gamma, 0.5 * gamma, _cu, _cv, 0.5 * _xi; + // std::cerr << "gamma " << gamma << std::endl; + + UnifiedCamera cam_calib(calib); + + size_t num_inliers; + Sophus::SE3d T_target_camera; + if (!estimateTransformation(cam_calib, corners, corner_ids, + aprilgrid_corner_pos_3d, T_target_camera, + num_inliers)) { + continue; + } + + double reprojErr = 0.0; + size_t numReprojected = computeReprojectionError( + cam_calib, corners, corner_ids, aprilgrid_corner_pos_3d, + T_target_camera, reprojErr); + + // std::cerr << "numReprojected " << numReprojected << " reprojErr " + // << reprojErr / numReprojected << std::endl; + + if (numReprojected > MIN_CORNERS) { + double avgReprojErr = reprojErr / numReprojected; + + if (avgReprojErr < minReprojErr) { + minReprojErr = avgReprojErr; + gamma0 = gamma; + success = true; + } + } + + } // If this observation has enough valid corners + } // For each row in the image. + + if (success) init_intr << 0.5 * gamma0, 0.5 * gamma0, _cu, _cv; + + return success; +} + +void CalibHelper::computeInitialPose( + const Calibration::Ptr &calib, size_t cam_id, + const Eigen::vector &aprilgrid_corner_pos_3d, + const CalibCornerData &cd, CalibInitPoseData &cp) { + if (cd.corners.size() < 8) { + cp.num_inliers = 0; + return; + } + + bool success; + size_t num_inliers; + + std::visit( + [&](const auto &cam) { + Sophus::SE3d T_target_camera; + success = estimateTransformation(cam, cd.corners, cd.corner_ids, + aprilgrid_corner_pos_3d, cp.T_a_c, + num_inliers); + }, + calib->intrinsics[cam_id].variant); + + if (success) { + Eigen::Matrix4d T_c_a_init = cp.T_a_c.inverse().matrix(); + + std::vector proj_success; + calib->intrinsics[cam_id].project(aprilgrid_corner_pos_3d, T_c_a_init, + cp.reprojected_corners, proj_success); + + cp.num_inliers = num_inliers; + } else { + cp.num_inliers = 0; + } +} + +size_t CalibHelper::computeReprojectionError( + const UnifiedCamera &cam_calib, + const Eigen::vector &corners, + const std::vector &corner_ids, + const Eigen::vector &aprilgrid_corner_pos_3d, + const Sophus::SE3d &T_target_camera, double &error) { + size_t num_projected = 0; + error = 0; + + Eigen::Matrix4d T_camera_target = T_target_camera.inverse().matrix(); + + for (size_t i = 0; i < corners.size(); i++) { + Eigen::Vector4d p_cam = + T_camera_target * aprilgrid_corner_pos_3d[corner_ids[i]]; + Eigen::Vector2d res; + cam_calib.project(p_cam, res); + res -= corners[i]; + + num_projected++; + error += res.norm(); + } + + return num_projected; +} +} // namespace basalt diff --git a/src/calibration/cam_calib.cpp b/src/calibration/cam_calib.cpp new file mode 100644 index 0000000..d852341 --- /dev/null +++ b/src/calibration/cam_calib.cpp @@ -0,0 +1,798 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +#include + +#include +namespace fs = std::experimental::filesystem; + +namespace basalt { + +CamCalib::CamCalib(const std::string &dataset_path, + const std::string &dataset_type, + const std::string &cache_path, + const std::string &cache_dataset_name, int skip_images, + const std::vector &cam_types, bool show_gui) + : dataset_path(dataset_path), + dataset_type(dataset_type), + cache_path(ensure_trailing_slash(cache_path)), + cache_dataset_name(cache_dataset_name), + skip_images(skip_images), + cam_types(cam_types), + show_gui(show_gui), + show_frame("ui.show_frame", 0, 0, 1500), + show_corners("ui.show_corners", true, false, true), + show_corners_rejected("ui.show_corners_rejected", false, false, true), + show_init_reproj("ui.show_init_reproj", false, false, true), + show_opt("ui.show_opt", true, false, true), + show_vign("ui.show_vign", false, false, true), + show_ids("ui.show_ids", false, false, true), + huber_thresh("ui.huber_thresh", 4.0, 0.1, 10.0), + opt_intr("ui.opt_intr", true, false, true) { + if (show_gui) initGui(); + + if (!fs::exists(cache_path)) { + fs::create_directory(cache_path); + } +} + +CamCalib::~CamCalib() { + if (processing_thread) { + processing_thread->join(); + } +} + +void CamCalib::initGui() { + pangolin::CreateWindowAndBind("Main", 1600, 1000); + + img_view_display = + &pangolin::CreateDisplay() + .SetBounds(0.5, 1.0, pangolin::Attach::Pix(UI_WIDTH), 1.0) + .SetLayout(pangolin::LayoutEqual); + + pangolin::View &vign_plot_display = + pangolin::CreateDisplay().SetBounds(0.0, 0.5, 0.7, 1.0); + + pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, + pangolin::Attach::Pix(UI_WIDTH)); + + vign_plotter.reset(new pangolin::Plotter(&vign_data_log, 0.0, 1000.0, 0.0, + 1.0, 0.01f, 0.01f)); + vign_plot_display.AddDisplay(*vign_plotter); + + pangolin::Var> load_dataset( + "ui.load_dataset", std::bind(&CamCalib::loadDataset, this)); + + pangolin::Var> detect_corners( + "ui.detect_corners", std::bind(&CamCalib::detectCorners, this)); + + pangolin::Var> init_cam_intrinsics( + "ui.init_cam_intr", std::bind(&CamCalib::initCamIntrinsics, this)); + + pangolin::Var> init_cam_poses( + "ui.init_cam_poses", std::bind(&CamCalib::initCamPoses, this)); + + pangolin::Var> init_cam_extrinsics( + "ui.init_cam_extr", std::bind(&CamCalib::initCamExtrinsics, this)); + + pangolin::Var> init_opt( + "ui.init_opt", std::bind(&CamCalib::initOptimization, this)); + + pangolin::Var> optimize( + "ui.optimize", std::bind(&CamCalib::optimize, this)); + + pangolin::Var> save_calib( + "ui.save_calib", std::bind(&CamCalib::saveCalib, this)); + + pangolin::Var> compute_vign( + "ui.compute_vign", std::bind(&CamCalib::computeVign, this)); + + setNumCameras(1); +} + +void CamCalib::computeVign() { + Eigen::vector optical_centers; + for (size_t i = 0; i < calib_opt->calib->intrinsics.size(); i++) { + optical_centers.emplace_back( + calib_opt->calib->intrinsics[i].getParam().segment<2>(2)); + } + + std::map> reprojected_vignette2; + for (size_t i = 0; i < vio_dataset->get_image_timestamps().size(); i++) { + int64_t timestamp_ns = vio_dataset->get_image_timestamps()[i]; + const std::vector img_vec = + vio_dataset->get_image_data(timestamp_ns); + + for (size_t j = 0; j < calib_opt->calib->intrinsics.size(); j++) { + TimeCamId tcid(timestamp_ns, j); + + auto it = reprojected_vignette.find(tcid); + + if (it != reprojected_vignette.end() && img_vec[j].img.get()) { + Eigen::vector rv; + rv.resize(it->second.size()); + + for (size_t k = 0; k < it->second.size(); k++) { + Eigen::Vector2d pos = it->second[k]; + + rv[k].head<2>() = pos; + + if (img_vec[j].img->InBounds(pos[0], pos[1], 1)) { + double val = img_vec[j].img->interp(pos); + val /= std::numeric_limits::max(); + rv[k][2] = val; + } else { + // invalid projection + rv[k][2] = -1; + } + } + + reprojected_vignette2.emplace(tcid, rv); + } + } + } + + VignetteEstimator ve(vio_dataset, optical_centers, reprojected_vignette2, + april_grid); + + ve.optimize(); + ve.compute_error(&reprojected_vignette_error); + ve.compute_data_log(vign_data_log); + + { + vign_plotter->ClearSeries(); + vign_plotter->ClearMarkers(); + + for (size_t i = 0; i < calib_opt->calib->intrinsics.size(); i++) { + vign_plotter->AddSeries("$i", "$" + std::to_string(2 * i), + pangolin::DrawingModeLine, + pangolin::Colour::Unspecified(), + "vignette camera " + std::to_string(i)); + } + + vign_plotter->ScaleViewSmooth(vign_data_log.Samples() / 1000.0f, 1.0f, 0.0f, + 0.5f); + } + + ve.save_vign_png(cache_path); + + calib_opt->setVignette(ve.get_vign_param()); +} + +void CamCalib::setNumCameras(size_t n) { + while (img_view.size() < n && show_gui) { + std::shared_ptr iv(new pangolin::ImageView); + + size_t idx = img_view.size(); + img_view.push_back(iv); + + img_view_display->AddDisplay(*iv); + iv->extern_draw_function = std::bind(&CamCalib::drawImageOverlay, this, + std::placeholders::_1, idx); + } +} + +void CamCalib::renderingLoop() { + while (!pangolin::ShouldQuit()) { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + if (vio_dataset.get()) { + if (show_frame.GuiChanged()) { + size_t frame_id = static_cast(show_frame); + int64_t timestamp = vio_dataset->get_image_timestamps()[frame_id]; + + const std::vector &img_vec = + vio_dataset->get_image_data(timestamp); + + for (size_t cam_id = 0; cam_id < vio_dataset->get_num_cams(); cam_id++) + if (img_vec[cam_id].img.get()) { + pangolin::GlPixFormat fmt; + fmt.glformat = GL_LUMINANCE; + fmt.gltype = GL_UNSIGNED_SHORT; + fmt.scalable_internal_format = GL_LUMINANCE16; + + img_view[cam_id]->SetImage( + img_vec[cam_id].img->ptr, img_vec[cam_id].img->w, + img_vec[cam_id].img->h, img_vec[cam_id].img->pitch, fmt); + } else { + img_view[cam_id]->Clear(); + } + } + } + + pangolin::FinishFrame(); + } +} + +void CamCalib::computeProjections() { + reprojected_corners.clear(); + reprojected_vignette.clear(); + + if (!calib_opt.get() || !vio_dataset.get()) return; + + for (size_t j = 0; j < vio_dataset->get_image_timestamps().size(); ++j) { + int64_t timestamp_ns = vio_dataset->get_image_timestamps()[j]; + + for (size_t i = 0; i < calib_opt->calib->intrinsics.size(); i++) { + TimeCamId tcid = std::make_pair(timestamp_ns, i); + + Eigen::vector rc, rv; + + Sophus::SE3d T_c_w_ = + (calib_opt->getT_w_i(timestamp_ns) * calib_opt->calib->T_i_c[i]) + .inverse(); + + Eigen::Matrix4d T_c_w = T_c_w_.matrix(); + + rc.resize(april_grid.aprilgrid_corner_pos_3d.size()); + rv.resize(april_grid.aprilgrid_vignette_pos_3d.size()); + + std::vector rc_success, rv_success; + + calib_opt->calib->intrinsics[i].project( + april_grid.aprilgrid_corner_pos_3d, T_c_w, rc, rc_success); + + calib_opt->calib->intrinsics[i].project( + april_grid.aprilgrid_vignette_pos_3d, T_c_w, rv, rv_success); + + reprojected_corners.emplace(tcid, rc); + reprojected_vignette.emplace(tcid, rv); + } + } +} + +void CamCalib::detectCorners() { + if (processing_thread) { + processing_thread->join(); + processing_thread.reset(); + } + + processing_thread.reset(new std::thread([this]() { + std::cout << "Started detecting corners" << std::endl; + + CalibHelper::detectCorners(this->vio_dataset, this->calib_corners, + this->calib_corners_rejected); + + std::string path = + cache_path + cache_dataset_name + "_detected_corners.cereal"; + std::ofstream os(path, std::ios::binary); + cereal::BinaryOutputArchive archive(os); + + archive(this->calib_corners); + archive(this->calib_corners_rejected); + + std::cout << "Done detecting corners. Saved them here: " << path + << std::endl; + })); + + if (!show_gui) { + processing_thread->join(); + processing_thread.reset(); + } +} + +void CamCalib::initCamIntrinsics() { + if (calib_corners.empty()) { + std::cerr << "No corners detected. Press detect_corners to start corner " + "detection." + << std::endl; + return; + } + + std::cout << "Started camera intrinsics initialization" << std::endl; + + if (!calib_opt) calib_opt.reset(new PosesOptimization); + + calib_opt->resetCalib(vio_dataset->get_num_cams(), cam_types); + + for (size_t j = 0; j < vio_dataset->get_num_cams(); j++) { + for (size_t i = 0; i < vio_dataset->get_image_timestamps().size(); i++) { + const int64_t timestamp_ns = vio_dataset->get_image_timestamps()[i]; + const std::vector &img_vec = + vio_dataset->get_image_data(timestamp_ns); + + TimeCamId tcid = std::make_pair(timestamp_ns, j); + + if (calib_corners.find(tcid) != calib_corners.end()) { + CalibCornerData cid = calib_corners.at(tcid); + + bool success = calib_opt->initializeIntrinsics( + j, cid.corners, cid.corner_ids, april_grid.aprilgrid_corner_pos_3d, + img_vec[j].img->w, img_vec[j].img->h); + if (success) break; + } + } + } + + std::cout << "Done camera intrinsics initialization:" << std::endl; + for (size_t j = 0; j < vio_dataset->get_num_cams(); j++) { + std::cout << "Cam " << j << ": " + << calib_opt->calib->intrinsics[j].getParam().transpose() + << std::endl; + } + + // set resolution + { + int64_t t_ns = vio_dataset->get_image_timestamps()[1]; + const auto img_data = vio_dataset->get_image_data(t_ns); + + Eigen::vector res; + + for (size_t i = 0; i < vio_dataset->get_num_cams(); i++) { + res.emplace_back(img_data[i].img->w, img_data[i].img->h); + } + + calib_opt->setResolution(res); + } +} + +void CamCalib::initCamPoses() { + if (calib_corners.empty()) { + std::cerr << "No corners detected. Press detect_corners to start corner " + "detection." + << std::endl; + return; + } + + if (!calib_opt.get() || !calib_opt->calibInitialized()) { + std::cerr << "No initial intrinsics. Press init_intrinsics initialize " + "intrinsics" + << std::endl; + return; + } + + if (processing_thread) { + processing_thread->join(); + processing_thread.reset(); + } + + std::cout << "Started initial camera pose computation " << std::endl; + + CalibHelper::initCamPoses(calib_opt->calib, this->vio_dataset, + april_grid.aprilgrid_corner_pos_3d, + this->calib_corners, this->calib_init_poses); + + std::string path = cache_path + cache_dataset_name + "_init_poses.cereal"; + std::ofstream os(path, std::ios::binary); + cereal::BinaryOutputArchive archive(os); + + archive(this->calib_init_poses); + + std::cout << "Done initial camera pose computation. Saved them here: " << path + << std::endl; +} + +void CamCalib::initCamExtrinsics() { + if (calib_init_poses.empty()) { + std::cerr << "No initial camera poses. Press init_cam_poses initialize " + "camera poses " + << std::endl; + return; + } + + if (!calib_opt.get() || !calib_opt->calibInitialized()) { + std::cerr << "No initial intrinsics. Press init_intrinsics initialize " + "intrinsics" + << std::endl; + return; + } + + for (size_t i = 0; i < vio_dataset->get_image_timestamps().size(); i++) { + int64_t timestamp_ns = vio_dataset->get_image_timestamps()[i]; + + TimeCamId tcid0 = std::make_pair(timestamp_ns, 0); + + if (calib_init_poses.find(tcid0) == calib_init_poses.end()) continue; + + Sophus::SE3d T_a_c0 = calib_init_poses.at(tcid0).T_a_c; + + bool success = true; + + for (size_t j = 1; j < vio_dataset->get_num_cams(); j++) { + TimeCamId tcid = std::make_pair(timestamp_ns, j); + + auto cd = calib_init_poses.find(tcid); + if (cd != calib_init_poses.end() && cd->second.num_inliers > 0) { + calib_opt->calib->T_i_c[j] = T_a_c0.inverse() * cd->second.T_a_c; + } else { + success = false; + } + } + + if (success) break; + } + + std::cout << "Done camera extrinsics initialization:" << std::endl; + for (size_t j = 0; j < vio_dataset->get_num_cams(); j++) { + std::cout << "T_c0_c" << j << ":\n" + << calib_opt->calib->T_i_c[j].matrix() << std::endl; + } +} + +void CamCalib::initOptimization() { + if (!calib_opt) { + std::cerr << "Calibration is not initialized. Initialize calibration first!" + << std::endl; + return; + } + + if (calib_init_poses.empty()) { + std::cerr << "No initial camera poses. Press init_cam_poses initialize " + "camera poses " + << std::endl; + return; + } + + calib_opt->setAprilgridCorners3d(april_grid.aprilgrid_corner_pos_3d); + + std::set invalid_timestamps; + for (const auto &kv : calib_corners) { + if (kv.second.corner_ids.size() < MIN_CORNERS) + invalid_timestamps.insert(kv.first.first); + } + + for (const auto &kv : calib_corners) { + if (invalid_timestamps.find(kv.first.first) == invalid_timestamps.end()) + calib_opt->addAprilgridMeasurement(kv.first.first, kv.first.second, + kv.second.corners, + kv.second.corner_ids); + } + + for (size_t j = 0; j < vio_dataset->get_image_timestamps().size(); ++j) { + int64_t timestamp_ns = vio_dataset->get_image_timestamps()[j]; + + TimeCamId tcid = std::make_pair(timestamp_ns, 0); + const CalibInitPoseData &cp = calib_init_poses.at(tcid); + + calib_opt->addPoseMeasurement( + timestamp_ns, cp.T_a_c * calib_opt->calib->T_i_c[0].inverse()); + } + + calib_opt->init(); + computeProjections(); + + std::cout << "Initialized optimization." << std::endl; +} + +void CamCalib::loadDataset() { + basalt::DatasetIoInterfacePtr dataset_io = + basalt::DatasetIoFactory::getDatasetIo(dataset_type); + + dataset_io->read(dataset_path); + + vio_dataset = dataset_io->get_data(); + setNumCameras(vio_dataset->get_num_cams()); + + if (skip_images > 1) { + std::vector new_image_timestamps; + for (size_t i = 0; i < vio_dataset->get_image_timestamps().size(); i++) { + if (i % skip_images == 0) + new_image_timestamps.push_back(vio_dataset->get_image_timestamps()[i]); + } + + vio_dataset->get_image_timestamps() = new_image_timestamps; + } + + // load detected corners if they exist + { + std::string path = + cache_path + cache_dataset_name + "_detected_corners.cereal"; + + std::ifstream is(path, std::ios::binary); + + if (is.good()) { + cereal::BinaryInputArchive archive(is); + + calib_corners.clear(); + calib_corners_rejected.clear(); + archive(calib_corners); + archive(calib_corners_rejected); + + std::cout << "Loaded detected corners from: " << path << std::endl; + } else { + std::cout << "No pre-processed detected corners found" << std::endl; + } + } + + // load initial poses if they exist + { + std::string path = cache_path + cache_dataset_name + "_init_poses.cereal"; + + std::ifstream is(path, std::ios::binary); + + if (is.good()) { + cereal::BinaryInputArchive archive(is); + + calib_init_poses.clear(); + archive(calib_init_poses); + + std::cout << "Loaded initial poses from: " << path << std::endl; + } else { + std::cout << "No pre-processed initial poses found" << std::endl; + } + } + + // load calibration if exist + { + if (!calib_opt) calib_opt.reset(new PosesOptimization); + + calib_opt->loadCalib(cache_path); + } + + reprojected_corners.clear(); + reprojected_vignette.clear(); + + if (show_gui) { + show_frame = 0; + + show_frame.Meta().range[1] = vio_dataset->get_image_timestamps().size() - 1; + show_frame.Meta().gui_changed = true; + } +} + +void CamCalib::optimize() { optimizeWithParam(true); } + +void CamCalib::optimizeWithParam(bool print_info, + std::map *stats) { + if (calib_init_poses.empty()) { + std::cerr << "No initial camera poses. Press init_cam_poses initialize " + "camera poses " + << std::endl; + return; + } + + if (!calib_opt.get() || !calib_opt->calibInitialized()) { + std::cerr << "No initial intrinsics. Press init_intrinsics initialize " + "intrinsics" + << std::endl; + return; + } + + if (calib_opt) { + // calib_opt->compute_projections(); + double error; + double reprojection_error; + int num_points; + + auto start = std::chrono::high_resolution_clock::now(); + + calib_opt->optimize(opt_intr, huber_thresh, error, num_points, + reprojection_error); + + auto finish = std::chrono::high_resolution_clock::now(); + + if (stats) { + stats->clear(); + + stats->emplace("energy_error", error); + stats->emplace("num_points", num_points); + stats->emplace("mean_energy_error", error / num_points); + stats->emplace("reprojection_error", reprojection_error); + stats->emplace("mean_reprojection_error", + reprojection_error / num_points); + } + + if (print_info) { + std::cout << "==================================" << std::endl; + + for (size_t i = 0; i < vio_dataset->get_num_cams(); i++) { + std::cout << "intrinsics " << i << ": " + << calib_opt->calib->intrinsics[i].getParam().transpose() + << std::endl; + std::cout << "T_i_c" << i << ":\n" + << calib_opt->calib->T_i_c[i].matrix() << std::endl; + } + + std::cout << "Current error: " << error << " num_points " << num_points + << " mean_error " << error / num_points + << " reprojection_error " << reprojection_error + << " mean reprojection " << reprojection_error / num_points + << " opt_time " + << std::chrono::duration_cast( + finish - start) + .count() + << "ms." << std::endl; + + std::cout << "==================================" << std::endl; + } + + if (show_gui) { + computeProjections(); + } + } +} + +void CamCalib::saveCalib() { + if (calib_opt) { + calib_opt->saveCalib(cache_path, vio_dataset->get_mocap_to_imu_offset_ns()); + + std::cout << "Saved calibration in " << cache_path << "/calibration.json" + << std::endl; + } +} + +void CamCalib::drawImageOverlay(pangolin::View &v, size_t cam_id) { + UNUSED(v); + + size_t frame_id = show_frame; + + if (vio_dataset && frame_id < vio_dataset->get_image_timestamps().size()) { + int64_t timestamp_ns = vio_dataset->get_image_timestamps()[frame_id]; + TimeCamId tcid = std::make_pair(timestamp_ns, cam_id); + + if (show_corners) { + glLineWidth(1.0); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (calib_corners.find(tcid) != calib_corners.end()) { + const CalibCornerData &cr = calib_corners.at(tcid); + const CalibCornerData &cr_rej = calib_corners_rejected.at(tcid); + + for (size_t i = 0; i < cr.corners.size(); i++) { + // the radius is the threshold used for maximum displacement. The + // search region is slightly larger. + const float radius = static_cast(cr.radii[i]); + const Eigen::Vector2f c = cr.corners[i].cast(); + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I().Text("%d", cr.corner_ids[i]).Draw(c[0], c[1]); + } + + pangolin::GlFont::I() + .Text("Detected %d corners (%d rejected)", cr.corners.size(), + cr_rej.corners.size()) + .Draw(5, 50); + + if (show_corners_rejected) { + glColor3f(1.0, 0.5, 0.0); + + for (size_t i = 0; i < cr_rej.corners.size(); i++) { + // the radius is the threshold used for maximum displacement. The + // search region is slightly larger. + const float radius = static_cast(cr_rej.radii[i]); + const Eigen::Vector2f c = cr_rej.corners[i].cast(); + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I() + .Text("%d", cr_rej.corner_ids[i]) + .Draw(c[0], c[1]); + } + } + + } else { + glLineWidth(1.0); + + pangolin::GlFont::I().Text("Corners not processed").Draw(5, 50); + } + } + + if (show_init_reproj) { + glLineWidth(1.0); + glColor3f(1.0, 1.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (calib_init_poses.find(tcid) != calib_init_poses.end()) { + const CalibInitPoseData &cr = calib_init_poses.at(tcid); + + for (size_t i = 0; i < cr.reprojected_corners.size(); i++) { + Eigen::Vector2d c = cr.reprojected_corners[i]; + pangolin::glDrawCirclePerimeter(c[0], c[1], 3.0); + + if (show_ids) pangolin::GlFont::I().Text("%d", i).Draw(c[0], c[1]); + } + + pangolin::GlFont::I() + .Text("Initial pose with %d inliers", cr.num_inliers) + .Draw(5, 100); + + } else { + pangolin::GlFont::I().Text("Initial pose not processed").Draw(5, 100); + } + } + + if (show_opt) { + glLineWidth(1.0); + glColor3f(1.0, 0.0, 1.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (reprojected_corners.find(tcid) != reprojected_corners.end()) { + if (calib_corners.at(tcid).corner_ids.size() >= MIN_CORNERS) { + const auto &rc = reprojected_corners.at(tcid); + + for (size_t i = 0; i < rc.size(); i++) { + Eigen::Vector2d c = rc[i]; + pangolin::glDrawCirclePerimeter(c[0], c[1], 3.0); + + if (show_ids) pangolin::GlFont::I().Text("%d", i).Draw(c[0], c[1]); + } + } else { + pangolin::GlFont::I().Text("Too few corners detected.").Draw(5, 150); + } + } + } + + if (show_vign) { + glLineWidth(1.0); + glColor3f(1.0, 1.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (reprojected_vignette.find(tcid) != reprojected_vignette.end()) { + if (calib_corners.at(tcid).corner_ids.size() >= MIN_CORNERS) { + const auto &rc = reprojected_vignette.at(tcid); + + bool has_errors = false; + auto it = reprojected_vignette_error.find(tcid); + if (it != reprojected_vignette_error.end()) has_errors = true; + + for (size_t i = 0; i < rc.size(); i++) { + Eigen::Vector2d c = rc[i].head<2>(); + pangolin::glDrawCirclePerimeter(c[0], c[1], 3.0); + + if (show_ids) { + if (has_errors) { + pangolin::GlFont::I() + .Text("%d(%f)", i, it->second[i]) + .Draw(c[0], c[1]); + } else { + pangolin::GlFont::I().Text("%d", i).Draw(c[0], c[1]); + } + } + } + } else { + pangolin::GlFont::I().Text("Too few corners detected.").Draw(5, 200); + } + } + } + } +} + +bool CamCalib::hasCorners() const { return !calib_corners.empty(); } + +} // namespace basalt diff --git a/src/calibration/cam_imu_calib.cpp b/src/calibration/cam_imu_calib.cpp new file mode 100644 index 0000000..1aa36ad --- /dev/null +++ b/src/calibration/cam_imu_calib.cpp @@ -0,0 +1,1054 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include + +namespace basalt { + +CamImuCalib::CamImuCalib(const std::string &dataset_path, + const std::string &dataset_type, + const std::string &cache_path, + const std::string &cache_dataset_name, int skip_images, + const std::vector &imu_noise, bool show_gui) + : dataset_path(dataset_path), + dataset_type(dataset_type), + cache_path(ensure_trailing_slash(cache_path)), + cache_dataset_name(cache_dataset_name), + skip_images(skip_images), + show_gui(show_gui), + imu_noise(imu_noise), + show_frame("ui.show_frame", 0, 0, 1500), + show_corners("ui.show_corners", true, false, true), + show_corners_rejected("ui.show_corners_rejected", false, false, true), + show_init_reproj("ui.show_init_reproj", false, false, true), + show_opt("ui.show_opt", true, false, true), + show_ids("ui.show_ids", false, false, true), + show_accel("ui.show_accel", true, false, true), + show_gyro("ui.show_gyro", false, false, true), + show_pos("ui.show_pos", false, false, true), + show_rot_error("ui.show_rot_error", false, false, true), + show_mocap("ui.show_mocap", false, false, true), + show_mocap_rot_error("ui.show_mocap_rot_error", false, false, true), + show_mocap_rot_vel("ui.show_mocap_rot_vel", false, false, true), + show_spline("ui.show_spline", true, false, true), + show_data("ui.show_data", true, false, true), + opt_intr("ui.opt_intr", false, false, true), + opt_poses("ui.opt_poses", false, false, true), + opt_corners("ui.opt_corners", true, false, true), + opt_cam_time_offset("ui.opt_cam_time_offset", false, false, true), + opt_imu_scale("ui.opt_imu_scale", false, false, true), + opt_mocap("ui.opt_mocap", false, false, true), + huber_thresh("ui.huber_thresh", 4.0, 0.1, 10.0) { + if (show_gui) initGui(); +} + +CamImuCalib::~CamImuCalib() { + if (processing_thread) { + processing_thread->join(); + } +} + +void CamImuCalib::initGui() { + pangolin::CreateWindowAndBind("Main", 1600, 1000); + + img_view_display = + &pangolin::CreateDisplay() + .SetBounds(0.5, 1.0, pangolin::Attach::Pix(UI_WIDTH), 1.0) + .SetLayout(pangolin::LayoutEqual); + + pangolin::View &plot_display = pangolin::CreateDisplay().SetBounds( + 0.0, 0.5, pangolin::Attach::Pix(UI_WIDTH), 1.0); + + pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, + pangolin::Attach::Pix(UI_WIDTH)); + + plotter = new pangolin::Plotter(&imu_data_log, 0.0, 100.0, -10.0, 10.0, 0.01f, + 0.01f); + plot_display.AddDisplay(*plotter); + + pangolin::Var> load_dataset( + "ui.load_dataset", std::bind(&CamImuCalib::loadDataset, this)); + + pangolin::Var> detect_corners( + "ui.detect_corners", std::bind(&CamImuCalib::detectCorners, this)); + + pangolin::Var> init_cam_poses( + "ui.init_cam_poses", std::bind(&CamImuCalib::initCamPoses, this)); + + pangolin::Var> init_cam_imu( + "ui.init_cam_imu", std::bind(&CamImuCalib::initCamImuTransform, this)); + + pangolin::Var> init_opt( + "ui.init_opt", std::bind(&CamImuCalib::initOptimization, this)); + + pangolin::Var> optimize( + "ui.optimize", std::bind(&CamImuCalib::optimize, this)); + + pangolin::Var> init_mocap( + "ui.init_mocap", std::bind(&CamImuCalib::initMocap, this)); + + pangolin::Var> save_calib( + "ui.save_calib", std::bind(&CamImuCalib::saveCalib, this)); + + pangolin::Var> save_mocap_calib( + "ui.save_mocap_calib", std::bind(&CamImuCalib::saveMocapCalib, this)); + + setNumCameras(1); +} + +void CamImuCalib::setNumCameras(size_t n) { + while (img_view.size() < n && show_gui) { + std::shared_ptr iv(new pangolin::ImageView); + + size_t idx = img_view.size(); + img_view.push_back(iv); + + img_view_display->AddDisplay(*iv); + iv->extern_draw_function = std::bind(&CamImuCalib::drawImageOverlay, this, + std::placeholders::_1, idx); + } +} + +void CamImuCalib::renderingLoop() { + while (!pangolin::ShouldQuit()) { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + if (vio_dataset.get()) { + if (show_frame.GuiChanged()) { + size_t frame_id = static_cast(show_frame); + int64_t timestamp = vio_dataset->get_image_timestamps()[frame_id]; + + const std::vector &img_vec = + vio_dataset->get_image_data(timestamp); + + for (size_t cam_id = 0; cam_id < vio_dataset->get_num_cams(); cam_id++) + if (img_vec[cam_id].img.get()) { + pangolin::GlPixFormat fmt; + fmt.glformat = GL_LUMINANCE; + fmt.gltype = GL_UNSIGNED_SHORT; + fmt.scalable_internal_format = GL_LUMINANCE16; + + img_view[cam_id]->SetImage( + img_vec[cam_id].img->ptr, img_vec[cam_id].img->w, + img_vec[cam_id].img->h, img_vec[cam_id].img->pitch, fmt); + } else { + img_view[cam_id]->Clear(); + } + drawPlots(); + } + + if (show_accel.GuiChanged() || show_gyro.GuiChanged() || + show_data.GuiChanged() || show_spline.GuiChanged() || + show_pos.GuiChanged() || show_rot_error.GuiChanged() || + show_mocap.GuiChanged() || show_mocap_rot_error.GuiChanged() || + show_mocap_rot_vel.GuiChanged()) { + drawPlots(); + } + } + + pangolin::FinishFrame(); + } +} + +void CamImuCalib::computeProjections() { + reprojected_corners.clear(); + + if (!calib_opt.get() || !vio_dataset.get()) return; + + for (size_t j = 0; j < vio_dataset->get_image_timestamps().size(); ++j) { + int64_t timestamp_ns = vio_dataset->get_image_timestamps()[j]; + + int64_t timestamp_corrected_ns = + timestamp_ns + calib_opt->getCamTimeOffsetNs(); + + if (timestamp_corrected_ns < calib_opt->getMinTimeNs() || + timestamp_corrected_ns >= calib_opt->getMaxTimeNs()) + continue; + + for (size_t i = 0; i < calib_opt->calib->intrinsics.size(); i++) { + TimeCamId tcid = std::make_pair(timestamp_ns, i); + + Eigen::vector rc; + + Sophus::SE3d T_c_w_ = (calib_opt->getT_w_i(timestamp_corrected_ns) * + calib_opt->getCamT_i_c(i)) + .inverse(); + + Eigen::Matrix4d T_c_w = T_c_w_.matrix(); + + rc.resize(april_grid.aprilgrid_corner_pos_3d.size()); + + std::vector proj_success; + calib_opt->calib->intrinsics[i].project( + april_grid.aprilgrid_corner_pos_3d, T_c_w, rc, proj_success); + + reprojected_corners.emplace(tcid, rc); + } + } +} + +void CamImuCalib::detectCorners() { + if (processing_thread) { + processing_thread->join(); + processing_thread.reset(); + } + + processing_thread.reset(new std::thread([this]() { + std::cout << "Started detecting corners" << std::endl; + + CalibHelper::detectCorners(this->vio_dataset, this->calib_corners, + this->calib_corners_rejected); + + std::string path = + cache_path + cache_dataset_name + "_detected_corners.cereal"; + std::ofstream os(path, std::ios::binary); + cereal::BinaryOutputArchive archive(os); + + archive(this->calib_corners); + archive(this->calib_corners_rejected); + + std::cout << "Done detecting corners. Saved them here: " << path + << std::endl; + })); + + if (!show_gui) { + processing_thread->join(); + processing_thread.reset(); + } +} + +void CamImuCalib::initCamPoses() { + if (calib_corners.empty()) { + std::cerr << "No corners detected. Press detect_corners to start corner " + "detection." + << std::endl; + return; + } + + if (!calib_opt.get() || !calib_opt->calibInitialized()) { + std::cerr << "No camera intrinsics. Calibrate camera using " + "basalt_calibrate first!" + << std::endl; + return; + } + + if (processing_thread) { + processing_thread->join(); + processing_thread.reset(); + } + { + std::cout << "Started initial camera pose computation " << std::endl; + + CalibHelper::initCamPoses(calib_opt->calib, this->vio_dataset, + april_grid.aprilgrid_corner_pos_3d, + this->calib_corners, this->calib_init_poses); + + std::string path = cache_path + cache_dataset_name + "_init_poses.cereal"; + std::ofstream os(path, std::ios::binary); + cereal::BinaryOutputArchive archive(os); + + archive(this->calib_init_poses); + + std::cout << "Done initial camera pose computation. Saved them here: " + << path << std::endl; + }; +} + +void CamImuCalib::initCamImuTransform() { + if (!calib_opt.get() || !calib_opt->calibInitialized()) { + std::cerr << "No camera intrinsics. Calibrate camera using " + "basalt_calibrate first!" + << std::endl; + return; + } + + if (calib_init_poses.empty()) { + std::cerr << "Initialize camera poses first!" << std::endl; + return; + } + + std::vector timestamps_cam; + Eigen::vector rot_vel_cam; + Eigen::vector rot_vel_imu; + + Sophus::SO3d R_i_c0_init = calib_opt->getCamT_i_c(0).so3(); + + for (size_t i = 1; i < vio_dataset->get_image_timestamps().size(); i++) { + int64_t timestamp0_ns = vio_dataset->get_image_timestamps()[i - 1]; + int64_t timestamp1_ns = vio_dataset->get_image_timestamps()[i]; + + TimeCamId tcid0 = std::make_pair(timestamp0_ns, 0); + TimeCamId tcid1 = std::make_pair(timestamp1_ns, 0); + + if (calib_init_poses.find(tcid0) == calib_init_poses.end()) continue; + if (calib_init_poses.find(tcid1) == calib_init_poses.end()) continue; + + Sophus::SE3d T_a_c0 = calib_init_poses.at(tcid0).T_a_c; + Sophus::SE3d T_a_c1 = calib_init_poses.at(tcid1).T_a_c; + + double dt = (timestamp1_ns - timestamp0_ns) * 1e-9; + + Eigen::Vector3d rot_vel_c0 = + R_i_c0_init * (T_a_c0.so3().inverse() * T_a_c1.so3()).log() / dt; + + timestamps_cam.push_back(timestamp0_ns); + rot_vel_cam.push_back(rot_vel_c0); + } + + for (size_t j = 0; j < timestamps_cam.size(); j++) { + int idx = -1; + int64_t min_dist = std::numeric_limits::max(); + + for (size_t i = 1; i < vio_dataset->get_gyro_data().size(); i++) { + int64_t dist = + vio_dataset->get_gyro_data()[i].timestamp_ns - timestamps_cam[j]; + if (std::abs(dist) < min_dist) { + min_dist = std::abs(dist); + idx = i; + } + } + + rot_vel_imu.push_back(vio_dataset->get_gyro_data()[idx].data); + } + + BASALT_ASSERT_STREAM(rot_vel_cam.size() == rot_vel_imu.size(), + "rot_vel_cam.size() " << rot_vel_cam.size() + << " rot_vel_imu.size() " + << rot_vel_imu.size()); + + // R_i_c * rot_vel_cam = rot_vel_imu + // R_i_c * rot_vel_cam * rot_vel_cam.T = rot_vel_imu * rot_vel_cam.T + // R_i_c = rot_vel_imu * rot_vel_cam.T * (rot_vel_cam * rot_vel_cam.T)^-1; + + Eigen::Matrix rot_vel_cam_m(3, rot_vel_cam.size()), + rot_vel_imu_m(3, rot_vel_imu.size()); + + for (size_t i = 0; i < rot_vel_cam.size(); i++) { + rot_vel_cam_m.col(i) = rot_vel_cam[i]; + rot_vel_imu_m.col(i) = rot_vel_imu[i]; + } + + Eigen::Matrix3d R_i_c0 = + rot_vel_imu_m * rot_vel_cam_m.transpose() * + (rot_vel_cam_m * rot_vel_cam_m.transpose()).inverse(); + + // std::cout << "raw R_i_c0\n" << R_i_c0 << std::endl; + + Eigen::AngleAxisd aa(R_i_c0); // RotationMatrix to AxisAngle + R_i_c0 = aa.toRotationMatrix(); + + // std::cout << "R_i_c0\n" << R_i_c0 << std::endl; + + Sophus::SE3d T_i_c0(R_i_c0, Eigen::Vector3d::Zero()); + + std::cout << "T_i_c0\n" << T_i_c0.matrix() << std::endl; + + for (size_t i = 0; i < vio_dataset->get_num_cams(); i++) { + calib_opt->getCamT_i_c(i) = T_i_c0 * calib_opt->getCamT_i_c(i); + } + + std::cout << "Done Camera-IMU extrinsics initialization:" << std::endl; + for (size_t j = 0; j < vio_dataset->get_num_cams(); j++) { + std::cout << "T_i_c" << j << ":\n" + << calib_opt->getCamT_i_c(j).matrix() << std::endl; + } +} + +void CamImuCalib::initOptimization() { + if (!calib_opt.get() || !calib_opt->calibInitialized()) { + std::cerr << "No camera intrinsics. Calibrate camera using " + "basalt_calibrate first!" + << std::endl; + return; + } + + calib_opt->setAprilgridCorners3d(april_grid.aprilgrid_corner_pos_3d); + + for (size_t i = 0; i < vio_dataset->get_accel_data().size(); i++) { + const basalt::AccelData &ad = vio_dataset->get_accel_data()[i]; + const basalt::GyroData &gd = vio_dataset->get_gyro_data()[i]; + + calib_opt->addAccelMeasurement(ad.timestamp_ns, ad.data); + calib_opt->addGyroMeasurement(gd.timestamp_ns, gd.data); + } + + std::set invalid_timestamps; + for (const auto &kv : calib_corners) { + if (kv.second.corner_ids.size() < MIN_CORNERS) + invalid_timestamps.insert(kv.first.first); + } + + for (const auto &kv : calib_corners) { + if (invalid_timestamps.find(kv.first.first) == invalid_timestamps.end()) + calib_opt->addAprilgridMeasurement(kv.first.first, kv.first.second, + kv.second.corners, + kv.second.corner_ids); + } + + for (size_t i = 0; i < vio_dataset->get_gt_timestamps().size(); i++) { + calib_opt->addMocapMeasurement(vio_dataset->get_gt_timestamps()[i], + vio_dataset->get_gt_pose_data()[i]); + } + + bool g_initialized = false; + Eigen::Vector3d g_a_init; + + for (size_t j = 0; j < vio_dataset->get_image_timestamps().size(); ++j) { + int64_t timestamp_ns = vio_dataset->get_image_timestamps()[j]; + + TimeCamId tcid = std::make_pair(timestamp_ns, 0); + const CalibInitPoseData &cp = calib_init_poses.at(tcid); + + calib_opt->addPoseMeasurement( + timestamp_ns, cp.T_a_c * calib_opt->getCamT_i_c(0).inverse()); + + if (!g_initialized) { + for (size_t i = 0; + i < vio_dataset->get_accel_data().size() && !g_initialized; i++) { + const basalt::AccelData &ad = vio_dataset->get_accel_data()[i]; + if (std::abs(ad.timestamp_ns - timestamp_ns) < 3000000) { + g_a_init = cp.T_a_c.so3() * ad.data; + g_initialized = true; + std::cout << "g_a initialized with " << g_a_init.transpose() + << std::endl; + } + } + } + } + + const int num_samples = 100; + double dt = 0.0; + for (int i = 0; i < num_samples; i++) { + dt += 1e-9 * (vio_dataset->get_gyro_data()[i + 1].timestamp_ns - + vio_dataset->get_gyro_data()[i].timestamp_ns); + } + dt /= num_samples; + + std::cout << "IMU dt: " << dt << " freq: " << 1.0 / dt << std::endl; + + calib_opt->calib->imu_update_rate = 1.0 / dt; + + calib_opt->setG(g_a_init); + calib_opt->init(); + computeProjections(); + recomputeDataLog(); + + std::cout << "Initialized optimization." << std::endl; +} + +void CamImuCalib::initMocap() { + if (!calib_opt.get() || !calib_opt->calibInitialized()) { + std::cerr << "Initalize optimization first!" << std::endl; + return; + } + + Sophus::SE3d T_w_moc; + + // TODO: check for failure cases.. + for (size_t i = vio_dataset->get_gt_timestamps().size() / 2; + i < vio_dataset->get_gt_timestamps().size(); i++) { + int64_t timestamp_ns = vio_dataset->get_gt_timestamps()[i]; + T_w_moc = calib_opt->getT_w_i(timestamp_ns) * + vio_dataset->get_gt_pose_data()[i].inverse(); + + std::cout << "Initialized T_w_moc:\n" << T_w_moc.matrix() << std::endl; + break; + } + + calib_opt->setT_w_moc(T_w_moc); + recomputeDataLog(); +} + +void CamImuCalib::loadDataset() { + basalt::DatasetIoInterfacePtr dataset_io = + basalt::DatasetIoFactory::getDatasetIo(dataset_type); + + dataset_io->read(dataset_path); + + vio_dataset = dataset_io->get_data(); + setNumCameras(vio_dataset->get_num_cams()); + + if (skip_images > 1) { + std::vector new_image_timestamps; + for (size_t i = 0; i < vio_dataset->get_image_timestamps().size(); i++) { + if (i % skip_images == 0) + new_image_timestamps.push_back(vio_dataset->get_image_timestamps()[i]); + } + + vio_dataset->get_image_timestamps() = new_image_timestamps; + } + + // load detected corners if they exist + { + std::string path = + cache_path + cache_dataset_name + "_detected_corners.cereal"; + + std::ifstream is(path, std::ios::binary); + + if (is.good()) { + cereal::BinaryInputArchive archive(is); + + calib_corners.clear(); + calib_corners_rejected.clear(); + archive(calib_corners); + archive(calib_corners_rejected); + + std::cout << "Loaded detected corners from: " << path << std::endl; + } else { + std::cout << "No pre-processed detected corners found" << std::endl; + } + } + + // load initial poses if they exist + { + std::string path = cache_path + cache_dataset_name + "_init_poses.cereal"; + + std::ifstream is(path, std::ios::binary); + + if (is.good()) { + cereal::BinaryInputArchive archive(is); + + calib_init_poses.clear(); + archive(calib_init_poses); + + std::cout << "Loaded initial poses from: " << path << std::endl; + } else { + std::cout << "No pre-processed initial poses found" << std::endl; + } + } + + // load calibration if exist + { + if (!calib_opt) calib_opt.reset(new SplineOptimization<5, double>); + + calib_opt->loadCalib(cache_path); + + calib_opt->calib->accel_noise_std = imu_noise[0]; + calib_opt->calib->gyro_noise_std = imu_noise[1]; + calib_opt->calib->accel_bias_std = imu_noise[2]; + calib_opt->calib->gyro_bias_std = imu_noise[3]; + } + calib_opt->resetMocapCalib(); + + reprojected_corners.clear(); + + if (show_gui) { + show_frame = 0; + + show_frame.Meta().range[1] = vio_dataset->get_image_timestamps().size() - 1; + show_frame.Meta().gui_changed = true; + + plotter->ClearSeries(); + recomputeDataLog(); + drawPlots(); + } +} + +void CamImuCalib::optimize() { optimizeWithParam(true); } + +void CamImuCalib::optimizeWithParam(bool print_info, + std::map *stats) { + if (!calib_opt.get() || !calib_opt->calibInitialized()) { + std::cerr << "Initalize optimization first!" << std::endl; + return; + } + + if (calib_opt) { + // calib_opt->compute_projections(); + double error; + double reprojection_error; + int num_points; + + auto start = std::chrono::high_resolution_clock::now(); + + calib_opt->optimize(opt_intr, opt_poses, opt_corners, opt_cam_time_offset, + opt_imu_scale, opt_mocap, huber_thresh, error, + num_points, reprojection_error); + + auto finish = std::chrono::high_resolution_clock::now(); + + if (stats) { + stats->clear(); + + stats->emplace("energy_error", error); + stats->emplace("num_points", num_points); + stats->emplace("mean_energy_error", error / num_points); + stats->emplace("reprojection_error", reprojection_error); + stats->emplace("mean_reprojection_error", + reprojection_error / num_points); + } + + if (print_info) { + std::cout << "==================================" << std::endl; + + for (size_t i = 0; i < vio_dataset->get_num_cams(); i++) { + std::cout << "intrinsics " << i << ": " + << calib_opt->getIntrinsics(i).transpose() << std::endl; + std::cout << "T_i_c" << i << ":\n" + << calib_opt->getCamT_i_c(i).matrix() << std::endl; + } + + std::cout << "T_w_moc:\n" + << calib_opt->getT_w_moc().matrix() << std::endl; + + std::cout << "T_mark_i:\n" + << calib_opt->getT_mark_i().matrix() << std::endl; + + std::cout << "cam_time_offset_ns: " << calib_opt->getCamTimeOffsetNs() + << std::endl; + + std::cout << "mocap_time_offset_ns: " << calib_opt->getMocapTimeOffsetNs() + << std::endl; + { + Eigen::Vector3d accel_bias; + Eigen::Matrix3d accel_scale; + calib_opt->getAccelBias().getBiasAndScale(accel_bias, accel_scale); + + std::cout << "accel_bias: " << accel_bias.transpose() + << "\naccel_scale:\n" + << Eigen::Matrix3d::Identity() + accel_scale << std::endl; + + Eigen::Vector3d gyro_bias; + Eigen::Matrix3d gyro_scale; + calib_opt->getGyroBias().getBiasAndScale(gyro_bias, gyro_scale); + + std::cout << "gyro_bias: " << gyro_bias.transpose() << "\ngyro_scale:\n" + << Eigen::Matrix3d::Identity() + gyro_scale << std::endl; + } + + std::cout << " g " << calib_opt->getG().transpose() + << " norm: " << calib_opt->getG().norm() << " g_mocap: " + << (calib_opt->getT_w_moc().inverse().so3() * calib_opt->getG()) + .transpose() + << std::endl; + + std::cout << "Current error: " << error << " num_points " << num_points + << " mean_error " << error / num_points + << " reprojection_error " << reprojection_error + << " mean reprojection " << reprojection_error / num_points + << " opt_time " + << std::chrono::duration_cast( + finish - start) + .count() + << "ms." << std::endl; + + std::cout << "==================================" << std::endl; + } + + // calib_opt->compute_error(error, num_points); + // std::cerr << "after opt error: " << error << " num_points " << + // num_points << std::endl; + + if (show_gui) { + computeProjections(); + recomputeDataLog(); + drawPlots(); + } + } +} + +void CamImuCalib::saveCalib() { + if (calib_opt) { + calib_opt->saveCalib(cache_path); + + std::cout << "Saved calibration in " << cache_path << "/calibration.json" + << std::endl; + } +} + +void CamImuCalib::saveMocapCalib() { + if (calib_opt) { + calib_opt->saveMocapCalib(cache_path, + vio_dataset->get_mocap_to_imu_offset_ns()); + + std::cout << "Saved Mocap calibration in " << cache_path + << "/mocap_calibration.json" << std::endl; + } +} + +void CamImuCalib::drawImageOverlay(pangolin::View &v, size_t cam_id) { + UNUSED(v); + + size_t frame_id = show_frame; + + if (vio_dataset && frame_id < vio_dataset->get_image_timestamps().size()) { + int64_t timestamp_ns = vio_dataset->get_image_timestamps()[frame_id]; + TimeCamId tcid = std::make_pair(timestamp_ns, cam_id); + + if (show_corners) { + glLineWidth(1.0); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (calib_corners.find(tcid) != calib_corners.end()) { + const CalibCornerData &cr = calib_corners.at(tcid); + const CalibCornerData &cr_rej = calib_corners_rejected.at(tcid); + + for (size_t i = 0; i < cr.corners.size(); i++) { + // the radius is the threshold used for maximum displacement. The + // search region is slightly larger. + const float radius = static_cast(cr.radii[i]); + const Eigen::Vector2f c = cr.corners[i].cast(); + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I().Text("%d", cr.corner_ids[i]).Draw(c[0], c[1]); + } + + pangolin::GlFont::I() + .Text("Detected %d corners (%d rejected)", cr.corners.size(), + cr_rej.corners.size()) + .Draw(5, 50); + + if (show_corners_rejected) { + glColor3f(1.0, 0.5, 0.0); + + for (size_t i = 0; i < cr_rej.corners.size(); i++) { + // the radius is the threshold used for maximum displacement. The + // search region is slightly larger. + const float radius = static_cast(cr_rej.radii[i]); + const Eigen::Vector2f c = cr_rej.corners[i].cast(); + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I() + .Text("%d", cr_rej.corner_ids[i]) + .Draw(c[0], c[1]); + } + } + + } else { + glLineWidth(1.0); + + pangolin::GlFont::I().Text("Corners not processed").Draw(5, 50); + } + } + + if (show_init_reproj) { + glLineWidth(1.0); + glColor3f(1.0, 1.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (calib_init_poses.find(tcid) != calib_init_poses.end()) { + const CalibInitPoseData &cr = calib_init_poses.at(tcid); + + for (size_t i = 0; i < cr.reprojected_corners.size(); i++) { + Eigen::Vector2d c = cr.reprojected_corners[i]; + pangolin::glDrawCirclePerimeter(c[0], c[1], 3.0); + + if (show_ids) pangolin::GlFont::I().Text("%d", i).Draw(c[0], c[1]); + } + + pangolin::GlFont::I() + .Text("Initial pose with %d inliers", cr.num_inliers) + .Draw(5, 100); + + } else { + pangolin::GlFont::I().Text("Initial pose not processed").Draw(5, 100); + } + } + + if (show_opt) { + glLineWidth(1.0); + glColor3f(1.0, 0.0, 1.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (reprojected_corners.find(tcid) != reprojected_corners.end()) { + if (calib_corners.at(tcid).corner_ids.size() >= MIN_CORNERS) { + const auto &rc = reprojected_corners.at(tcid); + + for (size_t i = 0; i < rc.size(); i++) { + Eigen::Vector2d c = rc[i]; + pangolin::glDrawCirclePerimeter(c[0], c[1], 3.0); + + if (show_ids) pangolin::GlFont::I().Text("%d", i).Draw(c[0], c[1]); + } + } else { + pangolin::GlFont::I().Text("Too few corners detected.").Draw(5, 150); + } + } + } + } +} + +void CamImuCalib::recomputeDataLog() { + imu_data_log.Clear(); + pose_data_log.Clear(); + mocap_data_log.Clear(); + + if (!vio_dataset || vio_dataset->get_accel_data().empty()) return; + + double min_time = vio_dataset->get_accel_data()[0].timestamp_ns * 1e-9; + + for (size_t i = 0; i < vio_dataset->get_accel_data().size(); i++) { + const basalt::AccelData &ad = vio_dataset->get_accel_data()[i]; + const basalt::GyroData &gd = vio_dataset->get_gyro_data()[i]; + + Eigen::Vector3d a_sp(0, 0, 0), g_sp(0, 0, 0); + + if (calib_opt && calib_opt->calibInitialized() && + calib_opt->initialized()) { + Sophus::SE3d pose_sp = calib_opt->getT_w_i(ad.timestamp_ns); + Eigen::Vector3d a_sp_w = calib_opt->getTransAccelWorld(ad.timestamp_ns); + + a_sp = calib_opt->getAccelBias().invertCalibration( + pose_sp.so3().inverse() * (a_sp_w + calib_opt->getG())); + + g_sp = calib_opt->getGyroBias().invertCalibration( + calib_opt->getRotVelBody(ad.timestamp_ns)); + } + + std::vector vals; + double t = ad.timestamp_ns * 1e-9 - min_time; + vals.push_back(t); + + for (int k = 0; k < 3; k++) vals.push_back(ad.data[k]); + for (int k = 0; k < 3; k++) vals.push_back(a_sp[k]); + for (int k = 0; k < 3; k++) vals.push_back(gd.data[k]); + for (int k = 0; k < 3; k++) vals.push_back(g_sp[k]); + + imu_data_log.Log(vals); + } + + for (size_t i = 0; i < vio_dataset->get_image_timestamps().size(); i++) { + int64_t timestamp_ns = vio_dataset->get_image_timestamps()[i]; + + TimeCamId tcid = std::make_pair(timestamp_ns, 0); + const auto &it = calib_init_poses.find(tcid); + + double t = timestamp_ns * 1e-9 - min_time; + + Sophus::SE3d pose_sp, pose_meas; + if (calib_opt && calib_opt->initialized()) + pose_sp = calib_opt->getT_w_i(timestamp_ns); + + if (it != calib_init_poses.end() && calib_opt && + calib_opt->calibInitialized()) + pose_meas = it->second.T_a_c * calib_opt->getCamT_i_c(0).inverse(); + + Eigen::Vector3d p_sp = pose_sp.translation(); + Eigen::Vector3d p_meas = pose_meas.translation(); + + double angle = + pose_sp.unit_quaternion().angularDistance(pose_meas.unit_quaternion()) * + 180 / M_PI; + + pose_data_log.Log(t, p_meas[0], p_meas[1], p_meas[2], p_sp[0], p_sp[1], + p_sp[2], angle); + } + + for (size_t i = 0; i < vio_dataset->get_gt_timestamps().size(); i++) { + int64_t timestamp_ns = vio_dataset->get_gt_timestamps()[i]; + + if (calib_opt && calib_opt->calibInitialized()) + timestamp_ns += calib_opt->getMocapTimeOffsetNs(); + + double t = timestamp_ns * 1e-9 - min_time; + + Sophus::SE3d pose_sp, pose_mocap; + if (calib_opt && calib_opt->calibInitialized()) { + if (timestamp_ns < calib_opt->getMinTimeNs() || + timestamp_ns > calib_opt->getMaxTimeNs()) + continue; + + pose_sp = calib_opt->getT_w_i(timestamp_ns); + pose_mocap = calib_opt->getT_w_moc() * + vio_dataset->get_gt_pose_data()[i] * + calib_opt->getT_mark_i(); + } + + Eigen::Vector3d p_sp = pose_sp.translation(); + Eigen::Vector3d p_mocap = pose_mocap.translation(); + + double angle = pose_sp.unit_quaternion().angularDistance( + pose_mocap.unit_quaternion()) * + 180 / M_PI; + + Eigen::Vector3d rot_vel(0, 0, 0); + if (i > 0) { + double dt = (vio_dataset->get_gt_timestamps()[i] - + vio_dataset->get_gt_timestamps()[i - 1]) * + 1e-9; + + rot_vel = (vio_dataset->get_gt_pose_data()[i - 1].so3().inverse() * + vio_dataset->get_gt_pose_data()[i].so3()) + .log() / + dt; + } + + std::vector valsd = {t, p_mocap[0], p_mocap[1], p_mocap[2], + p_sp[0], p_sp[1], p_sp[2], angle, + rot_vel[0], rot_vel[1], rot_vel[2]}; + + std::vector vals(valsd.begin(), valsd.end()); + + mocap_data_log.Log(vals); + } +} + +void CamImuCalib::drawPlots() { + plotter->ClearSeries(); + plotter->ClearMarkers(); + + if (show_accel) { + if (show_data) { + plotter->AddSeries("$0", "$1", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "a x"); + plotter->AddSeries("$0", "$2", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "a y"); + plotter->AddSeries("$0", "$3", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "a z"); + } + + if (show_spline) { + plotter->AddSeries("$0", "$4", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "a x Spline"); + plotter->AddSeries("$0", "$5", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "a y Spline"); + plotter->AddSeries("$0", "$6", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "a z Spline"); + } + } + + if (show_gyro) { + if (show_data) { + plotter->AddSeries("$0", "$7", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "g x"); + plotter->AddSeries("$0", "$8", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "g y"); + plotter->AddSeries("$0", "$9", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "g z"); + } + + if (show_spline) { + plotter->AddSeries("$0", "$10", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "g x Spline"); + plotter->AddSeries("$0", "$11", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "g y Spline"); + plotter->AddSeries("$0", "$12", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "g z Spline"); + } + } + + if (show_pos) { + if (show_data) { + plotter->AddSeries("$0", "$1", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "p x", &pose_data_log); + plotter->AddSeries("$0", "$2", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "p y", &pose_data_log); + plotter->AddSeries("$0", "$3", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "p z", &pose_data_log); + } + + if (show_spline) { + plotter->AddSeries("$0", "$4", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "p x Spline", &pose_data_log); + plotter->AddSeries("$0", "$5", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "p y Spline", + &pose_data_log); + plotter->AddSeries("$0", "$6", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "p z Spline", + &pose_data_log); + } + } + + if (show_rot_error) { + plotter->AddSeries("$0", "$7", pangolin::DrawingModeLine, + pangolin::Colour::White(), "rot error", &pose_data_log); + } + + if (show_mocap) { + if (show_data) { + plotter->AddSeries("$0", "$1", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "p x", &mocap_data_log); + plotter->AddSeries("$0", "$2", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "p y", &mocap_data_log); + plotter->AddSeries("$0", "$3", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "p z", &mocap_data_log); + } + + if (show_spline) { + plotter->AddSeries("$0", "$4", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "p x Spline", + &mocap_data_log); + plotter->AddSeries("$0", "$5", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "p y Spline", + &mocap_data_log); + plotter->AddSeries("$0", "$6", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "p z Spline", + &mocap_data_log); + } + } + + if (show_mocap_rot_error) { + plotter->AddSeries("$0", "$7", pangolin::DrawingModeLine, + pangolin::Colour::White(), "rot error", &mocap_data_log); + } + + if (show_mocap_rot_vel) { + plotter->AddSeries("$0", "$8", pangolin::DrawingModeLine, + pangolin::Colour(1, 1, 0), "rot vel x", &mocap_data_log); + plotter->AddSeries("$0", "$9", pangolin::DrawingModeLine, + pangolin::Colour(1, 0, 1), "rot vel y", &mocap_data_log); + plotter->AddSeries("$0", "$10", pangolin::DrawingModeLine, + pangolin::Colour(0, 1, 1), "rot vel z", &mocap_data_log); + } + + size_t frame_id = show_frame; + double min_time = vio_dataset->get_accel_data().empty() + ? vio_dataset->get_image_timestamps()[0] * 1e-9 + : vio_dataset->get_accel_data()[0].timestamp_ns * 1e-9; + + int64_t timestamp = vio_dataset->get_image_timestamps()[frame_id]; + if (calib_opt && calib_opt->calibInitialized()) + timestamp += calib_opt->getCamTimeOffsetNs(); + + double t = timestamp * 1e-9 - min_time; + plotter->AddMarker(pangolin::Marker::Vertical, t, pangolin::Marker::Equal, + pangolin::Colour::White()); +} + +bool CamImuCalib::hasCorners() const { return !calib_corners.empty(); } + +} // namespace basalt diff --git a/src/calibration/vignette.cpp b/src/calibration/vignette.cpp new file mode 100644 index 0000000..0a8619a --- /dev/null +++ b/src/calibration/vignette.cpp @@ -0,0 +1,306 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +namespace basalt { + +VignetteEstimator::VignetteEstimator( + const VioDatasetPtr &vio_dataset, + const Eigen::vector &optical_centers, + const std::map> + &reprojected_vignette, + const AprilGrid &april_grid) + : vio_dataset(vio_dataset), + optical_centers(optical_centers), + reprojected_vignette(reprojected_vignette), + april_grid(april_grid), + vign_param(vio_dataset->get_num_cams(), + RdSpline<1, SPLINE_N>(knot_spacing)) { + vign_size = 0; + + for (size_t i = 0; i < vio_dataset->get_num_cams(); i++) { + Eigen::Vector2d oc = optical_centers[i]; + + size_t new_size = oc.norm() * 1.1; + vign_size = std::max(vign_size, new_size); + } + + // std::cerr << vign_size << std::endl; + + for (size_t i = 0; i < vio_dataset->get_num_cams(); i++) { + while (vign_param[i].maxTimeNs() < + int64_t(vign_size) * int64_t(1e9 * 0.7)) { + vign_param[i].knots_push_back(Eigen::Matrix(1)); + } + + while (vign_param[i].maxTimeNs() < int64_t(vign_size) * int64_t(1e9)) { + vign_param[i].knots_push_back(Eigen::Matrix(0.01)); + } + } + + irradiance.resize(april_grid.aprilgrid_vignette_pos_3d.size()); + std::fill(irradiance.begin(), irradiance.end(), 1.0); +} + +void VignetteEstimator::compute_error( + std::map> *reprojected_vignette_error) { + double error = 0; + double mean_residual = 0; + double max_residual = 0; + int num_residuals = 0; + + TimeCamId tcid_max; + // int point_id = 0; + + if (reprojected_vignette_error) reprojected_vignette_error->clear(); + + for (const auto &kv : reprojected_vignette) { + const TimeCamId &tcid = kv.first; + const auto &points_2d_val = kv.second; + + Eigen::Vector2d oc = optical_centers[tcid.second]; + + BASALT_ASSERT(points_2d_val.size() == + april_grid.aprilgrid_vignette_pos_3d.size()); + + std::vector ve(april_grid.aprilgrid_vignette_pos_3d.size()); + + for (size_t i = 0; i < points_2d_val.size(); i++) { + if (points_2d_val[i][2] >= 0) { + double val = points_2d_val[i][2]; + int64_t loc = + (points_2d_val[i].head<2>() - oc).norm() * 1e9; // in pixels * 1e9 + double e = + irradiance[i] * vign_param[tcid.second].evaluate(loc)[0] - val; + ve[i] = e; + error += e * e; + mean_residual += std::abs(e); + max_residual = std::max(max_residual, std::abs(e)); + if (max_residual == std::abs(e)) { + tcid_max = tcid; + // point_id = i; + } + num_residuals++; + } + } + + if (reprojected_vignette_error) + reprojected_vignette_error->emplace(tcid, ve); + } + + // std::cerr << "error " << error << std::endl; + // std::cerr << "mean_residual " << mean_residual / num_residuals << + // std::endl; + // std::cerr << "max_residual " << max_residual << std::endl; + + // int frame_id = 0; + // for (size_t i = 0; i < vio_dataset->get_image_timestamps().size(); i++) { + // if (tcid_max.first == vio_dataset->get_image_timestamps()[i]) { + // frame_id = i; + // } + // } + + // std::cerr << "tcid_max " << frame_id << " " << tcid_max.second << " point + // id " + // << point_id << std::endl + // << std::endl; +} + +void VignetteEstimator::opt_irradience() { + std::vector new_irradiance(irradiance.size(), 0); + std::vector new_irradiance_count(irradiance.size(), 0); + + for (const auto &kv : reprojected_vignette) { + const TimeCamId &tcid = kv.first; + const auto &points_2d_val = kv.second; + + Eigen::Vector2d oc = optical_centers[tcid.second]; + + BASALT_ASSERT(points_2d_val.size() == + april_grid.aprilgrid_vignette_pos_3d.size()); + + for (size_t i = 0; i < points_2d_val.size(); i++) { + if (points_2d_val[i][2] >= 0) { + double val = points_2d_val[i][2]; + int64_t loc = + (points_2d_val[i].head<2>() - oc).norm() * 1e9; // in pixels * 1e9 + + new_irradiance[i] += val / vign_param[tcid.second].evaluate(loc)[0]; + new_irradiance_count[i] += 1; + } + } + } + + for (size_t i = 0; i < irradiance.size(); i++) { + if (new_irradiance_count[i] > 0) + irradiance[i] = new_irradiance[i] / new_irradiance_count[i]; + } +} + +void VignetteEstimator::opt_vign() { + size_t num_knots = vign_param[0].getKnots().size(); + + std::vector> new_vign_param( + vio_dataset->get_num_cams(), std::vector(num_knots, 0)); + std::vector> new_vign_param_count( + vio_dataset->get_num_cams(), std::vector(num_knots, 0)); + + for (const auto &kv : reprojected_vignette) { + const TimeCamId &tcid = kv.first; + const auto &points_2d_val = kv.second; + + // Sophus::SE3d T_w_cam = + // calib_opt->getT_w_i(tcid.first) * + // calib_opt->getCamT_i_c(tcid.second); + // Eigen::Vector3d opt_axis_w = T_w_cam.so3() * + // Eigen::Vector3d::UnitZ(); + // if (-opt_axis_w[2] < angle_threshold) continue; + + Eigen::Vector2d oc = optical_centers[tcid.second]; + + BASALT_ASSERT(points_2d_val.size() == + april_grid.aprilgrid_vignette_pos_3d.size()); + + for (size_t i = 0; i < points_2d_val.size(); i++) { + if (points_2d_val[i][2] >= 0) { + double val = points_2d_val[i][2]; + int64_t loc = (points_2d_val[i].head<2>() - oc).norm() * 1e9; + + RdSpline<1, SPLINE_N>::JacobianStruct J; + vign_param[tcid.second].evaluate(loc, &J); + + for (size_t k = 0; k < J.d_val_d_knot.size(); k++) { + new_vign_param[tcid.second][J.start_idx + k] += + J.d_val_d_knot[k] * val / irradiance[i]; + new_vign_param_count[tcid.second][J.start_idx + k] += + J.d_val_d_knot[k]; + } + } + } + } + + double max_val = 0; + for (size_t j = 0; j < vio_dataset->get_num_cams(); j++) + for (size_t i = 0; i < num_knots; i++) { + if (new_vign_param_count[j][i] > 0) { + // std::cerr << "update " << i << " " << j << std::endl; + double val = new_vign_param[j][i] / new_vign_param_count[j][i]; + max_val = std::max(max_val, val); + vign_param[j].getKnot(i)[0] = val; + } + } + + // normalize vignette + double max_val_inv = 1.0 / max_val; + for (size_t j = 0; j < vio_dataset->get_num_cams(); j++) + for (size_t i = 0; i < num_knots; i++) { + if (new_vign_param_count[j][i] > 0) { + vign_param[j].getKnot(i)[0] *= max_val_inv; + } + } +} + +void VignetteEstimator::optimize() { + compute_error(); + for (int i = 0; i < 10; i++) { + opt_irradience(); + compute_error(); + opt_vign(); + compute_error(); + } +} + +void VignetteEstimator::compute_data_log(pangolin::DataLog &vign_data_log) { + std::vector> num_proj_points( + 2, std::vector(vign_size, 0)); + + for (const auto &kv : reprojected_vignette) { + const TimeCamId &tcid = kv.first; + const auto &points_2d = kv.second; + + Eigen::Vector2d oc = optical_centers[tcid.second]; + + BASALT_ASSERT(points_2d.size() == + april_grid.aprilgrid_vignette_pos_3d.size()); + + for (size_t i = 0; i < points_2d.size(); i++) { + if (points_2d[i][2] >= 0) { + size_t loc = (points_2d[i].head<2>() - oc).norm(); + num_proj_points[tcid.second][loc] += 1.; + } + } + } + + vign_data_log.Clear(); + for (size_t i = 0; i < vign_size; i++) { + std::vector log_data; + for (size_t j = 0; j < vio_dataset->get_num_cams(); j++) { + int64_t loc = i * 1e9; + log_data.push_back(vign_param[j].evaluate(loc)[0]); + log_data.push_back(num_proj_points[j][i]); + } + vign_data_log.Log(log_data); + } +} + +void VignetteEstimator::save_vign_png(const std::string &path) { + for (size_t k = 0; k < vio_dataset->get_num_cams(); k++) { + auto img = + vio_dataset->get_image_data(vio_dataset->get_image_timestamps()[0])[0]; + pangolin::ManagedImage vign_img(img.img->w, img.img->h); + vign_img.Fill(0); + + Eigen::Vector2d oc = optical_centers[k]; + + for (size_t x = 0; x < vign_img.w; x++) { + for (size_t y = 0; y < vign_img.h; y++) { + int64_t loc = (Eigen::Vector2d(x, y) - oc).norm() * 1e9; + double val = vign_param[k].evaluate(loc)[0]; + if (val < 0.5) continue; + uint16_t val_int = + val >= 1.0 ? std::numeric_limits::max() + : uint16_t(val * std::numeric_limits::max()); + vign_img(x, y) = val_int; + } + } + + pangolin::SaveImage(vign_img.UnsafeReinterpret(), + pangolin::PixelFormatFromString("GRAY16LE"), + path + "/vingette_" + std::to_string(k) + ".png"); + } +} +} // namespace basalt diff --git a/src/io/dataset_io.cpp b/src/io/dataset_io.cpp new file mode 100644 index 0000000..ac1a044 --- /dev/null +++ b/src/io/dataset_io.cpp @@ -0,0 +1,57 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +namespace basalt { + +DatasetIoInterfacePtr DatasetIoFactory::getDatasetIo( + const std::string &dataset_type, bool with_images) { + if (dataset_type == "euroc") { + // return DatasetIoInterfacePtr(); + return DatasetIoInterfacePtr(new EurocIO); + } else if (dataset_type == "bag") { + return DatasetIoInterfacePtr(new RosbagIO(with_images)); + } else { + std::cerr << "Dataset type " << dataset_type << " is not supported" + << std::endl; + std::abort(); + } +} + +} // namespace basalt diff --git a/src/io/marg_data_io.cpp b/src/io/marg_data_io.cpp new file mode 100644 index 0000000..91a410c --- /dev/null +++ b/src/io/marg_data_io.cpp @@ -0,0 +1,228 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +namespace fs = std::experimental::filesystem; + +namespace basalt { + +MargDataSaver::MargDataSaver(const std::string& path) { + fs::remove_all(path); + fs::create_directory(path); + + save_image_queue.set_capacity(300); + + std::string img_path = path + "/images/"; + fs::create_directory(img_path); + + in_marg_queue.set_capacity(1000); + + auto save_func = [&, path]() { + basalt::MargData::Ptr data; + + std::unordered_set processed_opt_flow; + + while (true) { + in_marg_queue.pop(data); + + if (data.get()) { + int64_t kf_id = *data->kfs_to_marg.begin(); + + std::string p = path + "/" + std::to_string(kf_id) + ".cereal"; + std::ofstream os(p, std::ios::binary); + + { + cereal::BinaryOutputArchive archive(os); + archive(*data); + } + os.close(); + + for (const auto& d : data->opt_flow_res) { + if (processed_opt_flow.count(d->t_ns) == 0) { + save_image_queue.push(d); + processed_opt_flow.emplace(d->t_ns); + } + } + + } else { + save_image_queue.push(nullptr); + break; + } + } + + std::cout << "Finished MargDataSaver" << std::endl; + }; + + auto save_image_func = [&, img_path]() { + basalt::OpticalFlowResult::Ptr data; + + while (true) { + save_image_queue.pop(data); + + if (data.get()) { + std::string p = img_path + "/" + std::to_string(data->t_ns) + ".cereal"; + std::ofstream os(p, std::ios::binary); + + { + cereal::BinaryOutputArchive archive(os); + archive(data); + } + os.close(); + } else { + break; + } + } + + std::cout << "Finished image MargDataSaver" << std::endl; + }; + + saving_thread.reset(new std::thread(save_func)); + saving_img_thread.reset(new std::thread(save_image_func)); +} // namespace basalt + +MargDataLoader::MargDataLoader() : out_marg_queue(nullptr) {} + +void MargDataLoader::start(const std::string& path) { + auto func = [&, path]() { + std::string img_path = path + "/images/"; + + std::unordered_set saved_images; + + std::map opt_flow_res; + + for (const auto& entry : fs::directory_iterator(img_path)) { + OpticalFlowResult::Ptr data; + // std::cout << entry.path() << std::endl; + std::ifstream is(entry.path(), std::ios::binary); + { + cereal::BinaryInputArchive archive(is); + archive(data); + } + is.close(); + opt_flow_res[data->t_ns] = data; + } + + std::map filenames; + + for (auto& p : fs::directory_iterator(path)) { + std::string filename = p.path().filename(); + if (!std::isdigit(filename[0])) continue; + + size_t lastindex = filename.find_last_of("."); + std::string rawname = filename.substr(0, lastindex); + + int64_t t_ns = std::stol(rawname); + + filenames.emplace(t_ns, filename); + } + + for (const auto& kv : filenames) { + basalt::MargData::Ptr data(new basalt::MargData); + + std::string p = path + "/" + kv.second; + std::ifstream is(p, std::ios::binary); + + { + cereal::BinaryInputArchive archive(is); + archive(*data); + } + is.close(); + + for (const auto& d : data->kfs_all) { + data->opt_flow_res.emplace_back(opt_flow_res.at(d)); + } + + out_marg_queue->push(data); + } + + out_marg_queue->push(nullptr); + + std::cout << "Finished MargDataLoader" << std::endl; + }; + + processing_thread.reset(new std::thread(func)); +} +} // namespace basalt + +namespace cereal { + +template +void save(Archive& ar, const basalt::ManagedImage& m) { + ar(m.w); + ar(m.h); + ar(cereal::binary_data(m.ptr, sizeof(T) * m.w * m.h)); +} + +template +void load(Archive& ar, basalt::ManagedImage& m) { + size_t w; + size_t h; + ar(w); + ar(h); + m.Reinitialise(w, h); + ar(cereal::binary_data(m.ptr, sizeof(T) * m.w * m.h)); +} + +template +void serialize(Archive& ar, basalt::OpticalFlowResult& m) { + ar(m.t_ns); + ar(m.observations); + ar(m.input_images); +} + +template +void serialize(Archive& ar, basalt::OpticalFlowInput& m) { + ar(m.t_ns); + ar(m.img_data); +} + +template +void serialize(Archive& ar, basalt::ImageData& m) { + ar(m.exposure); + ar(m.img); +} + +template +void serialize(Archive& ar, Eigen::AffineCompact2f& m) { + ar(m.matrix()); +} +} // namespace cereal diff --git a/src/mapper.cpp b/src/mapper.cpp new file mode 100644 index 0000000..428245a --- /dev/null +++ b/src/mapper.cpp @@ -0,0 +1,647 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +namespace fs = std::experimental::filesystem; + +using basalt::POSE_SIZE; +using basalt::POSE_VEL_BIAS_SIZE; + +Eigen::Vector3d g(0, 0, -9.81); + +const Eigen::vector image_resolutions = {{752, 480}, + {752, 480}}; + +basalt::VioConfig vio_config; +basalt::NfrMapper::Ptr nrf_mapper; + +Eigen::vector gt_frame_t_w_i; +std::vector gt_frame_t_ns, image_t_ns; + +Eigen::vector mapper_points; +std::vector mapper_point_ids; + +std::map marg_data; + +Eigen::vector edges_vis; +Eigen::vector roll_pitch_vis; +Eigen::vector rel_edges_vis; + +void draw_image_overlay(pangolin::View& v, size_t cam_id); +void draw_scene(); +void load_data(const std::string& calib_path, + const std::string& marg_data_path); +void processMargData(basalt::MargData& m); +void extractNonlinearFactors(basalt::MargData& m); +void computeEdgeVis(); +void optimize(); +void randomInc(); +void randomYawInc(); +void compute_error(); +double alignButton(); +void detect(); +void match(); +void tracks(); +void optimize(); + +constexpr int UI_WIDTH = 200; + +basalt::Calibration calib; + +pangolin::Var show_frame1("ui.show_frame1", 0, 0, 1); +pangolin::Var show_cam1("ui.show_cam1", 0, 0, 0); +pangolin::Var show_frame2("ui.show_frame2", 0, 0, 1); +pangolin::Var show_cam2("ui.show_cam2", 0, 0, 0); +pangolin::Var lock_frames("ui.lock_frames", true, false, true); +pangolin::Var show_detected("ui.show_detected", true, false, true); +pangolin::Var show_matches("ui.show_matches", true, false, true); +pangolin::Var show_inliers("ui.show_inliers", true, false, true); +pangolin::Var show_ids("ui.show_ids", false, false, true); + +pangolin::Var num_opt_iter("ui.num_opt_iter", 10, 0, 20); + +pangolin::Var show_gt("ui.show_gt", true, false, true); +pangolin::Var show_edges("ui.show_edges", true, false, true); +pangolin::Var show_points("ui.show_points", true, false, true); + +using Button = pangolin::Var>; + +Button detect_btn("ui.detect", &detect); +Button match_btn("ui.match", &match); +Button tracks_btn("ui.tracks", &tracks); +Button optimize_btn("ui.optimize", &optimize); +Button align_btn("ui.aling_svd", &alignButton); + +pangolin::OpenGlRenderState camera; + +std::string marg_data_path; +std::string vocabulary; + +int main(int argc, char** argv) { + bool show_gui = true; + std::string cam_calib_path; + std::string result_path; + std::string config_path; + + CLI::App app{"App description"}; + + app.add_option("--show-gui", show_gui, "Show GUI"); + app.add_option("--cam-calib", cam_calib_path, + "Ground-truth camera calibration used for simulation.") + ->required(); + + app.add_option("--marg-data", marg_data_path, "Path to cache folder.") + ->required(); + + app.add_option("--config-path", config_path, "Path to config file."); + + app.add_option("--vocabulary", vocabulary, "Path to vocabulary.")->required(); + + app.add_option("--result-path", result_path, "Path to config file."); + + try { + app.parse(argc, argv); + } catch (const CLI::ParseError& e) { + return app.exit(e); + } + + if (!config_path.empty()) { + vio_config.load(config_path); + } + + load_data(cam_calib_path, marg_data_path); + + for (auto& kv : marg_data) { + nrf_mapper->addMargData(kv.second); + } + + computeEdgeVis(); + + { + std::cout << "Loaded " << nrf_mapper->img_data.size() << " images." + << std::endl; + + show_frame1.Meta().range[1] = nrf_mapper->img_data.size() - 1; + show_frame2.Meta().range[1] = nrf_mapper->img_data.size() - 1; + show_frame1.Meta().gui_changed = true; + show_frame2.Meta().gui_changed = true; + + show_cam1.Meta().range[1] = calib.intrinsics.size() - 1; + show_cam2.Meta().range[1] = calib.intrinsics.size() - 1; + if (calib.intrinsics.size() > 1) show_cam2 = 1; + + for (const auto& kv : nrf_mapper->img_data) { + image_t_ns.emplace_back(kv.first); + } + + std::sort(image_t_ns.begin(), image_t_ns.end()); + } + + if (show_gui) { + pangolin::CreateWindowAndBind("Main", 1800, 1000); + + glEnable(GL_DEPTH_TEST); + + pangolin::View& img_view_display = + pangolin::CreateDisplay() + .SetBounds(0.4, 1.0, pangolin::Attach::Pix(UI_WIDTH), 0.4) + .SetLayout(pangolin::LayoutEqual); + + pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, + pangolin::Attach::Pix(UI_WIDTH)); + + std::vector> img_view; + while (img_view.size() < calib.intrinsics.size()) { + std::shared_ptr iv(new pangolin::ImageView); + + size_t idx = img_view.size(); + img_view.push_back(iv); + + img_view_display.AddDisplay(*iv); + iv->extern_draw_function = + std::bind(&draw_image_overlay, std::placeholders::_1, idx); + } + + camera = pangolin::OpenGlRenderState( + pangolin::ProjectionMatrix(640, 480, 400, 400, 320, 240, 0.001, 10000), + pangolin::ModelViewLookAt(-3.4, -3.7, -8.3, 2.1, 0.6, 0.2, + pangolin::AxisNegY)); + + // pangolin::OpenGlRenderState camera( + // pangolin::ProjectionMatrixOrthographic(-30, 30, -30, 30, -30, 30), + // pangolin::ModelViewLookAt(-3.4, -3.7, -8.3, 2.1, 0.6, 0.2, + // pangolin::AxisNegY)); + + pangolin::View& display3D = + pangolin::CreateDisplay() + .SetAspect(-640 / 480.0) + .SetBounds(0.0, 1.0, 0.4, 1.0) + .SetHandler(new pangolin::Handler3D(camera)); + + while (!pangolin::ShouldQuit()) { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + if (lock_frames) { + // in case of locking frames, chaning one should change the other + if (show_frame1.GuiChanged()) { + show_frame2 = show_frame1; + show_frame2.Meta().gui_changed = true; + show_frame1.Meta().gui_changed = true; + } else if (show_frame2.GuiChanged()) { + show_frame1 = show_frame2; + show_frame1.Meta().gui_changed = true; + show_frame2.Meta().gui_changed = true; + } + } + + display3D.Activate(camera); + glClearColor(1.f, 1.f, 1.f, 1.0f); + + draw_scene(); + + if (show_frame1.GuiChanged() || show_cam1.GuiChanged()) { + size_t frame_id = static_cast(show_frame1); + int64_t timestamp = image_t_ns[frame_id]; + size_t cam_id = show_cam1; + + if (nrf_mapper->img_data.count(timestamp) > 0 && + nrf_mapper->img_data.at(timestamp).get()) { + const std::vector& img_vec = + nrf_mapper->img_data.at(timestamp)->img_data; + + pangolin::GlPixFormat fmt; + fmt.glformat = GL_LUMINANCE; + fmt.gltype = GL_UNSIGNED_SHORT; + fmt.scalable_internal_format = GL_LUMINANCE16; + + if (img_vec[cam_id].img.get()) { + img_view[0]->SetImage( + img_vec[cam_id].img->ptr, img_vec[cam_id].img->w, + img_vec[cam_id].img->h, img_vec[cam_id].img->pitch, fmt); + } else { + img_view[0]->Clear(); + } + } else { + img_view[0]->Clear(); + } + } + + if (show_frame2.GuiChanged() || show_cam2.GuiChanged()) { + size_t frame_id = static_cast(show_frame2); + int64_t timestamp = image_t_ns[frame_id]; + size_t cam_id = show_cam2; + + if (nrf_mapper->img_data.count(timestamp) > 0 && + nrf_mapper->img_data.at(timestamp).get()) { + const std::vector& img_vec = + nrf_mapper->img_data.at(timestamp)->img_data; + + pangolin::GlPixFormat fmt; + fmt.glformat = GL_LUMINANCE; + fmt.gltype = GL_UNSIGNED_SHORT; + fmt.scalable_internal_format = GL_LUMINANCE16; + + if (img_vec[cam_id].img.get()) { + img_view[1]->SetImage( + img_vec[cam_id].img->ptr, img_vec[cam_id].img->w, + img_vec[cam_id].img->h, img_vec[cam_id].img->pitch, fmt); + } else { + img_view[1]->Clear(); + } + } else { + img_view[1]->Clear(); + } + } + + pangolin::FinishFrame(); + + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + } + } else { + optimize(); + detect(); + match(); + tracks(); + optimize(); + + if (!result_path.empty()) { + double error = alignButton(); + + std::ofstream os(result_path); + os << error << std::endl; + os.close(); + } + } + + return 0; +} + +void draw_image_overlay(pangolin::View& v, size_t view_id) { + size_t frame_id = (view_id == 0) ? show_frame1 : show_frame2; + size_t cam_id = (view_id == 0) ? show_cam1 : show_cam2; + + basalt::TimeCamId tcid = std::make_pair(image_t_ns[frame_id], cam_id); + + float text_row = 20; + + if (show_detected) { + glLineWidth(1.0); + glColor3f(1.0, 0.0, 0.0); // red + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (nrf_mapper->feature_corners.find(tcid) != + nrf_mapper->feature_corners.end()) { + const basalt::KeypointsData& cr = nrf_mapper->feature_corners.at(tcid); + + for (size_t i = 0; i < cr.corners.size(); i++) { + Eigen::Vector2d c = cr.corners[i]; + double angle = cr.corner_angles[i]; + pangolin::glDrawCirclePerimeter(c[0], c[1], 3.0); + + Eigen::Vector2d r(3, 0); + Eigen::Rotation2Dd rot(angle); + r = rot * r; + + pangolin::glDrawLine(c, c + r); + } + + pangolin::GlFont::I() + .Text("Detected %d corners", cr.corners.size()) + .Draw(5, 20); + + } else { + glLineWidth(1.0); + + pangolin::GlFont::I().Text("Corners not processed").Draw(5, text_row); + } + text_row += 20; + } + + if (show_matches || show_inliers) { + glLineWidth(1.0); + glColor3f(0.0, 0.0, 1.0); // blue + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + size_t o_frame_id = (view_id == 0 ? show_frame2 : show_frame1); + size_t o_cam_id = (view_id == 0 ? show_cam2 : show_cam1); + + basalt::TimeCamId o_tcid = std::make_pair(image_t_ns[o_frame_id], o_cam_id); + + int idx = -1; + + auto it = nrf_mapper->feature_matches.find(std::make_pair(tcid, o_tcid)); + + if (it != nrf_mapper->feature_matches.end()) { + idx = 0; + } else { + it = nrf_mapper->feature_matches.find(std::make_pair(o_tcid, tcid)); + if (it != nrf_mapper->feature_matches.end()) { + idx = 1; + } + } + + if (idx >= 0 && show_matches) { + if (nrf_mapper->feature_corners.find(tcid) != + nrf_mapper->feature_corners.end()) { + const basalt::KeypointsData& cr = nrf_mapper->feature_corners.at(tcid); + + for (size_t i = 0; i < it->second.matches.size(); i++) { + size_t c_idx = idx == 0 ? it->second.matches[i].first + : it->second.matches[i].second; + + Eigen::Vector2d c = cr.corners[c_idx]; + double angle = cr.corner_angles[c_idx]; + pangolin::glDrawCirclePerimeter(c[0], c[1], 3.0); + + Eigen::Vector2d r(3, 0); + Eigen::Rotation2Dd rot(angle); + r = rot * r; + + pangolin::glDrawLine(c, c + r); + + if (show_ids) { + pangolin::GlFont::I().Text("%d", i).Draw(c[0], c[1]); + } + } + + pangolin::GlFont::I() + .Text("Detected %d matches", it->second.matches.size()) + .Draw(5, text_row); + text_row += 20; + } + } + + glColor3f(0.0, 1.0, 0.0); // green + + if (idx >= 0 && show_inliers) { + if (nrf_mapper->feature_corners.find(tcid) != + nrf_mapper->feature_corners.end()) { + const basalt::KeypointsData& cr = nrf_mapper->feature_corners.at(tcid); + + for (size_t i = 0; i < it->second.inliers.size(); i++) { + size_t c_idx = idx == 0 ? it->second.inliers[i].first + : it->second.inliers[i].second; + + Eigen::Vector2d c = cr.corners[c_idx]; + double angle = cr.corner_angles[c_idx]; + pangolin::glDrawCirclePerimeter(c[0], c[1], 3.0); + + Eigen::Vector2d r(3, 0); + Eigen::Rotation2Dd rot(angle); + r = rot * r; + + pangolin::glDrawLine(c, c + r); + + if (show_ids) { + pangolin::GlFont::I().Text("%d", i).Draw(c[0], c[1]); + } + } + + pangolin::GlFont::I() + .Text("Detected %d inliers", it->second.inliers.size()) + .Draw(5, text_row); + text_row += 20; + } + } + } +} + +void draw_scene() { + glPointSize(3); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + glColor3ubv(pose_color); + if (show_points) pangolin::glDrawPoints(mapper_points); + + glColor3ubv(gt_color); + if (show_gt) pangolin::glDrawLineStrip(gt_frame_t_w_i); + + glColor3f(0.0, 1.0, 0.0); + if (show_edges) pangolin::glDrawLines(edges_vis); + + glLineWidth(2); + glColor3f(1.0, 0.0, 1.0); + if (show_edges) pangolin::glDrawLines(roll_pitch_vis); + glLineWidth(1); + + glColor3f(1.0, 0.0, 0.0); + if (show_edges) pangolin::glDrawLines(rel_edges_vis); + + for (const auto& kv : nrf_mapper->getFramePoses()) { + pangolin::glDrawAxis(kv.second.getPose().matrix(), 0.1); + } + + pangolin::glDrawAxis(Sophus::SE3d().matrix(), 1.0); +} + +void load_data(const std::string& calib_path, const std::string& cache_path) { + { + std::ifstream os(calib_path, std::ios::binary); + + if (os.is_open()) { + cereal::JSONInputArchive archive(os); + archive(calib); + std::cout << "Loaded camera with " << calib.intrinsics.size() + << " cameras" << std::endl; + + } else { + std::cerr << "could not load camera calibration " << calib_path + << std::endl; + std::abort(); + } + } + + { + // Load gt. + { + std::string p = cache_path + "/gt.cereal"; + std::ifstream is(p, std::ios::binary); + + { + cereal::BinaryInputArchive archive(is); + archive(gt_frame_t_ns); + archive(gt_frame_t_w_i); + } + is.close(); + std::cout << "Loaded " << gt_frame_t_ns.size() << " timestamps and " + << gt_frame_t_w_i.size() << " poses" << std::endl; + } + } + + nrf_mapper.reset(new basalt::NfrMapper(calib, vio_config, vocabulary)); + + basalt::MargDataLoader mdl; + tbb::concurrent_bounded_queue marg_queue; + mdl.out_marg_queue = &marg_queue; + + mdl.start(cache_path); + + while (true) { + basalt::MargData::Ptr data; + marg_queue.pop(data); + + if (data.get()) { + int64_t t_ns = *data->kfs_to_marg.begin(); + marg_data[t_ns] = data; + + } else { + break; + } + } + + std::cout << "Loaded " << marg_data.size() << " marg data." << std::endl; +} + +void computeEdgeVis() { + edges_vis.clear(); + for (const auto& kv1 : nrf_mapper->obs) { + for (const auto& kv2 : kv1.second) { + Eigen::Vector3d p1 = nrf_mapper->getFramePoses() + .at(kv1.first.first) + .getPose() + .translation(); + Eigen::Vector3d p2 = nrf_mapper->getFramePoses() + .at(kv2.first.first) + .getPose() + .translation(); + + edges_vis.emplace_back(p1); + edges_vis.emplace_back(p2); + } + } + + roll_pitch_vis.clear(); + for (const auto& v : nrf_mapper->roll_pitch_factors) { + const Sophus::SE3d& T_w_i = + nrf_mapper->getFramePoses().at(v.t_ns).getPose(); + + Eigen::Vector3d p = T_w_i.translation(); + Eigen::Vector3d d = + v.R_w_i_meas * T_w_i.so3().inverse() * (-Eigen::Vector3d::UnitZ()); + + roll_pitch_vis.emplace_back(p); + roll_pitch_vis.emplace_back(p + 0.1 * d); + } + + rel_edges_vis.clear(); + for (const auto& v : nrf_mapper->rel_pose_factors) { + Eigen::Vector3d p1 = + nrf_mapper->getFramePoses().at(v.t_i_ns).getPose().translation(); + Eigen::Vector3d p2 = + nrf_mapper->getFramePoses().at(v.t_j_ns).getPose().translation(); + + rel_edges_vis.emplace_back(p1); + rel_edges_vis.emplace_back(p2); + } +} + +void optimize() { + nrf_mapper->optimize(num_opt_iter); + nrf_mapper->get_current_points(mapper_points, mapper_point_ids); + + computeEdgeVis(); +} + +double alignButton() { + Eigen::vector filter_t_w_i; + std::vector filter_t_ns; + + for (const auto& kv : nrf_mapper->getFramePoses()) { + filter_t_ns.emplace_back(kv.first); + filter_t_w_i.emplace_back(kv.second.getPose().translation()); + } + + return basalt::alignSVD(filter_t_ns, filter_t_w_i, gt_frame_t_ns, + gt_frame_t_w_i); +} + +void detect() { + nrf_mapper->feature_corners.clear(); + nrf_mapper->feature_matches.clear(); + nrf_mapper->detect_keypoints(); +} + +void match() { + nrf_mapper->feature_matches.clear(); + nrf_mapper->match_stereo(); + nrf_mapper->match_all(); +} + +void tracks() { + nrf_mapper->build_tracks(); + nrf_mapper->setup_opt(); + nrf_mapper->get_current_points(mapper_points, mapper_point_ids); + // nrf_mapper->get_current_points_with_color(mapper_points, + // mapper_points_color, + // mapper_point_ids); + computeEdgeVis(); +} diff --git a/src/mapper_sim.cpp b/src/mapper_sim.cpp new file mode 100644 index 0000000..860a99f --- /dev/null +++ b/src/mapper_sim.cpp @@ -0,0 +1,595 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +#include + +namespace fs = std::experimental::filesystem; + +using basalt::POSE_SIZE; +using basalt::POSE_VEL_BIAS_SIZE; + +Eigen::Vector3d g(0, 0, -9.81); + +std::shared_ptr> gt_spline; + +Eigen::vector gt_frame_T_w_i; +Eigen::vector gt_frame_t_w_i, vio_t_w_i; +std::vector gt_frame_t_ns; + +Eigen::vector gt_accel, gt_gyro, gt_accel_bias, gt_gyro_bias, + noisy_accel, noisy_gyro, gt_vel; + +std::vector gt_imu_t_ns; + +Eigen::vector filter_points; +std::vector filter_point_ids; + +std::map marg_data; + +Eigen::vector roll_pitch_factors; +Eigen::vector rel_pose_factors; + +Eigen::vector edges_vis; +Eigen::vector roll_pitch_vis; +Eigen::vector rel_edges_vis; + +Eigen::vector mapper_points; +std::vector mapper_point_ids; + +basalt::NfrMapper::Ptr nrf_mapper; + +std::map gt_observations; +std::map noisy_observations; + +void draw_scene(); +void load_data(const std::string& calib_path, + const std::string& marg_data_path); +void processMargData(basalt::MargData& m); +void extractNonlinearFactors(basalt::MargData& m); +void computeEdgeVis(); +void optimize(); +void randomInc(); +void randomYawInc(); +double alignButton(); +void setup_points(); + +constexpr int UI_WIDTH = 200; +constexpr int NUM_FRAMES = 500; + +basalt::Calibration calib; + +pangolin::Var show_edges("ui.show_edges", true, false, true); +pangolin::Var show_points("ui.show_points", true, false, true); + +using Button = pangolin::Var>; + +Button optimize_btn("ui.optimize", &optimize); +Button rand_inc_btn("ui.rand_inc", &randomInc); +Button rand_yaw_inc_btn("ui.rand_yaw", &randomYawInc); +Button setup_points_btn("ui.setup_points", &setup_points); +Button align_svd_btn("ui.align_svd", &alignButton); + +std::string marg_data_path; + +int main(int argc, char** argv) { + bool show_gui = true; + std::string cam_calib_path; + + CLI::App app{"App description"}; + + app.add_option("--show-gui", show_gui, "Show GUI"); + app.add_option("--cam-calib", cam_calib_path, + "Ground-truth camera calibration used for simulation.") + ->required(); + + app.add_option("--marg-data", marg_data_path, "Path to cache folder.") + ->required(); + + try { + app.parse(argc, argv); + } catch (const CLI::ParseError& e) { + return app.exit(e); + } + + load_data(cam_calib_path, marg_data_path); + + basalt::VioConfig config; + + nrf_mapper.reset(new basalt::NfrMapper(calib, config)); + + for (auto& kv : marg_data) { + nrf_mapper->addMargData(kv.second); + } + + computeEdgeVis(); + + std::cout << "roll_pitch_factors.size() " << roll_pitch_factors.size() + << std::endl; + std::cout << "rel_pose_factors.size() " << rel_pose_factors.size() + << std::endl; + + if (show_gui) { + pangolin::CreateWindowAndBind("Main", 1800, 1000); + + glEnable(GL_DEPTH_TEST); + + pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, + pangolin::Attach::Pix(UI_WIDTH)); + + pangolin::OpenGlRenderState camera( + pangolin::ProjectionMatrix(640, 480, 400, 400, 320, 240, 0.001, 10000), + pangolin::ModelViewLookAt(-8.4, -8.7, -8.3, 2.1, 0.6, 0.2, + pangolin::AxisNegY)); + + pangolin::View& display3D = + pangolin::CreateDisplay() + .SetAspect(-640 / 480.0) + .SetBounds(0.0, 1.0, pangolin::Attach::Pix(UI_WIDTH), 1.0) + .SetHandler(new pangolin::Handler3D(camera)); + + while (!pangolin::ShouldQuit()) { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + display3D.Activate(camera); + glClearColor(1.f, 1.f, 1.f, 1.0f); + + draw_scene(); + + pangolin::FinishFrame(); + + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + } + } + + return 0; +} + +void draw_scene() { + glPointSize(3); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + glColor3ubv(pose_color); + if (show_points) pangolin::glDrawPoints(mapper_points); + + glColor3ubv(gt_color); + pangolin::glDrawLineStrip(gt_frame_t_w_i); + + glColor3ubv(cam_color); + pangolin::glDrawLineStrip(vio_t_w_i); + + glColor3f(0.0, 1.0, 0.0); + if (show_edges) pangolin::glDrawLines(edges_vis); + + glColor3f(1.0, 0.0, 1.0); + if (show_edges) pangolin::glDrawLines(roll_pitch_vis); + + glColor3f(1.0, 0.0, 0.0); + if (show_edges) pangolin::glDrawLines(rel_edges_vis); + + for (const auto& kv : nrf_mapper->getFramePoses()) { + pangolin::glDrawAxis(kv.second.getPose().matrix(), 0.1); + } + + pangolin::glDrawAxis(Sophus::SE3d().matrix(), 1.0); +} + +void load_data(const std::string& calib_path, const std::string& cache_path) { + { + std::ifstream os(calib_path, std::ios::binary); + + if (os.is_open()) { + cereal::JSONInputArchive archive(os); + archive(calib); + std::cout << "Loaded camera with " << calib.intrinsics.size() + << " cameras" << std::endl; + + } else { + std::cerr << "could not load camera calibration " << calib_path + << std::endl; + std::abort(); + } + } + + { + std::string path = cache_path + "/gt_spline.cereal"; + std::cout << "path " << path << std::endl; + + std::ifstream is(path, std::ios::binary); + + if (is.is_open()) { + cereal::JSONInputArchive archive(is); + + int64_t t_ns; + Eigen::vector knots; + + archive(cereal::make_nvp("t_ns", t_ns)); + archive(cereal::make_nvp("knots", knots)); + + archive(cereal::make_nvp("gt_observations", gt_observations)); + archive(cereal::make_nvp("noisy_observations", noisy_observations)); + + std::cout << "path " << path << std::endl; + std::cout << "t_ns " << t_ns << std::endl; + std::cout << "knots " << knots.size() << std::endl; + + gt_spline.reset(new basalt::Se3Spline<5>(t_ns)); + + for (size_t i = 0; i < knots.size(); i++) { + gt_spline->knots_push_back(knots[i]); + } + + is.close(); + } else { + std::cerr << "could not open " << path << std::endl; + std::abort(); + } + } + + { + int64_t dt_ns = int64_t(1e9) / 50; + + for (int64_t t_ns = 0; t_ns < gt_spline->maxTimeNs(); t_ns += dt_ns) { + gt_frame_t_w_i.emplace_back(gt_spline->pose(t_ns).translation()); + gt_frame_t_ns.emplace_back(t_ns); + } + } + + basalt::MargDataLoader mdl; + tbb::concurrent_bounded_queue marg_queue; + mdl.out_marg_queue = &marg_queue; + + mdl.start(cache_path); + + while (true) { + basalt::MargData::Ptr data; + marg_queue.pop(data); + + if (data.get()) { + int64_t t_ns = *data->kfs_to_marg.begin(); + marg_data[t_ns] = data; + } else { + break; + } + } + + std::cout << "Loaded " << marg_data.size() << " marg data." << std::endl; +} + +void processMargData(basalt::MargData& m) { + BASALT_ASSERT(m.aom.total_size == size_t(m.abs_H.cols())); + + std::cout << "rank " << m.abs_H.fullPivLu().rank() << " size " + << m.abs_H.cols() << std::endl; + + basalt::AbsOrderMap aom_new; + std::set idx_to_keep; + std::set idx_to_marg; + + for (const auto& kv : m.aom.abs_order_map) { + if (kv.second.second == POSE_SIZE) { + for (size_t i = 0; i < POSE_SIZE; i++) + idx_to_keep.emplace(kv.second.first + i); + aom_new.abs_order_map.emplace(kv); + aom_new.total_size += POSE_SIZE; + } else if (kv.second.second == POSE_VEL_BIAS_SIZE) { + if (m.kfs_all.count(kv.first) > 0) { + for (size_t i = 0; i < POSE_SIZE; i++) + idx_to_keep.emplace(kv.second.first + i); + for (size_t i = POSE_SIZE; i < POSE_VEL_BIAS_SIZE; i++) + idx_to_marg.emplace(kv.second.first + i); + + aom_new.abs_order_map[kv.first] = + std::make_pair(aom_new.total_size, POSE_SIZE); + aom_new.total_size += POSE_SIZE; + + basalt::PoseStateWithLin p = m.frame_states.at(kv.first); + m.frame_poses[kv.first] = p; + m.frame_states.erase(kv.first); + } else { + for (size_t i = 0; i < POSE_VEL_BIAS_SIZE; i++) + idx_to_marg.emplace(kv.second.first + i); + m.frame_states.erase(kv.first); + } + } else { + std::cerr << "Unknown size" << std::endl; + std::abort(); + } + + std::cout << kv.first << " " << kv.second.first << " " << kv.second.second + << std::endl; + } + + Eigen::MatrixXd marg_H_new; + Eigen::VectorXd marg_b_new; + basalt::KeypointVioEstimator::marginalizeHelper( + m.abs_H, m.abs_b, idx_to_keep, idx_to_marg, marg_H_new, marg_b_new); + + std::cout << "new rank " << marg_H_new.fullPivLu().rank() << " size " + << marg_H_new.cols() << std::endl; + + m.abs_H = marg_H_new; + m.abs_b = marg_b_new; + m.aom = aom_new; + + BASALT_ASSERT(m.aom.total_size == size_t(m.abs_H.cols())); +} + +void extractNonlinearFactors(basalt::MargData& m) { + size_t asize = m.aom.total_size; + std::cout << "asize " << asize << std::endl; + + Eigen::MatrixXd cov_old; + cov_old.setIdentity(asize, asize); + m.abs_H.ldlt().solveInPlace(cov_old); + + int64_t kf_id = *m.kfs_to_marg.cbegin(); + int kf_start_idx = m.aom.abs_order_map.at(kf_id).first; + + auto state_kf = m.frame_poses.at(kf_id); + + Sophus::SE3d T_w_i_kf = state_kf.getPose(); + + Eigen::Vector3d pos = T_w_i_kf.translation(); + Eigen::Vector3d yaw_dir_body = + T_w_i_kf.so3().inverse() * Eigen::Vector3d::UnitX(); + + Sophus::Matrix d_pos_d_T_w_i; + Sophus::Matrix d_yaw_d_T_w_i; + Sophus::Matrix d_rp_d_T_w_i; + + basalt::absPositionError(T_w_i_kf, pos, &d_pos_d_T_w_i); + basalt::yawError(T_w_i_kf, yaw_dir_body, &d_yaw_d_T_w_i); + basalt::rollPitchError(T_w_i_kf, T_w_i_kf.so3(), &d_rp_d_T_w_i); + + { + Eigen::MatrixXd J; + J.setZero(POSE_SIZE, asize); + J.block<3, POSE_SIZE>(0, kf_start_idx) = d_pos_d_T_w_i; + J.block<1, POSE_SIZE>(3, kf_start_idx) = d_yaw_d_T_w_i; + J.block<2, POSE_SIZE>(4, kf_start_idx) = d_rp_d_T_w_i; + + Sophus::Matrix6d cov_new = J * cov_old * J.transpose(); + + // std::cout << "cov_new\n" << cov_new << std::endl; + + basalt::RollPitchFactor rpf; + rpf.t_ns = kf_id; + rpf.R_w_i_meas = T_w_i_kf.so3(); + rpf.cov_inv = cov_new.block<2, 2>(4, 4).inverse(); + + roll_pitch_factors.emplace_back(rpf); + } + + for (int64_t other_id : m.kfs_all) { + if (m.frame_poses.count(other_id) == 0 || other_id == kf_id) { + continue; + } + + auto state_o = m.frame_poses.at(other_id); + + Sophus::SE3d T_w_i_o = state_o.getPose(); + Sophus::SE3d T_kf_o = T_w_i_kf.inverse() * T_w_i_o; + + int o_start_idx = m.aom.abs_order_map.at(other_id).first; + + Sophus::Matrix6d d_res_d_T_w_i, d_res_d_T_w_j; + basalt::relPoseError(T_kf_o, T_w_i_kf, T_w_i_o, &d_res_d_T_w_i, + &d_res_d_T_w_j); + + Eigen::MatrixXd J; + J.setZero(POSE_SIZE, asize); + J.block(0, kf_start_idx) = d_res_d_T_w_i; + J.block(0, o_start_idx) = d_res_d_T_w_j; + + Sophus::Matrix6d cov_new = J * cov_old * J.transpose(); + basalt::RelPoseFactor rpf; + rpf.t_i_ns = kf_id; + rpf.t_j_ns = other_id; + rpf.T_i_j = T_kf_o; + rpf.cov_inv.setIdentity(); + cov_new.ldlt().solveInPlace(rpf.cov_inv); + + // std::cout << "rpf.cov_inv\n" << rpf.cov_inv << std::endl; + + rel_pose_factors.emplace_back(rpf); + } +} + +void computeEdgeVis() { + edges_vis.clear(); + for (const auto& kv1 : nrf_mapper->obs) { + for (const auto& kv2 : kv1.second) { + Eigen::Vector3d p1 = nrf_mapper->getFramePoses() + .at(kv1.first.first) + .getPose() + .translation(); + Eigen::Vector3d p2 = nrf_mapper->getFramePoses() + .at(kv2.first.first) + .getPose() + .translation(); + + edges_vis.emplace_back(p1); + edges_vis.emplace_back(p2); + } + } + + roll_pitch_vis.clear(); + for (const auto& v : nrf_mapper->roll_pitch_factors) { + const Sophus::SE3d& T_w_i = + nrf_mapper->getFramePoses().at(v.t_ns).getPose(); + + Eigen::Vector3d p = T_w_i.translation(); + Eigen::Vector3d d = + v.R_w_i_meas * T_w_i.so3().inverse() * (-Eigen::Vector3d::UnitZ()); + + roll_pitch_vis.emplace_back(p); + roll_pitch_vis.emplace_back(p + 0.1 * d); + } + + rel_edges_vis.clear(); + for (const auto& v : nrf_mapper->rel_pose_factors) { + Eigen::Vector3d p1 = + nrf_mapper->getFramePoses().at(v.t_i_ns).getPose().translation(); + Eigen::Vector3d p2 = + nrf_mapper->getFramePoses().at(v.t_j_ns).getPose().translation(); + + rel_edges_vis.emplace_back(p1); + rel_edges_vis.emplace_back(p2); + } +} + +void optimize() { + nrf_mapper->optimize(); + nrf_mapper->get_current_points(mapper_points, mapper_point_ids); + // nrf_mapper->get_current_points_with_color(mapper_points, + // mapper_points_color, + // mapper_point_ids); + + computeEdgeVis(); +} + +void randomInc() { + Sophus::Vector6d rnd = Sophus::Vector6d::Random().array().abs(); + Sophus::SE3d random_inc = Sophus::expd(rnd / 10); + + for (auto& kv : nrf_mapper->getFramePoses()) { + Sophus::SE3d pose = random_inc * kv.second.getPose(); + basalt::PoseStateWithLin p(kv.first, pose); + kv.second = p; + } + + computeEdgeVis(); +} + +void randomYawInc() { + Sophus::Vector6d rnd; + rnd.setZero(); + rnd[5] = std::abs(Eigen::Vector2d::Random()[0]); + + Sophus::SE3d random_inc = Sophus::expd(rnd); + + std::cout << "random_inc\n" << random_inc.matrix() << std::endl; + + for (auto& kv : nrf_mapper->getFramePoses()) { + Sophus::SE3d pose = random_inc * kv.second.getPose(); + basalt::PoseStateWithLin p(kv.first, pose); + kv.second = p; + } + + computeEdgeVis(); +} + +double alignButton() { + Eigen::vector filter_t_w_i; + std::vector filter_t_ns; + + for (const auto& kv : nrf_mapper->getFramePoses()) { + filter_t_ns.emplace_back(kv.first); + filter_t_w_i.emplace_back(kv.second.getPose().translation()); + } + + return basalt::alignSVD(filter_t_ns, filter_t_w_i, gt_frame_t_ns, + gt_frame_t_w_i); +} + +void setup_points() { + for (auto& kv : nrf_mapper->getFramePoses()) { + for (size_t i = 0; i < calib.intrinsics.size(); i++) { + basalt::TimeCamId tcid(kv.first, i); + auto obs = noisy_observations.at(tcid); + + basalt::KeypointsData kd; + kd.corners = obs.pos; + + nrf_mapper->feature_corners[tcid] = kd; + + for (size_t j = 0; j < kd.corners.size(); j++) { + nrf_mapper->feature_tracks[obs.id[j]][tcid] = j; + } + } + } + + for (auto it = nrf_mapper->feature_tracks.cbegin(); + it != nrf_mapper->feature_tracks.cend();) { + if (it->second.size() < 5) { + it = nrf_mapper->feature_tracks.erase(it); + } else { + ++it; + } + } + + std::cerr << "nrf_mapper->feature_tracks.size() " + << nrf_mapper->feature_tracks.size() << std::endl; + + nrf_mapper->setup_opt(); + + nrf_mapper->get_current_points(mapper_points, mapper_point_ids); +} diff --git a/src/mapper_sim_naive.cpp b/src/mapper_sim_naive.cpp new file mode 100644 index 0000000..6635197 --- /dev/null +++ b/src/mapper_sim_naive.cpp @@ -0,0 +1,751 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include + +#include + +#include + +#include + +// GUI functions +void draw_image_overlay(pangolin::View& v, size_t cam_id); +void draw_scene(); +void load_data(const std::string& calib_path); +void gen_data(); +void compute_projections(); +void setup_vio(); +void draw_plots(); +bool next_step(); +void alignButton(); + +static const int knot_time = 3; +static const double obs_std_dev = 0.5; +static const double accel_std_dev = 0.23; +static const double gyro_std_dev = 0.0027; + +static const double accel_bias_std_dev = 0.00123; +static const double gyro_bias_std_dev = 0.000234; + +Eigen::Vector3d g(0, 0, -9.81); + +// std::random_device rd{}; +// std::mt19937 gen{rd()}; +std::mt19937 gen{1}; + +std::normal_distribution<> obs_noise_dist{0, obs_std_dev}; +std::normal_distribution<> gyro_noise_dist{0, gyro_std_dev}; +std::normal_distribution<> accel_noise_dist{0, accel_std_dev}; + +std::normal_distribution<> gyro_bias_dist{0, gyro_bias_std_dev}; +std::normal_distribution<> accel_bias_dist{0, accel_bias_std_dev}; + +// Simulated data + +basalt::Se3Spline<5> gt_spline(int64_t(knot_time * 1e9)); + +Eigen::vector gt_points; +Eigen::vector gt_frame_T_w_i; +Eigen::vector gt_frame_t_w_i, vio_t_w_i; +std::vector gt_frame_t_ns, kf_t_ns; +Eigen::vector gt_accel, gt_gyro, gt_accel_bias, gt_gyro_bias, + noisy_accel, noisy_gyro, gt_vel; +std::vector gt_imu_t_ns; + +std::map gt_observations; +std::map noisy_observations; + +std::string marg_data_path; + +// VIO vars +basalt::Calibration calib; +basalt::KeypointVioEstimator::Ptr vio; + +// Visualization vars +std::unordered_map vis_map; +tbb::concurrent_bounded_queue out_vis_queue; +tbb::concurrent_bounded_queue out_state_queue; + +std::vector images; + +// Pangolin vars +constexpr int UI_WIDTH = 200; +pangolin::DataLog imu_data_log, vio_data_log, error_data_log; +pangolin::Plotter* plotter; + +pangolin::Var show_frame("ui.show_frame", 0, 0, 1000); + +pangolin::Var show_obs("ui.show_obs", true, false, true); +pangolin::Var show_obs_noisy("ui.show_obs_noisy", true, false, true); +pangolin::Var show_obs_vio("ui.show_obs_vio", true, false, true); + +pangolin::Var show_ids("ui.show_ids", false, false, true); + +pangolin::Var show_accel("ui.show_accel", false, false, true); +pangolin::Var show_gyro("ui.show_gyro", false, false, true); +pangolin::Var show_gt_vel("ui.show_gt_vel", false, false, true); +pangolin::Var show_gt_pos("ui.show_gt_pos", true, false, true); +pangolin::Var show_gt_bg("ui.show_gt_bg", false, false, true); +pangolin::Var show_gt_ba("ui.show_gt_ba", false, false, true); + +pangolin::Var show_est_vel("ui.show_est_vel", false, false, true); +pangolin::Var show_est_pos("ui.show_est_pos", true, false, true); +pangolin::Var show_est_bg("ui.show_est_bg", false, false, true); +pangolin::Var show_est_ba("ui.show_est_ba", false, false, true); + +using Button = pangolin::Var>; + +Button next_step_btn("ui.next_step", &next_step); + +pangolin::Var continue_btn("ui.continue_btn", true, false, true); + +Button align_step_btn("ui.align_button", &alignButton); + +int main(int argc, char** argv) { + srand(1); + + bool show_gui = true; + std::string cam_calib_path; + + CLI::App app{"App description"}; + + app.add_option("--show-gui", show_gui, "Show GUI"); + app.add_option("--cam-calib", cam_calib_path, + "Ground-truth camera calibration used for simulation.") + ->required(); + + app.add_option("--marg-data", marg_data_path, + "Folder to store marginalization data.") + ->required(); + + try { + app.parse(argc, argv); + } catch (const CLI::ParseError& e) { + return app.exit(e); + } + + load_data(cam_calib_path); + gen_data(); + + setup_vio(); + + vio->out_vis_queue = &out_vis_queue; + vio->out_state_queue = &out_state_queue; + + std::thread t0([&]() { + for (size_t i = 0; i < gt_imu_t_ns.size(); i++) { + basalt::ImuData::Ptr data(new basalt::ImuData); + data->t_ns = gt_imu_t_ns[i]; + + data->accel = noisy_accel[i]; + data->gyro = noisy_gyro[i]; + + data->accel_cov.setConstant(accel_std_dev * accel_std_dev); + data->gyro_cov.setConstant(gyro_std_dev * gyro_std_dev); + + vio->addIMUToQueue(data); + } + + vio->addIMUToQueue(nullptr); + + std::cout << "Finished t0" << std::endl; + }); + + std::thread t1([&]() { + for (const auto& t_ns : kf_t_ns) { + basalt::OpticalFlowResult::Ptr data(new basalt::OpticalFlowResult); + data->t_ns = t_ns; + + for (size_t j = 0; j < calib.T_i_c.size(); j++) { + data->observations.emplace_back(); + basalt::TimeCamId tcid(data->t_ns, j); + const basalt::SimObservations& obs = noisy_observations.at(tcid); + for (size_t k = 0; k < obs.pos.size(); k++) { + Eigen::AffineCompact2f t; + t.setIdentity(); + t.translation() = obs.pos[k].cast(); + data->observations.back()[obs.id[k]] = t; + } + } + + vio->addVisionToQueue(data); + } + + vio->addVisionToQueue(nullptr); + + std::cout << "Finished t1" << std::endl; + }); + + std::thread t2([&]() { + basalt::VioVisualizationData::Ptr data; + + while (true) { + out_vis_queue.pop(data); + + if (data.get()) { + vis_map[data->t_ns] = data; + } else { + break; + } + } + + std::cout << "Finished t2" << std::endl; + }); + + std::thread t3([&]() { + basalt::PoseVelBiasState::Ptr data; + + while (true) { + out_state_queue.pop(data); + + if (!data.get()) break; + + int64_t t_ns = data->t_ns; + + // std::cerr << "t_ns " << t_ns << std::endl; + Sophus::SE3d T_w_i = data->T_w_i; + Eigen::Vector3d vel_w_i = data->vel_w_i; + Eigen::Vector3d bg = data->bias_gyro; + Eigen::Vector3d ba = data->bias_accel; + + vio_t_w_i.emplace_back(T_w_i.translation()); + + { + std::vector vals; + vals.push_back(t_ns * 1e-9); + + for (int i = 0; i < 3; i++) vals.push_back(vel_w_i[i]); + for (int i = 0; i < 3; i++) vals.push_back(T_w_i.translation()[i]); + for (int i = 0; i < 3; i++) vals.push_back(bg[i]); + for (int i = 0; i < 3; i++) vals.push_back(ba[i]); + + vio_data_log.Log(vals); + } + } + + std::cout << "Finished t3" << std::endl; + }); + + if (show_gui) { + pangolin::CreateWindowAndBind("Main", 1800, 1000); + + glEnable(GL_DEPTH_TEST); + + pangolin::View& img_view_display = + pangolin::CreateDisplay() + .SetBounds(0.4, 1.0, pangolin::Attach::Pix(UI_WIDTH), 0.5) + .SetLayout(pangolin::LayoutEqual); + + pangolin::View& plot_display = pangolin::CreateDisplay().SetBounds( + 0.0, 0.4, pangolin::Attach::Pix(UI_WIDTH), 1.0); + + plotter = new pangolin::Plotter(&imu_data_log, 0.0, kf_t_ns.back() * 1e-9, + -10.0, 10.0, 0.01f, 0.01f); + plot_display.AddDisplay(*plotter); + + pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, + pangolin::Attach::Pix(UI_WIDTH)); + + std::vector> img_view; + while (img_view.size() < calib.intrinsics.size()) { + std::shared_ptr iv(new pangolin::ImageView); + + size_t idx = img_view.size(); + img_view.push_back(iv); + + img_view_display.AddDisplay(*iv); + iv->extern_draw_function = + std::bind(&draw_image_overlay, std::placeholders::_1, idx); + } + + pangolin::OpenGlRenderState camera( + pangolin::ProjectionMatrix(640, 480, 400, 400, 320, 240, 0.001, 10000), + pangolin::ModelViewLookAt(15, 3, 15, 0, 0, 0, pangolin::AxisZ)); + + pangolin::View& display3D = + pangolin::CreateDisplay() + .SetAspect(-640 / 480.0) + .SetBounds(0.4, 1.0, 0.5, 1.0) + .SetHandler(new pangolin::Handler3D(camera)); + + while (!pangolin::ShouldQuit()) { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + display3D.Activate(camera); + glClearColor(0.95f, 0.95f, 0.95f, 1.0f); + + draw_scene(); + + img_view_display.Activate(); + + if (show_frame.GuiChanged()) { + for (size_t i = 0; i < calib.intrinsics.size(); i++) { + // img_view[i]->SetImage(images[i]); + } + draw_plots(); + } + + if (show_accel.GuiChanged() || show_gyro.GuiChanged() || + show_gt_vel.GuiChanged() || show_gt_pos.GuiChanged() || + show_gt_ba.GuiChanged() || show_gt_bg.GuiChanged() || + show_est_vel.GuiChanged() || show_est_pos.GuiChanged() || + show_est_ba.GuiChanged() || show_est_bg.GuiChanged()) { + draw_plots(); + } + + pangolin::FinishFrame(); + + if (continue_btn) { + if (!next_step()) continue_btn = false; + } else { + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + } + } + } + + t0.join(); + t1.join(); + t2.join(); + t3.join(); + // t4.join(); + + return 0; +} + +void draw_image_overlay(pangolin::View& v, size_t cam_id) { + size_t frame_id = show_frame; + basalt::TimeCamId tcid = std::make_pair(kf_t_ns[frame_id], cam_id); + + if (show_obs) { + glLineWidth(1.0); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (gt_observations.find(tcid) != gt_observations.end()) { + const basalt::SimObservations& cr = gt_observations.at(tcid); + + for (size_t i = 0; i < cr.pos.size(); i++) { + const float radius = 2; + const Eigen::Vector2f c = cr.pos[i].cast(); + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I().Text("%d", cr.id[i]).Draw(c[0], c[1]); + } + + pangolin::GlFont::I().Text("%d gt points", cr.pos.size()).Draw(5, 20); + } + } + + if (show_obs_noisy) { + glLineWidth(1.0); + glColor3f(1.0, 1.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (noisy_observations.find(tcid) != noisy_observations.end()) { + const basalt::SimObservations& cr = noisy_observations.at(tcid); + + for (size_t i = 0; i < cr.pos.size(); i++) { + const float radius = 2; + const Eigen::Vector2f c = cr.pos[i].cast(); + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I().Text("%d", cr.id[i]).Draw(c[0], c[1]); + } + + pangolin::GlFont::I().Text("%d noisy points", cr.pos.size()).Draw(5, 40); + } + } + + if (show_obs_vio) { + glLineWidth(1.0); + glColor3f(0.0, 0.0, 1.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + auto it = vis_map.find(gt_frame_t_ns[frame_id]); + + if (it != vis_map.end() && cam_id < it->second->projections.size()) { + const auto& points = it->second->projections[cam_id]; + + if (points.size() > 0) { + double min_id = points[0][2], max_id = points[0][2]; + for (size_t i = 0; i < points.size(); i++) { + min_id = std::min(min_id, points[i][2]); + max_id = std::max(max_id, points[i][2]); + } + + for (size_t i = 0; i < points.size(); i++) { + const float radius = 2; + const Eigen::Vector4d c = points[i]; + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I().Text("%d", int(c[3])).Draw(c[0], c[1]); + } + } + + glColor3f(0.0, 0.0, 1.0); + pangolin::GlFont::I().Text("%d vio points", points.size()).Draw(5, 60); + } + } +} + +void draw_scene() { + glPointSize(3); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + glColor3ubv(gt_color); + pangolin::glDrawPoints(gt_points); + pangolin::glDrawLineStrip(gt_frame_t_w_i); + + glColor3ubv(cam_color); + pangolin::glDrawLineStrip(vio_t_w_i); + + size_t frame_id = show_frame; + + auto it = vis_map.find(kf_t_ns[frame_id]); + + if (it != vis_map.end()) { + for (const auto& p : it->second->states) + for (size_t i = 0; i < calib.T_i_c.size(); i++) + render_camera((p * calib.T_i_c[i]).matrix(), 2.0f, cam_color, 0.1f); + + for (const auto& p : it->second->frames) + for (size_t i = 0; i < calib.T_i_c.size(); i++) + render_camera((p * calib.T_i_c[i]).matrix(), 2.0f, pose_color, 0.1f); + + glColor3ubv(pose_color); + pangolin::glDrawPoints(it->second->points); + } + + // pangolin::glDrawAxis(gt_frame_T_w_i[frame_id].matrix(), 0.1); + + pangolin::glDrawAxis(Sophus::SE3d().matrix(), 1.0); +} + +void load_data(const std::string& calib_path) { + std::ifstream os(calib_path, std::ios::binary); + + if (os.is_open()) { + cereal::JSONInputArchive archive(os); + archive(calib); + std::cout << "Loaded camera with " << calib.intrinsics.size() + << " cameras" << std::endl; + + } else { + std::cerr << "could not load camera calibration " << calib_path + << std::endl; + std::abort(); + } +} + +void gen_data() { + // Save spline data + { + std::string path = marg_data_path + "/gt_spline.cereal"; + + std::cout << "Loading gt_spline " << path << std::endl; + + std::ifstream is(path, std::ios::binary); + { + cereal::JSONInputArchive archive(is); + + int64_t t_ns; + Eigen::vector knots; + + archive(cereal::make_nvp("t_ns", t_ns)); + archive(cereal::make_nvp("knots", knots)); + + gt_spline = basalt::Se3Spline<5>(t_ns); + + for (size_t i = 0; i < knots.size(); i++) { + gt_spline.knots_push_back(knots[i]); + } + + archive(cereal::make_nvp("noisy_accel", noisy_accel)); + archive(cereal::make_nvp("noisy_gyro", noisy_gyro)); + archive(cereal::make_nvp("noisy_accel", gt_accel)); + archive(cereal::make_nvp("gt_gyro", gt_gyro)); + archive(cereal::make_nvp("gt_accel_bias", gt_accel_bias)); + archive(cereal::make_nvp("gt_gyro_bias", gt_gyro_bias)); + + archive(cereal::make_nvp("gt_points", gt_points)); + + archive(cereal::make_nvp("gt_observations", gt_observations)); + archive(cereal::make_nvp("noisy_observations", noisy_observations)); + + archive(cereal::make_nvp("gt_points", gt_points)); + + archive(cereal::make_nvp("gt_frame_t_ns", gt_frame_t_ns)); + archive(cereal::make_nvp("gt_imu_t_ns", gt_imu_t_ns)); + } + + gt_frame_t_w_i.clear(); + for (int64_t t_ns : gt_frame_t_ns) { + gt_frame_t_w_i.emplace_back(gt_spline.pose(t_ns).translation()); + } + + is.close(); + } + + basalt::MargDataLoader mdl; + tbb::concurrent_bounded_queue marg_queue; + mdl.out_marg_queue = &marg_queue; + + mdl.start(marg_data_path); + + Eigen::map tmp_poses; + + while (true) { + basalt::MargData::Ptr data; + marg_queue.pop(data); + + if (data.get()) { + for (const auto& kv : data->frame_poses) { + tmp_poses[kv.first] = kv.second.getPose(); + } + + for (const auto& kv : data->frame_states) { + if (data->kfs_all.count(kv.first) > 0) { + tmp_poses[kv.first] = kv.second.getState().T_w_i; + } + } + + } else { + break; + } + } + + for (const auto& kv : tmp_poses) { + kf_t_ns.emplace_back(kv.first); + } + + show_frame.Meta().range[1] = kf_t_ns.size() - 1; +} + +void draw_plots() { + plotter->ClearSeries(); + plotter->ClearMarkers(); + + if (show_accel) { + plotter->AddSeries("$0", "$1", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "accel measurements x"); + plotter->AddSeries("$0", "$2", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "accel measurements y"); + plotter->AddSeries("$0", "$3", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "accel measurements z"); + } + + if (show_gyro) { + plotter->AddSeries("$0", "$4", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "gyro measurements x"); + plotter->AddSeries("$0", "$5", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "gyro measurements y"); + plotter->AddSeries("$0", "$6", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "gyro measurements z"); + } + + if (show_gt_vel) { + plotter->AddSeries("$0", "$7", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "ground-truth velocity x"); + plotter->AddSeries("$0", "$8", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "ground-truth velocity y"); + plotter->AddSeries("$0", "$9", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "ground-truth velocity z"); + } + + if (show_gt_pos) { + plotter->AddSeries("$0", "$10", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "ground-truth position x"); + plotter->AddSeries("$0", "$11", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "ground-truth position y"); + plotter->AddSeries("$0", "$12", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "ground-truth position z"); + } + + if (show_gt_bg) { + plotter->AddSeries("$0", "$13", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "ground-truth gyro bias x"); + plotter->AddSeries("$0", "$14", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "ground-truth gyro bias y"); + plotter->AddSeries("$0", "$15", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "ground-truth gyro bias z"); + } + + if (show_gt_ba) { + plotter->AddSeries("$0", "$16", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "ground-truth accel bias x"); + plotter->AddSeries("$0", "$17", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "ground-truth accel bias y"); + plotter->AddSeries("$0", "$18", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "ground-truth accel bias z"); + } + + if (show_est_vel) { + plotter->AddSeries("$0", "$1", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "estimated velocity x", + &vio_data_log); + plotter->AddSeries("$0", "$2", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "estimated velocity y", + &vio_data_log); + plotter->AddSeries("$0", "$3", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "estimated velocity z", + &vio_data_log); + } + + if (show_est_pos) { + plotter->AddSeries("$0", "$4", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "estimated position x", + &vio_data_log); + plotter->AddSeries("$0", "$5", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "estimated position y", + &vio_data_log); + plotter->AddSeries("$0", "$6", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "estimated position z", + &vio_data_log); + } + + if (show_est_bg) { + plotter->AddSeries("$0", "$7", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "estimated gyro bias x", + &vio_data_log); + plotter->AddSeries("$0", "$8", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "estimated gyro bias y", + &vio_data_log); + plotter->AddSeries("$0", "$9", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "estimated gyro bias z", + &vio_data_log); + } + + if (show_est_ba) { + plotter->AddSeries("$0", "$10", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "estimated accel bias x", + &vio_data_log); + plotter->AddSeries("$0", "$11", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "estimated accel bias y", + &vio_data_log); + plotter->AddSeries("$0", "$12", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "estimated accel bias z", + &vio_data_log); + } + + double t = kf_t_ns[show_frame] * 1e-9; + plotter->AddMarker(pangolin::Marker::Vertical, t, pangolin::Marker::Equal, + pangolin::Colour::White()); +} + +void setup_vio() { + int64_t t_init_ns = kf_t_ns.front(); + Sophus::SE3d T_w_i_init = gt_spline.pose(t_init_ns); + Eigen::Vector3d vel_w_i_init = gt_spline.transVelWorld(t_init_ns); + + std::cout << "Setting up filter: t_ns " << t_init_ns << std::endl; + std::cout << "T_w_i\n" << T_w_i_init.matrix() << std::endl; + std::cout << "vel_w_i " << vel_w_i_init.transpose() << std::endl; + + basalt::VioConfig config; + config.vio_debug = true; + + vio.reset(new basalt::KeypointVioEstimator( + t_init_ns, T_w_i_init, vel_w_i_init, gt_gyro_bias.front(), + gt_accel_bias.front(), 0.0001, g, calib, config)); + + vio->setMaxStates(10000); + vio->setMaxKfs(10000); + + // int iteration = 0; + vio_data_log.Clear(); + error_data_log.Clear(); + vio_t_w_i.clear(); +} + +bool next_step() { + if (show_frame < int(kf_t_ns.size()) - 1) { + show_frame = show_frame + 1; + show_frame.Meta().gui_changed = true; + return true; + } else { + return false; + } +} + +void alignButton() { + Eigen::vector vio_t_w_i; + + auto it = vis_map.find(kf_t_ns.back()); + + if (it != vis_map.end()) { + for (const auto& t : it->second->states) + vio_t_w_i.emplace_back(t.translation()); + + } else { + std::cerr << "Could not find results!!" << std::endl; + } + + BASALT_ASSERT(kf_t_ns.size() == vio_t_w_i.size()); + + basalt::alignSVD(kf_t_ns, vio_t_w_i, gt_frame_t_ns, gt_frame_t_w_i); +} diff --git a/src/opt_flow.cpp b/src/opt_flow.cpp new file mode 100644 index 0000000..233bf6f --- /dev/null +++ b/src/opt_flow.cpp @@ -0,0 +1,342 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include + +#include + +#include + +#include + +constexpr int UI_WIDTH = 200; + +void draw_image_overlay(pangolin::View& v, size_t cam_id); +void load_data(const std::string& calib_path); +bool next_step(); + +pangolin::Var show_frame("ui.show_frame", 0, 0, 1500); +pangolin::Var show_obs("ui.show_obs", true, false, true); +pangolin::Var show_ids("ui.show_ids", false, false, true); + +using Button = pangolin::Var>; +Button next_step_btn("ui.next_step", &next_step); +pangolin::Var continue_btn("ui.continue_btn", true, false, true); + +// Opt flow variables +basalt::VioDatasetPtr vio_dataset; + +basalt::VioConfig vio_config; +basalt::OpticalFlowBase::Ptr opt_flow_ptr; + +tbb::concurrent_unordered_map + observations; +tbb::concurrent_bounded_queue + observations_queue; + +basalt::Calibration calib; + +std::unordered_map keypoint_stats; + +void feed_images() { + std::cout << "Started input_data thread " << std::endl; + + for (size_t i = 0; i < vio_dataset->get_image_timestamps().size(); i++) { + basalt::OpticalFlowInput::Ptr data(new basalt::OpticalFlowInput); + + data->t_ns = vio_dataset->get_image_timestamps()[i]; + data->img_data = vio_dataset->get_image_data(data->t_ns); + + opt_flow_ptr->input_queue.push(data); + } + + // Indicate the end of the sequence + basalt::OpticalFlowInput::Ptr data; + opt_flow_ptr->input_queue.push(data); + + std::cout << "Finished input_data thread " << std::endl; +} + +void read_result() { + std::cout << "Started read_result thread " << std::endl; + + basalt::OpticalFlowResult::Ptr res; + + while (true) { + observations_queue.pop(res); + if (!res.get()) break; + + res->input_images.reset(); + + observations.emplace(res->t_ns, res); + + for (size_t i = 0; i < res->observations.size(); i++) + for (const auto& kv : res->observations.at(i)) { + if (keypoint_stats.count(kv.first) == 0) { + keypoint_stats[kv.first] = 1; + } else { + keypoint_stats[kv.first]++; + } + } + } + + std::cout << "Finished read_result thread " << std::endl; + + double sum = 0; + + for (const auto& kv : keypoint_stats) { + sum += kv.second; + } + + std::cout << "Mean track length: " << sum / keypoint_stats.size() + << " num_points: " << keypoint_stats.size() << std::endl; +} + +int main(int argc, char** argv) { + bool show_gui = true; + std::string cam_calib_path; + std::string dataset_path; + std::string dataset_type; + std::string config_path; + + CLI::App app{"App description"}; + + app.add_option("--show-gui", show_gui, "Show GUI"); + app.add_option("--cam-calib", cam_calib_path, + "Ground-truth camera calibration used for simulation.") + ->required(); + + app.add_option("--dataset-path", dataset_path, "Path to dataset.") + ->required(); + + app.add_option("--dataset-type", dataset_type, "Type of dataset.") + ->required(); + + app.add_option("--config-path", config_path, "Path to config file."); + + try { + app.parse(argc, argv); + } catch (const CLI::ParseError& e) { + return app.exit(e); + } + + if (!config_path.empty()) { + vio_config.load(config_path); + } + + load_data(cam_calib_path); + + { + basalt::DatasetIoInterfacePtr dataset_io = + basalt::DatasetIoFactory::getDatasetIo(dataset_type); + + dataset_io->read(dataset_path); + + vio_dataset = dataset_io->get_data(); + vio_dataset->get_image_timestamps().erase( + vio_dataset->get_image_timestamps().begin()); + + show_frame.Meta().range[1] = vio_dataset->get_image_timestamps().size() - 1; + show_frame.Meta().gui_changed = true; + + opt_flow_ptr = + basalt::OpticalFlowFactory::getOpticalFlow(vio_config, calib); + if (show_gui) opt_flow_ptr->output_queue = &observations_queue; + observations_queue.set_capacity(100); + + keypoint_stats.reserve(50000); + } + + std::thread t1(&feed_images); + + if (show_gui) { + std::thread t2(&read_result); + + pangolin::CreateWindowAndBind("Main", 1800, 1000); + + glEnable(GL_DEPTH_TEST); + + pangolin::View& img_view_display = + pangolin::CreateDisplay() + .SetBounds(0, 1.0, pangolin::Attach::Pix(UI_WIDTH), 1.0) + .SetLayout(pangolin::LayoutEqual); + + pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, + pangolin::Attach::Pix(UI_WIDTH)); + + std::vector> img_view; + while (img_view.size() < calib.intrinsics.size()) { + std::shared_ptr iv(new pangolin::ImageView); + + size_t idx = img_view.size(); + img_view.push_back(iv); + + img_view_display.AddDisplay(*iv); + iv->extern_draw_function = + std::bind(&draw_image_overlay, std::placeholders::_1, idx); + } + + while (!pangolin::ShouldQuit()) { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + glClearColor(0.95f, 0.95f, 0.95f, 1.0f); + + img_view_display.Activate(); + + if (show_frame.GuiChanged()) { + size_t frame_id = static_cast(show_frame); + int64_t timestamp = vio_dataset->get_image_timestamps()[frame_id]; + + const std::vector& img_vec = + vio_dataset->get_image_data(timestamp); + + for (size_t cam_id = 0; cam_id < calib.intrinsics.size(); cam_id++) { + if (img_vec[cam_id].img.get()) { + auto img = img_vec[cam_id].img->toPangoImage(); + + pangolin::GlPixFormat fmt; + fmt.glformat = GL_LUMINANCE; + fmt.gltype = GL_UNSIGNED_SHORT; + fmt.scalable_internal_format = GL_LUMINANCE16; + + img_view[cam_id]->SetImage(img.ptr, img.w, img.h, img.pitch, fmt); + } else { + img_view[cam_id]->Clear(); + } + } + } + + pangolin::FinishFrame(); + + if (continue_btn) { + if (!next_step()) { + continue_btn = false; + } + } else { + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + } + } + + t2.join(); + } + + t1.join(); + + return 0; +} + +void draw_image_overlay(pangolin::View& v, size_t cam_id) { + size_t frame_id = static_cast(show_frame); + int64_t t_ns = vio_dataset->get_image_timestamps()[frame_id]; + + if (show_obs) { + glLineWidth(1.0); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (observations.count(t_ns) > 0) { + const Eigen::map& kp_map = + observations.at(t_ns)->observations[cam_id]; + + for (const auto& kv : kp_map) { + Eigen::MatrixXf transformed_patch = + kv.second.linear() * opt_flow_ptr->patch_coord; + transformed_patch.colwise() += kv.second.translation(); + + for (int i = 0; i < transformed_patch.cols(); i++) { + const Eigen::Vector2f c = transformed_patch.col(i); + pangolin::glDrawCirclePerimeter(c[0], c[1], 0.5f); + } + + const Eigen::Vector2f c = kv.second.translation(); + + if (show_ids) + pangolin::GlFont::I().Text("%d", kv.first).Draw(5 + c[0], 5 + c[1]); + } + + pangolin::GlFont::I() + .Text("Tracked %d keypoints", kp_map.size()) + .Draw(5, 20); + } + } +} + +void load_data(const std::string& calib_path) { + std::ifstream os(calib_path, std::ios::binary); + + if (os.is_open()) { + cereal::JSONInputArchive archive(os); + archive(calib); + std::cout << "Loaded camera with " << calib.intrinsics.size() + << " cameras" << std::endl; + + } else { + std::cerr << "could not load camera calibration " << calib_path + << std::endl; + std::abort(); + } +} + +bool next_step() { + if (show_frame < int(vio_dataset->get_image_timestamps().size()) - 1) { + show_frame = show_frame + 1; + show_frame.Meta().gui_changed = true; + return true; + } else { + return false; + } +} diff --git a/src/optical_flow/optical_flow.cpp b/src/optical_flow/optical_flow.cpp new file mode 100644 index 0000000..7861fae --- /dev/null +++ b/src/optical_flow/optical_flow.cpp @@ -0,0 +1,101 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +namespace basalt { + +OpticalFlowBase::Ptr OpticalFlowFactory::getOpticalFlow( + const VioConfig& config, const Calibration& cam) { + OpticalFlowBase::Ptr res; + + if (config.optical_flow_type == "patch") { + switch (config.optical_flow_pattern) { + case 24: + res.reset(new PatchOpticalFlow(config, cam)); + break; + + case 52: + res.reset(new PatchOpticalFlow(config, cam)); + break; + + case 51: + res.reset(new PatchOpticalFlow(config, cam)); + break; + + case 50: + res.reset(new PatchOpticalFlow(config, cam)); + break; + + default: + std::cerr << "config.optical_flow_pattern " + << config.optical_flow_pattern << " is not supported." + << std::endl; + std::abort(); + } + } + + if (config.optical_flow_type == "frame_to_frame") { + switch (config.optical_flow_pattern) { + case 24: + res.reset(new FrameToFrameOpticalFlow(config, cam)); + break; + + case 52: + res.reset(new FrameToFrameOpticalFlow(config, cam)); + break; + + case 51: + res.reset(new FrameToFrameOpticalFlow(config, cam)); + break; + + case 50: + res.reset(new FrameToFrameOpticalFlow(config, cam)); + break; + + default: + std::cerr << "config.optical_flow_pattern " + << config.optical_flow_pattern << " is not supported." + << std::endl; + std::abort(); + } + } + return res; +} +} // namespace basalt diff --git a/src/utils/keypoints.cpp b/src/utils/keypoints.cpp new file mode 100644 index 0000000..2f162fb --- /dev/null +++ b/src/utils/keypoints.cpp @@ -0,0 +1,420 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include +#include +#include + +namespace basalt { + +// const int PATCH_SIZE = 31; +const int HALF_PATCH_SIZE = 15; +const int EDGE_THRESHOLD = 19; + +const static char pattern_31_x_a[256] = { + 8, 4, -11, 7, 2, 1, -2, -13, -13, 10, -13, -11, 7, -4, -13, + -9, 12, -3, -6, 11, 4, 5, 3, -8, -2, -13, -7, -4, -10, 5, + 5, 1, 9, 4, 2, -4, -8, 4, 0, -13, -3, -6, 8, 0, 7, + -13, 10, -6, 10, -13, -13, 3, 5, -1, 3, 2, -13, -13, -13, -7, + 6, -9, -2, -12, 3, -7, -3, 2, -11, -1, 5, -4, -9, -12, 10, + 7, -7, -4, 7, -7, -13, -3, 7, -13, 1, 2, -4, -1, 7, 1, + 9, -1, -13, 7, 12, 6, 5, 2, 3, 2, 9, -8, -11, 1, 6, + 2, 6, 3, 7, -11, -10, -5, -10, 8, 4, -10, 4, -2, -5, 7, + -9, -5, 8, -9, 1, 7, -2, 11, -12, 3, 5, 0, -9, 0, -1, + 5, 3, -13, -5, -4, 6, -7, -13, 1, 4, -2, 2, -2, 4, -6, + -3, 7, 4, -13, 7, 7, -7, -8, -13, 2, 10, -6, 8, 2, -11, + -12, -11, 5, -2, -1, -13, -10, -3, 2, -9, -4, -4, -6, 6, -13, + 11, 7, -1, -4, -7, -13, -7, -8, -5, -13, 1, 1, 9, 5, -1, + -9, -1, -13, 8, 2, 7, -10, -10, 4, 3, -4, 5, 4, -9, 0, + -12, 3, -10, 8, -8, 2, 10, 6, -7, -3, -1, -3, -8, 4, 2, + 6, 3, 11, -3, 4, 2, -10, -13, -13, 6, 0, -13, -9, -13, 5, + 2, -1, 9, 11, 3, -1, 3, -13, 5, 8, 7, -10, 7, 9, 7, + -1}; + +const static char pattern_31_y_a[256] = { + -3, 2, 9, -12, -13, -7, -10, -13, -3, 4, -8, 7, 7, -5, 2, + 0, -6, 6, -13, -13, 7, -3, -7, -7, 11, 12, 3, 2, -12, -12, + -6, 0, 11, 7, -1, -12, -5, 11, -8, -2, -2, 9, 12, 9, -5, + -6, 7, -3, -9, 8, 0, 3, 7, 7, -10, -4, 0, -7, 3, 12, + -10, -1, -5, 5, -10, -7, -2, 9, -13, 6, -3, -13, -6, -10, 2, + 12, -13, 9, -1, 6, 11, 7, -8, -7, -3, -6, 3, -13, 1, -1, + 1, -9, -13, 7, -5, 3, -13, -12, 8, 6, -12, 4, 12, 12, -9, + 3, 3, -3, 8, -5, 11, -8, 5, -1, -6, 12, -2, 0, -8, -6, + -13, -13, -8, -11, -8, -4, 1, -6, -9, 7, 5, -4, 12, 7, 2, + 11, 5, -4, 9, -7, 5, 6, 6, -10, 1, -2, -12, -13, 1, -10, + -13, 5, -2, 9, 1, -8, -4, 11, 6, 4, -5, -5, -3, -12, -2, + -13, 0, -3, -13, -8, -11, -2, 9, -3, -13, 6, 12, -11, -3, 11, + 11, -5, 12, -8, 1, -12, -2, 5, -1, 7, 5, 0, 12, -8, 11, + -3, -10, 1, -11, -13, -13, -10, -8, -6, 12, 2, -13, -13, 9, 3, + 1, 2, -10, -13, -12, 2, 6, 8, 10, -9, -13, -7, -2, 2, -5, + -9, -1, -1, 0, -11, -4, -6, 7, 12, 0, -1, 3, 8, -6, -9, + 7, -6, 5, -3, 0, 4, -6, 0, 8, 9, -4, 4, 3, -7, 0, + -6}; + +const static char pattern_31_x_b[256] = { + 9, 7, -8, 12, 2, 1, -2, -11, -12, 11, -8, -9, 12, -3, -12, -7, + 12, -2, -4, 12, 5, 10, 6, -6, -1, -8, -5, -3, -6, 6, 7, 4, + 11, 4, 4, -2, -7, 9, 1, -8, -2, -4, 10, 1, 11, -11, 12, -6, + 12, -8, -8, 7, 10, 1, 5, 3, -13, -12, -11, -4, 12, -7, 0, -7, + 8, -4, -1, 5, -5, 0, 5, -4, -9, -8, 12, 12, -6, -3, 12, -5, + -12, -2, 12, -11, 12, 3, -2, 1, 8, 3, 12, -1, -10, 10, 12, 7, + 6, 2, 4, 12, 10, -7, -4, 2, 7, 3, 11, 8, 9, -6, -5, -3, + -9, 12, 6, -8, 6, -2, -5, 10, -8, -5, 9, -9, 1, 9, -1, 12, + -6, 7, 10, 2, -5, 2, 1, 7, 6, -8, -3, -3, 8, -6, -5, 3, + 8, 2, 12, 0, 9, -3, -1, 12, 5, -9, 8, 7, -7, -7, -12, 3, + 12, -6, 9, 2, -10, -7, -10, 11, -1, 0, -12, -10, -2, 3, -4, -3, + -2, -4, 6, -5, 12, 12, 0, -3, -6, -8, -6, -6, -4, -8, 5, 10, + 10, 10, 1, -6, 1, -8, 10, 3, 12, -5, -8, 8, 8, -3, 10, 5, + -4, 3, -6, 4, -10, 12, -6, 3, 11, 8, -6, -3, -1, -3, -8, 12, + 3, 11, 7, 12, -3, 4, 2, -8, -11, -11, 11, 1, -9, -6, -8, 8, + 3, -1, 11, 12, 3, 0, 4, -10, 12, 9, 8, -10, 12, 10, 12, 0}; + +const static char pattern_31_y_b[256] = { + 5, -12, 2, -13, 12, 6, -4, -8, -9, 9, -9, 12, 6, 0, -3, + 5, -1, 12, -8, -8, 1, -3, 12, -2, -10, 10, -3, 7, 11, -7, + -1, -5, -13, 12, 4, 7, -10, 12, -13, 2, 3, -9, 7, 3, -10, + 0, 1, 12, -4, -12, -4, 8, -7, -12, 6, -10, 5, 12, 8, 7, + 8, -6, 12, 5, -13, 5, -7, -11, -13, -1, 2, 12, 6, -4, -3, + 12, 5, 4, 2, 1, 5, -6, -7, -12, 12, 0, -13, 9, -6, 12, + 6, 3, 5, 12, 9, 11, 10, 3, -6, -13, 3, 9, -6, -8, -4, + -2, 0, -8, 3, -4, 10, 12, 0, -6, -11, 7, 7, 12, 2, 12, + -8, -2, -13, 0, -2, 1, -4, -11, 4, 12, 8, 8, -13, 12, 7, + -9, -8, 9, -3, -12, 0, 12, -2, 10, -4, -13, 12, -6, 3, -5, + 1, -11, -7, -5, 6, 6, 1, -8, -8, 9, 3, 7, -8, 8, 3, + -9, -5, 8, 12, 9, -5, 11, -13, 2, 0, -10, -7, 9, 11, 5, + 6, -2, 7, -2, 7, -13, -8, -9, 5, 10, -13, -13, -1, -9, -13, + 2, 12, -10, -6, -6, -9, -7, -13, 5, -13, -3, -12, -1, 3, -9, + 1, -8, 9, 12, -5, 7, -8, -12, 5, 9, 5, 4, 3, 12, 11, + -13, 12, 4, 6, 12, 1, 1, 1, -13, -13, 4, -2, -3, -2, 10, + -9, -1, -2, -8, 5, 10, 5, 5, 11, -6, -12, 9, 4, -2, -2, + -11}; + +void detectKeypointsMapping(const basalt::Image& img_raw, + KeypointsData& kd, int num_features) { + cv::Mat image(img_raw.h, img_raw.w, CV_8U); + + uint8_t* dst = image.ptr(); + const uint16_t* src = img_raw.ptr; + + for (size_t i = 0; i < img_raw.size(); i++) { + dst[i] = (src[i] >> 8); + } + + std::vector points; + goodFeaturesToTrack(image, points, num_features, 0.01, 8); + + kd.corners.clear(); + kd.corner_angles.clear(); + kd.corner_descriptors.clear(); + + for (size_t i = 0; i < points.size(); i++) { + if (img_raw.InBounds(points[i].x, points[i].y, EDGE_THRESHOLD)) { + kd.corners.emplace_back(points[i].x, points[i].y); + } + } +} + +void detectKeypoints(const basalt::Image& img_raw, + KeypointsData& kd, int PATCH_SIZE, int num_points_cell, + const Eigen::vector& current_points) { + kd.corners.clear(); + kd.corner_angles.clear(); + kd.corner_descriptors.clear(); + + const size_t x_start = (img_raw.w % PATCH_SIZE) / 2; + const size_t x_stop = x_start + img_raw.w - PATCH_SIZE; + + const size_t y_start = (img_raw.h % PATCH_SIZE) / 2; + const size_t y_stop = y_start + img_raw.h - PATCH_SIZE; + + // std::cerr << "x_start " << x_start << " x_stop " << x_stop << std::endl; + // std::cerr << "y_start " << y_start << " y_stop " << y_stop << std::endl; + + Eigen::MatrixXi cells; + cells.setZero(img_raw.h / PATCH_SIZE + 1, img_raw.w / PATCH_SIZE + 1); + + for (const Eigen::Vector2d& p : current_points) { + if (p[0] >= x_start && p[1] >= y_start) { + int x = (p[0] - x_start) / PATCH_SIZE; + int y = (p[1] - y_start) / PATCH_SIZE; + + cells(y, x) += 1; + } + } + + for (size_t x = x_start; x < x_stop; x += PATCH_SIZE) { + for (size_t y = y_start; y < y_stop; y += PATCH_SIZE) { + if (cells((y - y_start) / PATCH_SIZE, (x - x_start) / PATCH_SIZE) > 0) + continue; + + const basalt::Image sub_img_raw = + img_raw.SubImage(x, y, PATCH_SIZE, PATCH_SIZE); + + cv::Mat subImg(PATCH_SIZE, PATCH_SIZE, CV_8U); + + for (int y = 0; y < PATCH_SIZE; y++) { + uchar* sub_ptr = subImg.ptr(y); + for (int x = 0; x < PATCH_SIZE; x++) { + sub_ptr[x] = (sub_img_raw(x, y) >> 8); + } + } + + int points_added = 0; + int threshold = 40; + + while (points_added < num_points_cell && threshold >= 10) { + std::vector points; + cv::FAST(subImg, points, threshold); + + std::sort(points.begin(), points.end(), + [](const cv::KeyPoint& a, const cv::KeyPoint& b) -> bool { + return a.response > b.response; + }); + + // std::cout << "Detected " << points.size() << " points. + // Threshold " + // << threshold << std::endl; + + for (size_t i = 0; i < points.size() && points_added < num_points_cell; + i++) + if (img_raw.InBounds(x + points[i].pt.x, y + points[i].pt.y, + EDGE_THRESHOLD)) { + kd.corners.emplace_back(x + points[i].pt.x, y + points[i].pt.y); + points_added++; + } + + threshold /= 2; + } + } + } + + // std::cout << "Total points: " << kd.corners.size() << std::endl; + + // cv::TermCriteria criteria = + // cv::TermCriteria(CV_TERMCRIT_EPS + CV_TERMCRIT_ITER, 40, 0.001); + // cv::Size winSize = cv::Size(5, 5); + // cv::Size zeroZone = cv::Size(-1, -1); + // cv::cornerSubPix(image, points, winSize, zeroZone, criteria); + + // for (size_t i = 0; i < points.size(); i++) { + // if (img_raw.InBounds(points[i].pt.x, points[i].pt.y, EDGE_THRESHOLD)) { + // kd.corners.emplace_back(points[i].pt.x, points[i].pt.y); + // } + // } +} + +void computeAngles(const basalt::Image& img_raw, + KeypointsData& kd, bool rotate_features) { + kd.corner_angles.resize(kd.corners.size()); + + for (size_t i = 0; i < kd.corners.size(); i++) { + const Eigen::Vector2d& p = kd.corners[i]; + + const int cx = p[0]; + const int cy = p[1]; + + double angle = 0; + + if (rotate_features) { + double m01 = 0, m10 = 0; + for (int x = -HALF_PATCH_SIZE; x <= HALF_PATCH_SIZE; x++) { + for (int y = -HALF_PATCH_SIZE; y <= HALF_PATCH_SIZE; y++) { + if (x * x + y * y <= HALF_PATCH_SIZE * HALF_PATCH_SIZE) { + double val = img_raw(cx + x, cy + y); + m01 += y * val; + m10 += x * val; + } + } + } + + angle = atan2(m01, m10); + } + + kd.corner_angles[i] = angle; + } +} + +void computeDescriptors(const basalt::Image& img_raw, + KeypointsData& kd) { + kd.corner_descriptors.resize(kd.corners.size()); + + for (size_t i = 0; i < kd.corners.size(); i++) { + std::bitset<256> descriptor; + + const Eigen::Vector2d& p = kd.corners[i]; + double angle = kd.corner_angles[i]; + + int cx = p[0]; + int cy = p[1]; + + Eigen::Rotation2Dd rot(angle); + Eigen::Matrix2d mat_rot = rot.matrix(); + + for (int i = 0; i < 256; i++) { + Eigen::Vector2d va(pattern_31_x_a[i], pattern_31_y_a[i]), + vb(pattern_31_x_b[i], pattern_31_y_b[i]); + + Eigen::Vector2i vva = (mat_rot * va).array().round().cast(); + Eigen::Vector2i vvb = (mat_rot * vb).array().round().cast(); + + descriptor[i] = + img_raw(cx + vva[0], cy + vva[1]) < img_raw(cx + vvb[0], cy + vvb[1]); + } + + kd.corner_descriptors[i] = descriptor; + } +} + +void matchFastHelper(const std::vector>& corner_descriptors_1, + const std::vector>& corner_descriptors_2, + std::map& matches, int threshold, + double test_dist) { + matches.clear(); + + for (size_t i = 0; i < corner_descriptors_1.size(); i++) { + int best_idx = -1, best_dist = 500; + int best2_dist = 500; + + for (size_t j = 0; j < corner_descriptors_2.size(); j++) { + int dist = (corner_descriptors_1[i] ^ corner_descriptors_2[j]).count(); + + if (dist <= best_dist) { + best2_dist = best_dist; + + best_dist = dist; + best_idx = j; + } else if (dist < best2_dist) { + best2_dist = dist; + } + } + + if (best_dist < threshold && best_dist * test_dist <= best2_dist) { + matches.emplace(i, best_idx); + } + } +} + +void matchDescriptors(const std::vector>& corner_descriptors_1, + const std::vector>& corner_descriptors_2, + std::vector>& matches, int threshold, + double dist_2_best) { + matches.clear(); + + std::map matches_1_2, matches_2_1; + matchFastHelper(corner_descriptors_1, corner_descriptors_2, matches_1_2, + threshold, dist_2_best); + matchFastHelper(corner_descriptors_2, corner_descriptors_1, matches_2_1, + threshold, dist_2_best); + + for (const auto& kv : matches_1_2) { + if (matches_2_1[kv.second] == kv.first) { + matches.emplace_back(kv.first, kv.second); + } + } +} + +void findInliersRansac(const KeypointsData& kd1, const KeypointsData& kd2, + const double ransac_thresh, const int ransac_min_inliers, + MatchData& md) { + md.inliers.clear(); + + opengv::bearingVectors_t bearingVectors1, bearingVectors2; + + for (size_t i = 0; i < md.matches.size(); i++) { + bearingVectors1.push_back(kd1.corners_3d[md.matches[i].first].head<3>()); + bearingVectors2.push_back(kd2.corners_3d[md.matches[i].second].head<3>()); + } + + // create the central relative adapter + opengv::relative_pose::CentralRelativeAdapter adapter(bearingVectors1, + bearingVectors2); + // create a RANSAC object + opengv::sac::Ransac< + opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem> + ransac; + // create a CentralRelativePoseSacProblem + // (set algorithm to STEWENIUS, NISTER, SEVENPT, or EIGHTPT) + std::shared_ptr< + opengv::sac_problems::relative_pose::CentralRelativePoseSacProblem> + relposeproblem_ptr( + new opengv::sac_problems::relative_pose:: + CentralRelativePoseSacProblem( + adapter, opengv::sac_problems::relative_pose:: + CentralRelativePoseSacProblem::STEWENIUS)); + // run ransac + ransac.sac_model_ = relposeproblem_ptr; + ransac.threshold_ = ransac_thresh; + ransac.max_iterations_ = 25; + ransac.computeModel(); + + // do non-linear refinement and add more inliers + const size_t num_inliers_ransac = ransac.inliers_.size(); + + adapter.sett12(ransac.model_coefficients_.topRightCorner<3, 1>()); + adapter.setR12(ransac.model_coefficients_.topLeftCorner<3, 3>()); + + const opengv::transformation_t nonlinear_transformation = + opengv::relative_pose::optimize_nonlinear(adapter, ransac.inliers_); + + ransac.sac_model_->selectWithinDistance(nonlinear_transformation, + ransac.threshold_, ransac.inliers_); + + // Sanity check if the number of inliers decreased, but only warn if it is by + // 3 or more, since some small fluctuation is expected. + if (ransac.inliers_.size() + 2 < num_inliers_ransac) { + std::cout << "Warning: non-linear refinement reduced the relative pose " + "ransac inlier count from " + << num_inliers_ransac << " to " << ransac.inliers_.size() << "." + << std::endl; + } + + // get the result (normalize translation) + md.T_i_j = Sophus::SE3d( + nonlinear_transformation.topLeftCorner<3, 3>(), + nonlinear_transformation.topRightCorner<3, 1>().normalized()); + + if ((long)ransac.inliers_.size() >= ransac_min_inliers) { + for (size_t i = 0; i < ransac.inliers_.size(); i++) + md.inliers.emplace_back(md.matches[ransac.inliers_[i]]); + } +} + +} // namespace basalt diff --git a/src/utils/vio_config.cpp b/src/utils/vio_config.cpp new file mode 100644 index 0000000..d0ce423 --- /dev/null +++ b/src/utils/vio_config.cpp @@ -0,0 +1,130 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 +#include + +namespace basalt { + +VioConfig::VioConfig() { + // optical_flow_type = "patch"; + optical_flow_type = "frame_to_frame"; + optical_flow_detection_grid_size = 50; + optical_flow_max_recovered_dist2 = 0.09f; + optical_flow_pattern = 51; + optical_flow_max_iterations = 5; + optical_flow_levels = 3; + optical_flow_epipolar_error = 0.005; + + vio_max_states = 3; + vio_max_kfs = 7; + vio_min_frames_after_kf = 5; + vio_new_kf_keypoints_thresh = 0.7; + vio_max_iterations = 5; + vio_debug = false; + vio_obs_std_dev = 0.5; + vio_obs_huber_thresh = 1.0; + + mapper_obs_std_dev = 0.25; + mapper_obs_huber_thresh = 1.5; + mapper_detection_num_points = 800; + mapper_num_frames_to_match = 30; + mapper_frames_to_match_threshold = 0.3; + mapper_min_matches = 20; + mapper_ransac_threshold = 5e-5; + mapper_min_track_length = 5; + mapper_max_hamming_distance = 70; + mapper_second_best_test_ratio = 1.2; +} + +void VioConfig::save(const std::string& filename) { + std::ofstream os(filename); + + { + cereal::JSONOutputArchive archive(os); + archive(*this); + } + os.close(); +} + +void VioConfig::load(const std::string& filename) { + std::ifstream is(filename); + + { + cereal::JSONInputArchive archive(is); + archive(*this); + } + is.close(); +} +} // namespace basalt + +namespace cereal { + +template +void serialize(Archive& ar, basalt::VioConfig& config) { + ar(CEREAL_NVP(config.optical_flow_type)); + ar(CEREAL_NVP(config.optical_flow_detection_grid_size)); + ar(CEREAL_NVP(config.optical_flow_max_recovered_dist2)); + ar(CEREAL_NVP(config.optical_flow_pattern)); + ar(CEREAL_NVP(config.optical_flow_max_iterations)); + ar(CEREAL_NVP(config.optical_flow_epipolar_error)); + ar(CEREAL_NVP(config.optical_flow_levels)); + + ar(CEREAL_NVP(config.vio_max_states)); + ar(CEREAL_NVP(config.vio_max_kfs)); + ar(CEREAL_NVP(config.vio_min_frames_after_kf)); + ar(CEREAL_NVP(config.vio_new_kf_keypoints_thresh)); + ar(CEREAL_NVP(config.vio_debug)); + ar(CEREAL_NVP(config.vio_max_iterations)); + + ar(CEREAL_NVP(config.vio_obs_std_dev)); + ar(CEREAL_NVP(config.vio_obs_huber_thresh)); + + ar(CEREAL_NVP(config.mapper_obs_std_dev)); + ar(CEREAL_NVP(config.mapper_obs_huber_thresh)); + ar(CEREAL_NVP(config.mapper_detection_num_points)); + ar(CEREAL_NVP(config.mapper_num_frames_to_match)); + ar(CEREAL_NVP(config.mapper_frames_to_match_threshold)); + ar(CEREAL_NVP(config.mapper_min_matches)); + ar(CEREAL_NVP(config.mapper_ransac_threshold)); + ar(CEREAL_NVP(config.mapper_min_track_length)); + ar(CEREAL_NVP(config.mapper_max_hamming_distance)); + ar(CEREAL_NVP(config.mapper_second_best_test_ratio)); +} +} // namespace cereal diff --git a/src/vi_estimator/ba_base.cpp b/src/vi_estimator/ba_base.cpp new file mode 100644 index 0000000..82b480d --- /dev/null +++ b/src/vi_estimator/ba_base.cpp @@ -0,0 +1,525 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +namespace basalt { + +Sophus::SE3d BundleAdjustmentBase::computeRelPose(const Sophus::SE3d& T_w_i_h, + const Sophus::SE3d& T_i_c_h, + const Sophus::SE3d& T_w_i_t, + const Sophus::SE3d& T_i_c_t, + Sophus::Matrix6d* d_rel_d_h, + Sophus::Matrix6d* d_rel_d_t) { + Sophus::SE3d tmp2 = (T_i_c_t).inverse(); + + Sophus::SE3d T_t_i_h_i; + T_t_i_h_i.so3() = T_w_i_t.so3().inverse() * T_w_i_h.so3(); + T_t_i_h_i.translation() = + T_w_i_t.so3().inverse() * (T_w_i_h.translation() - T_w_i_t.translation()); + + Sophus::SE3d tmp = tmp2 * T_t_i_h_i; + Sophus::SE3d res = tmp * T_i_c_h; + + if (d_rel_d_h) { + Eigen::Matrix3d R = T_w_i_h.so3().inverse().matrix(); + + Sophus::Matrix6d RR; + RR.setZero(); + RR.topLeftCorner<3, 3>() = R; + RR.bottomRightCorner<3, 3>() = R; + + *d_rel_d_h = tmp.Adj() * RR; + } + + if (d_rel_d_t) { + Eigen::Matrix3d R = T_w_i_t.so3().inverse().matrix(); + + Sophus::Matrix6d RR; + RR.setZero(); + RR.topLeftCorner<3, 3>() = R; + RR.bottomRightCorner<3, 3>() = R; + + *d_rel_d_t = -tmp2.Adj() * RR; + } + + return res; +} + +void BundleAdjustmentBase::updatePoints(const AbsOrderMap& aom, + const RelLinData& rld, + const Eigen::VectorXd& inc) { + Eigen::VectorXd rel_inc; + rel_inc.setZero(rld.order.size() * POSE_SIZE); + for (size_t i = 0; i < rld.order.size(); i++) { + const TimeCamId& tcid_h = rld.order[i].first; + const TimeCamId& tcid_t = rld.order[i].second; + + if (tcid_h.first != tcid_t.first) { + int abs_h_idx = aom.abs_order_map.at(tcid_h.first).first; + int abs_t_idx = aom.abs_order_map.at(tcid_t.first).first; + + rel_inc.segment(i * POSE_SIZE) = + rld.d_rel_d_h[i] * inc.segment(abs_h_idx) + + rld.d_rel_d_t[i] * inc.segment(abs_t_idx); + } + } + + for (const auto& kv : rld.lm_to_obs) { + int lm_idx = kv.first; + const auto& other_obs = kv.second; + + Eigen::Vector3d H_l_p_x; + H_l_p_x.setZero(); + + for (size_t k = 0; k < other_obs.size(); k++) { + int rel_idx = other_obs[k].first; + const FrameRelLinData& frld_other = rld.Hpppl.at(rel_idx); + + Eigen::Matrix H_l_p_other = + frld_other.Hpl[other_obs[k].second].transpose(); + + H_l_p_x += H_l_p_other * rel_inc.segment(rel_idx * POSE_SIZE); + + // std::cerr << "inc_p " << inc_p.transpose() << std::endl; + } + + Eigen::Vector3d inc_p = rld.Hll.at(lm_idx) * (rld.bl.at(lm_idx) - H_l_p_x); + + KeypointPosition& kpt = kpts[lm_idx]; + kpt.dir -= inc_p.head<2>(); + kpt.id -= inc_p[2]; + + kpt.id = std::max(0., kpt.id); + } +} + +void BundleAdjustmentBase::computeError(double& error) const { + error = 0; + + for (const auto& kv : obs) { + const TimeCamId& tcid_h = kv.first; + + for (const auto& obs_kv : kv.second) { + const TimeCamId& tcid_t = obs_kv.first; + + if (tcid_h != tcid_t) { + PoseStateWithLin state_h = getPoseStateWithLin(tcid_h.first); + PoseStateWithLin state_t = getPoseStateWithLin(tcid_t.first); + + Sophus::SE3d T_t_h_sophus = + computeRelPose(state_h.getPose(), calib.T_i_c[tcid_h.second], + state_t.getPose(), calib.T_i_c[tcid_t.second]); + + Eigen::Matrix4d T_t_h = T_t_h_sophus.matrix(); + + std::visit( + [&](const auto& cam) { + for (size_t i = 0; i < obs_kv.second.size(); i++) { + const KeypointObservation& kpt_obs = obs_kv.second[i]; + const KeypointPosition& kpt_pos = kpts.at(kpt_obs.kpt_id); + + Eigen::Vector2d res; + + bool valid = linearizePoint(kpt_obs, kpt_pos, T_t_h, cam, res); + + if (valid) { + double e = res.norm(); + double huber_weight = + e < huber_thresh ? 1.0 : huber_thresh / e; + double obs_weight = + huber_weight / (obs_std_dev * obs_std_dev); + + error += + (2 - huber_weight) * obs_weight * res.transpose() * res; + } + } + }, + calib.intrinsics[tcid_t.second].variant); + + } else { + // target and host are the same + // residual does not depend on the pose + // it just depends on the point + + std::visit( + [&](const auto& cam) { + for (size_t i = 0; i < obs_kv.second.size(); i++) { + const KeypointObservation& kpt_obs = obs_kv.second[i]; + const KeypointPosition& kpt_pos = kpts.at(kpt_obs.kpt_id); + + Eigen::Vector2d res; + + bool valid = linearizePoint(kpt_obs, kpt_pos, cam, res); + if (valid) { + double e = res.norm(); + double huber_weight = + e < huber_thresh ? 1.0 : huber_thresh / e; + double obs_weight = + huber_weight / (obs_std_dev * obs_std_dev); + + error += + (2 - huber_weight) * obs_weight * res.transpose() * res; + } + } + }, + calib.intrinsics[tcid_t.second].variant); + } + } + } +} + +void BundleAdjustmentBase::linearizeHelper( + Eigen::vector& rld_vec, + const Eigen::map>>& + obs_to_lin, + double& error) const { + error = 0; + + rld_vec.clear(); + + std::vector obs_tcid_vec; + for (const auto& kv : obs_to_lin) { + obs_tcid_vec.emplace_back(kv.first); + rld_vec.emplace_back(kpts.size(), kv.second.size()); + } + + tbb::parallel_for( + tbb::blocked_range(0, obs_tcid_vec.size()), + [&](const tbb::blocked_range& range) { + for (size_t r = range.begin(); r != range.end(); ++r) { + auto kv = obs_to_lin.find(obs_tcid_vec[r]); + + RelLinData& rld = rld_vec[r]; + + rld.error = 0; + + const TimeCamId& tcid_h = kv->first; + + for (const auto& obs_kv : kv->second) { + const TimeCamId& tcid_t = obs_kv.first; + if (tcid_h != tcid_t) { + // target and host are not the same + rld.order.emplace_back(std::make_pair(tcid_h, tcid_t)); + + PoseStateWithLin state_h = getPoseStateWithLin(tcid_h.first); + PoseStateWithLin state_t = getPoseStateWithLin(tcid_t.first); + + Sophus::Matrix6d d_rel_d_h, d_rel_d_t; + + Sophus::SE3d T_t_h_sophus = computeRelPose( + state_h.getPoseLin(), calib.T_i_c[tcid_h.second], + state_t.getPoseLin(), calib.T_i_c[tcid_t.second], &d_rel_d_h, + &d_rel_d_t); + + rld.d_rel_d_h.emplace_back(d_rel_d_h); + rld.d_rel_d_t.emplace_back(d_rel_d_t); + + if (state_h.isLinearized() || state_t.isLinearized()) { + T_t_h_sophus = computeRelPose( + state_h.getPose(), calib.T_i_c[tcid_h.second], + state_t.getPose(), calib.T_i_c[tcid_t.second]); + } + + Eigen::Matrix4d T_t_h = T_t_h_sophus.matrix(); + + FrameRelLinData frld; + + std::visit( + [&](const auto& cam) { + for (size_t i = 0; i < obs_kv.second.size(); i++) { + const KeypointObservation& kpt_obs = obs_kv.second[i]; + const KeypointPosition& kpt_pos = kpts.at(kpt_obs.kpt_id); + + Eigen::Vector2d res; + Eigen::Matrix d_res_d_xi; + Eigen::Matrix d_res_d_p; + + bool valid = linearizePoint(kpt_obs, kpt_pos, T_t_h, cam, + res, &d_res_d_xi, &d_res_d_p); + + if (valid) { + double e = res.norm(); + double huber_weight = + e < huber_thresh ? 1.0 : huber_thresh / e; + double obs_weight = + huber_weight / (obs_std_dev * obs_std_dev); + + rld.error += (2 - huber_weight) * obs_weight * + res.transpose() * res; + + if (rld.Hll.count(kpt_obs.kpt_id) == 0) { + rld.Hll[kpt_obs.kpt_id].setZero(); + rld.bl[kpt_obs.kpt_id].setZero(); + } + + rld.Hll[kpt_obs.kpt_id] += + obs_weight * d_res_d_p.transpose() * d_res_d_p; + rld.bl[kpt_obs.kpt_id] += + obs_weight * d_res_d_p.transpose() * res; + + frld.Hpp += + obs_weight * d_res_d_xi.transpose() * d_res_d_xi; + frld.bp += obs_weight * d_res_d_xi.transpose() * res; + frld.Hpl.emplace_back( + obs_weight * d_res_d_xi.transpose() * d_res_d_p); + frld.lm_id.emplace_back(kpt_obs.kpt_id); + + rld.lm_to_obs[kpt_obs.kpt_id].emplace_back( + rld.Hpppl.size(), frld.lm_id.size() - 1); + } + } + }, + calib.intrinsics[tcid_t.second].variant); + + rld.Hpppl.emplace_back(frld); + + } else { + // target and host are the same + // residual does not depend on the pose + // it just depends on the point + + std::visit( + [&](const auto& cam) { + for (size_t i = 0; i < obs_kv.second.size(); i++) { + const KeypointObservation& kpt_obs = obs_kv.second[i]; + const KeypointPosition& kpt_pos = kpts.at(kpt_obs.kpt_id); + + Eigen::Vector2d res; + Eigen::Matrix d_res_d_p; + + bool valid = linearizePoint(kpt_obs, kpt_pos, cam, res, + &d_res_d_p); + + if (valid) { + double e = res.norm(); + double huber_weight = + e < huber_thresh ? 1.0 : huber_thresh / e; + double obs_weight = + huber_weight / (obs_std_dev * obs_std_dev); + + rld.error += (2 - huber_weight) * obs_weight * + res.transpose() * res; + + if (rld.Hll.count(kpt_obs.kpt_id) == 0) { + rld.Hll[kpt_obs.kpt_id].setZero(); + rld.bl[kpt_obs.kpt_id].setZero(); + } + + rld.Hll[kpt_obs.kpt_id] += + obs_weight * d_res_d_p.transpose() * d_res_d_p; + rld.bl[kpt_obs.kpt_id] += + obs_weight * d_res_d_p.transpose() * res; + } + } + }, + calib.intrinsics[tcid_t.second].variant); + } + } + } + + }); + + for (const auto& rld : rld_vec) error += rld.error; +} + +void BundleAdjustmentBase::linearizeRel(const RelLinData& rld, + Eigen::MatrixXd& H, + Eigen::VectorXd& b) { + // std::cout << "linearizeRel: KF " << frame_states.size() << " obs " + // << obs.size() << std::endl; + + // Do schur complement + size_t msize = rld.order.size(); + H.setZero(POSE_SIZE * msize, POSE_SIZE * msize); + b.setZero(POSE_SIZE * msize); + + for (size_t i = 0; i < rld.order.size(); i++) { + const FrameRelLinData& frld = rld.Hpppl.at(i); + + H.block(POSE_SIZE * i, POSE_SIZE * i) += frld.Hpp; + b.segment(POSE_SIZE * i) += frld.bp; + + for (size_t j = 0; j < frld.lm_id.size(); j++) { + Eigen::Matrix H_pl_H_ll_inv; + int lm_id = frld.lm_id[j]; + + H_pl_H_ll_inv = frld.Hpl[j] * rld.Hll.at(lm_id); + b.segment(POSE_SIZE * i) -= H_pl_H_ll_inv * rld.bl.at(lm_id); + + const auto& other_obs = rld.lm_to_obs.at(lm_id); + for (size_t k = 0; k < other_obs.size(); k++) { + const FrameRelLinData& frld_other = rld.Hpppl.at(other_obs[k].first); + int other_i = other_obs[k].first; + + Eigen::Matrix H_l_p_other = + frld_other.Hpl[other_obs[k].second].transpose(); + + H.block(POSE_SIZE * i, POSE_SIZE * other_i) -= + H_pl_H_ll_inv * H_l_p_other; + } + } + } +} + +void BundleAdjustmentBase::get_current_points( + Eigen::vector& points, std::vector& ids) const { + points.clear(); + ids.clear(); + + for (const auto& kv_kpt : kpts) { + Eigen::Vector3d pt_cam = + StereographicParam::unproject(kv_kpt.second.dir).head<3>(); + pt_cam /= kv_kpt.second.id; + + Sophus::SE3d T_w_i; + + int64_t id = kv_kpt.second.kf_id.first; + if (frame_states.count(id) > 0) { + PoseVelBiasStateWithLin state = frame_states.at(id); + T_w_i = state.getState().T_w_i; + } else if (frame_poses.count(id) > 0) { + PoseStateWithLin state = frame_poses.at(id); + + T_w_i = state.getPose(); + } else { + std::cout << "Unknown frame id: " << id << std::endl; + std::abort(); + } + + const Sophus::SE3d& T_i_c = calib.T_i_c[kv_kpt.second.kf_id.second]; + + // std::cerr << "T_w_i\n" << T_w_i.matrix() << std::endl; + + points.emplace_back(T_w_i * T_i_c * pt_cam); + + ids.emplace_back(kv_kpt.first); + } +} + +Eigen::Vector4d BundleAdjustmentBase::triangulate(const Eigen::Vector3d& p0_3d, + const Eigen::Vector3d& p1_3d, + const Sophus::SE3d& T_0_1) { + Eigen::Vector3d p1_3d_unrotated = T_0_1.so3() * p1_3d; + Eigen::Vector2d b; + b[0] = T_0_1.translation().dot(p0_3d); + b[1] = T_0_1.translation().dot(p1_3d_unrotated); + Eigen::Matrix2d A; + A(0, 0) = p0_3d.dot(p0_3d); + A(1, 0) = p0_3d.dot(p1_3d_unrotated); + A(0, 1) = -A(1, 0); + A(1, 1) = -p1_3d_unrotated.dot(p1_3d_unrotated); + Eigen::Vector2d lambda = A.inverse() * b; + Eigen::Vector3d xm = lambda[0] * p0_3d; + Eigen::Vector3d xn = T_0_1.translation() + lambda[1] * p1_3d_unrotated; + + Eigen::Vector4d p0_triangulated; + p0_triangulated.head<3>() = (xm + xn) / 2; + p0_triangulated[3] = 0; + + return p0_triangulated; +} + +void BundleAdjustmentBase::marginalizeHelper(Eigen::MatrixXd& abs_H, + Eigen::VectorXd& abs_b, + const std::set& idx_to_keep, + const std::set& idx_to_marg, + Eigen::MatrixXd& marg_H, + Eigen::VectorXd& marg_b) { + int keep_size = idx_to_keep.size(); + int marg_size = idx_to_marg.size(); + + BASALT_ASSERT(keep_size + marg_size == abs_H.cols()); + + // Fill permutation matrix + Eigen::Matrix indices(idx_to_keep.size() + + idx_to_marg.size()); + + { + auto it = idx_to_keep.begin(); + for (size_t i = 0; i < idx_to_keep.size(); i++) { + indices[i] = *it; + it++; + } + } + + { + auto it = idx_to_marg.begin(); + for (size_t i = 0; i < idx_to_marg.size(); i++) { + indices[idx_to_keep.size() + i] = *it; + it++; + } + } + + const Eigen::PermutationWrapper> p( + indices); + + const Eigen::PermutationMatrix pt = p.transpose(); + + abs_b.applyOnTheLeft(pt); + abs_H.applyOnTheLeft(pt); + abs_H.applyOnTheRight(p); + + Eigen::MatrixXd H_mm_inv; + // H_mm_inv.setIdentity(marg_size, marg_size); + // abs_H.bottomRightCorner(marg_size, + // marg_size).ldlt().solveInPlace(H_mm_inv); + + H_mm_inv = abs_H.bottomRightCorner(marg_size, marg_size) + .fullPivLu() + .solve(Eigen::MatrixXd::Identity(marg_size, marg_size)); + + // H_mm_inv = abs_H.bottomRightCorner(marg_size, marg_size) + // .fullPivHouseholderQr() + // .solve(Eigen::MatrixXd::Identity(marg_size, marg_size)); + + abs_H.topRightCorner(keep_size, marg_size) *= H_mm_inv; + + marg_H = abs_H.topLeftCorner(keep_size, keep_size); + marg_b = abs_b.head(keep_size); + + marg_H -= abs_H.topRightCorner(keep_size, marg_size) * + abs_H.bottomLeftCorner(marg_size, keep_size); + marg_b -= abs_H.topRightCorner(keep_size, marg_size) * abs_b.tail(marg_size); + + abs_H.resize(0, 0); + abs_b.resize(0); +} +} diff --git a/src/vi_estimator/keypoint_vio.cpp b/src/vi_estimator/keypoint_vio.cpp new file mode 100644 index 0000000..19da9b0 --- /dev/null +++ b/src/vi_estimator/keypoint_vio.cpp @@ -0,0 +1,1054 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +#include +#include +#include + +#include + +namespace basalt { + +KeypointVioEstimator::KeypointVioEstimator( + int64_t t_ns, const Sophus::SE3d& T_w_i, const Eigen::Vector3d& vel_w_i, + const Eigen::Vector3d& bg, const Eigen::Vector3d& ba, double int_std_dev, + const Eigen::Vector3d& g, const basalt::Calibration& calib, + const VioConfig& config) + : take_kf(true), frames_after_kf(0), g(g), config(config) { + this->obs_std_dev = config.vio_obs_std_dev; + this->huber_thresh = config.vio_obs_huber_thresh; + this->calib = calib; + + last_state_t_ns = t_ns; + + imu_meas[t_ns] = IntegratedImuMeasurement(t_ns, bg, ba); + frame_states[t_ns] = + PoseVelBiasStateWithLin(t_ns, T_w_i, vel_w_i, bg, ba, true); + + // Setup marginalization + marg_H.setZero(POSE_VEL_BIAS_SIZE, POSE_VEL_BIAS_SIZE); + marg_b.setZero(POSE_VEL_BIAS_SIZE); + + // prior on position + marg_H.diagonal().head<3>().setConstant(prior_weight); + // prior on yaw + marg_H(5, 5) = prior_weight; + + // small prior to avoid jumps in bias + marg_H.diagonal().segment<3>(9).array() = 1e1; + marg_H.diagonal().segment<3>(12).array() = 1e2; + + std::cout << "marg_H\n" << marg_H << std::endl; + + marg_order.abs_order_map[t_ns] = std::make_pair(0, POSE_VEL_BIAS_SIZE); + marg_order.total_size = POSE_VEL_BIAS_SIZE; + marg_order.items = 1; + + gyro_bias_weight.setConstant(1.0 / + (calib.gyro_bias_std * calib.gyro_bias_std)); + accel_bias_weight.setConstant(1.0 / + (calib.accel_bias_std * calib.accel_bias_std)); + + max_states = std::numeric_limits::max(); + max_kfs = std::numeric_limits::max(); + + opt_started = false; + + vision_data_queue.set_capacity(10); + imu_data_queue.set_capacity(300); + + auto proc_func = [&] { + OpticalFlowResult::Ptr prev_frame, curr_frame; + IntegratedImuMeasurement::Ptr meas; + + ImuData::Ptr data; + imu_data_queue.pop(data); + + while (true) { + vision_data_queue.pop(curr_frame); + + if (!curr_frame.get()) { + break; + } + + if (prev_frame) { + // preintegrate measurements + + auto last_state = frame_states.at(last_state_t_ns); + + meas.reset(new IntegratedImuMeasurement( + prev_frame->t_ns, last_state.getState().bias_gyro, + last_state.getState().bias_accel)); + + while (data->t_ns <= prev_frame->t_ns) { + imu_data_queue.pop(data); + + if (!data.get()) break; + } + + while (data->t_ns <= curr_frame->t_ns) { + meas->integrate(*data); + imu_data_queue.pop(data); + if (!data.get()) break; + } + + if (meas->get_start_t_ns() + meas->get_dt_ns() < curr_frame->t_ns) { + int64_t tmp = data->t_ns; + data->t_ns = curr_frame->t_ns; + meas->integrate(*data); + data->t_ns = tmp; + } + } + + measure(curr_frame, meas); + prev_frame = curr_frame; + } + + if (out_vis_queue) out_vis_queue->push(nullptr); + if (out_marg_queue) out_marg_queue->push(nullptr); + if (out_state_queue) out_state_queue->push(nullptr); + + finished = true; + + std::cout << "Finished VIOFilter " << std::endl; + }; + + processing_thread.reset(new std::thread(proc_func)); +} + +void KeypointVioEstimator::addIMUToQueue(const ImuData::Ptr& data) { + imu_data_queue.emplace(data); +} + +void KeypointVioEstimator::addVisionToQueue( + const OpticalFlowResult::Ptr& data) { + vision_data_queue.push(data); +} + +bool KeypointVioEstimator::measure(const OpticalFlowResult::Ptr& opt_flow_meas, + const IntegratedImuMeasurement::Ptr& meas) { + if (meas.get()) { + BASALT_ASSERT(frame_states[last_state_t_ns].getState().t_ns == + meas->get_start_t_ns()); + BASALT_ASSERT(opt_flow_meas->t_ns == + meas->get_dt_ns() + meas->get_start_t_ns()); + + PoseVelBiasState next_state = frame_states.at(last_state_t_ns).getState(); + + meas->predictState(frame_states.at(last_state_t_ns).getState(), g, + next_state); + + last_state_t_ns = opt_flow_meas->t_ns; + next_state.t_ns = opt_flow_meas->t_ns; + + frame_states[last_state_t_ns] = next_state; + + imu_meas[meas->get_start_t_ns()] = *meas; + } + + // save results + prev_opt_flow_res[opt_flow_meas->t_ns] = opt_flow_meas; + + // Make new residual for existing keypoints + int connected0 = 0; + std::map num_points_connected; + std::unordered_set unconnected_obs0; + for (size_t i = 0; i < opt_flow_meas->observations.size(); i++) { + TimeCamId tcid_target(opt_flow_meas->t_ns, i); + + for (const auto& kv_obs : opt_flow_meas->observations[i]) { + int kpt_id = kv_obs.first; + + auto it = kpts.find(kpt_id); + if (it != kpts.end()) { + const TimeCamId& tcid_host = it->second.kf_id; + + KeypointObservation kobs; + kobs.kpt_id = kpt_id; + kobs.pos = kv_obs.second.translation().cast(); + + obs[tcid_host][tcid_target].push_back(kobs); + + if (num_points_connected.count(tcid_host.first) == 0) { + num_points_connected[tcid_host.first] = 0; + } + num_points_connected[tcid_host.first]++; + + if (i == 0) connected0++; + } else { + if (i == 0) { + unconnected_obs0.emplace(kpt_id); + } + } + } + } + + if (double(connected0) / (connected0 + unconnected_obs0.size()) < + config.vio_new_kf_keypoints_thresh && + frames_after_kf > config.vio_min_frames_after_kf) + take_kf = true; + + if (config.vio_debug) { + std::cout << "connected0 " << connected0 << " unconnected0 " + << unconnected_obs0.size() << std::endl; + } + + if (take_kf) { + // Triangulate new points from stereo and make keyframe for camera 0 + take_kf = false; + frames_after_kf = 0; + kf_ids.emplace(last_state_t_ns); + + TimeCamId tcidl(opt_flow_meas->t_ns, 0); + + int num_points_added = 0; + for (int lm_id : unconnected_obs0) { + // Find all observations + std::map kp_obs; + + for (const auto& kv : prev_opt_flow_res) { + for (size_t k = 0; k < kv.second->observations.size(); k++) { + auto it = kv.second->observations[k].find(lm_id); + if (it != kv.second->observations[k].end()) { + TimeCamId tcido(kv.first, k); + + KeypointObservation kobs; + kobs.kpt_id = lm_id; + kobs.pos = it->second.translation().cast(); + + // obs[tcidl][tcido].push_back(kobs); + kp_obs[tcido] = kobs; + } + } + } + + // triangulate + bool valid_kp = false; + for (const auto& kv_obs : kp_obs) { + if (valid_kp) break; + TimeCamId tcido = kv_obs.first; + + const Eigen::Vector2d p0 = opt_flow_meas->observations.at(0) + .at(lm_id) + .translation() + .cast(); + const Eigen::Vector2d p1 = prev_opt_flow_res[tcido.first] + ->observations[tcido.second] + .at(lm_id) + .translation() + .cast(); + + Eigen::Vector4d p0_3d, p1_3d; + bool valid1 = calib.intrinsics[0].unproject(p0, p0_3d); + bool valid2 = calib.intrinsics[tcido.second].unproject(p1, p1_3d); + if (!valid1 || !valid2) continue; + + Sophus::SE3d T_i0_i1 = + getPoseStateWithLin(tcidl.first).getPose().inverse() * + getPoseStateWithLin(tcido.first).getPose(); + Sophus::SE3d T_0_1 = + calib.T_i_c[0].inverse() * T_i0_i1 * calib.T_i_c[tcido.second]; + + if (T_0_1.translation().squaredNorm() < 0.03 * 0.03) continue; + + Eigen::Vector4d p0_triangulated = + triangulate(p0_3d.head<3>(), p1_3d.head<3>(), T_0_1); + + if (p0_triangulated[2] > 0) { + KeypointPosition kpt_pos; + kpt_pos.kf_id = tcidl; + kpt_pos.dir = StereographicParam::project(p0_triangulated); + kpt_pos.id = 1.0 / p0_triangulated.norm(); + + if (kpt_pos.id > 0 && kpt_pos.id < 10) { + kpts[lm_id] = kpt_pos; + + num_points_added++; + valid_kp = true; + } + } + } + + if (valid_kp) { + for (const auto& kv_obs : kp_obs) { + obs[tcidl][kv_obs.first].push_back(kv_obs.second); + } + } + } + + num_points_kf[opt_flow_meas->t_ns] = num_points_added; + } else { + frames_after_kf++; + } + + optimize(); + marginalize(num_points_connected); + + if (out_state_queue) { + PoseVelBiasStateWithLin p = frame_states.at(last_state_t_ns); + + PoseVelBiasState::Ptr data(new PoseVelBiasState(p.getState())); + + out_state_queue->push(data); + } + + if (out_vis_queue) { + VioVisualizationData::Ptr data(new VioVisualizationData); + + data->t_ns = last_state_t_ns; + + for (const auto& kv : frame_states) { + data->states.emplace_back(kv.second.getState().T_w_i); + } + + for (const auto& kv : frame_poses) { + data->frames.emplace_back(kv.second.getPose()); + } + + get_current_points(data->points, data->point_ids); + + data->projections.resize(opt_flow_meas->observations.size()); + computeProjections(data->projections); + + out_vis_queue->push(data); + } + + last_processed_t_ns = last_state_t_ns; + + return true; +} + +Eigen::VectorXd KeypointVioEstimator::checkNullspace( + const Eigen::MatrixXd& H, const Eigen::VectorXd& b, + const AbsOrderMap& order, + const Eigen::map& frame_states, + const Eigen::map& frame_poses) { + BASALT_ASSERT(size_t(H.cols()) == order.total_size); + size_t marg_size = order.total_size; + + Eigen::VectorXd inc_x, inc_y, inc_z, inc_roll, inc_pitch, inc_yaw; + inc_x.setZero(marg_size); + inc_y.setZero(marg_size); + inc_z.setZero(marg_size); + inc_roll.setZero(marg_size); + inc_pitch.setZero(marg_size); + inc_yaw.setZero(marg_size); + + int num_trans = 0; + Eigen::Vector3d mean_trans; + mean_trans.setZero(); + + // Compute mean translation + for (const auto& kv : order.abs_order_map) { + Eigen::Vector3d trans; + if (kv.second.second == POSE_SIZE) { + mean_trans += frame_poses.at(kv.first).getPoseLin().translation(); + num_trans++; + } else if (kv.second.second == POSE_VEL_BIAS_SIZE) { + mean_trans += frame_states.at(kv.first).getStateLin().T_w_i.translation(); + num_trans++; + } else { + std::cerr << "Unknown size of the state: " << kv.second.second + << std::endl; + std::abort(); + } + } + mean_trans /= num_trans; + + double eps = 0.01; + + // Compute nullspace increments + for (const auto& kv : order.abs_order_map) { + inc_x(kv.second.first + 0) = eps; + inc_y(kv.second.first + 1) = eps; + inc_z(kv.second.first + 2) = eps; + inc_roll(kv.second.first + 3) = eps; + inc_pitch(kv.second.first + 4) = eps; + inc_yaw(kv.second.first + 5) = eps; + + Eigen::Vector3d trans; + if (kv.second.second == POSE_SIZE) { + trans = frame_poses.at(kv.first).getPoseLin().translation(); + } else if (kv.second.second == POSE_VEL_BIAS_SIZE) { + trans = frame_states.at(kv.first).getStateLin().T_w_i.translation(); + } else { + BASALT_ASSERT(false); + } + + trans -= mean_trans; + + Eigen::Matrix3d J = -Sophus::SO3d::hat(trans); + J *= eps; + + inc_roll.segment<3>(kv.second.first) = J.col(0); + inc_pitch.segment<3>(kv.second.first) = J.col(1); + inc_yaw.segment<3>(kv.second.first) = J.col(2); + + if (kv.second.second == POSE_VEL_BIAS_SIZE) { + Eigen::Vector3d vel = frame_states.at(kv.first).getStateLin().vel_w_i; + Eigen::Matrix3d J_vel = -Sophus::SO3d::hat(vel); + J_vel *= eps; + + inc_roll.segment<3>(kv.second.first + POSE_SIZE) = J_vel.col(0); + inc_pitch.segment<3>(kv.second.first + POSE_SIZE) = J_vel.col(1); + inc_yaw.segment<3>(kv.second.first + POSE_SIZE) = J_vel.col(2); + } + } + + inc_x.normalize(); + inc_y.normalize(); + inc_z.normalize(); + inc_roll.normalize(); + inc_pitch.normalize(); + inc_yaw.normalize(); + + // std::cout << "inc_x " << inc_x.transpose() << std::endl; + // std::cout << "inc_y " << inc_y.transpose() << std::endl; + // std::cout << "inc_z " << inc_z.transpose() << std::endl; + // std::cout << "inc_yaw " << inc_yaw.transpose() << std::endl; + + Eigen::VectorXd inc_random; + inc_random.setRandom(marg_size); + inc_random.normalize(); + + Eigen::VectorXd xHx(7), xb(7); + xHx[0] = 0.5 * inc_x.transpose() * H * inc_x; + xHx[1] = 0.5 * inc_y.transpose() * H * inc_y; + xHx[2] = 0.5 * inc_z.transpose() * H * inc_z; + xHx[3] = 0.5 * inc_roll.transpose() * H * inc_roll; + xHx[4] = 0.5 * inc_pitch.transpose() * H * inc_pitch; + xHx[5] = 0.5 * inc_yaw.transpose() * H * inc_yaw; + xHx[6] = 0.5 * inc_random.transpose() * H * inc_random; + + xb[0] = inc_x.transpose() * b; + xb[1] = inc_y.transpose() * b; + xb[2] = inc_z.transpose() * b; + xb[3] = inc_roll.transpose() * b; + xb[4] = inc_pitch.transpose() * b; + xb[5] = inc_yaw.transpose() * b; + xb[6] = inc_random.transpose() * b; + + std::cout << "nullspace x_trans: " << xHx[0] << " + " << xb[0] << std::endl; + std::cout << "nullspace y_trans: " << xHx[1] << " + " << xb[1] << std::endl; + std::cout << "nullspace z_trans: " << xHx[2] << " + " << xb[2] << std::endl; + std::cout << "nullspace roll : " << xHx[3] << " + " << xb[3] << std::endl; + std::cout << "nullspace pitch : " << xHx[4] << " + " << xb[4] << std::endl; + std::cout << "nullspace yaw : " << xHx[5] << " + " << xb[5] << std::endl; + std::cout << "nullspace random : " << xHx[6] << " + " << xb[6] << std::endl; + + return xHx + xb; +} + +void KeypointVioEstimator::checkMargNullspace() const { + checkNullspace(marg_H, marg_b, marg_order, frame_states, frame_poses); +} + +void KeypointVioEstimator::marginalize( + const std::map& num_points_connected) { + if (!opt_started) return; + + if (frame_poses.size() > max_kfs || frame_states.size() >= max_states) { + // Marginalize + + const int states_to_remove = frame_states.size() - max_states + 1; + + auto it = frame_states.cbegin(); + for (int i = 0; i < states_to_remove; i++) it++; + int64_t last_state_to_marg = it->first; + + AbsOrderMap aom; + + // remove all frame_poses that are not kfs + std::set poses_to_marg; + for (const auto& kv : frame_poses) { + aom.abs_order_map[kv.first] = std::make_pair(aom.total_size, POSE_SIZE); + + if (kf_ids.count(kv.first) == 0) poses_to_marg.emplace(kv.first); + + // Check that we have the same order as marginalization + BASALT_ASSERT(marg_order.abs_order_map.at(kv.first) == + aom.abs_order_map.at(kv.first)); + + aom.total_size += POSE_SIZE; + aom.items++; + } + + std::set states_to_marg_vel_bias; + std::set states_to_marg_all; + for (const auto& kv : frame_states) { + if (kv.first > last_state_to_marg) break; + + if (kv.first != last_state_to_marg) { + if (kf_ids.count(kv.first) > 0) { + states_to_marg_vel_bias.emplace(kv.first); + } else { + states_to_marg_all.emplace(kv.first); + } + } + + aom.abs_order_map[kv.first] = + std::make_pair(aom.total_size, POSE_VEL_BIAS_SIZE); + + // Check that we have the same order as marginalization + if (aom.items < marg_order.abs_order_map.size()) + BASALT_ASSERT(marg_order.abs_order_map.at(kv.first) == + aom.abs_order_map.at(kv.first)); + + aom.total_size += POSE_VEL_BIAS_SIZE; + aom.items++; + } + + auto kf_ids_all = kf_ids; + std::set kfs_to_marg; + while (kf_ids.size() > max_kfs && !states_to_marg_vel_bias.empty()) { + int64_t id_to_marg = -1; + + { + std::vector ids; + for (int64_t id : kf_ids) { + ids.push_back(id); + } + + for (size_t i = 0; i < ids.size() - 2; i++) { + if (num_points_connected.count(ids[i]) == 0 || + (num_points_connected.at(ids[i]) / num_points_kf.at(ids[i]) < + 0.05)) { + id_to_marg = ids[i]; + break; + } + } + } + + if (id_to_marg < 0) { + std::vector ids; + for (int64_t id : kf_ids) { + ids.push_back(id); + } + + int64_t last_kf = *kf_ids.crbegin(); + double min_score = std::numeric_limits::max(); + int64_t min_score_id = -1; + + for (size_t i = 0; i < ids.size() - 2; i++) { + double denom = 0; + for (size_t j = 0; j < ids.size() - 2; j++) { + denom += 1 / ((frame_poses.at(ids[i]).getPose().translation() - + frame_poses.at(ids[j]).getPose().translation()) + .norm() + + 1e-5); + } + + double score = + std::sqrt( + (frame_poses.at(ids[i]).getPose().translation() - + frame_states.at(last_kf).getState().T_w_i.translation()) + .norm()) * + denom; + + if (score < min_score) { + min_score_id = ids[i]; + min_score = score; + } + } + + id_to_marg = min_score_id; + } + + kfs_to_marg.emplace(id_to_marg); + poses_to_marg.emplace(id_to_marg); + + kf_ids.erase(id_to_marg); + } + + // std::cout << "marg order" << std::endl; + // aom.print_order(); + + // std::cout << "marg prior order" << std::endl; + // marg_order.print_order(); + + if (config.vio_debug) { + std::cout << "states_to_remove " << states_to_remove << std::endl; + std::cout << "poses_to_marg.size() " << poses_to_marg.size() << std::endl; + std::cout << "states_to_marg.size() " << states_to_marg_all.size() + << std::endl; + std::cout << "state_to_marg_vel_bias.size() " + << states_to_marg_vel_bias.size() << std::endl; + std::cout << "kfs_to_marg.size() " << kfs_to_marg.size() << std::endl; + } + + size_t asize = aom.total_size; + + double marg_prior_error; + double imu_error, bg_error, ba_error; + + DenseAccumulator accum; + accum.reset(asize); + + { + // Linearize points + + Eigen::map>> + obs_to_lin; + + for (auto it = obs.cbegin(); it != obs.cend();) { + if (kfs_to_marg.count(it->first.first) > 0) { + for (auto it2 = it->second.cbegin(); it2 != it->second.cend(); + ++it2) { + if (it2->first.first <= last_state_to_marg) + obs_to_lin[it->first].emplace(*it2); + } + it = obs.erase(it); + } else { + ++it; + } + } + + double rld_error; + Eigen::vector rld_vec; + + linearizeHelper(rld_vec, obs_to_lin, rld_error); + + for (auto& rld : rld_vec) { + rld.invert_keypoint_hessians(); + + Eigen::MatrixXd rel_H; + Eigen::VectorXd rel_b; + linearizeRel(rld, rel_H, rel_b); + + linearizeAbs(rel_H, rel_b, rld, aom, accum); + } + + // remove points + for (auto it = kpts.cbegin(); it != kpts.cend();) { + if (kfs_to_marg.count(it->second.kf_id.first) > 0) { + it = kpts.erase(it); + } else { + ++it; + } + } + } + + linearizeAbsIMU(aom, accum.getH(), accum.getB(), imu_error, bg_error, + ba_error, frame_states, imu_meas, gyro_bias_weight, + accel_bias_weight, g); + linearizeMargPrior(aom, accum.getH(), accum.getB(), marg_prior_error); + + // Save marginalization prior + if (out_marg_queue && !kfs_to_marg.empty()) { + // int64_t kf_id = *kfs_to_marg.begin(); + + { + MargData::Ptr m(new MargData); + m->aom = aom; + m->abs_H = accum.getH(); + m->abs_b = accum.getB(); + m->frame_poses = frame_poses; + m->frame_states = frame_states; + m->kfs_all = kf_ids_all; + m->kfs_to_marg = kfs_to_marg; + + for (int64_t t : m->kfs_all) { + m->opt_flow_res.emplace_back(prev_opt_flow_res.at(t)); + } + + out_marg_queue->push(m); + } + } + + std::set idx_to_keep, idx_to_marg; + for (const auto& kv : aom.abs_order_map) { + if (kv.second.second == POSE_SIZE) { + int start_idx = kv.second.first; + if (poses_to_marg.count(kv.first) == 0) { + for (size_t i = 0; i < POSE_SIZE; i++) + idx_to_keep.emplace(start_idx + i); + } else { + for (size_t i = 0; i < POSE_SIZE; i++) + idx_to_marg.emplace(start_idx + i); + } + } else { + BASALT_ASSERT(kv.second.second == POSE_VEL_BIAS_SIZE); + // state + int start_idx = kv.second.first; + if (states_to_marg_all.count(kv.first) > 0) { + for (size_t i = 0; i < POSE_VEL_BIAS_SIZE; i++) + idx_to_marg.emplace(start_idx + i); + } else if (states_to_marg_vel_bias.count(kv.first) > 0) { + for (size_t i = 0; i < POSE_SIZE; i++) + idx_to_keep.emplace(start_idx + i); + for (size_t i = POSE_SIZE; i < POSE_VEL_BIAS_SIZE; i++) + idx_to_marg.emplace(start_idx + i); + } else { + BASALT_ASSERT(kv.first == last_state_to_marg); + for (size_t i = 0; i < POSE_VEL_BIAS_SIZE; i++) + idx_to_keep.emplace(start_idx + i); + } + } + } + + if (config.vio_debug) { + std::cout << "keeping " << idx_to_keep.size() << " marg " + << idx_to_marg.size() << " total " << asize << std::endl; + std::cout << "last_state_to_marg " << last_state_to_marg + << " frame_poses " << frame_poses.size() << " frame_states " + << frame_states.size() << std::endl; + } + + Eigen::MatrixXd marg_H_new; + Eigen::VectorXd marg_b_new; + marginalizeHelper(accum.getH(), accum.getB(), idx_to_keep, idx_to_marg, + marg_H_new, marg_b_new); + + { + BASALT_ASSERT(frame_states.at(last_state_to_marg).isLinearized() == + false); + frame_states.at(last_state_to_marg).setLinTrue(); + } + + for (const int64_t id : states_to_marg_all) { + frame_states.erase(id); + imu_meas.erase(id); + prev_opt_flow_res.erase(id); + } + + for (const int64_t id : states_to_marg_vel_bias) { + const PoseVelBiasStateWithLin& state = frame_states.at(id); + PoseStateWithLin pose(state); + + frame_poses[id] = pose; + frame_states.erase(id); + imu_meas.erase(id); + } + + for (const int64_t id : poses_to_marg) { + frame_poses.erase(id); + prev_opt_flow_res.erase(id); + } + + for (auto it = obs.begin(); it != obs.end(); ++it) { + for (auto it2 = it->second.cbegin(); it2 != it->second.cend();) { + if (poses_to_marg.count(it2->first.first) > 0 || + states_to_marg_all.count(it2->first.first) > 0) { + it2 = it->second.erase(it2); + } else { + ++it2; + } + } + } + + AbsOrderMap marg_order_new; + + for (const auto& kv : frame_poses) { + marg_order_new.abs_order_map[kv.first] = + std::make_pair(marg_order_new.total_size, POSE_SIZE); + + marg_order_new.total_size += POSE_SIZE; + marg_order_new.items++; + } + + { + marg_order_new.abs_order_map[last_state_to_marg] = + std::make_pair(marg_order_new.total_size, POSE_VEL_BIAS_SIZE); + marg_order_new.total_size += POSE_VEL_BIAS_SIZE; + marg_order_new.items++; + } + + marg_H = marg_H_new; + marg_b = marg_b_new; + marg_order = marg_order_new; + + BASALT_ASSERT(size_t(marg_H.cols()) == marg_order.total_size); + + Eigen::VectorXd delta; + computeDelta(marg_order, delta); + marg_b -= marg_H * delta; + + if (config.vio_debug) { + std::cout << "marginalizaon done!!" << std::endl; + + std::cout << "======== Marg nullspace ==========" << std::endl; + checkMargNullspace(); + std::cout << "=================================" << std::endl; + } + + // std::cout << "new marg prior order" << std::endl; + // marg_order.print_order(); + } +} + +void KeypointVioEstimator::computeDelta(const AbsOrderMap& marg_order, + Eigen::VectorXd& delta) const { + size_t marg_size = marg_order.total_size; + delta.setZero(marg_size); + for (const auto& kv : marg_order.abs_order_map) { + if (kv.second.second == POSE_SIZE) { + BASALT_ASSERT(frame_poses.at(kv.first).isLinearized()); + delta.segment(kv.second.first) = + frame_poses.at(kv.first).getDelta(); + } else if (kv.second.second == POSE_VEL_BIAS_SIZE) { + BASALT_ASSERT(frame_states.at(kv.first).isLinearized()); + delta.segment(kv.second.first) = + frame_states.at(kv.first).getDelta(); + } else { + BASALT_ASSERT(false); + } + } +} + +void KeypointVioEstimator::optimize() { + if (config.vio_debug) { + std::cout << "=================================" << std::endl; + } + + if (opt_started || frame_states.size() > 4) { + // Optimize + opt_started = true; + + AbsOrderMap aom; + + for (const auto& kv : frame_poses) { + aom.abs_order_map[kv.first] = std::make_pair(aom.total_size, POSE_SIZE); + + // Check that we have the same order as marginalization + BASALT_ASSERT(marg_order.abs_order_map.at(kv.first) == + aom.abs_order_map.at(kv.first)); + + aom.total_size += POSE_SIZE; + aom.items++; + } + + for (const auto& kv : frame_states) { + aom.abs_order_map[kv.first] = + std::make_pair(aom.total_size, POSE_VEL_BIAS_SIZE); + + // Check that we have the same order as marginalization + if (aom.items < marg_order.abs_order_map.size()) + BASALT_ASSERT(marg_order.abs_order_map.at(kv.first) == + aom.abs_order_map.at(kv.first)); + + aom.total_size += POSE_VEL_BIAS_SIZE; + aom.items++; + } + + // std::cout << "opt order" << std::endl; + // aom.print_order(); + + // std::cout << "marg prior order" << std::endl; + // marg_order.print_order(); + + for (int iter = 0; iter < config.vio_max_iterations; iter++) { + auto t1 = std::chrono::high_resolution_clock::now(); + + double rld_error; + Eigen::vector rld_vec; + linearizeHelper(rld_vec, obs, rld_error); + + BundleAdjustmentBase::LinearizeAbsReduce> lopt( + aom); + + tbb::blocked_range::iterator> range( + rld_vec.begin(), rld_vec.end()); + + tbb::parallel_reduce(range, lopt); + + double marg_prior_error = 0; + double imu_error = 0, bg_error = 0, ba_error = 0; + linearizeAbsIMU(aom, lopt.accum.getH(), lopt.accum.getB(), imu_error, + bg_error, ba_error, frame_states, imu_meas, + gyro_bias_weight, accel_bias_weight, g); + linearizeMargPrior(aom, lopt.accum.getH(), lopt.accum.getB(), + marg_prior_error); + + double error_total = + rld_error + imu_error + marg_prior_error + ba_error + bg_error; + + lopt.accum.getH().diagonal() *= 1.0001; + const Eigen::VectorXd inc = lopt.accum.solve(); + + // apply increment to poses + for (auto& kv : frame_poses) { + int idx = aom.abs_order_map.at(kv.first).first; + kv.second.applyInc(-inc.segment(idx)); + } + + // apply increment to states + for (auto& kv : frame_states) { + int idx = aom.abs_order_map.at(kv.first).first; + kv.second.applyInc(-inc.segment(idx)); + } + + // Update points + tbb::blocked_range keys_range(0, rld_vec.size()); + auto update_points_func = [&](const tbb::blocked_range& r) { + for (size_t i = r.begin(); i != r.end(); ++i) { + const auto& rld = rld_vec[i]; + updatePoints(aom, rld, inc); + } + }; + tbb::parallel_for(keys_range, update_points_func); + + if (config.vio_debug) { + double after_update_marg_prior_error = 0; + double after_update_vision_error = 0, after_update_imu_error = 0, + after_bg_error = 0, after_ba_error = 0; + + computeError(after_update_vision_error); + computeImuError(aom, after_update_imu_error, after_bg_error, + after_ba_error, frame_states, imu_meas, + gyro_bias_weight, accel_bias_weight, g); + computeMargPriorError(after_update_marg_prior_error); + + double after_error_total = + after_update_vision_error + after_update_imu_error + + after_update_marg_prior_error + after_bg_error + after_ba_error; + + double error_diff = error_total - after_error_total; + + auto t2 = std::chrono::high_resolution_clock::now(); + + auto elapsed = + std::chrono::duration_cast(t2 - t1); + + std::cout << "iter " << iter + << " before_update_error: vision: " << rld_error + << " imu: " << imu_error << " bg_error: " << bg_error + << " ba_error: " << ba_error + << " marg_prior: " << marg_prior_error + << " total: " << error_total << std::endl; + + std::cout << "iter " << iter << " after_update_error: vision: " + << after_update_vision_error + << " imu: " << after_update_imu_error + << " bg_error: " << after_bg_error + << " ba_error: " << after_ba_error + << " marg prior: " << after_update_marg_prior_error + << " total: " << after_error_total << " max_inc " + << inc.array().abs().maxCoeff() << " error_diff " + << error_diff << " time : " << elapsed.count() + << "(us), num_states " << frame_states.size() + << " num_poses " << frame_poses.size() << std::endl; + + if (after_error_total > error_total) { + std::cout << "increased error after update!!!" << std::endl; + } + } + + if (inc.array().abs().maxCoeff() < 1e-4) break; + + // std::cerr << "LT\n" << LT << std::endl; + // std::cerr << "z_p\n" << z_p.transpose() << std::endl; + // std::cerr << "inc\n" << inc.transpose() << std::endl; + } + } + + if (config.vio_debug) { + std::cout << "=================================" << std::endl; + } +} + +void KeypointVioEstimator::computeProjections( + std::vector>& data) const { + for (const auto& kv : obs) { + const TimeCamId& tcid_h = kv.first; + + for (const auto& obs_kv : kv.second) { + const TimeCamId& tcid_t = obs_kv.first; + + if (tcid_t.first != last_state_t_ns) continue; + + if (tcid_h != tcid_t) { + PoseStateWithLin state_h = getPoseStateWithLin(tcid_h.first); + PoseStateWithLin state_t = getPoseStateWithLin(tcid_t.first); + + Sophus::SE3d T_t_h_sophus = + computeRelPose(state_h.getPose(), calib.T_i_c[tcid_h.second], + state_t.getPose(), calib.T_i_c[tcid_t.second]); + + Eigen::Matrix4d T_t_h = T_t_h_sophus.matrix(); + + FrameRelLinData rld; + + std::visit( + [&](const auto& cam) { + for (size_t i = 0; i < obs_kv.second.size(); i++) { + const KeypointObservation& kpt_obs = obs_kv.second[i]; + const KeypointPosition& kpt_pos = kpts.at(kpt_obs.kpt_id); + + Eigen::Vector2d res; + Eigen::Vector4d proj; + + linearizePoint(kpt_obs, kpt_pos, T_t_h, cam, res, nullptr, + nullptr, &proj); + + proj[3] = kpt_obs.kpt_id; + data[tcid_t.second].emplace_back(proj); + } + }, + calib.intrinsics[tcid_t.second].variant); + + } else { + // target and host are the same + // residual does not depend on the pose + // it just depends on the point + + std::visit( + [&](const auto& cam) { + for (size_t i = 0; i < obs_kv.second.size(); i++) { + const KeypointObservation& kpt_obs = obs_kv.second[i]; + const KeypointPosition& kpt_pos = kpts.at(kpt_obs.kpt_id); + + Eigen::Vector2d res; + Eigen::Vector4d proj; + + linearizePoint(kpt_obs, kpt_pos, Eigen::Matrix4d::Identity(), + cam, res, nullptr, nullptr, &proj); + + proj[3] = kpt_obs.kpt_id; + data[tcid_t.second].emplace_back(proj); + } + }, + calib.intrinsics[tcid_t.second].variant); + } + } + } +} + +} // namespace basalt diff --git a/src/vi_estimator/keypoint_vio_linearize.cpp b/src/vi_estimator/keypoint_vio_linearize.cpp new file mode 100644 index 0000000..8a68501 --- /dev/null +++ b/src/vi_estimator/keypoint_vio_linearize.cpp @@ -0,0 +1,266 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +namespace basalt { + +void KeypointVioEstimator::linearizeMargPrior(const AbsOrderMap& aom, + Eigen::MatrixXd& abs_H, + Eigen::VectorXd& abs_b, + double& marg_prior_error) const { + // Assumed to be in the top left corner + + BASALT_ASSERT(size_t(marg_H.cols()) == marg_order.total_size); + + size_t marg_size = marg_order.total_size; + abs_H.topLeftCorner(marg_size, marg_size) += marg_H; + + Eigen::VectorXd delta; + computeDelta(marg_order, delta); + + abs_b.head(marg_size) += marg_b; + abs_b.head(marg_size) += marg_H * delta; + + marg_prior_error = 0.5 * delta.transpose() * marg_H * delta; + marg_prior_error += delta.transpose() * marg_b; +} + +void KeypointVioEstimator::computeMargPriorError( + double& marg_prior_error) const { + BASALT_ASSERT(size_t(marg_H.cols()) == marg_order.total_size); + + Eigen::VectorXd delta; + computeDelta(marg_order, delta); + + marg_prior_error = 0.5 * delta.transpose() * marg_H * delta; + marg_prior_error += delta.transpose() * marg_b; +} + +void KeypointVioEstimator::linearizeAbsIMU( + const AbsOrderMap& aom, Eigen::MatrixXd& abs_H, Eigen::VectorXd& abs_b, + double& imu_error, double& bg_error, double& ba_error, + const Eigen::map& states, + const Eigen::map& imu_meas, + const Eigen::Vector3d& gyro_bias_weight, + const Eigen::Vector3d& accel_bias_weight, const Eigen::Vector3d& g) { + imu_error = 0; + bg_error = 0; + ba_error = 0; + for (const auto& kv : imu_meas) { + if (kv.second.get_dt_ns() != 0) { + int64_t start_t = kv.second.get_start_t_ns(); + int64_t end_t = kv.second.get_start_t_ns() + kv.second.get_dt_ns(); + + if (aom.abs_order_map.count(start_t) == 0 || + aom.abs_order_map.count(end_t) == 0) + continue; + + const size_t start_idx = aom.abs_order_map.at(start_t).first; + const size_t end_idx = aom.abs_order_map.at(end_t).first; + + PoseVelBiasStateWithLin start_state = states.at(start_t); + PoseVelBiasStateWithLin end_state = states.at(end_t); + + IntegratedImuMeasurement::MatNN d_res_d_start, d_res_d_end; + IntegratedImuMeasurement::MatN3 d_res_d_bg, d_res_d_ba; + + PoseVelState::VecN res = kv.second.residual( + start_state.getStateLin(), g, end_state.getStateLin(), + start_state.getStateLin().bias_gyro, + start_state.getStateLin().bias_accel, &d_res_d_start, &d_res_d_end, + &d_res_d_bg, &d_res_d_ba); + + if (start_state.isLinearized() || end_state.isLinearized()) { + res = + kv.second.residual(start_state.getState(), g, end_state.getState(), + start_state.getState().bias_gyro, + start_state.getState().bias_accel); + } + + // error + imu_error += 0.5 * res.transpose() * kv.second.get_cov_inv() * res; + + // states + abs_H.block<9, 9>(start_idx, start_idx) += + d_res_d_start.transpose() * kv.second.get_cov_inv() * d_res_d_start; + abs_H.block<9, 9>(start_idx, end_idx) += + d_res_d_start.transpose() * kv.second.get_cov_inv() * d_res_d_end; + abs_H.block<9, 9>(end_idx, start_idx) += + d_res_d_end.transpose() * kv.second.get_cov_inv() * d_res_d_start; + abs_H.block<9, 9>(end_idx, end_idx) += + d_res_d_end.transpose() * kv.second.get_cov_inv() * d_res_d_end; + + abs_b.segment<9>(start_idx) += + d_res_d_start.transpose() * kv.second.get_cov_inv() * res; + abs_b.segment<9>(end_idx) += + d_res_d_end.transpose() * kv.second.get_cov_inv() * res; + + // bias + IntegratedImuMeasurement::MatN6 d_res_d_bga; + d_res_d_bga.topLeftCorner<9, 3>() = d_res_d_bg; + d_res_d_bga.topRightCorner<9, 3>() = d_res_d_ba; + + abs_H.block<6, 6>(start_idx + 9, start_idx + 9) += + d_res_d_bga.transpose() * kv.second.get_cov_inv() * d_res_d_bga; + + abs_H.block<9, 6>(start_idx, start_idx + 9) += + d_res_d_start.transpose() * kv.second.get_cov_inv() * d_res_d_bga; + + abs_H.block<9, 6>(end_idx, start_idx + 9) += + d_res_d_end.transpose() * kv.second.get_cov_inv() * d_res_d_bga; + + abs_H.block<6, 9>(start_idx + 9, start_idx) += + d_res_d_bga.transpose() * kv.second.get_cov_inv() * d_res_d_start; + + abs_H.block<6, 9>(start_idx + 9, end_idx) += + d_res_d_bga.transpose() * kv.second.get_cov_inv() * d_res_d_end; + + abs_b.segment<6>(start_idx + 9) += + d_res_d_bga.transpose() * kv.second.get_cov_inv() * res; + + // difference between biases + double dt = kv.second.get_dt_ns() * 1e-9; + { + Eigen::Vector3d gyro_bias_weight_dt = gyro_bias_weight / dt; + + // std::cerr << "gyro_bias_weight_dt " << + // gyro_bias_weight_dt.transpose() + // << std::endl; + + Eigen::Vector3d res_bg = + start_state.getState().bias_gyro - end_state.getState().bias_gyro; + + abs_H.block<3, 3>(start_idx + 9, start_idx + 9) += + gyro_bias_weight_dt.asDiagonal(); + abs_H.block<3, 3>(end_idx + 9, end_idx + 9) += + gyro_bias_weight_dt.asDiagonal(); + + abs_H.block<3, 3>(end_idx + 9, start_idx + 9) -= + gyro_bias_weight_dt.asDiagonal(); + abs_H.block<3, 3>(start_idx + 9, end_idx + 9) -= + gyro_bias_weight_dt.asDiagonal(); + + abs_b.segment<3>(start_idx + 9) += + gyro_bias_weight_dt.asDiagonal() * res_bg; + abs_b.segment<3>(end_idx + 9) -= + gyro_bias_weight_dt.asDiagonal() * res_bg; + + bg_error += 0.5 * res_bg.transpose() * + gyro_bias_weight_dt.asDiagonal() * res_bg; + } + + { + Eigen::Vector3d accel_bias_weight_dt = accel_bias_weight / dt; + Eigen::Vector3d res_ba = + start_state.getState().bias_accel - end_state.getState().bias_accel; + + abs_H.block<3, 3>(start_idx + 12, start_idx + 12) += + accel_bias_weight_dt.asDiagonal(); + abs_H.block<3, 3>(end_idx + 12, end_idx + 12) += + accel_bias_weight_dt.asDiagonal(); + abs_H.block<3, 3>(end_idx + 12, start_idx + 12) -= + accel_bias_weight_dt.asDiagonal(); + abs_H.block<3, 3>(start_idx + 12, end_idx + 12) -= + accel_bias_weight_dt.asDiagonal(); + + abs_b.segment<3>(start_idx + 12) += + accel_bias_weight_dt.asDiagonal() * res_ba; + abs_b.segment<3>(end_idx + 12) -= + accel_bias_weight_dt.asDiagonal() * res_ba; + + ba_error += 0.5 * res_ba.transpose() * + accel_bias_weight_dt.asDiagonal() * res_ba; + } + } + } +} + +void KeypointVioEstimator::computeImuError( + const AbsOrderMap& aom, double& imu_error, double& bg_error, + double& ba_error, + const Eigen::map& states, + const Eigen::map& imu_meas, + const Eigen::Vector3d& gyro_bias_weight, + const Eigen::Vector3d& accel_bias_weight, const Eigen::Vector3d& g) { + imu_error = 0; + bg_error = 0; + ba_error = 0; + for (const auto& kv : imu_meas) { + if (kv.second.get_dt_ns() != 0) { + int64_t start_t = kv.second.get_start_t_ns(); + int64_t end_t = kv.second.get_start_t_ns() + kv.second.get_dt_ns(); + + if (aom.abs_order_map.count(start_t) == 0 || + aom.abs_order_map.count(end_t) == 0) + continue; + + PoseVelBiasStateWithLin start_state = states.at(start_t); + PoseVelBiasStateWithLin end_state = states.at(end_t); + + const PoseVelState::VecN res = kv.second.residual( + start_state.getState(), g, end_state.getState(), + start_state.getState().bias_gyro, start_state.getState().bias_accel); + + // std::cout << "res: (" << start_t << "," << end_t << ") " + // << res.transpose() << std::endl; + + // std::cerr << "cov_inv:\n" << kv.second.get_cov_inv() << + // std::endl; + + imu_error += 0.5 * res.transpose() * kv.second.get_cov_inv() * res; + + double dt = kv.second.get_dt_ns() * 1e-9; + { + Eigen::Vector3d gyro_bias_weight_dt = gyro_bias_weight / dt; + Eigen::Vector3d res_bg = + start_state.getState().bias_gyro - end_state.getState().bias_gyro; + + bg_error += 0.5 * res_bg.transpose() * + gyro_bias_weight_dt.asDiagonal() * res_bg; + } + + { + Eigen::Vector3d accel_bias_weight_dt = accel_bias_weight / dt; + Eigen::Vector3d res_ba = + start_state.getState().bias_accel - end_state.getState().bias_accel; + + ba_error += 0.5 * res_ba.transpose() * + accel_bias_weight_dt.asDiagonal() * res_ba; + } + } + } +} +} // namespace basalt diff --git a/src/vi_estimator/nfr_mapper.cpp b/src/vi_estimator/nfr_mapper.cpp new file mode 100644 index 0000000..863ce72 --- /dev/null +++ b/src/vi_estimator/nfr_mapper.cpp @@ -0,0 +1,675 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 +#include +#include + +#include + +namespace basalt { + +NfrMapper::NfrMapper(const Calibration& calib, const VioConfig& config, + const std::string& vocabulary) + : config(config) { + this->calib = calib; + this->obs_std_dev = config.mapper_obs_std_dev; + this->huber_thresh = config.mapper_obs_huber_thresh; + + if (!vocabulary.empty()) { + DBoW3::Vocabulary voc(vocabulary); + bow_database.setVocabulary(voc); + } +} + +void NfrMapper::addMargData(MargData::Ptr& data) { + for (const auto& kv : data->frame_poses) { + PoseStateWithLin p(kv.second.getT_ns(), kv.second.getPose()); + + frame_poses[kv.first] = p; + } + + for (const auto& kv : data->frame_states) { + if (data->kfs_all.count(kv.first) > 0) { + auto state = kv.second; + PoseStateWithLin p(state.getState().t_ns, state.getState().T_w_i); + frame_poses[kv.first] = p; + } + } + + processMargData(*data); + extractNonlinearFactors(*data); +} + +void NfrMapper::processMargData(MargData& m) { + BASALT_ASSERT(m.aom.total_size == size_t(m.abs_H.cols())); + + // std::cout << "rank " << m.abs_H.fullPivLu().rank() << " size " + // << m.abs_H.cols() << std::endl; + + AbsOrderMap aom_new; + std::set idx_to_keep; + std::set idx_to_marg; + + for (const auto& kv : m.aom.abs_order_map) { + if (kv.second.second == POSE_SIZE) { + for (size_t i = 0; i < POSE_SIZE; i++) + idx_to_keep.emplace(kv.second.first + i); + aom_new.abs_order_map.emplace(kv); + aom_new.total_size += POSE_SIZE; + } else if (kv.second.second == POSE_VEL_BIAS_SIZE) { + if (m.kfs_all.count(kv.first) > 0) { + for (size_t i = 0; i < POSE_SIZE; i++) + idx_to_keep.emplace(kv.second.first + i); + for (size_t i = POSE_SIZE; i < POSE_VEL_BIAS_SIZE; i++) + idx_to_marg.emplace(kv.second.first + i); + + aom_new.abs_order_map[kv.first] = + std::make_pair(aom_new.total_size, POSE_SIZE); + aom_new.total_size += POSE_SIZE; + + PoseStateWithLin p = m.frame_states.at(kv.first); + m.frame_poses[kv.first] = p; + m.frame_states.erase(kv.first); + } else { + for (size_t i = 0; i < POSE_VEL_BIAS_SIZE; i++) + idx_to_marg.emplace(kv.second.first + i); + m.frame_states.erase(kv.first); + } + } else { + std::cerr << "Unknown size" << std::endl; + std::abort(); + } + + // std::cout << kv.first << " " << kv.second.first << " " << + // kv.second.second + // << std::endl; + } + + Eigen::MatrixXd marg_H_new; + Eigen::VectorXd marg_b_new; + BundleAdjustmentBase::marginalizeHelper(m.abs_H, m.abs_b, idx_to_keep, + idx_to_marg, marg_H_new, marg_b_new); + + // std::cout << "new rank " << marg_H_new.fullPivLu().rank() << " size " + // << marg_H_new.cols() << std::endl; + + m.abs_H = marg_H_new; + m.abs_b = marg_b_new; + m.aom = aom_new; + + BASALT_ASSERT(m.aom.total_size == size_t(m.abs_H.cols())); + + // save image data + { + for (const auto& v : m.opt_flow_res) { + img_data[v->t_ns] = v->input_images; + } + } +} + +void NfrMapper::extractNonlinearFactors(MargData& m) { + size_t asize = m.aom.total_size; + // std::cout << "asize " << asize << std::endl; + + Eigen::MatrixXd cov_old; + cov_old.setIdentity(asize, asize); + m.abs_H.ldlt().solveInPlace(cov_old); + + int64_t kf_id = *m.kfs_to_marg.cbegin(); + int kf_start_idx = m.aom.abs_order_map.at(kf_id).first; + + auto state_kf = m.frame_poses.at(kf_id); + + Sophus::SE3d T_w_i_kf = state_kf.getPose(); + + Eigen::Vector3d pos = T_w_i_kf.translation(); + Eigen::Vector3d yaw_dir_body = + T_w_i_kf.so3().inverse() * Eigen::Vector3d::UnitX(); + + Sophus::Matrix d_pos_d_T_w_i; + Sophus::Matrix d_yaw_d_T_w_i; + Sophus::Matrix d_rp_d_T_w_i; + + absPositionError(T_w_i_kf, pos, &d_pos_d_T_w_i); + yawError(T_w_i_kf, yaw_dir_body, &d_yaw_d_T_w_i); + rollPitchError(T_w_i_kf, T_w_i_kf.so3(), &d_rp_d_T_w_i); + + { + Eigen::MatrixXd J; + J.setZero(POSE_SIZE, asize); + J.block<3, POSE_SIZE>(0, kf_start_idx) = d_pos_d_T_w_i; + J.block<1, POSE_SIZE>(3, kf_start_idx) = d_yaw_d_T_w_i; + J.block<2, POSE_SIZE>(4, kf_start_idx) = d_rp_d_T_w_i; + + Sophus::Matrix6d cov_new = J * cov_old * J.transpose(); + + // std::cout << "cov_new\n" << cov_new << std::endl; + + RollPitchFactor rpf; + rpf.t_ns = kf_id; + rpf.R_w_i_meas = T_w_i_kf.so3(); + rpf.cov_inv = cov_new.block<2, 2>(4, 4).inverse(); + + roll_pitch_factors.emplace_back(rpf); + } + + for (int64_t other_id : m.kfs_all) { + if (m.frame_poses.count(other_id) == 0 || other_id == kf_id) { + continue; + } + + auto state_o = m.frame_poses.at(other_id); + + Sophus::SE3d T_w_i_o = state_o.getPose(); + Sophus::SE3d T_kf_o = T_w_i_kf.inverse() * T_w_i_o; + + int o_start_idx = m.aom.abs_order_map.at(other_id).first; + + Sophus::Matrix6d d_res_d_T_w_i, d_res_d_T_w_j; + relPoseError(T_kf_o, T_w_i_kf, T_w_i_o, &d_res_d_T_w_i, &d_res_d_T_w_j); + + Eigen::MatrixXd J; + J.setZero(POSE_SIZE, asize); + J.block(0, kf_start_idx) = d_res_d_T_w_i; + J.block(0, o_start_idx) = d_res_d_T_w_j; + + Sophus::Matrix6d cov_new = J * cov_old * J.transpose(); + RelPoseFactor rpf; + rpf.t_i_ns = kf_id; + rpf.t_j_ns = other_id; + rpf.T_i_j = T_kf_o; + rpf.cov_inv.setIdentity(); + cov_new.ldlt().solveInPlace(rpf.cov_inv); + + // std::cout << "rpf.cov_inv\n" << rpf.cov_inv << std::endl; + + rel_pose_factors.emplace_back(rpf); + } +} + +void NfrMapper::optimize(int num_iterations) { + AbsOrderMap aom; + + for (const auto& kv : frame_poses) { + aom.abs_order_map[kv.first] = std::make_pair(aom.total_size, POSE_SIZE); + aom.total_size += POSE_SIZE; + } + + for (int iter = 0; iter < num_iterations; iter++) { + auto t1 = std::chrono::high_resolution_clock::now(); + + double rld_error; + Eigen::vector rld_vec; + linearizeHelper(rld_vec, obs, rld_error); + + // SparseHashAccumulator accum; + // accum.reset(aom.total_size); + + // for (auto& rld : rld_vec) { + // rld.invert_keypoint_hessians(); + + // Eigen::MatrixXd rel_H; + // Eigen::VectorXd rel_b; + // linearizeRel(rld, rel_H, rel_b); + + // linearizeAbs(rel_H, rel_b, rld, aom, accum); + // } + + MapperLinearizeAbsReduce> lopt(aom, + &frame_poses); + tbb::blocked_range::iterator> range( + rld_vec.begin(), rld_vec.end()); + tbb::blocked_range::const_iterator> range1( + roll_pitch_factors.begin(), roll_pitch_factors.end()); + tbb::blocked_range::const_iterator> range2( + rel_pose_factors.begin(), rel_pose_factors.end()); + + tbb::parallel_reduce(range, lopt); + tbb::parallel_reduce(range1, lopt); + tbb::parallel_reduce(range2, lopt); + + double error_total = rld_error + lopt.rel_error + lopt.roll_pitch_error; + + std::cout << "iter " << iter + << " before_update_error: vision: " << rld_error + << " rel_error: " << lopt.rel_error + << " roll_pitch_error: " << lopt.roll_pitch_error + << " total: " << error_total << std::endl; + + lopt.accum.iterative_solver = true; + lopt.accum.print_info = true; + + const Eigen::VectorXd inc = lopt.accum.solve(); + + // apply increment to poses + for (auto& kv : frame_poses) { + int idx = aom.abs_order_map.at(kv.first).first; + BASALT_ASSERT(!kv.second.isLinearized()); + kv.second.applyInc(-inc.segment(idx)); + } + + // Update points + tbb::blocked_range keys_range(0, rld_vec.size()); + auto update_points_func = [&](const tbb::blocked_range& r) { + for (size_t i = r.begin(); i != r.end(); ++i) { + const auto& rld = rld_vec[i]; + updatePoints(aom, rld, inc); + } + }; + tbb::parallel_for(keys_range, update_points_func); + + double after_update_vision_error = 0; + double after_rel_error = 0; + double after_roll_pitch_error = 0; + + computeError(after_update_vision_error); + computeRelPose(after_rel_error); + computeRollPitch(after_roll_pitch_error); + + double after_error_total = + after_update_vision_error + after_rel_error + after_roll_pitch_error; + + double error_diff = error_total - after_error_total; + + auto t2 = std::chrono::high_resolution_clock::now(); + + auto elapsed = + std::chrono::duration_cast(t2 - t1); + + std::cout << "iter " << iter + << " after_update_error: vision: " << after_update_vision_error + << " rel_error: " << after_rel_error + << " roll_pitch_error: " << after_roll_pitch_error + << " total: " << after_error_total << " max_inc " + << inc.array().abs().maxCoeff() << " error_diff " << error_diff + << " time : " << elapsed.count() << "(us), num_states " + << frame_states.size() << " num_poses " << frame_poses.size() + << std::endl; + + if (after_error_total > error_total) { + std::cout << "increased error after update!!!" << std::endl; + } + + if (inc.array().abs().maxCoeff() < 1e-4) break; + + // std::cerr << "LT\n" << LT << std::endl; + // std::cerr << "z_p\n" << z_p.transpose() << std::endl; + // std::cerr << "inc\n" << inc.transpose() << std::endl; + } +} + +Eigen::map& NfrMapper::getFramePoses() { + return frame_poses; +} + +void NfrMapper::computeRelPose(double& rel_error) { + rel_error = 0; + + for (const RelPoseFactor& rpf : rel_pose_factors) { + const Sophus::SE3d& pose_i = frame_poses.at(rpf.t_i_ns).getPose(); + const Sophus::SE3d& pose_j = frame_poses.at(rpf.t_j_ns).getPose(); + + Sophus::Vector6d res = relPoseError(rpf.T_i_j, pose_i, pose_j); + + rel_error += res.transpose() * rpf.cov_inv * res; + } +} + +void NfrMapper::computeRollPitch(double& roll_pitch_error) { + roll_pitch_error = 0; + + for (const RollPitchFactor& rpf : roll_pitch_factors) { + const Sophus::SE3d& pose = frame_poses.at(rpf.t_ns).getPose(); + + Sophus::Vector2d res = rollPitchError(pose, rpf.R_w_i_meas); + + roll_pitch_error += res.transpose() * rpf.cov_inv * res; + } +} + +void NfrMapper::detect_keypoints() { + std::vector keys; + for (const auto& kv : img_data) { + keys.emplace_back(kv.first); + } + + auto t1 = std::chrono::high_resolution_clock::now(); + + tbb::parallel_for( + tbb::blocked_range(0, keys.size()), + [&](const tbb::blocked_range& r) { + for (size_t j = r.begin(); j != r.end(); ++j) { + auto kv = img_data.find(keys[j]); + if (kv->second.get()) { + for (size_t i = 0; i < kv->second->img_data.size(); i++) { + TimeCamId tcid(kv->first, i); + KeypointsData kd; + + if (!kv->second->img_data[i].img.get()) continue; + + const Image img = + kv->second->img_data[i].img->Reinterpret(); + + detectKeypointsMapping(img, kd, + config.mapper_detection_num_points); + computeAngles(img, kd, true); + computeDescriptors(img, kd); + + std::vector success; + calib.intrinsics[tcid.second].unproject(kd.corners, kd.corners_3d, + success); + + feature_corners[tcid] = kd; + + auto& bow = bow_data[tcid]; + + if (bow_database.usingDirectIndex()) { + bow_database.getVocabulary()->transform( + kd.corner_descriptors, bow.first, bow.second, + bow_database.getDirectIndexLevels()); + } else { + bow_database.getVocabulary()->transform(kd.corner_descriptors, + bow.first); + } + } + } + } + }); + + auto t2 = std::chrono::high_resolution_clock::now(); + + for (const auto& kv : bow_data) { + int bow_id; + if (bow_database.usingDirectIndex()) { + bow_id = bow_database.add(kv.second.first, kv.second.second); + } else { + bow_id = bow_database.add(kv.second.first); + } + bow_id_to_tcid[bow_id] = kv.first; + } + + auto t3 = std::chrono::high_resolution_clock::now(); + + auto elapsed1 = + std::chrono::duration_cast(t2 - t1); + auto elapsed2 = + std::chrono::duration_cast(t3 - t2); + + std::cout << "Processed " << feature_corners.size() << " frames." + << std::endl; + + std::cout << "Detection time: " << elapsed1.count() * 1e-6 + << "s. Adding to DB time: " << elapsed2.count() * 1e-6 << "s." + << std::endl; +} + +void NfrMapper::match_stereo() { + // Pose of camera 1 (right) w.r.t camera 0 (left) + const Sophus::SE3d T_0_1 = calib.T_i_c[0].inverse() * calib.T_i_c[1]; + + // Essential matrix + Eigen::Matrix4d E; + computeEssential(T_0_1, E); + + std::cout << "Matching " << img_data.size() << " stereo pairs..." + << std::endl; + + int num_matches = 0; + int num_inliers = 0; + + for (const auto& kv : img_data) { + const TimeCamId tcid1(kv.first, 0), tcid2(kv.first, 1); + + MatchData md; + md.T_i_j = T_0_1; + + const KeypointsData& kd1 = feature_corners[tcid1]; + const KeypointsData& kd2 = feature_corners[tcid2]; + + matchDescriptors(kd1.corner_descriptors, kd2.corner_descriptors, md.matches, + config.mapper_max_hamming_distance, + config.mapper_second_best_test_ratio); + + num_matches += md.matches.size(); + + findInliersEssential(kd1, kd2, E, 1e-3, md); + + if (md.inliers.size() > 16) { + num_inliers += md.inliers.size(); + feature_matches[std::make_pair(tcid1, tcid2)] = md; + } + } + + std::cout << "Matched " << img_data.size() << " stereo pairs with " + << num_inliers << " inlier matches (" << num_matches << " total)." + << std::endl; +} + +void NfrMapper::match_all() { + std::vector keys; + std::unordered_map id_to_key_idx; + + for (const auto& kv : feature_corners) { + id_to_key_idx[kv.first] = keys.size(); + keys.push_back(kv.first); + } + + auto t1 = std::chrono::high_resolution_clock::now(); + + struct match_pair { + size_t i; + size_t j; + double score; + }; + + tbb::concurrent_vector ids_to_match; + + tbb::blocked_range keys_range(0, keys.size()); + auto compute_pairs = [&](const tbb::blocked_range& r) { + for (size_t i = r.begin(); i != r.end(); ++i) { + DBoW3::QueryResults q; + + auto it = bow_data.find(keys[i]); + + if (it != bow_data.end()) { + bow_database.query(it->second.first, q, + config.mapper_num_frames_to_match); + + for (const auto& r : q) { + // Match only previous frames + + size_t j = id_to_key_idx.at(bow_id_to_tcid.at(r.Id)); + if (r.Score > config.mapper_frames_to_match_threshold && + keys[i].first < keys[j].first) { + match_pair m; + m.i = i; + m.j = j; + m.score = r.Score; + + ids_to_match.emplace_back(m); + } + } + } + } + }; + + tbb::parallel_for(keys_range, compute_pairs); + + auto t2 = std::chrono::high_resolution_clock::now(); + + std::cout << "Matching " << ids_to_match.size() << " image pairs..." + << std::endl; + + std::atomic total_matched = 0; + + tbb::blocked_range range(0, ids_to_match.size()); + auto match_func = [&](const tbb::blocked_range& r) { + int matched = 0; + + for (size_t j = r.begin(); j != r.end(); ++j) { + const TimeCamId& id1 = keys[ids_to_match[j].i]; + const TimeCamId& id2 = keys[ids_to_match[j].j]; + + const KeypointsData& f1 = feature_corners[id1]; + const KeypointsData& f2 = feature_corners[id2]; + + MatchData md; + + matchDescriptors(f1.corner_descriptors, f2.corner_descriptors, md.matches, + 70, 1.2); + + if (int(md.matches.size()) > config.mapper_min_matches) { + matched++; + + findInliersRansac(f1, f2, config.mapper_ransac_threshold, + config.mapper_min_matches, md); + } + + if (!md.inliers.empty()) feature_matches[std::make_pair(id1, id2)] = md; + } + total_matched += matched; + }; + + tbb::parallel_for(range, match_func); + // match_func(range); + + auto t3 = std::chrono::high_resolution_clock::now(); + + auto elapsed1 = + std::chrono::duration_cast(t2 - t1); + auto elapsed2 = + std::chrono::duration_cast(t3 - t2); + + // + int num_matches = 0; + int num_inliers = 0; + + for (const auto& kv : feature_matches) { + num_matches += kv.second.matches.size(); + num_inliers += kv.second.inliers.size(); + } + + std::cout << "Matched " << ids_to_match.size() << " image pairs with " + << num_inliers << " inlier matches (" << num_matches << " total)." + << std::endl; + + std::cout << "DB query " << elapsed1.count() * 1e-6 << "s. matching " + << elapsed2.count() * 1e-6 + << "s. Geometric verification attemts: " << total_matched << "." + << std::endl; +} + +void NfrMapper::build_tracks() { + TrackBuilder trackBuilder; + // Build: Efficient fusion of correspondences + trackBuilder.Build(feature_matches); + // Filter: Remove tracks that have conflict + trackBuilder.Filter(config.mapper_min_track_length); + // Export tree to usable data structure + trackBuilder.Export(feature_tracks); + + // info + size_t inlier_match_count = 0; + for (const auto& it : feature_matches) { + inlier_match_count += it.second.inliers.size(); + } + + size_t total_track_obs_count = 0; + for (const auto& it : feature_tracks) { + total_track_obs_count += it.second.size(); + } + + std::cout << "Built " << feature_tracks.size() << " feature tracks from " + << inlier_match_count << " matches. Average track length is " + << total_track_obs_count / (double)feature_tracks.size() << "." + << std::endl; +} + +void NfrMapper::setup_opt() { + for (const auto& kv : feature_tracks) { + if (kv.second.size() < 2) continue; + + // Take first observation as host + auto it = kv.second.begin(); + TimeCamId tcid_h = it->first; + + FeatureId feat_id_h = it->second; + Eigen::Vector2d pos_2d_h = feature_corners.at(tcid_h).corners[feat_id_h]; + Eigen::Vector4d pos_3d_h; + calib.intrinsics[tcid_h.second].unproject(pos_2d_h, pos_3d_h); + + it++; + + for (; it != kv.second.end(); it++) { + TimeCamId tcid_o = it->first; + + FeatureId feat_id_o = it->second; + Eigen::Vector2d pos_2d_o = feature_corners.at(tcid_o).corners[feat_id_o]; + Eigen::Vector4d pos_3d_o; + calib.intrinsics[tcid_o.second].unproject(pos_2d_o, pos_3d_o); + + Sophus::SE3d T_w_h = + frame_poses.at(tcid_h.first).getPose() * calib.T_i_c[tcid_h.second]; + Sophus::SE3d T_w_o = + frame_poses.at(tcid_o.first).getPose() * calib.T_i_c[tcid_o.second]; + + Eigen::Vector4d pos_3d = triangulate( + pos_3d_h.head<3>(), pos_3d_o.head<3>(), T_w_h.inverse() * T_w_o); + + if (pos_3d[2] < 0.5 || pos_3d.norm() < 0.5) continue; + + KeypointPosition pos; + pos.kf_id = tcid_h; + pos.dir = StereographicParam::project(pos_3d); + pos.id = 1.0 / pos_3d.norm(); + + kpts[kv.first] = pos; + + for (const auto& obs_kv : kv.second) { + KeypointObservation ko; + ko.kpt_id = kv.first; + ko.pos = feature_corners.at(obs_kv.first).corners[obs_kv.second]; + + obs[tcid_h][obs_kv.first].emplace_back(ko); + } + break; + } + } +} + +} // namespace basalt diff --git a/src/vi_estimator/vio_estimator.cpp b/src/vi_estimator/vio_estimator.cpp new file mode 100644 index 0000000..dfd10b2 --- /dev/null +++ b/src/vi_estimator/vio_estimator.cpp @@ -0,0 +1,153 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 + +namespace basalt { + +VioEstimatorBase::Ptr VioEstimatorFactory::getVioEstimator( + const VioConfig& config, const Calibration& cam, int64_t t_ns, + const Sophus::SE3d& T_w_i, const Eigen::Vector3d& vel_w_i, + const Eigen::Vector3d& bg, const Eigen::Vector3d& ba, double int_std_dev, + const Eigen::Vector3d& g) { + KeypointVioEstimator::Ptr res; + + res.reset(new KeypointVioEstimator(t_ns, T_w_i, vel_w_i, bg, ba, int_std_dev, + g, cam, config)); + + res->setMaxKfs(config.vio_max_kfs); + res->setMaxStates(config.vio_max_states); + + return res; +} + +double alignSVD(const std::vector& filter_t_ns, + const Eigen::vector& filter_t_w_i, + const std::vector& gt_t_ns, + Eigen::vector& gt_t_w_i) { + Eigen::vector est_associations; + Eigen::vector gt_associations; + + for (size_t i = 0; i < filter_t_w_i.size(); i++) { + int64_t t_ns = filter_t_ns[i]; + + size_t j; + for (j = 0; j < gt_t_ns.size(); j++) { + if (gt_t_ns.at(j) > t_ns) break; + } + j--; + + if (j >= gt_t_ns.size() - 1) { + continue; + } + + double dt_ns = t_ns - gt_t_ns.at(j); + double int_t_ns = gt_t_ns.at(j + 1) - gt_t_ns.at(j); + + BASALT_ASSERT_STREAM(dt_ns >= 0, "dt_ns " << dt_ns); + BASALT_ASSERT_STREAM(int_t_ns > 0, "int_t_ns " << int_t_ns); + + // Skip if the interval between gt larger than 100ms + if (int_t_ns > 1e8) continue; + + double ratio = dt_ns / int_t_ns; + + BASALT_ASSERT(ratio >= 0); + BASALT_ASSERT(ratio < 1); + + Eigen::Vector3d gt = (1 - ratio) * gt_t_w_i[j] + ratio * gt_t_w_i[j + 1]; + + gt_associations.emplace_back(gt); + est_associations.emplace_back(filter_t_w_i[i]); + } + + int num_kfs = est_associations.size(); + + Eigen::Matrix gt, est; + gt.setZero(3, num_kfs); + est.setZero(3, num_kfs); + + for (size_t i = 0; i < est_associations.size(); i++) { + gt.col(i) = gt_associations[i]; + est.col(i) = est_associations[i]; + } + + Eigen::Vector3d mean_gt = gt.rowwise().mean(); + Eigen::Vector3d mean_est = est.rowwise().mean(); + + gt.colwise() -= mean_gt; + est.colwise() -= mean_est; + + Eigen::Matrix3d cov = gt * est.transpose(); + + Eigen::JacobiSVD svd( + cov, Eigen::ComputeFullU | Eigen::ComputeFullV); + + Eigen::Matrix3d S; + S.setIdentity(); + + if (svd.matrixU().determinant() * svd.matrixV().determinant() < 0) + S(2, 2) = -1; + + Eigen::Matrix3d rot_gt_est = svd.matrixU() * S * svd.matrixV().transpose(); + Eigen::Vector3d trans = mean_gt - rot_gt_est * mean_est; + + Sophus::SE3d T_gt_est(rot_gt_est, trans); + Sophus::SE3d T_est_gt = T_gt_est.inverse(); + + for (size_t i = 0; i < gt_t_w_i.size(); i++) { + gt_t_w_i[i] = T_est_gt * gt_t_w_i[i]; + } + + double error = 0; + for (size_t i = 0; i < est_associations.size(); i++) { + est_associations[i] = T_gt_est * est_associations[i]; + Eigen::Vector3d res = est_associations[i] - gt_associations[i]; + + error += res.transpose() * res; + } + + error /= est_associations.size(); + error = std::sqrt(error); + + std::cout << "T_align\n" << T_gt_est.matrix() << std::endl; + std::cout << "error " << error << std::endl; + std::cout << "number of associations " << num_kfs << std::endl; + + return error; +} +} // namespace basalt diff --git a/src/vio.cpp b/src/vio.cpp new file mode 100644 index 0000000..2e4583f --- /dev/null +++ b/src/vio.cpp @@ -0,0 +1,682 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 +#include +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include + +#include + +#include + +// GUI functions +void draw_image_overlay(pangolin::View& v, size_t cam_id); +void draw_scene(); +void load_data(const std::string& calib_path); +bool next_step(); +bool prev_step(); +void draw_plots(); +void alignButton(); + +// Pangolin variables +constexpr int UI_WIDTH = 200; + +using Button = pangolin::Var>; + +pangolin::DataLog imu_data_log, vio_data_log, error_data_log; +pangolin::Plotter* plotter; + +pangolin::Var show_frame("ui.show_frame", 0, 0, 1500); + +pangolin::Var show_obs("ui.show_obs", true, false, true); +pangolin::Var show_ids("ui.show_ids", false, false, true); + +pangolin::Var show_est_pos("ui.show_est_pos", true, false, true); +pangolin::Var show_est_vel("ui.show_est_vel", false, false, true); +pangolin::Var show_est_bg("ui.show_est_bg", false, false, true); +pangolin::Var show_est_ba("ui.show_est_ba", false, false, true); + +pangolin::Var show_gt("ui.show_gt", true, false, true); + +Button next_step_btn("ui.next_step", &next_step); +Button prev_step_btn("ui.prev_step", &prev_step); + +pangolin::Var continue_btn("ui.continue_btn", false, false, true); +pangolin::Var continue_fast("ui.continue_fast", true, false, true); + +Button align_svd_btn("ui.align_svd", &alignButton); + +pangolin::Var follow("ui.follow", true, false, true); + +// Visualization variables +std::unordered_map vis_map; + +tbb::concurrent_bounded_queue out_vis_queue; +tbb::concurrent_bounded_queue out_state_queue; + +std::vector vio_t_ns; +Eigen::vector vio_t_w_i; + +std::vector gt_t_ns; +Eigen::vector gt_t_w_i; + +std::string marg_data_path; +size_t last_frame_processed = 0; + +tbb::concurrent_unordered_map timestamp_to_id; + +std::mutex m; +std::condition_variable cv; +bool step_by_step = false; + +// VIO variables +basalt::Calibration calib; + +basalt::VioDatasetPtr vio_dataset; +basalt::VioConfig vio_config; +basalt::OpticalFlowBase::Ptr opt_flow_ptr; +basalt::VioEstimatorBase::Ptr vio; + +// Feed functions +void feed_images() { + std::cout << "Started input_data thread " << std::endl; + + for (size_t i = 0; i < vio_dataset->get_image_timestamps().size(); i++) { + if (step_by_step) { + std::unique_lock lk(m); + cv.wait(lk); + } + + basalt::OpticalFlowInput::Ptr data(new basalt::OpticalFlowInput); + + data->t_ns = vio_dataset->get_image_timestamps()[i]; + data->img_data = vio_dataset->get_image_data(data->t_ns); + + timestamp_to_id[data->t_ns] = i; + + opt_flow_ptr->input_queue.push(data); + } + + // Indicate the end of the sequence + opt_flow_ptr->input_queue.push(nullptr); + + std::cout << "Finished input_data thread " << std::endl; +} + +void feed_imu() { + for (size_t i = 0; i < vio_dataset->get_gyro_data().size(); i++) { + basalt::ImuData::Ptr data(new basalt::ImuData); + data->t_ns = vio_dataset->get_gyro_data()[i].timestamp_ns; + + data->accel = vio_dataset->get_accel_data()[i].data; + data->gyro = vio_dataset->get_gyro_data()[i].data; + + const double accel_noise_std = calib.dicreete_time_accel_noise_std(); + const double gyro_noise_std = calib.dicreete_time_gyro_noise_std(); + + data->accel_cov.setConstant(accel_noise_std * accel_noise_std); + data->gyro_cov.setConstant(gyro_noise_std * gyro_noise_std); + + vio->imu_data_queue.push(data); + } + vio->imu_data_queue.push(nullptr); +} + +int main(int argc, char** argv) { + bool show_gui = true; + bool print_queue = false; + std::string cam_calib_path; + std::string dataset_path; + std::string dataset_type; + std::string config_path; + std::string result_path; + int num_threads = 0; + + CLI::App app{"App description"}; + + app.add_option("--show-gui", show_gui, "Show GUI"); + app.add_option("--cam-calib", cam_calib_path, + "Ground-truth camera calibration used for simulation.") + ->required(); + + app.add_option("--dataset-path", dataset_path, "Path to dataset.") + ->required(); + + app.add_option("--dataset-type", dataset_type, "Dataset type .") + ->required(); + + app.add_option("--marg-data", marg_data_path, + "Path to folder where marginalization data will be stored."); + + app.add_option("--print-queue", print_queue, "Print queue."); + app.add_option("--config-path", config_path, "Path to config file."); + app.add_option("--result-path", result_path, + "Path to result file where the system will write RMSE ATE."); + app.add_option("--num-threads", num_threads, "Number of threads."); + app.add_option("--step-by-step", step_by_step, "Path to config file."); + + if (num_threads > 0) { + tbb::task_scheduler_init init(num_threads); + } + + try { + app.parse(argc, argv); + } catch (const CLI::ParseError& e) { + return app.exit(e); + } + + if (!config_path.empty()) { + vio_config.load(config_path); + } + + load_data(cam_calib_path); + + { + basalt::DatasetIoInterfacePtr dataset_io = + basalt::DatasetIoFactory::getDatasetIo(dataset_type); + + dataset_io->read(dataset_path); + + vio_dataset = dataset_io->get_data(); + vio_dataset->get_image_timestamps().erase( + vio_dataset->get_image_timestamps().begin()); + + show_frame.Meta().range[1] = vio_dataset->get_image_timestamps().size() - 1; + show_frame.Meta().gui_changed = true; + + opt_flow_ptr = + basalt::OpticalFlowFactory::getOpticalFlow(vio_config, calib); + + for (size_t i = 0; i < vio_dataset->get_gt_pose_data().size(); i++) { + gt_t_ns.push_back(vio_dataset->get_gt_timestamps()[i]); + gt_t_w_i.push_back(vio_dataset->get_gt_pose_data()[i].translation()); + } + } + + const int64_t start_t_ns = vio_dataset->get_image_timestamps().front(); + Sophus::SE3d T_w_i_init; + Eigen::Vector3d vel_w_i_init; + + { + int64_t t_init_ns = vio_dataset->get_image_timestamps()[0]; + + { + T_w_i_init.setQuaternion(Eigen::Quaterniond::FromTwoVectors( + vio_dataset->get_accel_data()[0].data, Eigen::Vector3d::UnitZ())); + + std::cout << "T_w_i_init\n" << T_w_i_init.matrix() << std::endl; + std::cout + << "accel_w " + << (T_w_i_init * vio_dataset->get_accel_data()[0].data).transpose() + << std::endl; + } + + vel_w_i_init.setZero(); + + std::cout << "Setting up filter: t_ns " << t_init_ns << std::endl; + std::cout << "T_w_i\n" << T_w_i_init.matrix() << std::endl; + std::cout << "vel_w_i " << vel_w_i_init.transpose() << std::endl; + + vio = basalt::VioEstimatorFactory::getVioEstimator( + vio_config, calib, t_init_ns, T_w_i_init, vel_w_i_init, + Eigen::Vector3d::Zero(), Eigen::Vector3d::Zero(), 0.0001, + basalt::constants::g); + + opt_flow_ptr->output_queue = &vio->vision_data_queue; + if (show_gui) vio->out_vis_queue = &out_vis_queue; + vio->out_state_queue = &out_state_queue; + } + + basalt::MargDataSaver::Ptr marg_data_saver; + + if (!marg_data_path.empty()) { + marg_data_saver.reset(new basalt::MargDataSaver(marg_data_path)); + vio->out_marg_queue = &marg_data_saver->in_marg_queue; + + // Save gt. + { + std::string p = marg_data_path + "/gt.cereal"; + std::ofstream os(p, std::ios::binary); + + { + cereal::BinaryOutputArchive archive(os); + archive(gt_t_ns); + archive(gt_t_w_i); + } + os.close(); + } + } + + vio_data_log.Clear(); + + std::thread t1(&feed_images); + std::thread t2(&feed_imu); + + std::shared_ptr t3; + + if (show_gui) + t3.reset(new std::thread([&]() { + basalt::VioVisualizationData::Ptr data; + + while (true) { + out_vis_queue.pop(data); + + if (data.get()) { + vis_map[data->t_ns] = data; + } else { + break; + } + } + + std::cout << "Finished t3" << std::endl; + })); + + std::thread t4([&]() { + basalt::PoseVelBiasState::Ptr data; + + while (true) { + out_state_queue.pop(data); + + if (!data.get()) break; + + int64_t t_ns = data->t_ns; + + // std::cerr << "t_ns " << t_ns << std::endl; + Sophus::SE3d T_w_i = data->T_w_i; + Eigen::Vector3d vel_w_i = data->vel_w_i; + Eigen::Vector3d bg = data->bias_gyro; + Eigen::Vector3d ba = data->bias_accel; + + vio_t_ns.emplace_back(data->t_ns); + vio_t_w_i.emplace_back(T_w_i.translation()); + + if (show_gui) { + std::vector vals; + vals.push_back((t_ns - start_t_ns) * 1e-9); + + for (int i = 0; i < 3; i++) vals.push_back(vel_w_i[i]); + for (int i = 0; i < 3; i++) vals.push_back(T_w_i.translation()[i]); + for (int i = 0; i < 3; i++) vals.push_back(bg[i]); + for (int i = 0; i < 3; i++) vals.push_back(ba[i]); + + vio_data_log.Log(vals); + } + } + + std::cout << "Finished t4" << std::endl; + }); + + std::shared_ptr t5; + + if (print_queue) { + t5.reset(new std::thread([&]() { + while (true) { + std::cout << "opt_flow_ptr->input_queue " + << opt_flow_ptr->input_queue.size() + << " opt_flow_ptr->output_queue " + << opt_flow_ptr->output_queue->size() << " out_state_queue " + << out_state_queue.size() << std::endl; + sleep(1); + } + })); + } + + if (show_gui) { + pangolin::CreateWindowAndBind("Main", 1800, 1000); + + glEnable(GL_DEPTH_TEST); + + pangolin::View& img_view_display = + pangolin::CreateDisplay() + .SetBounds(0.4, 1.0, pangolin::Attach::Pix(UI_WIDTH), 0.4) + .SetLayout(pangolin::LayoutEqual); + + pangolin::View& plot_display = pangolin::CreateDisplay().SetBounds( + 0.0, 0.4, pangolin::Attach::Pix(UI_WIDTH), 1.0); + + plotter = new pangolin::Plotter(&imu_data_log, 0.0, 100, -10.0, 10.0, 0.01f, + 0.01f); + plot_display.AddDisplay(*plotter); + + pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, + pangolin::Attach::Pix(UI_WIDTH)); + + std::vector> img_view; + while (img_view.size() < calib.intrinsics.size()) { + std::shared_ptr iv(new pangolin::ImageView); + + size_t idx = img_view.size(); + img_view.push_back(iv); + + img_view_display.AddDisplay(*iv); + iv->extern_draw_function = + std::bind(&draw_image_overlay, std::placeholders::_1, idx); + } + + Eigen::Vector3d cam_p(-0.5, -3, -5); + cam_p = T_w_i_init.so3() * calib.T_i_c[0].so3() * cam_p; + + pangolin::OpenGlRenderState camera( + pangolin::ProjectionMatrix(640, 480, 400, 400, 320, 240, 0.001, 10000), + pangolin::ModelViewLookAt(cam_p[0], cam_p[1], cam_p[2], 0, 0, 0, + pangolin::AxisZ)); + + pangolin::View& display3D = + pangolin::CreateDisplay() + .SetAspect(-640 / 480.0) + .SetBounds(0.4, 1.0, 0.4, 1.0) + .SetHandler(new pangolin::Handler3D(camera)); + + while (!pangolin::ShouldQuit()) { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + if (follow) { + size_t frame_id = show_frame; + int64_t t_ns = vio_dataset->get_image_timestamps()[frame_id]; + auto it = vis_map.find(t_ns); + + if (it != vis_map.end()) { + auto T_w_i = it->second->states.back(); + T_w_i.so3() = Sophus::SO3d(); + + camera.Follow(T_w_i.matrix()); + } + } + + display3D.Activate(camera); + glClearColor(1.0f, 1.0f, 1.0f, 1.0f); + + draw_scene(); + + img_view_display.Activate(); + + if (show_frame.GuiChanged()) { + for (size_t cam_id = 0; cam_id < calib.intrinsics.size(); cam_id++) { + size_t frame_id = static_cast(show_frame); + int64_t timestamp = vio_dataset->get_image_timestamps()[frame_id]; + + std::vector img_vec = + vio_dataset->get_image_data(timestamp); + + pangolin::GlPixFormat fmt; + fmt.glformat = GL_LUMINANCE; + fmt.gltype = GL_UNSIGNED_SHORT; + fmt.scalable_internal_format = GL_LUMINANCE16; + + img_view[cam_id]->SetImage( + img_vec[cam_id].img->ptr, img_vec[cam_id].img->w, + img_vec[cam_id].img->h, img_vec[cam_id].img->pitch, fmt); + } + + draw_plots(); + } + + if (show_est_vel.GuiChanged() || show_est_pos.GuiChanged() || + show_est_ba.GuiChanged() || show_est_bg.GuiChanged()) { + draw_plots(); + } + + pangolin::FinishFrame(); + + if (continue_btn) { + if (!next_step()) + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + } else { + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + } + + if (continue_fast) { + int64_t t_ns = vio->last_processed_t_ns; + if (timestamp_to_id.count(t_ns)) { + show_frame = timestamp_to_id[t_ns]; + show_frame.Meta().gui_changed = true; + } + + if (vio->finished) { + continue_fast = false; + } + } + } + } + + t1.join(); + t2.join(); + if (t3.get()) t3->join(); + t4.join(); + + if (!result_path.empty()) { + double error = basalt::alignSVD(vio_t_ns, vio_t_w_i, gt_t_ns, gt_t_w_i); + + std::ofstream os(result_path); + os << error << std::endl; + os.close(); + } + + return 0; +} + +void draw_image_overlay(pangolin::View& v, size_t cam_id) { + // size_t frame_id = show_frame; + // basalt::TimeCamId tcid = + // std::make_pair(vio_dataset->get_image_timestamps()[frame_id], + // cam_id); + + size_t frame_id = show_frame; + auto it = vis_map.find(vio_dataset->get_image_timestamps()[frame_id]); + + if (show_obs) { + glLineWidth(1.0); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (it != vis_map.end() && cam_id < it->second->projections.size()) { + const auto& points = it->second->projections[cam_id]; + + if (points.size() > 0) { + double min_id = points[0][2], max_id = points[0][2]; + + for (const auto& points2 : it->second->projections) + for (const auto& p : points2) { + min_id = std::min(min_id, p[2]); + max_id = std::max(max_id, p[2]); + } + + for (const auto& c : points) { + const float radius = 6.5; + + float r, g, b; + getcolor(c[2] - min_id, max_id - min_id, b, g, r); + glColor3f(r, g, b); + + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I().Text("%d", int(c[3])).Draw(c[0], c[1]); + } + } + + glColor3f(1.0, 0.0, 0.0); + pangolin::GlFont::I() + .Text("Tracked %d points", points.size()) + .Draw(5, 20); + } + } +} + +void draw_scene() { + glPointSize(3); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + glColor3ubv(cam_color); + Eigen::vector sub_gt(vio_t_w_i.begin(), + vio_t_w_i.begin() + show_frame); + pangolin::glDrawLineStrip(sub_gt); + + glColor3ubv(gt_color); + if (show_gt) pangolin::glDrawLineStrip(gt_t_w_i); + + size_t frame_id = show_frame; + int64_t t_ns = vio_dataset->get_image_timestamps()[frame_id]; + auto it = vis_map.find(t_ns); + + if (it != vis_map.end()) { + for (const auto& p : it->second->states) + for (size_t i = 0; i < calib.T_i_c.size(); i++) + render_camera((p * calib.T_i_c[i]).matrix(), 2.0f, state_color, 0.1f); + + for (const auto& p : it->second->frames) + for (size_t i = 0; i < calib.T_i_c.size(); i++) + render_camera((p * calib.T_i_c[i]).matrix(), 2.0f, pose_color, 0.1f); + + for (size_t i = 0; i < calib.T_i_c.size(); i++) + render_camera((it->second->states.back() * calib.T_i_c[i]).matrix(), 2.0f, + cam_color, 0.1f); + + glColor3ubv(pose_color); + pangolin::glDrawPoints(it->second->points); + } + + pangolin::glDrawAxis(Sophus::SE3d().matrix(), 1.0); +} + +void load_data(const std::string& calib_path) { + std::ifstream os(calib_path, std::ios::binary); + + if (os.is_open()) { + cereal::JSONInputArchive archive(os); + archive(calib); + std::cout << "Loaded camera with " << calib.intrinsics.size() << " cameras" + << std::endl; + + } else { + std::cerr << "could not load camera calibration " << calib_path + << std::endl; + std::abort(); + } +} + +bool next_step() { + if (show_frame < int(vio_dataset->get_image_timestamps().size()) - 1) { + show_frame = show_frame + 1; + show_frame.Meta().gui_changed = true; + cv.notify_one(); + return true; + } else { + return false; + } +} + +bool prev_step() { + if (show_frame > 1) { + show_frame = show_frame - 1; + show_frame.Meta().gui_changed = true; + return true; + } else { + return false; + } +} + +void draw_plots() { + plotter->ClearSeries(); + plotter->ClearMarkers(); + + if (show_est_pos) { + plotter->AddSeries("$0", "$4", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "position x", &vio_data_log); + plotter->AddSeries("$0", "$5", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "position y", &vio_data_log); + plotter->AddSeries("$0", "$6", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "position z", &vio_data_log); + } + + if (show_est_vel) { + plotter->AddSeries("$0", "$1", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "velocity x", &vio_data_log); + plotter->AddSeries("$0", "$2", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "velocity y", &vio_data_log); + plotter->AddSeries("$0", "$3", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "velocity z", &vio_data_log); + } + + if (show_est_bg) { + plotter->AddSeries("$0", "$7", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "gyro bias x", &vio_data_log); + plotter->AddSeries("$0", "$8", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "gyro bias y", &vio_data_log); + plotter->AddSeries("$0", "$9", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "gyro bias z", &vio_data_log); + } + + if (show_est_ba) { + plotter->AddSeries("$0", "$10", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "accel bias x", &vio_data_log); + plotter->AddSeries("$0", "$11", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "accel bias y", + &vio_data_log); + plotter->AddSeries("$0", "$12", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "accel bias z", &vio_data_log); + } + + double t = vio_dataset->get_image_timestamps()[show_frame] * 1e-9; + plotter->AddMarker(pangolin::Marker::Vertical, t, pangolin::Marker::Equal, + pangolin::Colour::White()); +} + +void alignButton() { basalt::alignSVD(vio_t_ns, vio_t_w_i, gt_t_ns, gt_t_w_i); } diff --git a/src/vio_sim.cpp b/src/vio_sim.cpp new file mode 100644 index 0000000..bacbd17 --- /dev/null +++ b/src/vio_sim.cpp @@ -0,0 +1,900 @@ +/** +BSD 3-Clause License + +This file is part of the Basalt project. +https://gitlab.com/VladyslavUsenko/basalt.git + +Copyright (c) 2019, Vladyslav Usenko and Nikolaus Demmel. +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +* Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + +* Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +* Neither the name 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 +#include + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include + +#include + +// GUI functions +void draw_image_overlay(pangolin::View& v, size_t cam_id); +void draw_scene(); +void load_data(const std::string& calib_path); +void gen_data(); +void compute_projections(); +void setup_vio(); +void draw_plots(); +bool next_step(); +void alignButton(); + +// Parameters for simulations +int NUM_POINTS = 1000; +double POINT_DIST = 10.0; +constexpr int NUM_FRAMES = 1000; +constexpr int CAM_FREQ = 20; +constexpr int IMU_FREQ = 200; + +static const int knot_time = 3; +static const double obs_std_dev = 0.5; +static const double accel_std_dev = 0.5; +static const double gyro_std_dev = 0.008; + +static const double accel_bias_std_dev = 0.00123; +static const double gyro_bias_std_dev = 0.000234; + +Eigen::Vector3d g(0, 0, -9.81); + +// std::random_device rd{}; +// std::mt19937 gen{rd()}; +std::mt19937 gen{1}; + +std::normal_distribution<> obs_noise_dist{0, obs_std_dev}; +std::normal_distribution<> gyro_noise_dist{0, gyro_std_dev}; +std::normal_distribution<> accel_noise_dist{0, accel_std_dev}; + +std::normal_distribution<> gyro_bias_dist{0, gyro_bias_std_dev}; +std::normal_distribution<> accel_bias_dist{0, accel_bias_std_dev}; + +// Simulated data + +basalt::Se3Spline<5> gt_spline(int64_t(knot_time * 1e9)); + +Eigen::vector gt_points; +Eigen::vector gt_frame_T_w_i; +Eigen::vector gt_frame_t_w_i, vio_t_w_i; +std::vector gt_frame_t_ns; +Eigen::vector gt_accel, gt_gyro, gt_accel_bias, gt_gyro_bias, + noisy_accel, noisy_gyro, gt_vel; +std::vector gt_imu_t_ns; + +std::map gt_observations; +std::map noisy_observations; + +std::string marg_data_path; + +// VIO vars +basalt::Calibration calib; +basalt::KeypointVioEstimator::Ptr vio; + +// Visualization vars +std::unordered_map vis_map; +tbb::concurrent_bounded_queue out_vis_queue; +tbb::concurrent_bounded_queue out_state_queue; + +std::vector images; + +// Pangolin vars +constexpr int UI_WIDTH = 200; +pangolin::DataLog imu_data_log, vio_data_log, error_data_log; +pangolin::Plotter* plotter; + +pangolin::Var show_frame("ui.show_frame", 0, 0, NUM_FRAMES - 1); + +pangolin::Var show_obs("ui.show_obs", true, false, true); +pangolin::Var show_obs_noisy("ui.show_obs_noisy", true, false, true); +pangolin::Var show_obs_vio("ui.show_obs_vio", true, false, true); + +pangolin::Var show_ids("ui.show_ids", false, false, true); + +pangolin::Var show_accel("ui.show_accel", false, false, true); +pangolin::Var show_gyro("ui.show_gyro", false, false, true); +pangolin::Var show_gt_vel("ui.show_gt_vel", false, false, true); +pangolin::Var show_gt_pos("ui.show_gt_pos", true, false, true); +pangolin::Var show_gt_bg("ui.show_gt_bg", false, false, true); +pangolin::Var show_gt_ba("ui.show_gt_ba", false, false, true); + +pangolin::Var show_est_vel("ui.show_est_vel", false, false, true); +pangolin::Var show_est_pos("ui.show_est_pos", true, false, true); +pangolin::Var show_est_bg("ui.show_est_bg", false, false, true); +pangolin::Var show_est_ba("ui.show_est_ba", false, false, true); + +using Button = pangolin::Var>; + +Button next_step_btn("ui.next_step", &next_step); + +pangolin::Var continue_btn("ui.continue_btn", true, false, true); + +Button align_step_btn("ui.align_button", &alignButton); + +int main(int argc, char** argv) { + srand(1); + + bool show_gui = true; + std::string cam_calib_path; + + CLI::App app{"App description"}; + + app.add_option("--show-gui", show_gui, "Show GUI"); + app.add_option("--cam-calib", cam_calib_path, + "Ground-truth camera calibration used for simulation.") + ->required(); + + app.add_option("--marg-data", marg_data_path, + "Folder to store marginalization data.") + ->required(); + + app.add_option("--num-points", NUM_POINTS, "Number of points in simulation."); + + try { + app.parse(argc, argv); + } catch (const CLI::ParseError& e) { + return app.exit(e); + } + + basalt::MargDataSaver::Ptr mds; + if (!marg_data_path.empty()) { + mds.reset(new basalt::MargDataSaver(marg_data_path)); + } + + load_data(cam_calib_path); + gen_data(); + + setup_vio(); + + vio->out_vis_queue = &out_vis_queue; + vio->out_state_queue = &out_state_queue; + + if (mds.get()) { + vio->out_marg_queue = &mds->in_marg_queue; + } + + std::thread t0([&]() { + for (size_t i = 0; i < gt_imu_t_ns.size(); i++) { + basalt::ImuData::Ptr data(new basalt::ImuData); + data->t_ns = gt_imu_t_ns[i]; + + data->accel = noisy_accel[i]; + data->gyro = noisy_gyro[i]; + + data->accel_cov.setConstant(accel_std_dev * accel_std_dev); + data->gyro_cov.setConstant(gyro_std_dev * gyro_std_dev); + + vio->addIMUToQueue(data); + } + + vio->addIMUToQueue(nullptr); + + std::cout << "Finished t0" << std::endl; + }); + + std::thread t1([&]() { + for (size_t i = 0; i < gt_frame_t_ns.size(); i++) { + basalt::OpticalFlowResult::Ptr data(new basalt::OpticalFlowResult); + data->t_ns = gt_frame_t_ns[i]; + + for (size_t j = 0; j < calib.T_i_c.size(); j++) { + data->observations.emplace_back(); + basalt::TimeCamId tcid(data->t_ns, j); + const basalt::SimObservations& obs = noisy_observations.at(tcid); + for (size_t k = 0; k < obs.pos.size(); k++) { + Eigen::AffineCompact2f t; + t.setIdentity(); + t.translation() = obs.pos[k].cast(); + data->observations.back()[obs.id[k]] = t; + } + } + + vio->addVisionToQueue(data); + } + + vio->addVisionToQueue(nullptr); + + std::cout << "Finished t1" << std::endl; + }); + + std::thread t2([&]() { + basalt::VioVisualizationData::Ptr data; + + while (true) { + out_vis_queue.pop(data); + + if (data.get()) { + vis_map[data->t_ns] = data; + } else { + break; + } + } + + std::cout << "Finished t2" << std::endl; + }); + + std::thread t3([&]() { + basalt::PoseVelBiasState::Ptr data; + + while (true) { + out_state_queue.pop(data); + + if (!data.get()) break; + + int64_t t_ns = data->t_ns; + + // std::cerr << "t_ns " << t_ns << std::endl; + Sophus::SE3d T_w_i = data->T_w_i; + Eigen::Vector3d vel_w_i = data->vel_w_i; + Eigen::Vector3d bg = data->bias_gyro; + Eigen::Vector3d ba = data->bias_accel; + + vio_t_w_i.emplace_back(T_w_i.translation()); + + { + std::vector vals; + vals.push_back(t_ns * 1e-9); + + for (int i = 0; i < 3; i++) vals.push_back(vel_w_i[i]); + for (int i = 0; i < 3; i++) vals.push_back(T_w_i.translation()[i]); + for (int i = 0; i < 3; i++) vals.push_back(bg[i]); + for (int i = 0; i < 3; i++) vals.push_back(ba[i]); + + vio_data_log.Log(vals); + } + } + + std::cout << "Finished t3" << std::endl; + }); + + // std::thread t4([&]() { + + // basalt::MargData::Ptr data; + + // while (true) { + // out_marg_queue.pop(data); + + // if (data.get()) { + // int64_t kf_id = *data->kfs_to_marg.begin(); + + // std::string path = cache_path + "/" + std::to_string(kf_id) + + // ".cereal"; + // std::ofstream os(path, std::ios::binary); + + // { + // cereal::BinaryOutputArchive archive(os); + // archive(*data); + // } + // os.close(); + + // } else { + // break; + // } + // } + + // std::cout << "Finished t4" << std::endl; + + // }); + + if (show_gui) { + pangolin::CreateWindowAndBind("Main", 1800, 1000); + + glEnable(GL_DEPTH_TEST); + + pangolin::View& img_view_display = + pangolin::CreateDisplay() + .SetBounds(0.4, 1.0, pangolin::Attach::Pix(UI_WIDTH), 0.5) + .SetLayout(pangolin::LayoutEqual); + + pangolin::View& plot_display = pangolin::CreateDisplay().SetBounds( + 0.0, 0.4, pangolin::Attach::Pix(UI_WIDTH), 1.0); + + plotter = new pangolin::Plotter(&imu_data_log, 0.0, + gt_frame_t_ns[NUM_FRAMES - 1] * 1e-9, -10.0, + 10.0, 0.01f, 0.01f); + plot_display.AddDisplay(*plotter); + + pangolin::CreatePanel("ui").SetBounds(0.0, 1.0, 0.0, + pangolin::Attach::Pix(UI_WIDTH)); + + std::vector> img_view; + while (img_view.size() < calib.intrinsics.size()) { + std::shared_ptr iv(new pangolin::ImageView); + + size_t idx = img_view.size(); + img_view.push_back(iv); + + img_view_display.AddDisplay(*iv); + iv->extern_draw_function = + std::bind(&draw_image_overlay, std::placeholders::_1, idx); + } + + pangolin::OpenGlRenderState camera( + pangolin::ProjectionMatrix(640, 480, 400, 400, 320, 240, 0.001, 10000), + pangolin::ModelViewLookAt(15, 3, 15, 0, 0, 0, pangolin::AxisZ)); + + pangolin::View& display3D = + pangolin::CreateDisplay() + .SetAspect(-640 / 480.0) + .SetBounds(0.4, 1.0, 0.5, 1.0) + .SetHandler(new pangolin::Handler3D(camera)); + + while (!pangolin::ShouldQuit()) { + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + display3D.Activate(camera); + glClearColor(0.95f, 0.95f, 0.95f, 1.0f); + + draw_scene(); + + img_view_display.Activate(); + + if (show_frame.GuiChanged()) { + for (size_t i = 0; i < calib.intrinsics.size(); i++) { + img_view[i]->SetImage(images[i]); + } + draw_plots(); + } + + if (show_accel.GuiChanged() || show_gyro.GuiChanged() || + show_gt_vel.GuiChanged() || show_gt_pos.GuiChanged() || + show_gt_ba.GuiChanged() || show_gt_bg.GuiChanged() || + show_est_vel.GuiChanged() || show_est_pos.GuiChanged() || + show_est_ba.GuiChanged() || show_est_bg.GuiChanged()) { + draw_plots(); + } + + pangolin::FinishFrame(); + + if (continue_btn) { + if (!next_step()) continue_btn = false; + } else { + std::this_thread::sleep_for(std::chrono::milliseconds(50)); + } + } + } + + t0.join(); + t1.join(); + t2.join(); + t3.join(); + // t4.join(); + + return 0; +} + +void draw_image_overlay(pangolin::View& v, size_t cam_id) { + size_t frame_id = show_frame; + basalt::TimeCamId tcid = std::make_pair(gt_frame_t_ns[frame_id], cam_id); + + if (show_obs) { + glLineWidth(1.0); + glColor3ubv(gt_color); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (gt_observations.find(tcid) != gt_observations.end()) { + const basalt::SimObservations& cr = gt_observations.at(tcid); + + for (size_t i = 0; i < cr.pos.size(); i++) { + const float radius = 2; + const Eigen::Vector2f c = cr.pos[i].cast(); + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I().Text("%d", cr.id[i]).Draw(c[0], c[1]); + } + + pangolin::GlFont::I().Text("%d gt points", cr.pos.size()).Draw(5, 20); + } + } + + if (show_obs_noisy) { + glLineWidth(1.0); + glColor3f(1.0, 1.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + if (noisy_observations.find(tcid) != noisy_observations.end()) { + const basalt::SimObservations& cr = noisy_observations.at(tcid); + + for (size_t i = 0; i < cr.pos.size(); i++) { + const float radius = 2; + const Eigen::Vector2f c = cr.pos[i].cast(); + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I().Text("%d", cr.id[i]).Draw(c[0], c[1]); + } + + pangolin::GlFont::I().Text("%d noisy points", cr.pos.size()).Draw(5, 40); + } + } + + if (show_obs_vio) { + glLineWidth(1.0); + glColor3f(0.0, 0.0, 1.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + auto it = vis_map.find(gt_frame_t_ns[frame_id]); + + if (it != vis_map.end() && cam_id < it->second->projections.size()) { + const auto& points = it->second->projections[cam_id]; + + if (points.size() > 0) { + double min_id = points[0][2], max_id = points[0][2]; + for (size_t i = 0; i < points.size(); i++) { + min_id = std::min(min_id, points[i][2]); + max_id = std::max(max_id, points[i][2]); + } + + for (size_t i = 0; i < points.size(); i++) { + const float radius = 2; + const Eigen::Vector4d c = points[i]; + pangolin::glDrawCirclePerimeter(c[0], c[1], radius); + + if (show_ids) + pangolin::GlFont::I().Text("%d", int(c[3])).Draw(c[0], c[1]); + } + } + + glColor3f(0.0, 0.0, 1.0); + pangolin::GlFont::I().Text("%d vio points", points.size()).Draw(5, 60); + } + } +} + +void draw_scene() { + glPointSize(3); + glColor3f(1.0, 0.0, 0.0); + glEnable(GL_BLEND); + glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA); + + glColor3ubv(gt_color); + pangolin::glDrawPoints(gt_points); + pangolin::glDrawLineStrip(gt_frame_t_w_i); + + glColor3ubv(cam_color); + pangolin::glDrawLineStrip(vio_t_w_i); + + size_t frame_id = show_frame; + + auto it = vis_map.find(gt_frame_t_ns[frame_id]); + + if (it != vis_map.end()) { + for (const auto& p : it->second->states) + for (size_t i = 0; i < calib.T_i_c.size(); i++) + render_camera((p * calib.T_i_c[i]).matrix(), 2.0f, cam_color, 0.1f); + + for (const auto& p : it->second->frames) + for (size_t i = 0; i < calib.T_i_c.size(); i++) + render_camera((p * calib.T_i_c[i]).matrix(), 2.0f, pose_color, 0.1f); + + glColor3ubv(pose_color); + pangolin::glDrawPoints(it->second->points); + } + + pangolin::glDrawAxis(gt_frame_T_w_i[frame_id].matrix(), 0.1); + + pangolin::glDrawAxis(Sophus::SE3d().matrix(), 1.0); +} + +void load_data(const std::string& calib_path) { + std::ifstream os(calib_path, std::ios::binary); + + if (os.is_open()) { + cereal::JSONInputArchive archive(os); + archive(calib); + std::cout << "Loaded camera with " << calib.intrinsics.size() + << " cameras" << std::endl; + + } else { + std::cerr << "could not load camera calibration " << calib_path + << std::endl; + std::abort(); + } +} + +void compute_projections() { + for (size_t i = 0; i < gt_frame_T_w_i.size(); i++) { + for (size_t j = 0; j < calib.T_i_c.size(); j++) { + basalt::TimeCamId tcid(gt_frame_t_ns[i], j); + basalt::SimObservations obs, obs_noisy; + + for (size_t k = 0; k < gt_points.size(); k++) { + Eigen::Vector4d p_cam; + p_cam.head<3>() = + (gt_frame_T_w_i[i] * calib.T_i_c[j]).inverse() * gt_points[k]; + + std::visit( + [&](const auto& cam) { + if (p_cam[2] > 0.1) { + Eigen::Vector2d p_2d; + cam.project(p_cam, p_2d); + + const int border = 5; + if (p_2d[0] >= border && p_2d[1] >= border && + p_2d[0] < calib.resolution[j][0] - border - 1 && + p_2d[1] < calib.resolution[j][1] - border - 1) { + obs.pos.emplace_back(p_2d); + obs.id.emplace_back(k); + + p_2d[0] += obs_noise_dist(gen); + p_2d[1] += obs_noise_dist(gen); + + obs_noisy.pos.emplace_back(p_2d); + obs_noisy.id.emplace_back(k); + } + } + }, + calib.intrinsics[j].variant); + } + + gt_observations[tcid] = obs; + noisy_observations[tcid] = obs_noisy; + } + } +} + +void gen_data() { + for (size_t i = 0; i < calib.intrinsics.size(); i++) { + images.emplace_back(); + images.back() = pangolin::TypedImage( + calib.resolution[i][0], calib.resolution[i][1], + pangolin::PixelFormatFromString("GRAY8")); + + images.back().Fill(200); + } + show_frame.Meta().gui_changed = true; + + double seconds = NUM_FRAMES / CAM_FREQ; + int num_knots = seconds / knot_time + 5; + // for (int i = 0; i < 2; i++) gt_spline.knots_push_back(Sophus::SE3d()); + gt_spline.genRandomTrajectory(num_knots); + + int64_t t_ns = 0; + int64_t dt_ns = int64_t(1e9) / CAM_FREQ; + + for (int i = 0; i < NUM_FRAMES; i++) { + gt_frame_T_w_i.emplace_back(gt_spline.pose(t_ns)); + gt_frame_t_w_i.emplace_back(gt_frame_T_w_i.back().translation()); + gt_frame_t_ns.emplace_back(t_ns); + + t_ns += dt_ns; + } + + dt_ns = int64_t(1e9) / IMU_FREQ; + + int64_t offset = + dt_ns / 2; // Offset to make IMU in the center of the interval + t_ns = offset; + + imu_data_log.Clear(); + + gt_accel_bias.clear(); + gt_gyro_bias.clear(); + + gt_accel_bias.emplace_back(Eigen::Vector3d::Random() / 10); + gt_gyro_bias.emplace_back(Eigen::Vector3d::Random() / 100); + + // gt_accel_bias.emplace_back(Eigen::Vector3d::Zero()); + // gt_gyro_bias.emplace_back(Eigen::Vector3d::Zero()); + + while (t_ns < gt_frame_t_ns.back()) { + Sophus::SE3d pose = gt_spline.pose(t_ns); + Eigen::Vector3d accel_body = + pose.so3().inverse() * (gt_spline.transAccelWorld(t_ns) - g); + Eigen::Vector3d rot_vel_body = gt_spline.rotVelBody(t_ns); + + gt_accel.emplace_back(accel_body); + gt_gyro.emplace_back(rot_vel_body); + gt_vel.emplace_back(gt_spline.transVelWorld(t_ns)); + + accel_body[0] += accel_noise_dist(gen); + accel_body[1] += accel_noise_dist(gen); + accel_body[2] += accel_noise_dist(gen); + + accel_body += gt_accel_bias.back(); + + rot_vel_body[0] += gyro_noise_dist(gen); + rot_vel_body[1] += gyro_noise_dist(gen); + rot_vel_body[2] += gyro_noise_dist(gen); + + rot_vel_body += gt_gyro_bias.back(); + + noisy_accel.emplace_back(accel_body); + noisy_gyro.emplace_back(rot_vel_body); + + gt_imu_t_ns.emplace_back(t_ns + offset); + + std::vector vals; + vals.push_back(t_ns * 1e-9); + + for (int i = 0; i < 3; i++) vals.push_back(gt_accel.back()[i]); + for (int i = 0; i < 3; i++) vals.push_back(gt_gyro.back()[i]); + for (int i = 0; i < 3; i++) vals.push_back(gt_vel.back()[i]); + for (int i = 0; i < 3; i++) vals.push_back(pose.translation()[i]); + for (int i = 0; i < 3; i++) vals.push_back(gt_gyro_bias.back()[i]); + for (int i = 0; i < 3; i++) vals.push_back(gt_accel_bias.back()[i]); + + imu_data_log.Log(vals); + + double dt_sqrt = std::sqrt(dt_ns * 1e-9); + Eigen::Vector3d gt_accel_bias_next = gt_accel_bias.back(); + gt_accel_bias_next[0] += accel_bias_dist(gen) * dt_sqrt; + gt_accel_bias_next[1] += accel_bias_dist(gen) * dt_sqrt; + gt_accel_bias_next[2] += accel_bias_dist(gen) * dt_sqrt; + gt_accel_bias.emplace_back(gt_accel_bias_next); + + Eigen::Vector3d gt_gyro_bias_next = gt_gyro_bias.back(); + gt_gyro_bias_next[0] += gyro_bias_dist(gen) * dt_sqrt; + gt_gyro_bias_next[1] += gyro_bias_dist(gen) * dt_sqrt; + gt_gyro_bias_next[2] += gyro_bias_dist(gen) * dt_sqrt; + gt_gyro_bias.emplace_back(gt_gyro_bias_next); + + t_ns += dt_ns; + } + + show_accel.Meta().gui_changed = true; + + for (int i = 0; i < NUM_POINTS; i++) { + Eigen::Vector3d point; + + point = Eigen::Vector3d::Random().normalized() * POINT_DIST; + + gt_points.push_back(point); + } + + compute_projections(); + + // Save spline data + { + std::string path = marg_data_path + "/gt_spline.cereal"; + + std::cout << "Saving gt_spline " << path << std::endl; + + std::ofstream os(path, std::ios::binary); + { + cereal::JSONOutputArchive archive(os); + + int64_t t_ns = gt_spline.getDtNs(); + + Eigen::vector knots; + for (size_t i = 0; i < gt_spline.numKnots(); i++) { + knots.push_back(gt_spline.getKnot(i)); + } + + archive(cereal::make_nvp("t_ns", t_ns)); + archive(cereal::make_nvp("knots", knots)); + + archive(cereal::make_nvp("noisy_accel", noisy_accel)); + archive(cereal::make_nvp("noisy_gyro", noisy_gyro)); + archive(cereal::make_nvp("noisy_accel", gt_accel)); + archive(cereal::make_nvp("gt_gyro", gt_gyro)); + archive(cereal::make_nvp("gt_points", gt_points)); + archive(cereal::make_nvp("gt_accel_bias", gt_accel_bias)); + archive(cereal::make_nvp("gt_gyro_bias", gt_gyro_bias)); + + archive(cereal::make_nvp("gt_observations", gt_observations)); + archive(cereal::make_nvp("noisy_observations", noisy_observations)); + + archive(cereal::make_nvp("gt_points", gt_points)); + + archive(cereal::make_nvp("gt_frame_t_ns", gt_frame_t_ns)); + archive(cereal::make_nvp("gt_imu_t_ns", gt_imu_t_ns)); + } + + os.close(); + } +} + +void draw_plots() { + plotter->ClearSeries(); + plotter->ClearMarkers(); + + if (show_accel) { + plotter->AddSeries("$0", "$1", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "accel measurements x"); + plotter->AddSeries("$0", "$2", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "accel measurements y"); + plotter->AddSeries("$0", "$3", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "accel measurements z"); + } + + if (show_gyro) { + plotter->AddSeries("$0", "$4", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "gyro measurements x"); + plotter->AddSeries("$0", "$5", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "gyro measurements y"); + plotter->AddSeries("$0", "$6", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "gyro measurements z"); + } + + if (show_gt_vel) { + plotter->AddSeries("$0", "$7", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "ground-truth velocity x"); + plotter->AddSeries("$0", "$8", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "ground-truth velocity y"); + plotter->AddSeries("$0", "$9", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "ground-truth velocity z"); + } + + if (show_gt_pos) { + plotter->AddSeries("$0", "$10", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "ground-truth position x"); + plotter->AddSeries("$0", "$11", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "ground-truth position y"); + plotter->AddSeries("$0", "$12", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "ground-truth position z"); + } + + if (show_gt_bg) { + plotter->AddSeries("$0", "$13", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "ground-truth gyro bias x"); + plotter->AddSeries("$0", "$14", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "ground-truth gyro bias y"); + plotter->AddSeries("$0", "$15", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "ground-truth gyro bias z"); + } + + if (show_gt_ba) { + plotter->AddSeries("$0", "$16", pangolin::DrawingModeDashed, + pangolin::Colour::Red(), "ground-truth accel bias x"); + plotter->AddSeries("$0", "$17", pangolin::DrawingModeDashed, + pangolin::Colour::Green(), "ground-truth accel bias y"); + plotter->AddSeries("$0", "$18", pangolin::DrawingModeDashed, + pangolin::Colour::Blue(), "ground-truth accel bias z"); + } + + if (show_est_vel) { + plotter->AddSeries("$0", "$1", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "estimated velocity x", + &vio_data_log); + plotter->AddSeries("$0", "$2", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "estimated velocity y", + &vio_data_log); + plotter->AddSeries("$0", "$3", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "estimated velocity z", + &vio_data_log); + } + + if (show_est_pos) { + plotter->AddSeries("$0", "$4", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "estimated position x", + &vio_data_log); + plotter->AddSeries("$0", "$5", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "estimated position y", + &vio_data_log); + plotter->AddSeries("$0", "$6", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "estimated position z", + &vio_data_log); + } + + if (show_est_bg) { + plotter->AddSeries("$0", "$7", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "estimated gyro bias x", + &vio_data_log); + plotter->AddSeries("$0", "$8", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "estimated gyro bias y", + &vio_data_log); + plotter->AddSeries("$0", "$9", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "estimated gyro bias z", + &vio_data_log); + } + + if (show_est_ba) { + plotter->AddSeries("$0", "$10", pangolin::DrawingModeLine, + pangolin::Colour::Red(), "estimated accel bias x", + &vio_data_log); + plotter->AddSeries("$0", "$11", pangolin::DrawingModeLine, + pangolin::Colour::Green(), "estimated accel bias y", + &vio_data_log); + plotter->AddSeries("$0", "$12", pangolin::DrawingModeLine, + pangolin::Colour::Blue(), "estimated accel bias z", + &vio_data_log); + } + + double t = gt_frame_t_ns[show_frame] * 1e-9; + plotter->AddMarker(pangolin::Marker::Vertical, t, pangolin::Marker::Equal, + pangolin::Colour::White()); +} + +void setup_vio() { + int64_t t_init_ns = gt_frame_t_ns[0]; + Sophus::SE3d T_w_i_init = gt_frame_T_w_i[0]; + Eigen::Vector3d vel_w_i_init = gt_spline.transVelWorld(t_init_ns); + + std::cout << "Setting up filter: t_ns " << t_init_ns << std::endl; + std::cout << "T_w_i\n" << T_w_i_init.matrix() << std::endl; + std::cout << "vel_w_i " << vel_w_i_init.transpose() << std::endl; + + Eigen::Vector3d gyro_bias_std; + gyro_bias_std.setConstant(gyro_bias_std_dev); + + Eigen::Vector3d accel_bias_std; + accel_bias_std.setConstant(accel_bias_std_dev); + + basalt::VioConfig config; + + vio.reset(new basalt::KeypointVioEstimator( + t_init_ns, T_w_i_init, vel_w_i_init, gt_gyro_bias.front(), + gt_accel_bias.front(), 0.0001, g, calib, config)); + + vio->setMaxStates(3); + vio->setMaxKfs(5); + + // int iteration = 0; + vio_data_log.Clear(); + error_data_log.Clear(); + vio_t_w_i.clear(); +} + +bool next_step() { + if (show_frame < NUM_FRAMES - 1) { + show_frame = show_frame + 1; + show_frame.Meta().gui_changed = true; + return true; + } else { + return false; + } +} + +void alignButton() { + basalt::alignSVD(gt_frame_t_ns, vio_t_w_i, gt_frame_t_ns, gt_frame_t_w_i); +} diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt new file mode 100644 index 0000000..26d576a --- /dev/null +++ b/test/CMakeLists.txt @@ -0,0 +1,31 @@ +cmake_minimum_required(VERSION 3.2) + +find_package(TBB REQUIRED) +include_directories(${TBB_INCLUDE_DIR}) + +set(GTEST_MAIN_LIBRARY gtest_main) +set(GTEST_LIBRARY gtest) + + +include_directories(../thirdparty/basalt-headers/test/include) + + +add_executable(test_image src/test_image.cpp) +target_link_libraries(test_image ${GTEST_LIBRARY} ${GTEST_MAIN_LIBRARY} ${OpenCV_LIBS} basalt) + +add_executable(test_spline_opt src/test_spline_opt.cpp) +target_link_libraries(test_spline_opt ${GTEST_LIBRARY} ${GTEST_MAIN_LIBRARY} ${TBB_LIBRARIES} opengv basalt) + +add_executable(test_vio src/test_vio.cpp) +target_link_libraries(test_vio ${GTEST_LIBRARY} ${GTEST_MAIN_LIBRARY} ${TBB_LIBRARIES} opengv basalt) + +add_executable(test_nfr src/test_nfr.cpp) +target_link_libraries(test_nfr ${GTEST_LIBRARY} ${GTEST_MAIN_LIBRARY} ${TBB_LIBRARIES} opengv basalt) + + +enable_testing() + +add_test(test_image test_image COMMAND Test) +add_test(test_spline_opt test_spline_opt COMMAND Test) +add_test(test_vio test_vio COMMAND Test) +add_test(test_nfr test_nfr COMMAND Test) diff --git a/test/src/test_image.cpp b/test/src/test_image.cpp new file mode 100644 index 0000000..ab47c20 --- /dev/null +++ b/test/src/test_image.cpp @@ -0,0 +1,127 @@ + +#include + +#include + +#include "gtest/gtest.h" +#include "test_utils.h" + +void setImageData(uint16_t *imageArray, int size) { + double norm = RAND_MAX; + norm /= (double)std::numeric_limits::max(); + + for (int i = 0; i < size; i++) { + imageArray[i] = (unsigned char)(rand() / norm); + } +} + +TEST(Pattern, ImageInterp) { + Eigen::Vector2d offset(231.234242, 123.23424); + + basalt::ManagedImage img(640, 480); + setImageData(img.ptr, img.size()); + + Eigen::Vector3d vg = img.interpGrad(offset); + + Eigen::Matrix J = vg.tail<2>(); + + // std::cerr << "vg\n" << vg << std::endl; + + test_jacobian("d_val_d_p", J, + [&](const Eigen::Vector2d &x) { + Eigen::Matrix res; + Eigen::Vector2d p1 = offset + x; + res[0] = img.interpGrad(p1)[0]; + return res; + }, + Eigen::Vector2d::Zero(), 1.0); +} + +TEST(Image, ImageInterpolate) { + Eigen::Vector2i offset(231, 123); + + basalt::ManagedImage img(640, 480); + setImageData(img.ptr, img.size()); + + double eps = 1e-12; + double threshold = 1e-8; + + { + Eigen::Vector2i pi = offset; + Eigen::Vector2d pd = pi.cast() + Eigen::Vector2d(eps, eps); + + uint16_t val1 = img(pi); + double val2 = img.interp(pd); + double val3 = img.interpGrad(pd)[0]; + + EXPECT_LE(std::abs(val2 - val1), threshold); + EXPECT_FLOAT_EQ(val2, val3); + } + + { + Eigen::Vector2i pi = offset; + Eigen::Vector2d pd = pi.cast() + Eigen::Vector2d(eps, eps); + + uint16_t val1 = img(pi); + double val2 = img.interp(pd); + double val3 = img.interpGrad(pd)[0]; + + EXPECT_LE(std::abs(val2 - val1), threshold); + EXPECT_FLOAT_EQ(val2, val3); + } + + { + Eigen::Vector2i pi = offset + Eigen::Vector2i(1, 0); + Eigen::Vector2d pd = pi.cast() + Eigen::Vector2d(-eps, eps); + + uint16_t val1 = img(pi); + double val2 = img.interp(pd); + double val3 = img.interpGrad(pd)[0]; + + EXPECT_LE(std::abs(val2 - val1), threshold); + EXPECT_FLOAT_EQ(val2, val3); + } + + { + Eigen::Vector2i pi = offset + Eigen::Vector2i(0, 1); + Eigen::Vector2d pd = pi.cast() + Eigen::Vector2d(eps, -eps); + + uint16_t val1 = img(pi); + double val2 = img.interp(pd); + double val3 = img.interpGrad(pd)[0]; + + EXPECT_LE(std::abs(val2 - val1), threshold); + EXPECT_FLOAT_EQ(val2, val3); + } + + { + Eigen::Vector2i pi = offset + Eigen::Vector2i(1, 1); + Eigen::Vector2d pd = pi.cast() + Eigen::Vector2d(-eps, -eps); + + uint16_t val1 = img(pi); + double val2 = img.interp(pd); + double val3 = img.interpGrad(pd)[0]; + + EXPECT_LE(std::abs(val2 - val1), threshold); + EXPECT_FLOAT_EQ(val2, val3); + } +} + +TEST(Image, ImageInterpolateGrad) { + Eigen::Vector2i offset(231, 123); + + basalt::ManagedImage img(640, 480); + setImageData(img.ptr, img.size()); + + Eigen::Vector2d pd = offset.cast() + Eigen::Vector2d(0.4, 0.34345); + + Eigen::Vector3d valGrad = img.interpGrad(pd); + Eigen::Matrix J = valGrad.tail<2>(); + + test_jacobian( + "d_res_d_x", J, + [&](const Eigen::Vector2d &x) { + return Eigen::Matrix(img.interp(pd + x)); + }, + Eigen::Vector2d::Zero(), 1); +} diff --git a/test/src/test_nfr.cpp b/test/src/test_nfr.cpp new file mode 100644 index 0000000..ebf6fea --- /dev/null +++ b/test/src/test_nfr.cpp @@ -0,0 +1,137 @@ + + +#include +#include + +#include + +#include "gtest/gtest.h" +#include "test_utils.h" + +static const double accel_std_dev = 0.23; +static const double gyro_std_dev = 0.0027; + +// Smaller noise for testing +// static const double accel_std_dev = 0.00023; +// static const double gyro_std_dev = 0.0000027; + +std::random_device rd{}; +std::mt19937 gen{rd()}; + +std::normal_distribution<> gyro_noise_dist{0, gyro_std_dev}; +std::normal_distribution<> accel_noise_dist{0, accel_std_dev}; + +TEST(PreIntegrationTestSuite, RelPoseTest) { + Sophus::SE3d T_w_i = Sophus::expd(Sophus::Vector6d::Random()); + Sophus::SE3d T_w_j = Sophus::expd(Sophus::Vector6d::Random()); + + Sophus::SE3d T_i_j = + Sophus::expd(Sophus::Vector6d::Random() / 100) * T_w_i.inverse() * T_w_j; + + Sophus::Matrix6d d_res_d_T_w_i, d_res_d_T_w_j; + basalt::relPoseError(T_i_j, T_w_i, T_w_j, &d_res_d_T_w_i, &d_res_d_T_w_j); + + { + Sophus::Vector6d x0; + x0.setZero(); + test_jacobian("d_res_d_T_w_i", d_res_d_T_w_i, + [&](const Sophus::Vector6d& x) { + auto T_w_i_new = T_w_i; + basalt::PoseState::incPose(x, T_w_i_new); + + return basalt::relPoseError(T_i_j, T_w_i_new, T_w_j); + + }, + x0); + } + + { + Sophus::Vector6d x0; + x0.setZero(); + test_jacobian("d_res_d_T_w_j", d_res_d_T_w_j, + [&](const Sophus::Vector6d& x) { + auto T_w_j_new = T_w_j; + basalt::PoseState::incPose(x, T_w_j_new); + + return basalt::relPoseError(T_i_j, T_w_i, T_w_j_new); + + }, + x0); + } +} + +TEST(PreIntegrationTestSuite, AbsPositionTest) { + Sophus::SE3d T_w_i = Sophus::expd(Sophus::Vector6d::Random()); + + Eigen::Vector3d pos = T_w_i.translation() + Eigen::Vector3d::Random() / 10; + + Sophus::Matrix d_res_d_T_w_i; + basalt::absPositionError(T_w_i, pos, &d_res_d_T_w_i); + + { + Sophus::Vector6d x0; + x0.setZero(); + test_jacobian("d_res_d_T_w_i", d_res_d_T_w_i, + [&](const Sophus::Vector6d& x) { + auto T_w_i_new = T_w_i; + basalt::PoseState::incPose(x, T_w_i_new); + + return basalt::absPositionError(T_w_i_new, pos); + + }, + x0); + } +} + +TEST(PreIntegrationTestSuite, YawTest) { + Sophus::SE3d T_w_i = Sophus::expd(Sophus::Vector6d::Random()); + + Eigen::Vector3d yaw_dir_body = + T_w_i.so3().inverse() * Eigen::Vector3d::UnitX(); + + T_w_i = Sophus::expd(Sophus::Vector6d::Random() / 100) * T_w_i; + + Sophus::Matrix d_res_d_T_w_i; + basalt::yawError(T_w_i, yaw_dir_body, &d_res_d_T_w_i); + + { + Sophus::Vector6d x0; + x0.setZero(); + test_jacobian("d_res_d_T_w_i", d_res_d_T_w_i, + [&](const Sophus::Vector6d& x) { + auto T_w_i_new = T_w_i; + basalt::PoseState::incPose(x, T_w_i_new); + + double res = basalt::yawError(T_w_i_new, yaw_dir_body); + + return Eigen::Matrix(res); + + }, + x0); + } +} + +TEST(PreIntegrationTestSuite, RollPitchTest) { + Sophus::SE3d T_w_i = Sophus::expd(Sophus::Vector6d::Random()); + + Sophus::SO3d R_w_i = T_w_i.so3(); + + T_w_i = Sophus::expd(Sophus::Vector6d::Random() / 100) * T_w_i; + + Sophus::Matrix d_res_d_T_w_i; + basalt::rollPitchError(T_w_i, R_w_i, &d_res_d_T_w_i); + + { + Sophus::Vector6d x0; + x0.setZero(); + test_jacobian("d_res_d_T_w_i", d_res_d_T_w_i, + [&](const Sophus::Vector6d& x) { + auto T_w_i_new = T_w_i; + basalt::PoseState::incPose(x, T_w_i_new); + + return basalt::rollPitchError(T_w_i_new, R_w_i); + + }, + x0); + } +} diff --git a/test/src/test_spline_opt.cpp b/test/src/test_spline_opt.cpp new file mode 100644 index 0000000..de154d2 --- /dev/null +++ b/test/src/test_spline_opt.cpp @@ -0,0 +1,109 @@ + + +#include + +#include + +#include "gtest/gtest.h" +#include "test_utils.h" + +TEST(SplineOpt, SplineOptTest) { + tbb::task_scheduler_init init( + tbb::task_scheduler_init::default_num_threads()); + + int num_knots = 15; + + basalt::CalibAccelBias accel_bias_full; + accel_bias_full.setRandom(); + + basalt::CalibGyroBias gyro_bias_full; + gyro_bias_full.setRandom(); + + Eigen::Vector3d g(0, 0, -9.81); + + basalt::Se3Spline<5> gt_spline(int64_t(2e9)); + gt_spline.genRandomTrajectory(num_knots); + + basalt::SplineOptimization<5, double> spline_opt(int64_t(2e9)); + + int64_t pose_dt_ns = 1e8; + for (int64_t t_ns = pose_dt_ns / 2; t_ns < gt_spline.maxTimeNs(); + t_ns += pose_dt_ns) { + Sophus::SE3d pose_gt = gt_spline.pose(t_ns); + + spline_opt.addPoseMeasurement(t_ns, pose_gt); + } + + int64_t dt_ns = 1e7; + for (int64_t t_ns = 0; t_ns < gt_spline.maxTimeNs(); t_ns += dt_ns) { + Sophus::SE3d pose = gt_spline.pose(t_ns); + Eigen::Vector3d accel_body = + pose.so3().inverse() * (gt_spline.transAccelWorld(t_ns) + g); + + // accel_body + accel_bias = (I + scale) * meas + + spline_opt.addAccelMeasurement( + t_ns, accel_bias_full.invertCalibration(accel_body)); + } + + for (int64_t t_ns = 0; t_ns < gt_spline.maxTimeNs(); t_ns += dt_ns) { + Eigen::Vector3d rot_vel_body = gt_spline.rotVelBody(t_ns); + + spline_opt.addGyroMeasurement( + t_ns, gyro_bias_full.invertCalibration(rot_vel_body)); + } + + spline_opt.resetCalib(0, {}); + + spline_opt.initSpline(gt_spline); + spline_opt.init(); + + double error; + double reprojection_error; + int num_inliers; + for (int i = 0; i < 5; i++) + spline_opt.optimize(false, true, false, false, true, false, 0.002, error, + num_inliers, reprojection_error); + + ASSERT_TRUE( + spline_opt.getAccelBias().getParam().isApprox(accel_bias_full.getParam())) + << "spline_opt.getCalib().accel_bias " + << spline_opt.getGyroBias().getParam().transpose() << " and accel_bias " + << accel_bias_full.getParam().transpose() << " are not the same"; + + ASSERT_TRUE( + spline_opt.getGyroBias().getParam().isApprox(gyro_bias_full.getParam())) + << "spline_opt.getCalib().gyro_bias " + << spline_opt.getGyroBias().getParam().transpose() << " and gyro_bias " + << gyro_bias_full.getParam().transpose() << " are not the same"; + + ASSERT_TRUE(spline_opt.getG().isApprox(g)) + << "spline_opt.getG() " << spline_opt.getG().transpose() << " and g " + << g.transpose() << " are not the same"; + + for (int64_t t_ns = 0; t_ns < gt_spline.maxTimeNs(); t_ns += 1e7) { + Sophus::SE3d pose_gt = gt_spline.pose(t_ns); + Sophus::SE3d pose = spline_opt.getSpline().pose(t_ns); + + Eigen::Vector3d pos_gt = pose_gt.translation(); + Eigen::Vector3d pos = pose.translation(); + + Eigen::Vector4d quat_gt = pose_gt.unit_quaternion().coeffs(); + Eigen::Vector4d quat = pose.unit_quaternion().coeffs(); + + Eigen::Vector3d accel_gt = gt_spline.transAccelWorld(t_ns); + Eigen::Vector3d accel = spline_opt.getSpline().transAccelWorld(t_ns); + + Eigen::Vector3d gyro_gt = gt_spline.rotVelBody(t_ns); + Eigen::Vector3d gyro = spline_opt.getSpline().rotVelBody(t_ns); + + ASSERT_TRUE(pos_gt.isApprox(pos)) << "pos_gt and pos are not the same"; + + ASSERT_TRUE(quat_gt.isApprox(quat)) << "quat_gt and quat are not the same"; + + ASSERT_TRUE(accel_gt.isApprox(accel)) + << "accel_gt and accel are not the same"; + + ASSERT_TRUE(gyro_gt.isApprox(gyro)) << "gyro_gt and gyro are not the same"; + } +} diff --git a/test/src/test_vio.cpp b/test/src/test_vio.cpp new file mode 100644 index 0000000..ab039fa --- /dev/null +++ b/test/src/test_vio.cpp @@ -0,0 +1,408 @@ + + +#include +#include + +#include + +#include "gtest/gtest.h" +#include "test_utils.h" + +static const double accel_std_dev = 0.23; +static const double gyro_std_dev = 0.0027; + +// Smaller noise for testing +// static const double accel_std_dev = 0.00023; +// static const double gyro_std_dev = 0.0000027; + +std::random_device rd{}; +std::mt19937 gen{rd()}; + +std::normal_distribution<> gyro_noise_dist{0, gyro_std_dev}; +std::normal_distribution<> accel_noise_dist{0, accel_std_dev}; + +TEST(PreIntegrationTestSuite, ImuNullspace2Test) { + int num_knots = 15; + + Eigen::Vector3d bg, ba; + bg = Eigen::Vector3d::Random() / 100; + ba = Eigen::Vector3d::Random() / 10; + + basalt::IntegratedImuMeasurement imu_meas(0, bg, ba); + + basalt::Se3Spline<5> gt_spline(int64_t(10e9)); + gt_spline.genRandomTrajectory(num_knots); + + basalt::PoseVelBiasState state0, state1, state1_gt; + + state0.t_ns = 0; + state0.T_w_i = gt_spline.pose(int64_t(0)); + state0.vel_w_i = gt_spline.transVelWorld(int64_t(0)); + state0.bias_gyro = bg; + state0.bias_accel = ba; + + int64_t dt_ns = 1e7; + for (int64_t t_ns = dt_ns / 2; + t_ns < int64_t(1e8); // gt_spline.maxTimeNs() - int64_t(1e9); + t_ns += dt_ns) { + Sophus::SE3d pose = gt_spline.pose(t_ns); + Eigen::Vector3d accel_body = + pose.so3().inverse() * + (gt_spline.transAccelWorld(t_ns) - basalt::constants::g); + Eigen::Vector3d rot_vel_body = gt_spline.rotVelBody(t_ns); + + basalt::ImuData data; + data.accel = accel_body + ba; + data.gyro = rot_vel_body + bg; + + data.accel[0] += accel_noise_dist(gen); + data.accel[1] += accel_noise_dist(gen); + data.accel[2] += accel_noise_dist(gen); + + data.gyro[0] += gyro_noise_dist(gen); + data.gyro[1] += gyro_noise_dist(gen); + data.gyro[2] += gyro_noise_dist(gen); + + data.accel_cov.setConstant(accel_std_dev * accel_std_dev); + data.gyro_cov.setConstant(gyro_std_dev * gyro_std_dev); + + data.t_ns = t_ns + dt_ns / 2; // measurement in the middle of the interval; + + imu_meas.integrate(data); + } + + state1.t_ns = imu_meas.get_dt_ns(); + state1.T_w_i = gt_spline.pose(imu_meas.get_dt_ns()) * + Sophus::expd(Sophus::Vector6d::Random() / 10); + state1.vel_w_i = gt_spline.transVelWorld(imu_meas.get_dt_ns()) + + Sophus::Vector3d::Random() / 10; + state1.bias_gyro = bg; + state1.bias_accel = ba; + + Eigen::Vector3d gyro_weight; + gyro_weight.setConstant(1e6); + + Eigen::Vector3d accel_weight; + accel_weight.setConstant(1e6); + + Eigen::map imu_meas_vec; + Eigen::map frame_states; + Eigen::map frame_poses; + + imu_meas_vec[state0.t_ns] = imu_meas; + frame_states[state0.t_ns] = state0; + frame_states[state1.t_ns] = state1; + + int asize = 30; + Eigen::MatrixXd H; + Eigen::VectorXd b; + H.setZero(asize, asize); + b.setZero(asize); + + basalt::AbsOrderMap aom; + aom.total_size = 30; + aom.items = 2; + aom.abs_order_map[state0.t_ns] = std::make_pair(0, 15); + aom.abs_order_map[state1.t_ns] = std::make_pair(15, 15); + + double imu_error, bg_error, ba_error; + basalt::KeypointVioEstimator::linearizeAbsIMU( + aom, H, b, imu_error, bg_error, ba_error, frame_states, imu_meas_vec, + gyro_weight, accel_weight, basalt::constants::g); + + // Check quadratic approximation + for (int i = 0; i < 10; i++) { + Eigen::VectorXd rand_inc; + rand_inc.setRandom(asize); + rand_inc.normalize(); + rand_inc /= 10000; + + auto frame_states_copy = frame_states; + frame_states_copy[state0.t_ns].applyInc(rand_inc.segment<15>(0)); + frame_states_copy[state1.t_ns].applyInc(rand_inc.segment<15>(15)); + + double imu_error_u, bg_error_u, ba_error_u; + basalt::KeypointVioEstimator::computeImuError( + aom, imu_error_u, bg_error_u, ba_error_u, frame_states_copy, + imu_meas_vec, gyro_weight, accel_weight, basalt::constants::g); + + double e0 = imu_error + bg_error + ba_error; + double e1 = imu_error_u + bg_error_u + ba_error_u - e0; + + double e2 = 0.5 * rand_inc.transpose() * H * rand_inc; + e2 += rand_inc.transpose() * b; + + EXPECT_LE(std::abs(e1 - e2), 1e-2) << "e1 " << e1 << " e2 " << e2; + } + + std::cout << "=========================================" << std::endl; + Eigen::VectorXd null_res = basalt::KeypointVioEstimator::checkNullspace( + H, b, aom, frame_states, frame_poses); + std::cout << "=========================================" << std::endl; + + EXPECT_LE(std::abs(null_res[0]), 1e-8); + EXPECT_LE(std::abs(null_res[1]), 1e-8); + EXPECT_LE(std::abs(null_res[2]), 1e-8); + EXPECT_LE(std::abs(null_res[5]), 1e-6); +} + +TEST(PreIntegrationTestSuite, ImuNullspace3Test) { + int num_knots = 15; + + Eigen::Vector3d bg, ba; + bg = Eigen::Vector3d::Random() / 100; + ba = Eigen::Vector3d::Random() / 10; + + basalt::IntegratedImuMeasurement imu_meas1(0, bg, ba); + + basalt::Se3Spline<5> gt_spline(int64_t(10e9)); + gt_spline.genRandomTrajectory(num_knots); + + basalt::PoseVelBiasState state0, state1, state2; + + state0.t_ns = 0; + state0.T_w_i = gt_spline.pose(int64_t(0)); + state0.vel_w_i = gt_spline.transVelWorld(int64_t(0)); + state0.bias_gyro = bg; + state0.bias_accel = ba; + + int64_t dt_ns = 1e7; + for (int64_t t_ns = dt_ns / 2; + t_ns < int64_t(1e9); // gt_spline.maxTimeNs() - int64_t(1e9); + t_ns += dt_ns) { + Sophus::SE3d pose = gt_spline.pose(t_ns); + Eigen::Vector3d accel_body = + pose.so3().inverse() * + (gt_spline.transAccelWorld(t_ns) - basalt::constants::g); + Eigen::Vector3d rot_vel_body = gt_spline.rotVelBody(t_ns); + + basalt::ImuData data; + data.accel = accel_body + ba; + data.gyro = rot_vel_body + bg; + + data.accel[0] += accel_noise_dist(gen); + data.accel[1] += accel_noise_dist(gen); + data.accel[2] += accel_noise_dist(gen); + + data.gyro[0] += gyro_noise_dist(gen); + data.gyro[1] += gyro_noise_dist(gen); + data.gyro[2] += gyro_noise_dist(gen); + + data.accel_cov.setConstant(accel_std_dev * accel_std_dev); + data.gyro_cov.setConstant(gyro_std_dev * gyro_std_dev); + + data.t_ns = t_ns + dt_ns / 2; // measurement in the middle of the interval; + + imu_meas1.integrate(data); + } + + basalt::IntegratedImuMeasurement imu_meas2(imu_meas1.get_dt_ns(), bg, ba); + for (int64_t t_ns = imu_meas1.get_dt_ns() + dt_ns / 2; + t_ns < int64_t(2e9); // gt_spline.maxTimeNs() - int64_t(1e9); + t_ns += dt_ns) { + Sophus::SE3d pose = gt_spline.pose(t_ns); + Eigen::Vector3d accel_body = + pose.so3().inverse() * + (gt_spline.transAccelWorld(t_ns) - basalt::constants::g); + Eigen::Vector3d rot_vel_body = gt_spline.rotVelBody(t_ns); + + basalt::ImuData data; + data.accel = accel_body + ba; + data.gyro = rot_vel_body + bg; + + data.accel[0] += accel_noise_dist(gen); + data.accel[1] += accel_noise_dist(gen); + data.accel[2] += accel_noise_dist(gen); + + data.gyro[0] += gyro_noise_dist(gen); + data.gyro[1] += gyro_noise_dist(gen); + data.gyro[2] += gyro_noise_dist(gen); + + data.accel_cov.setConstant(accel_std_dev * accel_std_dev); + data.gyro_cov.setConstant(gyro_std_dev * gyro_std_dev); + + data.t_ns = t_ns + dt_ns / 2; // measurement in the middle of the interval; + + imu_meas2.integrate(data); + } + + state1.t_ns = imu_meas1.get_dt_ns(); + state1.T_w_i = gt_spline.pose(state1.t_ns) * + Sophus::expd(Sophus::Vector6d::Random() / 10); + state1.vel_w_i = + gt_spline.transVelWorld(state1.t_ns) + Sophus::Vector3d::Random() / 10; + state1.bias_gyro = bg; + state1.bias_accel = ba; + + state2.t_ns = imu_meas1.get_dt_ns() + imu_meas2.get_dt_ns(); + state2.T_w_i = gt_spline.pose(state2.t_ns) * + Sophus::expd(Sophus::Vector6d::Random() / 10); + state2.vel_w_i = + gt_spline.transVelWorld(state2.t_ns) + Sophus::Vector3d::Random() / 10; + state2.bias_gyro = bg; + state2.bias_accel = ba; + + Eigen::Vector3d gyro_weight; + gyro_weight.setConstant(1e6); + + Eigen::Vector3d accel_weight; + accel_weight.setConstant(1e6); + + Eigen::map imu_meas_vec; + Eigen::map frame_states; + Eigen::map frame_poses; + + imu_meas_vec[imu_meas1.get_start_t_ns()] = imu_meas1; + imu_meas_vec[imu_meas2.get_start_t_ns()] = imu_meas2; + frame_states[state0.t_ns] = state0; + frame_states[state1.t_ns] = state1; + frame_states[state2.t_ns] = state2; + + int asize = 45; + Eigen::MatrixXd H; + Eigen::VectorXd b; + H.setZero(asize, asize); + b.setZero(asize); + + basalt::AbsOrderMap aom; + aom.total_size = asize; + aom.items = 2; + aom.abs_order_map[state0.t_ns] = std::make_pair(0, 15); + aom.abs_order_map[state1.t_ns] = std::make_pair(15, 15); + aom.abs_order_map[state2.t_ns] = std::make_pair(30, 15); + + double imu_error, bg_error, ba_error; + basalt::KeypointVioEstimator::linearizeAbsIMU( + aom, H, b, imu_error, bg_error, ba_error, frame_states, imu_meas_vec, + gyro_weight, accel_weight, basalt::constants::g); + + std::cout << "=========================================" << std::endl; + Eigen::VectorXd null_res = basalt::KeypointVioEstimator::checkNullspace( + H, b, aom, frame_states, frame_poses); + std::cout << "=========================================" << std::endl; + + EXPECT_LE(std::abs(null_res[0]), 1e-8); + EXPECT_LE(std::abs(null_res[1]), 1e-8); + EXPECT_LE(std::abs(null_res[2]), 1e-8); + EXPECT_LE(std::abs(null_res[5]), 1e-6); +} + +TEST(PreIntegrationTestSuite, RelPoseTest) { + Sophus::SE3d T_w_i_h = Sophus::expd(Sophus::Vector6d::Random()); + Sophus::SE3d T_w_i_t = Sophus::expd(Sophus::Vector6d::Random()); + + Sophus::SE3d T_i_c_h = Sophus::expd(Sophus::Vector6d::Random() / 10); + Sophus::SE3d T_i_c_t = Sophus::expd(Sophus::Vector6d::Random() / 10); + + Sophus::Matrix6d d_rel_d_h, d_rel_d_t; + + Sophus::SE3d T_t_h_sophus = basalt::KeypointVioEstimator::computeRelPose( + T_w_i_h, T_i_c_h, T_w_i_t, T_i_c_t, &d_rel_d_h, &d_rel_d_t); + + { + Sophus::Vector6d x0; + x0.setZero(); + test_jacobian( + "d_rel_d_h", d_rel_d_h, + [&](const Sophus::Vector6d& x) { + Sophus::SE3d T_w_h_new = T_w_i_h; + basalt::PoseState::incPose(x, T_w_h_new); + + Sophus::SE3d T_t_h_sophus_new = + basalt::KeypointVioEstimator::computeRelPose(T_w_h_new, T_i_c_h, + T_w_i_t, T_i_c_t); + + return Sophus::logd(T_t_h_sophus_new * T_t_h_sophus.inverse()); + }, + x0); + } + + { + Sophus::Vector6d x0; + x0.setZero(); + test_jacobian( + "d_rel_d_t", d_rel_d_t, + [&](const Sophus::Vector6d& x) { + Sophus::SE3d T_w_t_new = T_w_i_t; + basalt::PoseState::incPose(x, T_w_t_new); + + Sophus::SE3d T_t_h_sophus_new = + basalt::KeypointVioEstimator::computeRelPose(T_w_i_h, T_i_c_h, + T_w_t_new, T_i_c_t); + return Sophus::logd(T_t_h_sophus_new * T_t_h_sophus.inverse()); + }, + x0); + } +} + +TEST(PreIntegrationTestSuite, LinearizePointsTest) { + basalt::ExtendedUnifiedCamera cam = + basalt::ExtendedUnifiedCamera::getTestProjections()[0]; + + basalt::KeypointVioEstimator::KeypointPosition kpt_pos; + + Eigen::Vector4d point3d; + cam.unproject(Eigen::Vector2d::Random() * 50, point3d); + kpt_pos.dir = basalt::StereographicParam::project(point3d); + kpt_pos.id = 0.1231231; + + Sophus::SE3d T_w_h = Sophus::expd(Sophus::Vector6d::Random() / 100); + Sophus::SE3d T_w_t = Sophus::expd(Sophus::Vector6d::Random() / 100); + T_w_t.translation()[0] += 0.1; + + Sophus::SE3d T_t_h_sophus = T_w_t.inverse() * T_w_h; + Eigen::Matrix4d T_t_h = T_t_h_sophus.matrix(); + + Eigen::Vector4d p_trans; + p_trans = basalt::StereographicParam::unproject(kpt_pos.dir); + p_trans(3) = kpt_pos.id; + + p_trans = T_t_h * p_trans; + + basalt::KeypointVioEstimator::KeypointObservation kpt_obs; + cam.project(p_trans, kpt_obs.pos); + + Eigen::Vector2d res; + Eigen::Matrix d_res_d_xi; + Eigen::Matrix d_res_d_p; + + basalt::KeypointVioEstimator::linearizePoint(kpt_obs, kpt_pos, T_t_h, cam, + res, &d_res_d_xi, &d_res_d_p); + + { + Sophus::Vector6d x0; + x0.setZero(); + test_jacobian("d_res_d_xi", d_res_d_xi, + [&](const Sophus::Vector6d& x) { + Eigen::Matrix4d T_t_h_new = + (Sophus::expd(x) * T_t_h_sophus).matrix(); + + Eigen::Vector2d res; + basalt::KeypointVioEstimator::linearizePoint( + kpt_obs, kpt_pos, T_t_h_new, cam, res); + + return res; + }, + x0); + } + + { + Eigen::Vector3d x0; + x0.setZero(); + test_jacobian("d_res_d_p", d_res_d_p, + [&](const Eigen::Vector3d& x) { + basalt::KeypointVioEstimator::KeypointPosition kpt_pos_new = + kpt_pos; + + kpt_pos_new.dir += x.head<2>(); + kpt_pos_new.id += x[2]; + + Eigen::Vector2d res; + basalt::KeypointVioEstimator::linearizePoint( + kpt_obs, kpt_pos_new, T_t_h, cam, res); + + return res; + }, + x0); + } +} diff --git a/thirdparty/CLI11 b/thirdparty/CLI11 new file mode 160000 index 0000000..76d2cde --- /dev/null +++ b/thirdparty/CLI11 @@ -0,0 +1 @@ +Subproject commit 76d2cde6568c9c8870b728aa9bc64b70b29127fd diff --git a/thirdparty/DBoW3/CMakeLists.txt b/thirdparty/DBoW3/CMakeLists.txt new file mode 100644 index 0000000..c03b656 --- /dev/null +++ b/thirdparty/DBoW3/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 2.8) +PROJECT(DBoW3) +set(PROJECT_VERSION "0.0.1") +string(REGEX MATCHALL "[0-9]" PROJECT_VERSION_PARTS "${PROJECT_VERSION}") +list(GET PROJECT_VERSION_PARTS 0 PROJECT_VERSION_MAJOR) +list(GET PROJECT_VERSION_PARTS 1 PROJECT_VERSION_MINOR) +list(GET PROJECT_VERSION_PARTS 2 PROJECT_VERSION_PATCH) +set(PROJECT_SOVERSION "${PROJECT_VERSION_MAJOR}.${PROJECT_VERSION_MINOR}") + +#------------------------------------------------ +# DIRS +#------------------------------------------------ +ADD_SUBDIRECTORY(src) +set(LIBRARY_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/lib) + diff --git a/thirdparty/DBoW3/LICENSE.txt b/thirdparty/DBoW3/LICENSE.txt new file mode 100644 index 0000000..fa723d9 --- /dev/null +++ b/thirdparty/DBoW3/LICENSE.txt @@ -0,0 +1,44 @@ +DBoW3: bag-of-words library for C++ with generic descriptors + +Copyright (c) 2015 Dorian Galvez-Lopez (Universidad de Zaragoza) +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 copyright holders nor the names of its + contributors may be used to endorse or promote products derived + from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +''AS IS'' AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED +TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDERS 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. + +If you use it in an academic work, please cite: + + @ARTICLE{GalvezTRO12, + author={G\'alvez-L\'opez, Dorian and Tard\'os, J. D.}, + journal={IEEE Transactions on Robotics}, + title={Bags of Binary Words for Fast Place Recognition in Image Sequences}, + year={2012}, + month={October}, + volume={28}, + number={5}, + pages={1188--1197}, + doi={10.1109/TRO.2012.2197158}, + ISSN={1552-3098} + } + diff --git a/thirdparty/DBoW3/README.txt b/thirdparty/DBoW3/README.txt new file mode 100644 index 0000000..aab0eae --- /dev/null +++ b/thirdparty/DBoW3/README.txt @@ -0,0 +1,7 @@ +You should have received this DBoW3 version along with ORB-SLAM2 (https://github.com/raulmur/ORB_SLAM2). +See the original DBoW3 library at: https://github.com/dorian3d/DBoW3 +All files included in this version are BSD, see LICENSE.txt + +We also use Random.h, Random.cpp, Timestamp.pp and Timestamp.h from DLib/DUtils. +See the original DLib library at: https://github.com/dorian3d/DLib +All files included in this version are BSD, see LICENSE.txt diff --git a/thirdparty/DBoW3/src/BowVector.cpp b/thirdparty/DBoW3/src/BowVector.cpp new file mode 100644 index 0000000..5af960b --- /dev/null +++ b/thirdparty/DBoW3/src/BowVector.cpp @@ -0,0 +1,136 @@ +/** + * File: BowVector.cpp + * Date: March 2011 + * Author: Dorian Galvez-Lopez + * Description: bag of words vector + * License: see the LICENSE.txt file + * + */ + +#include +#include +#include +#include +#include + +#include "BowVector.h" + +namespace DBoW3 { + +// -------------------------------------------------------------------------- + +BowVector::BowVector(void) {} + +// -------------------------------------------------------------------------- + +BowVector::~BowVector(void) {} + +// -------------------------------------------------------------------------- + +void BowVector::addWeight(WordId id, WordValue v) { + BowVector::iterator vit = this->lower_bound(id); + + if (vit != this->end() && !(this->key_comp()(id, vit->first))) { + vit->second += v; + } else { + this->insert(vit, BowVector::value_type(id, v)); + } +} + +// -------------------------------------------------------------------------- + +void BowVector::addIfNotExist(WordId id, WordValue v) { + BowVector::iterator vit = this->lower_bound(id); + + if (vit == this->end() || (this->key_comp()(id, vit->first))) { + this->insert(vit, BowVector::value_type(id, v)); + } +} + +// -------------------------------------------------------------------------- + +void BowVector::normalize(LNorm norm_type) { + double norm = 0.0; + BowVector::iterator it; + + if (norm_type == DBoW3::L1) { + for (it = begin(); it != end(); ++it) norm += fabs(it->second); + } else { + for (it = begin(); it != end(); ++it) norm += it->second * it->second; + norm = sqrt(norm); + } + + if (norm > 0.0) { + for (it = begin(); it != end(); ++it) it->second /= norm; + } +} + +// -------------------------------------------------------------------------- + +std::ostream &operator<<(std::ostream &out, const BowVector &v) { + BowVector::const_iterator vit; + // std::vector::const_iterator iit; + unsigned int i = 0; + const size_t N = v.size(); + for (vit = v.begin(); vit != v.end(); ++vit, ++i) { + out << "<" << vit->first << ", " << vit->second << ">"; + + if (i < N - 1) out << ", "; + } + return out; +} + +// -------------------------------------------------------------------------- + +void BowVector::saveM(const std::string &filename, size_t W) const { + std::fstream f(filename.c_str(), std::ios::out); + + WordId last = 0; + BowVector::const_iterator bit; + for (bit = this->begin(); bit != this->end(); ++bit) { + for (; last < bit->first; ++last) { + f << "0 "; + } + f << bit->second << " "; + + last = bit->first + 1; + } + for (; last < (WordId)W; ++last) f << "0 "; + + f.close(); +} +// -------------------------------------------------------------------------- + +void BowVector::toStream(std::ostream &str) const { + uint32_t s = size(); + str.write((char *)&s, sizeof(s)); + for (auto d : *this) { + str.write((char *)&d.first, sizeof(d.first)); + str.write((char *)&d.second, sizeof(d.second)); + } +} +// -------------------------------------------------------------------------- + +void BowVector::fromStream(std::istream &str) { + clear(); + uint32_t s; + + str.read((char *)&s, sizeof(s)); + for (uint32_t i = 0; i < s; i++) { + WordId wid; + WordValue wv; + str.read((char *)&wid, sizeof(wid)); + str.read((char *)&wv, sizeof(wv)); + insert(std::make_pair(wid, wv)); + } +} + +uint64_t BowVector::getSignature() const { + uint64_t sig = 0; + for (auto ww : *this) sig += ww.first + 1e6 * ww.second; + return sig; +} + +// -------------------------------------------------------------------------- + +} // namespace DBoW3 diff --git a/thirdparty/DBoW3/src/BowVector.h b/thirdparty/DBoW3/src/BowVector.h new file mode 100644 index 0000000..d8c17e0 --- /dev/null +++ b/thirdparty/DBoW3/src/BowVector.h @@ -0,0 +1,117 @@ +/** + * File: BowVector.h + * Date: March 2011 + * Author: Dorian Galvez-Lopez + * Description: bag of words vector + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_BOW_VECTOR__ +#define __D_T_BOW_VECTOR__ + +#include +#include +#include "exports.h" +#if _WIN32 +#include +#endif +namespace DBoW3 { + +/// Id of words +typedef unsigned int WordId; + +/// Value of a word +typedef double WordValue; + +/// Id of nodes in the vocabulary tree +typedef unsigned int NodeId; + +/// L-norms for normalization +enum LNorm +{ + L1, + L2 +}; + +/// Weighting type +enum WeightingType +{ + TF_IDF, + TF, + IDF, + BINARY +}; + +/// Scoring type +enum ScoringType +{ + L1_NORM, + L2_NORM, + CHI_SQUARE, + KL, + BHATTACHARYYA, + DOT_PRODUCT +}; + +/// Vector of words to represent images +class DBOW_API BowVector: + public std::map +{ +public: + + /** + * Constructor + */ + BowVector(void); + + /** + * Destructor + */ + ~BowVector(void); + + /** + * Adds a value to a word value existing in the vector, or creates a new + * word with the given value + * @param id word id to look for + * @param v value to create the word with, or to add to existing word + */ + void addWeight(WordId id, WordValue v); + + /** + * Adds a word with a value to the vector only if this does not exist yet + * @param id word id to look for + * @param v value to give to the word if this does not exist + */ + void addIfNotExist(WordId id, WordValue v); + + /** + * L1-Normalizes the values in the vector + * @param norm_type norm used + */ + void normalize(LNorm norm_type); + + /** + * Prints the content of the bow vector + * @param out stream + * @param v + */ + friend std::ostream& operator<<(std::ostream &out, const BowVector &v); + + /** + * Saves the bow vector as a vector in a matlab file + * @param filename + * @param W number of words in the vocabulary + */ + void saveM(const std::string &filename, size_t W) const; + + //returns a unique number from the configuration + uint64_t getSignature()const; + //serialization + void toStream(std::ostream &str)const; + void fromStream(std::istream &str); +}; + +} // namespace DBoW3 + +#endif diff --git a/thirdparty/DBoW3/src/CMakeLists.txt b/thirdparty/DBoW3/src/CMakeLists.txt new file mode 100644 index 0000000..7d1019b --- /dev/null +++ b/thirdparty/DBoW3/src/CMakeLists.txt @@ -0,0 +1,20 @@ +FILE(GLOB hdrs_base "*.h" ) +FILE(GLOB srcs_base "*.c*") + +FILE(GLOB hdrs ${hdrs_base} ) +FILE(GLOB srcs ${srcs_base} ) + + +ADD_LIBRARY(${PROJECT_NAME} ${srcs} ${hdrs}) +INCLUDE_DIRECTORIES(${CMAKE_CURRENT_BINARY_DIR} ) + +SET_TARGET_PROPERTIES(${PROJECT_NAME} PROPERTIES # create *nix style library versions + symbolic links + DEFINE_SYMBOL DBOW_DSO_EXPORTS + VERSION ${PROJECT_VERSION} + SOVERSION ${PROJECT_SOVERSION} + CLEAN_DIRECT_OUTPUT 1 # allow creating static and shared libs without conflicts + OUTPUT_NAME "${PROJECT_NAME}${PROJECT_DLLVERSION}" # avoid conflicts between library and binary target names +) + +TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${REQUIRED_LIBRARIES} ${OpenCV_LIBS}) + diff --git a/thirdparty/DBoW3/src/DBoW3.h b/thirdparty/DBoW3/src/DBoW3.h new file mode 100644 index 0000000..aabeadb --- /dev/null +++ b/thirdparty/DBoW3/src/DBoW3.h @@ -0,0 +1,68 @@ +/* + * File: DBoW3.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: Generic include file for the DBoW3 classes and + * the specialized vocabularies and databases + * License: see the LICENSE.txt file + * + */ + +/*! \mainpage DBoW3 Library + * + * DBoW3 library for C++: + * Bag-of-word image database for image retrieval. + * + * Written by Rafael Muñoz Salinas, + * University of Cordoba (Spain) + * + * + * \section requirements Requirements + * This library requires the OpenCV libraries, + * as well as the boost::dynamic_bitset class. + * + * \section citation Citation + * If you use this software in academic works, please cite: +

    +   @@ARTICLE{GalvezTRO12,
    +    author={Galvez-Lopez, Dorian and Tardos, J. D.}, 
    +    journal={IEEE Transactions on Robotics},
    +    title={Bags of Binary Words for Fast Place Recognition in Image Sequences},
    +    year={2012},
    +    month={October},
    +    volume={28},
    +    number={5},
    +    pages={1188--1197},
    +    doi={10.1109/TRO.2012.2197158},
    +    ISSN={1552-3098}
    +  }
    + 
    + * + * \section license License + * This file is licensed under a Creative Commons + * Attribution-NonCommercial-ShareAlike 3.0 license. + * This file can be freely used and users can use, download and edit this file + * provided that credit is attributed to the original author. No users are + * permitted to use this file for commercial purposes unless explicit permission + * is given by the original author. Derivative works must be licensed using the + * same or similar license. + * Check http://creativecommons.org/licenses/by-nc-sa/3.0/ to obtain further + * details. + * + */ + +#ifndef __D_T_DBOW3__ +#define __D_T_DBOW3__ + +/// Includes all the data structures to manage vocabularies and image databases + +#include "Vocabulary.h" +#include "Database.h" +#include "BowVector.h" +#include "FeatureVector.h" +#include "QueryResults.h" + + + +#endif + diff --git a/thirdparty/DBoW3/src/Database.cpp b/thirdparty/DBoW3/src/Database.cpp new file mode 100644 index 0000000..c31bd74 --- /dev/null +++ b/thirdparty/DBoW3/src/Database.cpp @@ -0,0 +1,855 @@ +#include "Database.h" + +#include + +namespace DBoW3 { + +// For query functions +static int MIN_COMMON_WORDS = 5; + +// -------------------------------------------------------------------------- + +Database::Database(bool use_di, int di_levels) + : m_voc(NULL), m_use_di(use_di), m_dilevels(di_levels), m_nentries(0) {} + +// -------------------------------------------------------------------------- + +Database::Database(const Vocabulary &voc, bool use_di, int di_levels) + : m_voc(NULL), m_use_di(use_di), m_dilevels(di_levels) { + setVocabulary(voc); + clear(); +} + +// -------------------------------------------------------------------------- + +Database::Database(const Database &db) : m_voc(NULL) { *this = db; } + +// -------------------------------------------------------------------------- + +Database::Database(const std::string &filename) : m_voc(NULL) { + load(filename); +} + +// -------------------------------------------------------------------------- + +Database::Database(const char *filename) : m_voc(NULL) { load(filename); } + +// -------------------------------------------------------------------------- + +Database::~Database(void) { delete m_voc; } + +// -------------------------------------------------------------------------- + +Database &Database::operator=(const Database &db) { + if (this != &db) { + m_dfile = db.m_dfile; + m_dilevels = db.m_dilevels; + m_ifile = db.m_ifile; + m_nentries = db.m_nentries; + m_use_di = db.m_use_di; + if (db.m_voc != 0) setVocabulary(*db.m_voc); + } + return *this; +} + +// -------------------------------------------------------------------------- + +EntryId Database::add(const cv::Mat &features, BowVector *bowvec, + FeatureVector *fvec) { + std::vector vf(features.rows); + for (int r = 0; r < features.rows; r++) vf[r] = features.rowRange(r, r + 1); + return add(vf, bowvec, fvec); +} + +EntryId Database::add(const std::vector &features, BowVector *bowvec, + FeatureVector *fvec) { + BowVector aux; + BowVector &v = (bowvec ? *bowvec : aux); + + if (m_use_di && fvec != NULL) { + m_voc->transform(features, v, *fvec, m_dilevels); // with features + return add(v, *fvec); + } else if (m_use_di) { + FeatureVector fv; + m_voc->transform(features, v, fv, m_dilevels); // with features + return add(v, fv); + } else if (fvec != NULL) { + m_voc->transform(features, v, *fvec, m_dilevels); // with features + return add(v); + } else { + m_voc->transform(features, v); // with features + return add(v); + } +} + +EntryId Database::add(const std::vector> &features, + BowVector *bowvec, FeatureVector *fvec) { + BowVector aux; + BowVector &v = (bowvec ? *bowvec : aux); + + if (m_use_di && fvec != NULL) { + m_voc->transform(features, v, *fvec, m_dilevels); // with features + return add(v, *fvec); + } else if (m_use_di) { + FeatureVector fv; + m_voc->transform(features, v, fv, m_dilevels); // with features + return add(v, fv); + } else if (fvec != NULL) { + m_voc->transform(features, v, *fvec, m_dilevels); // with features + return add(v); + } else { + m_voc->transform(features, v); // with features + return add(v); + } +} + +// --------------------------------------------------------------------------- + +EntryId Database::add(const BowVector &v, const FeatureVector &fv) { + EntryId entry_id = m_nentries++; + + BowVector::const_iterator vit; + // std::vector::const_iterator iit; + + if (m_use_di) { + // update direct file + if (entry_id == m_dfile.size()) { + m_dfile.push_back(fv); + } else { + m_dfile[entry_id] = fv; + } + } + + // update inverted file + for (vit = v.begin(); vit != v.end(); ++vit) { + const WordId &word_id = vit->first; + const WordValue &word_weight = vit->second; + + IFRow &ifrow = m_ifile[word_id]; + ifrow.push_back(IFPair(entry_id, word_weight)); + } + + return entry_id; +} + +// -------------------------------------------------------------------------- + +void Database::setVocabulary(const Vocabulary &voc) { + delete m_voc; + m_voc = new Vocabulary(voc); + clear(); +} + +// -------------------------------------------------------------------------- + +void Database::setVocabulary(const Vocabulary &voc, bool use_di, + int di_levels) { + m_use_di = use_di; + m_dilevels = di_levels; + delete m_voc; + m_voc = new Vocabulary(voc); + clear(); +} + +// -------------------------------------------------------------------------- + +void Database::clear() { + // resize vectors + m_ifile.resize(0); + m_ifile.resize(m_voc->size()); + m_dfile.resize(0); + m_nentries = 0; +} + +// -------------------------------------------------------------------------- + +void Database::allocate(int nd, int ni) { + // m_ifile already contains |words| items + if (ni > 0) { + for (auto rit = m_ifile.begin(); rit != m_ifile.end(); ++rit) { + int n = (int)rit->size(); + if (ni > n) { + rit->resize(ni); + rit->resize(n); + } + } + } + + if (m_use_di && (int)m_dfile.size() < nd) { + m_dfile.resize(nd); + } +} + +// -------------------------------------------------------------------------- + +void Database::query(const cv::Mat &features, QueryResults &ret, + int max_results, int max_id) const { + std::vector vf(features.rows); + for (int r = 0; r < features.rows; r++) vf[r] = features.rowRange(r, r + 1); + query(vf, ret, max_results, max_id); +} + +void Database::query(const std::vector &features, QueryResults &ret, + int max_results, int max_id) const { + BowVector vec; + m_voc->transform(features, vec); + query(vec, ret, max_results, max_id); +} + +void Database::query(const std::vector> &features, + QueryResults &ret, int max_results, int max_id) const { + BowVector vec; + m_voc->transform(features, vec); + query(vec, ret, max_results, max_id); +} + +// -------------------------------------------------------------------------- + +void Database::query(const BowVector &vec, QueryResults &ret, int max_results, + int max_id) const { + ret.resize(0); + + switch (m_voc->getScoringType()) { + case L1_NORM: + queryL1(vec, ret, max_results, max_id); + break; + + case L2_NORM: + queryL2(vec, ret, max_results, max_id); + break; + + case CHI_SQUARE: + queryChiSquare(vec, ret, max_results, max_id); + break; + + case KL: + queryKL(vec, ret, max_results, max_id); + break; + + case BHATTACHARYYA: + queryBhattacharyya(vec, ret, max_results, max_id); + break; + + case DOT_PRODUCT: + queryDotProduct(vec, ret, max_results, max_id); + break; + } +} + +// -------------------------------------------------------------------------- + +void Database::queryL1(const BowVector &vec, QueryResults &ret, int max_results, + int max_id) const { + BowVector::const_iterator vit; + + std::unordered_map pairs; + + for (vit = vec.begin(); vit != vec.end(); ++vit) { + const WordId word_id = vit->first; + const WordValue &qvalue = vit->second; + + const IFRow &row = m_ifile[word_id]; + + // IFRows are sorted in ascending entry_id order + + for (const auto &rit : row) { + const EntryId &entry_id = rit.entry_id; + const WordValue &dvalue = rit.word_weight; + + if ((int)entry_id < max_id || max_id == -1) { + double value = fabs(qvalue - dvalue) - fabs(qvalue) - fabs(dvalue); + + auto it = pairs.find(entry_id); + if (it != pairs.end()) { + it->second += value; + } else { + pairs.emplace(entry_id, value); + } + } + + } // for each inverted row + } // for each query word + + // move to vector + ret.reserve(pairs.size()); + for (const auto &pit : pairs) { + ret.push_back(Result(pit.first, pit.second)); + } + + // resulting "scores" are now in [-2 best .. 0 worst] + + // sort vector in ascending order of score + std::sort(ret.begin(), ret.end()); + // (ret is inverted now --the lower the better--) + + // cut vector + if (max_results > 0 && (int)ret.size() > max_results) ret.resize(max_results); + + // complete and scale score to [0 worst .. 1 best] + // ||v - w||_{L1} = 2 + Sum(|v_i - w_i| - |v_i| - |w_i|) + // for all i | v_i != 0 and w_i != 0 + // (Nister, 2006) + // scaled_||v - w||_{L1} = 1 - 0.5 * ||v - w||_{L1} + QueryResults::iterator qit; + for (qit = ret.begin(); qit != ret.end(); qit++) + qit->Score = -qit->Score / 2.0; +} + +// -------------------------------------------------------------------------- + +void Database::queryL2(const BowVector &vec, QueryResults &ret, int max_results, + int max_id) const { + BowVector::const_iterator vit; + + std::map pairs; + std::map::iterator pit; + + // map counters; + // map::iterator cit; + + for (vit = vec.begin(); vit != vec.end(); ++vit) { + const WordId word_id = vit->first; + const WordValue &qvalue = vit->second; + + const IFRow &row = m_ifile[word_id]; + + // IFRows are sorted in ascending entry_id order + + for (auto rit = row.begin(); rit != row.end(); ++rit) { + const EntryId entry_id = rit->entry_id; + const WordValue &dvalue = rit->word_weight; + + if ((int)entry_id < max_id || max_id == -1) { + double value = -qvalue * dvalue; // minus sign for sorting trick + + pit = pairs.lower_bound(entry_id); + // cit = counters.lower_bound(entry_id); + if (pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) { + pit->second += value; + // cit->second += 1; + } else { + pairs.insert(pit, + std::map::value_type(entry_id, value)); + + // counters.insert(cit, + // map::value_type(entry_id, 1)); + } + } + + } // for each inverted row + } // for each query word + + // move to vector + ret.reserve(pairs.size()); + // cit = counters.begin(); + for (pit = pairs.begin(); pit != pairs.end(); ++pit) //, ++cit) + { + ret.push_back(Result(pit->first, pit->second)); // / cit->second)); + } + + // resulting "scores" are now in [-1 best .. 0 worst] + + // sort vector in ascending order of score + std::sort(ret.begin(), ret.end()); + // (ret is inverted now --the lower the better--) + + // cut vector + if (max_results > 0 && (int)ret.size() > max_results) ret.resize(max_results); + + // complete and scale score to [0 worst .. 1 best] + // ||v - w||_{L2} = sqrt( 2 - 2 * Sum(v_i * w_i) + // for all i | v_i != 0 and w_i != 0 ) + // (Nister, 2006) + QueryResults::iterator qit; + for (qit = ret.begin(); qit != ret.end(); qit++) { + if (qit->Score <= -1.0) // rounding error + qit->Score = 1.0; + else + qit->Score = 1.0 - sqrt(1.0 + qit->Score); // [0..1] + // the + sign is ok, it is due to - sign in + // value = - qvalue * dvalue + } +} + +// -------------------------------------------------------------------------- + +void Database::queryChiSquare(const BowVector &vec, QueryResults &ret, + int max_results, int max_id) const { + BowVector::const_iterator vit; + + std::map> pairs; + std::map>::iterator pit; + + std::map> sums; // < sum vi, sum wi > + std::map>::iterator sit; + + // In the current implementation, we suppose vec is not normalized + + // map expected; + // map::iterator eit; + + for (vit = vec.begin(); vit != vec.end(); ++vit) { + const WordId word_id = vit->first; + const WordValue &qvalue = vit->second; + + const IFRow &row = m_ifile[word_id]; + + // IFRows are sorted in ascending entry_id order + + for (auto rit = row.begin(); rit != row.end(); ++rit) { + const EntryId entry_id = rit->entry_id; + const WordValue &dvalue = rit->word_weight; + + if ((int)entry_id < max_id || max_id == -1) { + // (v-w)^2/(v+w) - v - w = -4 vw/(v+w) + // we move the 4 out + double value = 0; + if (qvalue + dvalue != 0.0) // words may have weight zero + value = -qvalue * dvalue / (qvalue + dvalue); + + pit = pairs.lower_bound(entry_id); + sit = sums.lower_bound(entry_id); + // eit = expected.lower_bound(entry_id); + if (pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) { + pit->second.first += value; + pit->second.second += 1; + // eit->second += dvalue; + sit->second.first += qvalue; + sit->second.second += dvalue; + } else { + pairs.insert(pit, + std::map>::value_type( + entry_id, std::make_pair(value, 1))); + // expected.insert(eit, + // map::value_type(entry_id, dvalue)); + + sums.insert(sit, + std::map>::value_type( + entry_id, std::make_pair(qvalue, dvalue))); + } + } + + } // for each inverted row + } // for each query word + + // move to vector + ret.reserve(pairs.size()); + sit = sums.begin(); + for (pit = pairs.begin(); pit != pairs.end(); ++pit, ++sit) { + if (pit->second.second >= MIN_COMMON_WORDS) { + ret.push_back(Result(pit->first, pit->second.first)); + ret.back().nWords = pit->second.second; + ret.back().sumCommonVi = sit->second.first; + ret.back().sumCommonWi = sit->second.second; + ret.back().expectedChiScore = + 2 * sit->second.second / (1 + sit->second.second); + } + + // ret.push_back(Result(pit->first, pit->second)); + } + + // resulting "scores" are now in [-2 best .. 0 worst] + // we have to add +2 to the scores to obtain the chi square score + + // sort vector in ascending order of score + std::sort(ret.begin(), ret.end()); + // (ret is inverted now --the lower the better--) + + // cut vector + if (max_results > 0 && (int)ret.size() > max_results) ret.resize(max_results); + + // complete and scale score to [0 worst .. 1 best] + QueryResults::iterator qit; + for (qit = ret.begin(); qit != ret.end(); qit++) { + // this takes the 4 into account + qit->Score = -2. * qit->Score; // [0..1] + + qit->chiScore = qit->Score; + } +} + +// -------------------------------------------------------------------------- + +void Database::queryKL(const BowVector &vec, QueryResults &ret, int max_results, + int max_id) const { + BowVector::const_iterator vit; + + std::map pairs; + std::map::iterator pit; + + for (vit = vec.begin(); vit != vec.end(); ++vit) { + const WordId word_id = vit->first; + const WordValue &vi = vit->second; + + const IFRow &row = m_ifile[word_id]; + + // IFRows are sorted in ascending entry_id order + + for (auto rit = row.begin(); rit != row.end(); ++rit) { + const EntryId entry_id = rit->entry_id; + const WordValue &wi = rit->word_weight; + + if ((int)entry_id < max_id || max_id == -1) { + double value = 0; + if (vi != 0 && wi != 0) value = vi * log(vi / wi); + + pit = pairs.lower_bound(entry_id); + if (pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) { + pit->second += value; + } else { + pairs.insert(pit, + std::map::value_type(entry_id, value)); + } + } + + } // for each inverted row + } // for each query word + + // resulting "scores" are now in [-X worst .. 0 best .. X worst] + // but we cannot make sure which ones are better without calculating + // the complete score + + // complete scores and move to vector + ret.reserve(pairs.size()); + for (pit = pairs.begin(); pit != pairs.end(); ++pit) { + EntryId eid = pit->first; + double value = 0.0; + + for (vit = vec.begin(); vit != vec.end(); ++vit) { + const WordValue &vi = vit->second; + const IFRow &row = m_ifile[vit->first]; + + if (vi != 0) { + if (row.end() == find(row.begin(), row.end(), eid)) { + value += vi * (log(vi) - GeneralScoring::LOG_EPS); + } + } + } + + pit->second += value; + + // to vector + ret.push_back(Result(pit->first, pit->second)); + } + + // real scores are now in [0 best .. X worst] + + // sort vector in ascending order + // (scores are inverted now --the lower the better--) + std::sort(ret.begin(), ret.end()); + + // cut vector + if (max_results > 0 && (int)ret.size() > max_results) ret.resize(max_results); + + // cannot scale scores +} + +// -------------------------------------------------------------------------- + +void Database::queryBhattacharyya(const BowVector &vec, QueryResults &ret, + int max_results, int max_id) const { + BowVector::const_iterator vit; + + // map pairs; + // map::iterator pit; + + std::map> pairs; // > + std::map>::iterator pit; + + for (vit = vec.begin(); vit != vec.end(); ++vit) { + const WordId word_id = vit->first; + const WordValue &qvalue = vit->second; + + const IFRow &row = m_ifile[word_id]; + + // IFRows are sorted in ascending entry_id order + + for (auto rit = row.begin(); rit != row.end(); ++rit) { + const EntryId entry_id = rit->entry_id; + const WordValue &dvalue = rit->word_weight; + + if ((int)entry_id < max_id || max_id == -1) { + double value = sqrt(qvalue * dvalue); + + pit = pairs.lower_bound(entry_id); + if (pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) { + pit->second.first += value; + pit->second.second += 1; + } else { + pairs.insert(pit, + std::map>::value_type( + entry_id, std::make_pair(value, 1))); + } + } + + } // for each inverted row + } // for each query word + + // move to vector + ret.reserve(pairs.size()); + for (pit = pairs.begin(); pit != pairs.end(); ++pit) { + if (pit->second.second >= MIN_COMMON_WORDS) { + ret.push_back(Result(pit->first, pit->second.first)); + ret.back().nWords = pit->second.second; + ret.back().bhatScore = pit->second.first; + } + } + + // scores are already in [0..1] + + // sort vector in descending order + std::sort(ret.begin(), ret.end(), Result::gt); + + // cut vector + if (max_results > 0 && (int)ret.size() > max_results) ret.resize(max_results); +} + +// --------------------------------------------------------------------------- + +void Database::queryDotProduct(const BowVector &vec, QueryResults &ret, + int max_results, int max_id) const { + BowVector::const_iterator vit; + + std::map pairs; + std::map::iterator pit; + + for (vit = vec.begin(); vit != vec.end(); ++vit) { + const WordId word_id = vit->first; + const WordValue &qvalue = vit->second; + + const IFRow &row = m_ifile[word_id]; + + // IFRows are sorted in ascending entry_id order + + for (auto rit = row.begin(); rit != row.end(); ++rit) { + const EntryId entry_id = rit->entry_id; + const WordValue &dvalue = rit->word_weight; + + if ((int)entry_id < max_id || max_id == -1) { + double value; + if (this->m_voc->getWeightingType() == BINARY) + value = 1; + else + value = qvalue * dvalue; + + pit = pairs.lower_bound(entry_id); + if (pit != pairs.end() && !(pairs.key_comp()(entry_id, pit->first))) { + pit->second += value; + } else { + pairs.insert(pit, + std::map::value_type(entry_id, value)); + } + } + + } // for each inverted row + } // for each query word + + // move to vector + ret.reserve(pairs.size()); + for (pit = pairs.begin(); pit != pairs.end(); ++pit) { + ret.push_back(Result(pit->first, pit->second)); + } + + // scores are the greater the better + + // sort vector in descending order + std::sort(ret.begin(), ret.end(), Result::gt); + + // cut vector + if (max_results > 0 && (int)ret.size() > max_results) ret.resize(max_results); + + // these scores cannot be scaled +} + +// --------------------------------------------------------------------------- + +const FeatureVector &Database::retrieveFeatures(EntryId id) const { + assert(id < size()); + return m_dfile[id]; +} + +// -------------------------------------------------------------------------- + +void Database::save(const std::string &filename) const { + cv::FileStorage fs(filename.c_str(), cv::FileStorage::WRITE); + if (!fs.isOpened()) throw std::string("Could not open file ") + filename; + + save(fs); +} + +// -------------------------------------------------------------------------- + +void Database::save(cv::FileStorage &fs, const std::string &name) const { + // Format YAML: + // vocabulary { ... see TemplatedVocabulary::save } + // database + // { + // nEntries: + // usingDI: + // diLevels: + // invertedIndex + // [ + // [ + // { + // imageId: + // weight: + // } + // ] + // ] + // directIndex + // [ + // [ + // { + // nodeId: + // features: [ ] + // } + // ] + // ] + + // invertedIndex[i] is for the i-th word + // directIndex[i] is for the i-th entry + // directIndex may be empty if not using direct index + // + // imageId's and nodeId's must be stored in ascending order + // (according to the construction of the indexes) + + m_voc->save(fs); + + fs << name << "{"; + + fs << "nEntries" << m_nentries; + fs << "usingDI" << (m_use_di ? 1 : 0); + fs << "diLevels" << m_dilevels; + + fs << "invertedIndex" + << "["; + + for (auto iit = m_ifile.begin(); iit != m_ifile.end(); ++iit) { + fs << "["; // word of IF + for (auto irit = iit->begin(); irit != iit->end(); ++irit) { + fs << "{:" + << "imageId" << (int)irit->entry_id << "weight" << irit->word_weight + << "}"; + } + fs << "]"; // word of IF + } + + fs << "]"; // invertedIndex + + fs << "directIndex" + << "["; + + for (auto dit = m_dfile.begin(); dit != m_dfile.end(); ++dit) { + fs << "["; // entry of DF + + for (auto drit = dit->begin(); drit != dit->end(); ++drit) { + NodeId nid = drit->first; + const std::vector &features = drit->second; + + // save info of last_nid + fs << "{"; + fs << "nodeId" << (int)nid; + // msvc++ 2010 with opencv 2.3.1 does not allow FileStorage::operator<< + // with vectors of unsigned int + fs << "features" + << "[" << *(const std::vector *)(&features) << "]"; + fs << "}"; + } + + fs << "]"; // entry of DF + } + + fs << "]"; // directIndex + + fs << "}"; // database +} + +// -------------------------------------------------------------------------- + +void Database::load(const std::string &filename) { + cv::FileStorage fs(filename.c_str(), cv::FileStorage::READ); + if (!fs.isOpened()) throw std::string("Could not open file ") + filename; + + load(fs); +} + +// -------------------------------------------------------------------------- + +void Database::load(const cv::FileStorage &fs, const std::string &name) { + // load voc first + // subclasses must instantiate m_voc before calling this ::load + if (!m_voc) m_voc = new Vocabulary; + + m_voc->load(fs); + + // load database now + clear(); // resizes inverted file + + cv::FileNode fdb = fs[name]; + + m_nentries = (int)fdb["nEntries"]; + m_use_di = (int)fdb["usingDI"] != 0; + m_dilevels = (int)fdb["diLevels"]; + + cv::FileNode fn = fdb["invertedIndex"]; + for (WordId wid = 0; wid < fn.size(); ++wid) { + cv::FileNode fw = fn[wid]; + + for (unsigned int i = 0; i < fw.size(); ++i) { + EntryId eid = (int)fw[i]["imageId"]; + WordValue v = fw[i]["weight"]; + + m_ifile[wid].push_back(IFPair(eid, v)); + } + } + + if (m_use_di) { + fn = fdb["directIndex"]; + + m_dfile.resize(fn.size()); + assert(m_nentries == (int)fn.size()); + + FeatureVector::iterator dit; + for (EntryId eid = 0; eid < fn.size(); ++eid) { + cv::FileNode fe = fn[eid]; + + m_dfile[eid].clear(); + for (unsigned int i = 0; i < fe.size(); ++i) { + NodeId nid = (int)fe[i]["nodeId"]; + + dit = m_dfile[eid].insert(m_dfile[eid].end(), + make_pair(nid, std::vector())); + + // this failed to compile with some opencv versions (2.3.1) + // fe[i]["features"] >> dit->second; + + // this was ok until OpenCV 2.4.1 + // std::vector aux; + // fe[i]["features"] >> aux; // OpenCV < 2.4.1 + // dit->second.resize(aux.size()); + // std::copy(aux.begin(), aux.end(), dit->second.begin()); + + cv::FileNode ff = fe[i]["features"][0]; + dit->second.reserve(ff.size()); + + cv::FileNodeIterator ffit; + for (ffit = ff.begin(); ffit != ff.end(); ++ffit) { + dit->second.push_back((int)*ffit); + } + } + } // for each entry + } // if use_id +} + +std::ostream &operator<<(std::ostream &os, const Database &db) { + os << "Database: Entries = " << db.size() << ", " + "Using direct index = " + << (db.usingDirectIndex() ? "yes" : "no"); + + if (db.usingDirectIndex()) + os << ", Direct index levels = " << db.getDirectIndexLevels(); + + os << ". " << *db.getVocabulary(); + return os; +} +} // namespace DBoW3 diff --git a/thirdparty/DBoW3/src/Database.h b/thirdparty/DBoW3/src/Database.h new file mode 100644 index 0000000..2397404 --- /dev/null +++ b/thirdparty/DBoW3/src/Database.h @@ -0,0 +1,354 @@ +/** + * File: Database.h + * Date: March 2011 + * Modified By Rafael Muñoz in 2016 + * Author: Dorian Galvez-Lopez + * Description: database of images + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_DATABASE__ +#define __D_T_DATABASE__ + +#include +#include +#include +#include +#include +#include +#include + +#include "BowVector.h" +#include "FeatureVector.h" +#include "QueryResults.h" +#include "ScoringObject.h" +#include "Vocabulary.h" +#include "exports.h" + +namespace DBoW3 { + +/// Database +class DBOW_API Database { + public: + /** + * Creates an empty database without vocabulary + * @param use_di a direct index is used to store feature indexes + * @param di_levels levels to go up the vocabulary tree to select the + * node id to store in the direct index when adding images + */ + explicit Database(bool use_di = true, int di_levels = 0); + + /** + * Creates a database with the given vocabulary + * @param T class inherited from Vocabulary + * @param voc vocabulary + * @param use_di a direct index is used to store feature indexes + * @param di_levels levels to go up the vocabulary tree to select the + * node id to store in the direct index when adding images + */ + + explicit Database(const Vocabulary &voc, bool use_di = true, + int di_levels = 0); + + /** + * Copy constructor. Copies the vocabulary too + * @param db object to copy + */ + Database(const Database &db); + + /** + * Creates the database from a file + * @param filename + */ + Database(const std::string &filename); + + /** + * Creates the database from a file + * @param filename + */ + Database(const char *filename); + + /** + * Destructor + */ + virtual ~Database(void); + + /** + * Copies the given database and its vocabulary + * @param db database to copy + */ + Database &operator=(const Database &db); + + /** + * Sets the vocabulary to use and clears the content of the database. + * @param T class inherited from Vocabulary + * @param voc vocabulary to copy + */ + void setVocabulary(const Vocabulary &voc); + + /** + * Sets the vocabulary to use and the direct index parameters, and clears + * the content of the database + * @param T class inherited from Vocabulary + * @param voc vocabulary to copy + * @param use_di a direct index is used to store feature indexes + * @param di_levels levels to go up the vocabulary tree to select the + * node id to store in the direct index when adding images + */ + + void setVocabulary(const Vocabulary &voc, bool use_di, int di_levels = 0); + + /** + * Returns a pointer to the vocabulary used + * @return vocabulary + */ + inline const Vocabulary *getVocabulary() const { return m_voc; } + + /** + * Allocates some memory for the direct and inverted indexes + * @param nd number of expected image entries in the database + * @param ni number of expected words per image + * @note Use 0 to ignore a parameter + */ + void allocate(int nd = 0, int ni = 0); + + /** + * Adds an entry to the database and returns its index + * @param features features of the new entry + * @param bowvec if given, the bow vector of these features is returned + * @param fvec if given, the vector of nodes and feature indexes is returned + * @return id of new entry + */ + EntryId add(const std::vector> &features, + BowVector *bowvec = NULL, FeatureVector *fvec = NULL); + + /** + * Adds an entry to the database and returns its index + * @param features features of the new entry + * @param bowvec if given, the bow vector of these features is returned + * @param fvec if given, the vector of nodes and feature indexes is returned + * @return id of new entry + */ + EntryId add(const std::vector &features, BowVector *bowvec = NULL, + FeatureVector *fvec = NULL); + /** + * Adds an entry to the database and returns its index + * @param features features of the new entry, one per row + * @param bowvec if given, the bow vector of these features is returned + * @param fvec if given, the vector of nodes and feature indexes is returned + * @return id of new entry + */ + EntryId add(const cv::Mat &features, BowVector *bowvec = NULL, + FeatureVector *fvec = NULL); + + /** + * Adss an entry to the database and returns its index + * @param vec bow vector + * @param fec feature vector to add the entry. Only necessary if using the + * direct index + * @return id of new entry + */ + EntryId add(const BowVector &vec, const FeatureVector &fec = FeatureVector()); + + /** + * Empties the database + */ + inline void clear(); + + /** + * Returns the number of entries in the database + * @return number of entries in the database + */ + unsigned int size() const { return m_nentries; } + + /** + * Checks if the direct index is being used + * @return true iff using direct index + */ + bool usingDirectIndex() const { return m_use_di; } + + /** + * Returns the di levels when using direct index + * @return di levels + */ + int getDirectIndexLevels() const { return m_dilevels; } + + /** + * Queries the database with some features + * @param features query features + * @param ret (out) query results + * @param max_results number of results to return. <= 0 means all + * @param max_id only entries with id <= max_id are returned in ret. + * < 0 means all + */ + void query(const std::vector &features, QueryResults &ret, + int max_results = 1, int max_id = -1) const; + + void query(const std::vector> &features, QueryResults &ret, + int max_results = 1, int max_id = -1) const; + + /** + * Queries the database with some features + * @param features query features,one per row + * @param ret (out) query results + * @param max_results number of results to return. <= 0 means all + * @param max_id only entries with id <= max_id are returned in ret. + * < 0 means all + */ + void query(const cv::Mat &features, QueryResults &ret, int max_results = 1, + int max_id = -1) const; + + /** + * Queries the database with a vector + * @param vec bow vector already normalized + * @param ret results + * @param max_results number of results to return. <= 0 means all + * @param max_id only entries with id <= max_id are returned in ret. + * < 0 means all + */ + void query(const BowVector &vec, QueryResults &ret, int max_results = 1, + int max_id = -1) const; + + /** + * Returns the a feature vector associated with a database entry + * @param id entry id (must be < size()) + * @return const reference to map of nodes and their associated features in + * the given entry + */ + const FeatureVector &retrieveFeatures(EntryId id) const; + + /** + * Stores the database in a file + * @param filename + */ + void save(const std::string &filename) const; + + /** + * Loads the database from a file + * @param filename + */ + void load(const std::string &filename); + + /** + * Stores the database in the given file storage structure + * @param fs + * @param name node name + */ + virtual void save(cv::FileStorage &fs, + const std::string &name = "database") const; + + /** + * Loads the database from the given file storage structure + * @param fs + * @param name node name + */ + virtual void load(const cv::FileStorage &fs, + const std::string &name = "database"); + + // -------------------------------------------------------------------------- + + /** + * Writes printable information of the database + * @param os stream to write to + * @param db + */ + DBOW_API friend std::ostream &operator<<(std::ostream &os, + const Database &db); + + protected: + /// Query with L1 scoring + void queryL1(const BowVector &vec, QueryResults &ret, int max_results, + int max_id) const; + + /// Query with L2 scoring + void queryL2(const BowVector &vec, QueryResults &ret, int max_results, + int max_id) const; + + /// Query with Chi square scoring + void queryChiSquare(const BowVector &vec, QueryResults &ret, int max_results, + int max_id) const; + + /// Query with Bhattacharyya scoring + void queryBhattacharyya(const BowVector &vec, QueryResults &ret, + int max_results, int max_id) const; + + /// Query with KL divergence scoring + void queryKL(const BowVector &vec, QueryResults &ret, int max_results, + int max_id) const; + + /// Query with dot product scoring + void queryDotProduct(const BowVector &vec, QueryResults &ret, int max_results, + int max_id) const; + + protected: + /* Inverted file declaration */ + + /// Item of IFRow + struct IFPair { + /// Entry id + EntryId entry_id; + + /// Word weight in this entry + WordValue word_weight; + + /** + * Creates an empty pair + */ + IFPair() {} + + /** + * Creates an inverted file pair + * @param eid entry id + * @param wv word weight + */ + IFPair(EntryId eid, WordValue wv) : entry_id(eid), word_weight(wv) {} + + /** + * Compares the entry ids + * @param eid + * @return true iff this entry id is the same as eid + */ + inline bool operator==(EntryId eid) const { return entry_id == eid; } + }; + + /// Row of InvertedFile + typedef std::vector IFRow; + // IFRows are sorted in ascending entry_id order + + /// Inverted index + typedef std::vector InvertedFile; + // InvertedFile[word_id] --> inverted file of that word + + /* Direct file declaration */ + + /// Direct index + typedef std::vector DirectFile; + // DirectFile[entry_id] --> [ directentry, ... ] + + protected: + /// Associated vocabulary + Vocabulary *m_voc; + + /// Flag to use direct index + bool m_use_di; + + /// Levels to go up the vocabulary tree to select nodes to store + /// in the direct index + int m_dilevels; + + /// Inverted file (must have size() == |words|) + InvertedFile m_ifile; + + /// Direct file (resized for allocation) + DirectFile m_dfile; + + /// Number of valid entries in m_dfile + int m_nentries; +}; + +// -------------------------------------------------------------------------- + +} // namespace DBoW3 + +#endif diff --git a/thirdparty/DBoW3/src/DescManip.cpp b/thirdparty/DBoW3/src/DescManip.cpp new file mode 100644 index 0000000..aa0553d --- /dev/null +++ b/thirdparty/DBoW3/src/DescManip.cpp @@ -0,0 +1,239 @@ +/** + * File: DescManip.cpp + * Date: June 2012 + * Author: Dorian Galvez-Lopez + * Description: functions for ORB descriptors + * License: see the LICENSE.txt file + * + */ + +#include +#include +#include +#include +#include +#include + +#include "DescManip.h" + +using namespace std; + +namespace DBoW3 { + +// -------------------------------------------------------------------------- + +void DescManip::meanValue(const std::vector &descriptors, + cv::Mat &mean) { + if (descriptors.empty()) return; + + if (descriptors.size() == 1) { + mean = descriptors[0].clone(); + return; + } + // binary descriptor + if (descriptors[0].type() == CV_8U) { + // determine number of bytes of the binary descriptor + int L = getDescSizeBytes(descriptors[0]); + vector sum(L * 8, 0); + + for (size_t i = 0; i < descriptors.size(); ++i) { + const cv::Mat &d = descriptors[i]; + const unsigned char *p = d.ptr(); + + for (int j = 0; j < d.cols; ++j, ++p) { + if (*p & (1 << 7)) ++sum[j * 8]; + if (*p & (1 << 6)) ++sum[j * 8 + 1]; + if (*p & (1 << 5)) ++sum[j * 8 + 2]; + if (*p & (1 << 4)) ++sum[j * 8 + 3]; + if (*p & (1 << 3)) ++sum[j * 8 + 4]; + if (*p & (1 << 2)) ++sum[j * 8 + 5]; + if (*p & (1 << 1)) ++sum[j * 8 + 6]; + if (*p & (1)) ++sum[j * 8 + 7]; + } + } + + mean = cv::Mat::zeros(1, L, CV_8U); + unsigned char *p = mean.ptr(); + + const int N2 = (int)descriptors.size() / 2 + descriptors.size() % 2; + for (size_t i = 0; i < sum.size(); ++i) { + if (sum[i] >= N2) { + // set bit + *p |= 1 << (7 - (i % 8)); + } + + if (i % 8 == 7) ++p; + } + } + // non binary descriptor + else { + assert(descriptors[0].type() == CV_32F); // ensure it is float + + mean.create(1, descriptors[0].cols, descriptors[0].type()); + mean.setTo(cv::Scalar::all(0)); + float inv_s = 1. / double(descriptors.size()); + for (size_t i = 0; i < descriptors.size(); i++) + mean += descriptors[i] * inv_s; + } +} + +// -------------------------------------------------------------------------- +// static inline uint32_t distance_8uc1(const cv::Mat &a, const cv::Mat &b); + +double DescManip::distance(const cv::Mat &a, const cv::Mat &b) { + // binary descriptor + if (a.type() == CV_8U) { + // Bit count function got from: + // http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetKernighan + // This implementation assumes that a.cols (CV_8U) % sizeof(uint64_t) == 0 + + const uint64_t *pa, *pb; + pa = a.ptr(); // a & b are actually CV_8U + pb = b.ptr(); + + uint64_t v, ret = 0; + for (size_t i = 0; i < a.cols / sizeof(uint64_t); ++i, ++pa, ++pb) { + v = *pa ^ *pb; + v = v - ((v >> 1) & (uint64_t) ~(uint64_t)0 / 3); + v = (v & (uint64_t) ~(uint64_t)0 / 15 * 3) + + ((v >> 2) & (uint64_t) ~(uint64_t)0 / 15 * 3); + v = (v + (v >> 4)) & (uint64_t) ~(uint64_t)0 / 255 * 15; + ret += (uint64_t)(v * ((uint64_t) ~(uint64_t)0 / 255)) >> + (sizeof(uint64_t) - 1) * CHAR_BIT; + } + + return ret; + } else { + double sqd = 0.; + assert(a.type() == CV_32F); + assert(a.rows == 1); + const float *a_ptr = a.ptr(0); + const float *b_ptr = b.ptr(0); + for (int i = 0; i < a.cols; i++) + sqd += (a_ptr[i] - b_ptr[i]) * (a_ptr[i] - b_ptr[i]); + return sqd; + } +} + +// -------------------------------------------------------------------------- + +std::string DescManip::toString(const cv::Mat &a) { + stringstream ss; + // introduce a magic value to distinguish from DBoW3 + ss << "dbw3 "; + // save size and type + + ss << a.type() << " " << a.cols << " "; + + if (a.type() == CV_8U) { + const unsigned char *p = a.ptr(); + for (int i = 0; i < a.cols; ++i, ++p) ss << (int)*p << " "; + } else { + const float *p = a.ptr(); + for (int i = 0; i < a.cols; ++i, ++p) ss << *p << " "; + } + + return ss.str(); +} + +// -------------------------------------------------------------------------- + +void DescManip::fromString(cv::Mat &a, const std::string &s) { + // check if the dbow3 is present + string ss_aux; + ss_aux.reserve(10); + for (size_t i = 0; i < 10 && i < s.size(); i++) ss_aux.push_back(s[i]); + if (ss_aux.find("dbw3") == std::string::npos) { // is DBoW3 + // READ UNTIL END + stringstream ss(s); + int val; + vector data; + data.reserve(100); + while (ss >> val) data.push_back(val); + // copy to a + a.create(1, data.size(), CV_8UC1); + memcpy(a.ptr(0), &data[0], data.size()); + } else { + int type, cols; + stringstream ss(s); + ss >> type >> cols; + a.create(1, cols, type); + if (type == CV_8UC1) { + unsigned char *p = a.ptr(); + int n; + for (int i = 0; i < a.cols; ++i, ++p) + if (ss >> n) *p = (unsigned char)n; + } else { + float *p = a.ptr(); + for (int i = 0; i < a.cols; ++i, ++p) + if (!(ss >> *p)) + cerr << "Error reading. Unexpected EOF. DescManip::fromString" + << endl; + } + } +} + +// -------------------------------------------------------------------------- + +void DescManip::toMat32F(const std::vector &descriptors, + cv::Mat &mat) { + if (descriptors.empty()) { + mat.release(); + return; + } + + if (descriptors[0].type() == CV_8UC1) { + const size_t N = descriptors.size(); + int L = getDescSizeBytes(descriptors[0]); + mat.create(N, L * 8, CV_32F); + float *p = mat.ptr(); + + for (size_t i = 0; i < N; ++i) { + const int C = descriptors[i].cols; + const unsigned char *desc = descriptors[i].ptr(); + + for (int j = 0; j < C; ++j, p += 8) { + p[0] = (desc[j] & (1 << 7) ? 1 : 0); + p[1] = (desc[j] & (1 << 6) ? 1 : 0); + p[2] = (desc[j] & (1 << 5) ? 1 : 0); + p[3] = (desc[j] & (1 << 4) ? 1 : 0); + p[4] = (desc[j] & (1 << 3) ? 1 : 0); + p[5] = (desc[j] & (1 << 2) ? 1 : 0); + p[6] = (desc[j] & (1 << 1) ? 1 : 0); + p[7] = desc[j] & (1); + } + } + } else { + assert(descriptors[0].type() == CV_32F); + const int N = descriptors.size(); + int L = descriptors[0].cols; + mat.create(N, L, CV_32F); + for (int i = 0; i < N; ++i) + memcpy(mat.ptr(i), descriptors[i].ptr(0), + sizeof(float) * L); + } +} + +void DescManip::toStream(const cv::Mat &m, std::ostream &str) { + assert(m.rows == 1 || m.isContinuous()); + int type = m.type(); + int cols = m.cols; + int rows = m.rows; + str.write((char *)&cols, sizeof(cols)); + str.write((char *)&rows, sizeof(rows)); + str.write((char *)&type, sizeof(type)); + str.write((char *)m.ptr(0), m.elemSize() * m.cols); +} + +void DescManip::fromStream(cv::Mat &m, std::istream &str) { + int type, cols, rows; + str.read((char *)&cols, sizeof(cols)); + str.read((char *)&rows, sizeof(rows)); + str.read((char *)&type, sizeof(type)); + m.create(rows, cols, type); + str.read((char *)m.ptr(0), m.elemSize() * m.cols); +} + +// -------------------------------------------------------------------------- + +} // namespace DBoW3 diff --git a/thirdparty/DBoW3/src/DescManip.h b/thirdparty/DBoW3/src/DescManip.h new file mode 100644 index 0000000..8281176 --- /dev/null +++ b/thirdparty/DBoW3/src/DescManip.h @@ -0,0 +1,99 @@ +/** + * File: FClass.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: generic FClass to instantiate templated classes + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_DESCMANIP__ +#define __D_T_DESCMANIP__ + +#include +#include +#include +#include "exports.h" + +namespace DBoW3 { + +/// Class to manipulate descriptors (calculating means, differences and IO +/// routines) +class DBOW_API DescManip { + public: + /** + * Calculates the mean value of a set of descriptors + * @param descriptors + * @param mean mean descriptor + */ + static void meanValue(const std::vector &descriptors, cv::Mat &mean); + + /** + * Calculates the distance between two descriptors + * @param a + * @param b + * @return distance + */ + static double distance(const cv::Mat &a, const cv::Mat &b); + static inline uint32_t distance_8uc1(const cv::Mat &a, const cv::Mat &b); + + /** + * Returns a string version of the descriptor + * @param a descriptor + * @return string version + */ + static std::string toString(const cv::Mat &a); + + /** + * Returns a descriptor from a string + * @param a descriptor + * @param s string version + */ + static void fromString(cv::Mat &a, const std::string &s); + + /** + * Returns a mat with the descriptors in float format + * @param descriptors + * @param mat (out) NxL 32F matrix + */ + static void toMat32F(const std::vector &descriptors, cv::Mat &mat); + + /**io routines*/ + static void toStream(const cv::Mat &m, std::ostream &str); + static void fromStream(cv::Mat &m, std::istream &str); + + public: + /**Returns the number of bytes of the descriptor + * used for binary descriptors only*/ + static size_t getDescSizeBytes(const cv::Mat &d) { + return d.cols * d.elemSize(); + } +}; + +uint32_t DescManip::distance_8uc1(const cv::Mat &a, const cv::Mat &b) { + // binary descriptor + + // Bit count function got from: + // http://graphics.stanford.edu/~seander/bithacks.html#CountBitsSetKernighan + // This implementation assumes that a.cols (CV_8U) % sizeof(uint64_t) == 0 + + const uint64_t *pa, *pb; + pa = a.ptr(); // a & b are actually CV_8U + pb = b.ptr(); + + uint64_t v, ret = 0; + size_t n = a.cols / sizeof(uint64_t); + for (size_t i = 0; i < n; ++i, ++pa, ++pb) { + v = *pa ^ *pb; + v = v - ((v >> 1) & (uint64_t) ~(uint64_t)0 / 3); + v = (v & (uint64_t) ~(uint64_t)0 / 15 * 3) + + ((v >> 2) & (uint64_t) ~(uint64_t)0 / 15 * 3); + v = (v + (v >> 4)) & (uint64_t) ~(uint64_t)0 / 255 * 15; + ret += (uint64_t)(v * ((uint64_t) ~(uint64_t)0 / 255)) >> + (sizeof(uint64_t) - 1) * CHAR_BIT; + } + return ret; +} +} // namespace DBoW3 + +#endif diff --git a/thirdparty/DBoW3/src/FeatureVector.cpp b/thirdparty/DBoW3/src/FeatureVector.cpp new file mode 100644 index 0000000..880eab1 --- /dev/null +++ b/thirdparty/DBoW3/src/FeatureVector.cpp @@ -0,0 +1,85 @@ +/** + * File: FeatureVector.cpp + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: feature vector + * License: see the LICENSE.txt file + * + */ + +#include "FeatureVector.h" +#include +#include +#include + +namespace DBoW3 { + +// --------------------------------------------------------------------------- + +FeatureVector::FeatureVector(void) +{ +} + +// --------------------------------------------------------------------------- + +FeatureVector::~FeatureVector(void) +{ +} + +// --------------------------------------------------------------------------- + +void FeatureVector::addFeature(NodeId id, unsigned int i_feature) +{ + FeatureVector::iterator vit = this->lower_bound(id); + + if(vit != this->end() && vit->first == id) + { + vit->second.push_back(i_feature); + } + else + { + vit = this->insert(vit, FeatureVector::value_type(id, + std::vector() )); + vit->second.push_back(i_feature); + } +} + +// --------------------------------------------------------------------------- + +std::ostream& operator<<(std::ostream &out, + const FeatureVector &v) +{ + if(!v.empty()) + { + FeatureVector::const_iterator vit = v.begin(); + + const std::vector* f = &vit->second; + + out << "<" << vit->first << ": ["; + if(!f->empty()) out << (*f)[0]; + for(unsigned int i = 1; i < f->size(); ++i) + { + out << ", " << (*f)[i]; + } + out << "]>"; + + for(++vit; vit != v.end(); ++vit) + { + f = &vit->second; + + out << ", <" << vit->first << ": ["; + if(!f->empty()) out << (*f)[0]; + for(unsigned int i = 1; i < f->size(); ++i) + { + out << ", " << (*f)[i]; + } + out << "]>"; + } + } + + return out; +} + +// --------------------------------------------------------------------------- + +} // namespace DBoW3 diff --git a/thirdparty/DBoW3/src/FeatureVector.h b/thirdparty/DBoW3/src/FeatureVector.h new file mode 100644 index 0000000..f06bc1e --- /dev/null +++ b/thirdparty/DBoW3/src/FeatureVector.h @@ -0,0 +1,55 @@ +/** + * File: FeatureVector.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: feature vector + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_FEATURE_VECTOR__ +#define __D_T_FEATURE_VECTOR__ + +#include "BowVector.h" +#include +#include +#include "exports.h" +namespace DBoW3 { + +/// Vector of nodes with indexes of local features +class DBOW_API FeatureVector: + public std::map > +{ +public: + + /** + * Constructor + */ + FeatureVector(void); + + /** + * Destructor + */ + ~FeatureVector(void); + + /** + * Adds a feature to an existing node, or adds a new node with an initial + * feature + * @param id node id to add or to modify + * @param i_feature index of feature to add to the given node + */ + void addFeature(NodeId id, unsigned int i_feature); + + /** + * Sends a string versions of the feature vector through the stream + * @param out stream + * @param v feature vector + */ + friend std::ostream& operator<<(std::ostream &out, const FeatureVector &v); + +}; + +} // namespace DBoW3 + +#endif + diff --git a/thirdparty/DBoW3/src/QueryResults.cpp b/thirdparty/DBoW3/src/QueryResults.cpp new file mode 100644 index 0000000..7062400 --- /dev/null +++ b/thirdparty/DBoW3/src/QueryResults.cpp @@ -0,0 +1,63 @@ +/** + * File: QueryResults.cpp + * Date: March, November 2011 + * Author: Dorian Galvez-Lopez + * Description: structure to store results of database queries + * License: see the LICENSE.txt file + * + */ + +#include +#include +#include "QueryResults.h" + +using namespace std; + +namespace DBoW3 +{ + +// --------------------------------------------------------------------------- + +ostream & operator<<(ostream& os, const Result& ret ) +{ + os << ""; + return os; +} + +// --------------------------------------------------------------------------- + +ostream & operator<<(ostream& os, const QueryResults& ret ) +{ + if(ret.size() == 1) + os << "1 result:" << endl; + else + os << ret.size() << " results:" << endl; + + QueryResults::const_iterator rit; + for(rit = ret.begin(); rit != ret.end(); ++rit) + { + os << *rit; + if(rit + 1 != ret.end()) os << endl; + } + return os; +} + +// --------------------------------------------------------------------------- + +void QueryResults::saveM(const std::string &filename) const +{ + fstream f(filename.c_str(), ios::out); + + QueryResults::const_iterator qit; + for(qit = begin(); qit != end(); ++qit) + { + f << qit->Id << " " << qit->Score << endl; + } + + f.close(); +} + +// --------------------------------------------------------------------------- + +} // namespace DBoW3 + diff --git a/thirdparty/DBoW3/src/QueryResults.h b/thirdparty/DBoW3/src/QueryResults.h new file mode 100644 index 0000000..bebbd1e --- /dev/null +++ b/thirdparty/DBoW3/src/QueryResults.h @@ -0,0 +1,205 @@ +/** + * File: QueryResults.h + * Date: March, November 2011 + * Author: Dorian Galvez-Lopez + * Description: structure to store results of database queries + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_QUERY_RESULTS__ +#define __D_T_QUERY_RESULTS__ + +#include +#include "exports.h" +namespace DBoW3 { + +/// Id of entries of the database +typedef unsigned int EntryId; + +/// Single result of a query +class DBOW_API Result +{ +public: + + /// Entry id + EntryId Id; + + /// Score obtained + double Score; + + /// debug + int nWords; // words in common + // !!! this is filled only by Bhatt score! + // (and for BCMatching, BCThresholding then) + + double bhatScore, chiScore; + /// debug + + // only done by ChiSq and BCThresholding + double sumCommonVi; + double sumCommonWi; + double expectedChiScore; + /// debug + + /** + * Empty constructors + */ + inline Result(){} + + /** + * Creates a result with the given data + * @param _id entry id + * @param _score score + */ + inline Result(EntryId _id, double _score): Id(_id), Score(_score){} + + /** + * Compares the scores of two results + * @return true iff this.score < r.score + */ + inline bool operator<(const Result &r) const + { + return this->Score < r.Score; + } + + /** + * Compares the scores of two results + * @return true iff this.score > r.score + */ + inline bool operator>(const Result &r) const + { + return this->Score > r.Score; + } + + /** + * Compares the entry id of the result + * @return true iff this.id == id + */ + inline bool operator==(EntryId id) const + { + return this->Id == id; + } + + /** + * Compares the score of this entry with a given one + * @param s score to compare with + * @return true iff this score < s + */ + inline bool operator<(double s) const + { + return this->Score < s; + } + + /** + * Compares the score of this entry with a given one + * @param s score to compare with + * @return true iff this score > s + */ + inline bool operator>(double s) const + { + return this->Score > s; + } + + /** + * Compares the score of two results + * @param a + * @param b + * @return true iff a.Score > b.Score + */ + static inline bool gt(const Result &a, const Result &b) + { + return a.Score > b.Score; + } + + /** + * Compares the scores of two results + * @return true iff a.Score > b.Score + */ + inline static bool ge(const Result &a, const Result &b) + { + return a.Score > b.Score; + } + + /** + * Returns true iff a.Score >= b.Score + * @param a + * @param b + * @return true iff a.Score >= b.Score + */ + static inline bool geq(const Result &a, const Result &b) + { + return a.Score >= b.Score; + } + + /** + * Returns true iff a.Score >= s + * @param a + * @param s + * @return true iff a.Score >= s + */ + static inline bool geqv(const Result &a, double s) + { + return a.Score >= s; + } + + + /** + * Returns true iff a.Id < b.Id + * @param a + * @param b + * @return true iff a.Id < b.Id + */ + static inline bool ltId(const Result &a, const Result &b) + { + return a.Id < b.Id; + } + + /** + * Prints a string version of the result + * @param os ostream + * @param ret Result to print + */ + friend std::ostream & operator<<(std::ostream& os, const Result& ret ); +}; + +/// Multiple results from a query +class QueryResults: public std::vector +{ +public: + + /** + * Multiplies all the scores in the vector by factor + * @param factor + */ + inline void scaleScores(double factor); + + /** + * Prints a string version of the results + * @param os ostream + * @param ret QueryResults to print + */ + DBOW_API friend std::ostream & operator<<(std::ostream& os, const QueryResults& ret ); + + /** + * Saves a matlab file with the results + * @param filename + */ + void saveM(const std::string &filename) const; + +}; + +// -------------------------------------------------------------------------- + +inline void QueryResults::scaleScores(double factor) +{ + for(QueryResults::iterator qit = begin(); qit != end(); ++qit) + qit->Score *= factor; +} + +// -------------------------------------------------------------------------- + +} // namespace TemplatedBoW + +#endif + diff --git a/thirdparty/DBoW3/src/ScoringObject.cpp b/thirdparty/DBoW3/src/ScoringObject.cpp new file mode 100644 index 0000000..7cf0812 --- /dev/null +++ b/thirdparty/DBoW3/src/ScoringObject.cpp @@ -0,0 +1,315 @@ +/** + * File: ScoringObject.cpp + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: functions to compute bow scores + * License: see the LICENSE.txt file + * + */ + +#include +#include "Vocabulary.h" +#include "BowVector.h" + +using namespace DBoW3; + +// If you change the type of WordValue, make sure you change also the +// epsilon value (this is needed by the KL method) +const double GeneralScoring::LOG_EPS = log(DBL_EPSILON); // FLT_EPSILON + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double L1Scoring::score(const BowVector &v1, const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += fabs(vi - wi) - fabs(vi) - fabs(wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + // ||v - w||_{L1} = 2 + Sum(|v_i - w_i| - |v_i| - |w_i|) + // for all i | v_i != 0 and w_i != 0 + // (Nister, 2006) + // scaled_||v - w||_{L1} = 1 - 0.5 * ||v - w||_{L1} + score = -score/2.0; + + return score; // [0..1] +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double L2Scoring::score(const BowVector &v1, const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += vi * wi; + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + // ||v - w||_{L2} = sqrt( 2 - 2 * Sum(v_i * w_i) ) + // for all i | v_i != 0 and w_i != 0 ) + // (Nister, 2006) + if(score >= 1) // rounding errors + score = 1.0; + else + score = 1.0 - sqrt(1.0 - score); // [0..1] + + return score; +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double ChiSquareScoring::score(const BowVector &v1, const BowVector &v2) + const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + // all the items are taken into account + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + // (v-w)^2/(v+w) - v - w = -4 vw/(v+w) + // we move the -4 out + if(vi + wi != 0.0) score += vi * wi / (vi + wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + } + } + + // this takes the -4 into account + score = 2. * score; // [0..1] + + return score; +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double KLScoring::score(const BowVector &v1, const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + // all the items or v are taken into account + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + if(vi != 0 && wi != 0) score += vi * log(vi/wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + score += vi * (log(vi) - LOG_EPS); + ++v1_it; + } + else + { + // move v2_it forward, do not add any score + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + // sum rest of items of v + for(; v1_it != v1_end; ++v1_it) + if(v1_it->second != 0) + score += v1_it->second * (log(v1_it->second) - LOG_EPS); + + return score; // cannot be scaled +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double BhattacharyyaScoring::score(const BowVector &v1, + const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += sqrt(vi * wi); + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + return score; // already scaled +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + +double DotProductScoring::score(const BowVector &v1, + const BowVector &v2) const +{ + BowVector::const_iterator v1_it, v2_it; + const BowVector::const_iterator v1_end = v1.end(); + const BowVector::const_iterator v2_end = v2.end(); + + v1_it = v1.begin(); + v2_it = v2.begin(); + + double score = 0; + + while(v1_it != v1_end && v2_it != v2_end) + { + const WordValue& vi = v1_it->second; + const WordValue& wi = v2_it->second; + + if(v1_it->first == v2_it->first) + { + score += vi * wi; + + // move v1 and v2 forward + ++v1_it; + ++v2_it; + } + else if(v1_it->first < v2_it->first) + { + // move v1 forward + v1_it = v1.lower_bound(v2_it->first); + // v1_it = (first element >= v2_it.id) + } + else + { + // move v2 forward + v2_it = v2.lower_bound(v1_it->first); + // v2_it = (first element >= v1_it.id) + } + } + + return score; // cannot scale +} + +// --------------------------------------------------------------------------- +// --------------------------------------------------------------------------- + diff --git a/thirdparty/DBoW3/src/ScoringObject.h b/thirdparty/DBoW3/src/ScoringObject.h new file mode 100644 index 0000000..8d6c64e --- /dev/null +++ b/thirdparty/DBoW3/src/ScoringObject.h @@ -0,0 +1,95 @@ +/** + * File: ScoringObject.h + * Date: November 2011 + * Author: Dorian Galvez-Lopez + * Description: functions to compute bow scores + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T_SCORING_OBJECT__ +#define __D_T_SCORING_OBJECT__ + +#include "BowVector.h" +#include "exports.h" +namespace DBoW3 { + +/// Base class of scoring functions +class DBOW_API GeneralScoring +{ +public: + /** + * Computes the score between two vectors. Vectors must be sorted and + * normalized if necessary + * @param v (in/out) + * @param w (in/out) + * @return score + */ + virtual double score(const BowVector &v, const BowVector &w) const = 0; + + /** + * Returns whether a vector must be normalized before scoring according + * to the scoring scheme + * @param norm norm to use + * @return true iff must normalize + */ + virtual bool mustNormalize(LNorm &norm) const = 0; + + /// Log of epsilon + static const double LOG_EPS; + // If you change the type of WordValue, make sure you change also the + // epsilon value (this is needed by the KL method) + + virtual ~GeneralScoring() {} //!< Required for virtual base classes +}; + +/** + * Macro for defining Scoring classes + * @param NAME name of class + * @param MUSTNORMALIZE if vectors must be normalized to compute the score + * @param NORM type of norm to use when MUSTNORMALIZE + */ +#define __SCORING_CLASS(NAME, MUSTNORMALIZE, NORM) \ + NAME: public GeneralScoring \ + { public: \ + /** \ + * Computes score between two vectors \ + * @param v \ + * @param w \ + * @return score between v and w \ + */ \ + virtual double score(const BowVector &v, const BowVector &w) const; \ + \ + /** \ + * Says if a vector must be normalized according to the scoring function \ + * @param norm (out) if true, norm to use + * @return true iff vectors must be normalized \ + */ \ + virtual inline bool mustNormalize(LNorm &norm) const \ + { norm = NORM; return MUSTNORMALIZE; } \ + } + +/// L1 Scoring object +class __SCORING_CLASS(L1Scoring, true, L1); + +/// L2 Scoring object +class __SCORING_CLASS(L2Scoring, true, L2); + +/// Chi square Scoring object +class __SCORING_CLASS(ChiSquareScoring, true, L1); + +/// KL divergence Scoring object +class __SCORING_CLASS(KLScoring, true, L1); + +/// Bhattacharyya Scoring object +class __SCORING_CLASS(BhattacharyyaScoring, true, L1); + +/// Dot product Scoring object +class __SCORING_CLASS(DotProductScoring, false, L1); + +#undef __SCORING_CLASS + +} // namespace DBoW3 + +#endif + diff --git a/thirdparty/DBoW3/src/Vocabulary.cpp b/thirdparty/DBoW3/src/Vocabulary.cpp new file mode 100644 index 0000000..47d64f5 --- /dev/null +++ b/thirdparty/DBoW3/src/Vocabulary.cpp @@ -0,0 +1,1558 @@ +#include "Vocabulary.h" +#include +#include +#include "DescManip.h" +#include "quicklz.h" +#include "timers.h" + +namespace DBoW3 { +// -------------------------------------------------------------------------- + +Vocabulary::Vocabulary(int k, int L, WeightingType weighting, + ScoringType scoring) + : m_k(k), + m_L(L), + m_weighting(weighting), + m_scoring(scoring), + m_scoring_object(NULL) { + createScoringObject(); +} + +// -------------------------------------------------------------------------- + +Vocabulary::Vocabulary(const std::string &filename) : m_scoring_object(NULL) { + load(filename); +} + +// -------------------------------------------------------------------------- + +Vocabulary::Vocabulary(const char *filename) : m_scoring_object(NULL) { + load(filename); +} + +// -------------------------------------------------------------------------- + +void Vocabulary::createScoringObject() { + delete m_scoring_object; + m_scoring_object = NULL; + + switch (m_scoring) { + case L1_NORM: + m_scoring_object = new L1Scoring; + break; + + case L2_NORM: + m_scoring_object = new L2Scoring; + break; + + case CHI_SQUARE: + m_scoring_object = new ChiSquareScoring; + break; + + case KL: + m_scoring_object = new KLScoring; + break; + + case BHATTACHARYYA: + m_scoring_object = new BhattacharyyaScoring; + break; + + case DOT_PRODUCT: + m_scoring_object = new DotProductScoring; + break; + } +} + +// -------------------------------------------------------------------------- + +void Vocabulary::setScoringType(ScoringType type) { + m_scoring = type; + createScoringObject(); +} + +// -------------------------------------------------------------------------- + +void Vocabulary::setWeightingType(WeightingType type) { + this->m_weighting = type; +} + +// -------------------------------------------------------------------------- + +Vocabulary::Vocabulary(const Vocabulary &voc) : m_scoring_object(NULL) { + *this = voc; +} + +// -------------------------------------------------------------------------- + +Vocabulary::~Vocabulary() { delete m_scoring_object; } + +// -------------------------------------------------------------------------- + +Vocabulary &Vocabulary::operator=(const Vocabulary &voc) { + this->m_k = voc.m_k; + this->m_L = voc.m_L; + this->m_scoring = voc.m_scoring; + this->m_weighting = voc.m_weighting; + + this->createScoringObject(); + + this->m_nodes.clear(); + this->m_words.clear(); + + this->m_nodes = voc.m_nodes; + this->createWords(); + + return *this; +} + +void Vocabulary::create(const std::vector &training_features) { + std::vector> vtf(training_features.size()); + for (size_t i = 0; i < training_features.size(); i++) { + vtf[i].resize(training_features[i].rows); + for (int r = 0; r < training_features[i].rows; r++) + vtf[i][r] = training_features[i].rowRange(r, r + 1); + } + create(vtf); +} + +void Vocabulary::create( + const std::vector> &training_features) { + m_nodes.clear(); + m_words.clear(); + + // expected_nodes = Sum_{i=0..L} ( k^i ) + int expected_nodes = + (int)((pow((double)m_k, (double)m_L + 1) - 1) / (m_k - 1)); + + m_nodes.reserve(expected_nodes); // avoid allocations when creating the tree + + std::vector features; + getFeatures(training_features, features); + + // create root + m_nodes.push_back(Node(0)); // root + + // create the tree + HKmeansStep(0, features, 1); + + // create the words + createWords(); + + // and set the weight of each node of the tree + setNodeWeights(training_features); +} + +// -------------------------------------------------------------------------- + +void Vocabulary::create( + const std::vector> &training_features, int k, int L) { + m_k = k; + m_L = L; + + create(training_features); +} + +// -------------------------------------------------------------------------- + +void Vocabulary::create( + const std::vector> &training_features, int k, int L, + WeightingType weighting, ScoringType scoring) { + m_k = k; + m_L = L; + m_weighting = weighting; + m_scoring = scoring; + createScoringObject(); + + create(training_features); +} + +// -------------------------------------------------------------------------- + +void Vocabulary::getFeatures( + const std::vector> &training_features, + std::vector &features) const { + features.resize(0); + for (size_t i = 0; i < training_features.size(); i++) + for (size_t j = 0; j < training_features[i].size(); j++) + features.push_back(training_features[i][j]); +} + +// -------------------------------------------------------------------------- + +void Vocabulary::HKmeansStep(NodeId parent_id, + const std::vector &descriptors, + int current_level) { + if (descriptors.empty()) return; + + // features associated to each cluster + std::vector clusters; + std::vector> groups; // groups[i] = [j1, j2, ...] + // j1, j2, ... indices of descriptors associated to cluster i + + clusters.reserve(m_k); + groups.reserve(m_k); + + if ((int)descriptors.size() <= m_k) { + // trivial case: one cluster per feature + groups.resize(descriptors.size()); + + for (unsigned int i = 0; i < descriptors.size(); i++) { + groups[i].push_back(i); + clusters.push_back(descriptors[i]); + } + } else { + // select clusters and groups with kmeans + + bool first_time = true; + bool goon = true; + + // to check if clusters move after iterations + std::vector last_association, current_association; + + while (goon) { + // 1. Calculate clusters + + if (first_time) { + // random sample + initiateClusters(descriptors, clusters); + } else { + // calculate cluster centres + + for (unsigned int c = 0; c < clusters.size(); ++c) { + std::vector cluster_descriptors; + cluster_descriptors.reserve(groups[c].size()); + std::vector::const_iterator vit; + for (vit = groups[c].begin(); vit != groups[c].end(); ++vit) { + cluster_descriptors.push_back(descriptors[*vit]); + } + + DescManip::meanValue(cluster_descriptors, clusters[c]); + } + + } // if(!first_time) + + // 2. Associate features with clusters + + // calculate distances to cluster centers + groups.clear(); + groups.resize(clusters.size(), std::vector()); + current_association.resize(descriptors.size()); + + // assoc.clear(); + + // unsigned int d = 0; + for (auto fit = descriptors.begin(); fit != descriptors.end(); + ++fit) //, ++d) + { + double best_dist = DescManip::distance((*fit), clusters[0]); + unsigned int icluster = 0; + + for (unsigned int c = 1; c < clusters.size(); ++c) { + double dist = DescManip::distance((*fit), clusters[c]); + if (dist < best_dist) { + best_dist = dist; + icluster = c; + } + } + + // assoc.ref(icluster, d) = 1; + + groups[icluster].push_back(fit - descriptors.begin()); + current_association[fit - descriptors.begin()] = icluster; + } + + // kmeans++ ensures all the clusters has any feature associated with them + + // 3. check convergence + if (first_time) { + first_time = false; + } else { + // goon = !eqUChar(last_assoc, assoc); + + goon = false; + for (unsigned int i = 0; i < current_association.size(); i++) { + if (current_association[i] != last_association[i]) { + goon = true; + break; + } + } + } + + if (goon) { + // copy last feature-cluster association + last_association = current_association; + // last_assoc = assoc.clone(); + } + + } // while(goon) + + } // if must run kmeans + + // create nodes + for (unsigned int i = 0; i < clusters.size(); ++i) { + NodeId id = m_nodes.size(); + m_nodes.push_back(Node(id)); + m_nodes.back().descriptor = clusters[i]; + m_nodes.back().parent = parent_id; + m_nodes[parent_id].children.push_back(id); + } + + // go on with the next level + if (current_level < m_L) { + // iterate again with the resulting clusters + const std::vector &children_ids = m_nodes[parent_id].children; + for (unsigned int i = 0; i < clusters.size(); ++i) { + NodeId id = children_ids[i]; + + std::vector child_features; + child_features.reserve(groups[i].size()); + + std::vector::const_iterator vit; + for (vit = groups[i].begin(); vit != groups[i].end(); ++vit) { + child_features.push_back(descriptors[*vit]); + } + + if (child_features.size() > 1) { + HKmeansStep(id, child_features, current_level + 1); + } + } + } +} + +// -------------------------------------------------------------------------- + +void Vocabulary::initiateClusters(const std::vector &descriptors, + std::vector &clusters) const { + initiateClustersKMpp(descriptors, clusters); +} + +// -------------------------------------------------------------------------- + +void Vocabulary::initiateClustersKMpp(const std::vector &pfeatures, + std::vector &clusters) const { + // Implements kmeans++ seeding algorithm + // Algorithm: + // 1. Choose one center uniformly at random from among the data points. + // 2. For each data point x, compute D(x), the distance between x and the + // nearest + // center that has already been chosen. + // 3. Add one new data point as a center. Each point x is chosen with + // probability + // proportional to D(x)^2. + // 4. Repeat Steps 2 and 3 until k centers have been chosen. + // 5. Now that the initial centers have been chosen, proceed using standard + // k-means + // clustering. + + // DUtils::Random::SeedRandOnce(); + + clusters.resize(0); + clusters.reserve(m_k); + std::vector min_dists(pfeatures.size(), + std::numeric_limits::max()); + + // 1. + + int ifeature = + rand() % + pfeatures.size(); // DUtils::Random::RandomInt(0, pfeatures.size()-1); + + // create first cluster + clusters.push_back(pfeatures[ifeature]); + + // compute the initial distances + std::vector::iterator dit; + dit = min_dists.begin(); + for (auto fit = pfeatures.begin(); fit != pfeatures.end(); ++fit, ++dit) { + *dit = DescManip::distance((*fit), clusters.back()); + } + + while ((int)clusters.size() < m_k) { + // 2. + dit = min_dists.begin(); + for (auto fit = pfeatures.begin(); fit != pfeatures.end(); ++fit, ++dit) { + if (*dit > 0) { + double dist = DescManip::distance((*fit), clusters.back()); + if (dist < *dit) *dit = dist; + } + } + + // 3. + double dist_sum = std::accumulate(min_dists.begin(), min_dists.end(), 0.0); + + if (dist_sum > 0) { + double cut_d; + do { + cut_d = (double(rand()) / double(RAND_MAX)) * dist_sum; + } while (cut_d == 0.0); + + double d_up_now = 0; + for (dit = min_dists.begin(); dit != min_dists.end(); ++dit) { + d_up_now += *dit; + if (d_up_now >= cut_d) break; + } + + if (dit == min_dists.end()) + ifeature = pfeatures.size() - 1; + else + ifeature = dit - min_dists.begin(); + + clusters.push_back(pfeatures[ifeature]); + } // if dist_sum > 0 + else + break; + + } // while(used_clusters < m_k) +} + +// -------------------------------------------------------------------------- + +void Vocabulary::createWords() { + m_words.resize(0); + + if (!m_nodes.empty()) { + m_words.reserve((int)pow((double)m_k, (double)m_L)); + + auto nit = m_nodes.begin(); // ignore root + for (++nit; nit != m_nodes.end(); ++nit) { + if (nit->isLeaf()) { + nit->word_id = m_words.size(); + m_words.push_back(&(*nit)); + } + } + } +} + +// -------------------------------------------------------------------------- + +void Vocabulary::setNodeWeights( + const std::vector> &training_features) { + const unsigned int NWords = m_words.size(); + const unsigned int NDocs = training_features.size(); + + if (m_weighting == TF || m_weighting == BINARY) { + // idf part must be 1 always + for (unsigned int i = 0; i < NWords; i++) m_words[i]->weight = 1; + } else if (m_weighting == IDF || m_weighting == TF_IDF) { + // IDF and TF-IDF: we calculte the idf path now + + // Note: this actually calculates the idf part of the tf-idf score. + // The complete tf-idf score is calculated in ::transform + + std::vector Ni(NWords, 0); + std::vector counted(NWords, false); + + for (auto mit = training_features.begin(); mit != training_features.end(); + ++mit) { + fill(counted.begin(), counted.end(), false); + + for (auto fit = mit->begin(); fit < mit->end(); ++fit) { + WordId word_id; + transform(*fit, word_id); + + if (!counted[word_id]) { + Ni[word_id]++; + counted[word_id] = true; + } + } + } + + // set ln(N/Ni) + for (unsigned int i = 0; i < NWords; i++) { + if (Ni[i] > 0) { + m_words[i]->weight = log((double)NDocs / (double)Ni[i]); + } // else // This cannot occur if using kmeans++ + } + } +} + +// -------------------------------------------------------------------------- + +// -------------------------------------------------------------------------- + +float Vocabulary::getEffectiveLevels() const { + long sum = 0; + for (auto wit = m_words.begin(); wit != m_words.end(); ++wit) { + const Node *p = *wit; + + for (; p->id != 0; sum++) p = &m_nodes[p->parent]; + } + + return (float)((double)sum / (double)m_words.size()); +} + +// -------------------------------------------------------------------------- + +cv::Mat Vocabulary::getWord(WordId wid) const { + return m_words[wid]->descriptor; +} + +// -------------------------------------------------------------------------- + +WordValue Vocabulary::getWordWeight(WordId wid) const { + return m_words[wid]->weight; +} + +// -------------------------------------------------------------------------- + +WordId Vocabulary::transform(const cv::Mat &feature) const { + if (empty()) { + return 0; + } + + WordId wid; + transform(feature, wid); + return wid; +} + +// -------------------------------------------------------------------------- + +void Vocabulary::transform(const cv::Mat &features, BowVector &v) const { + // std::vector vf(features.rows); + // for(int r=0;rmustNormalize(norm); + + if (m_weighting == TF || m_weighting == TF_IDF) { + for (int r = 0; r < features.rows; r++) { + WordId id; + WordValue w; + // w is the idf value if TF_IDF, 1 if TF + transform(features.row(r), id, w); + // not stopped + if (w > 0) v.addWeight(id, w); + } + + if (!v.empty() && !must) { + // unnecessary when normalizing + const double nd = v.size(); + for (BowVector::iterator vit = v.begin(); vit != v.end(); vit++) + vit->second /= nd; + } + + } else // IDF || BINARY + { + for (int r = 0; r < features.rows; r++) { + WordId id; + WordValue w; + // w is idf if IDF, or 1 if BINARY + + transform(features.row(r), id, w); + + // not stopped + if (w > 0) v.addIfNotExist(id, w); + + } // if add_features + } // if m_weighting == ... + + if (must) v.normalize(norm); +} + +void Vocabulary::transform(const std::vector &features, + BowVector &v) const { + v.clear(); + + if (empty()) { + return; + } + + // normalize + LNorm norm; + bool must = m_scoring_object->mustNormalize(norm); + + if (m_weighting == TF || m_weighting == TF_IDF) { + for (auto fit = features.begin(); fit < features.end(); ++fit) { + WordId id; + WordValue w; + // w is the idf value if TF_IDF, 1 if TF + + transform(*fit, id, w); + + // not stopped + if (w > 0) v.addWeight(id, w); + } + + if (!v.empty() && !must) { + // unnecessary when normalizing + const double nd = v.size(); + for (BowVector::iterator vit = v.begin(); vit != v.end(); vit++) + vit->second /= nd; + } + + } else // IDF || BINARY + { + for (auto fit = features.begin(); fit < features.end(); ++fit) { + WordId id; + WordValue w; + // w is idf if IDF, or 1 if BINARY + + transform(*fit, id, w); + + // not stopped + if (w > 0) v.addIfNotExist(id, w); + + } // if add_features + } // if m_weighting == ... + + if (must) v.normalize(norm); +} + +void Vocabulary::transform(const std::vector> &features, + BowVector &v) const { + v.clear(); + + if (empty()) { + return; + } + + // normalize + LNorm norm; + bool must = m_scoring_object->mustNormalize(norm); + + if (m_weighting == TF || m_weighting == TF_IDF) { + for (auto fit = features.begin(); fit < features.end(); ++fit) { + WordId id; + WordValue w; + // w is the idf value if TF_IDF, 1 if TF + + transform(*fit, id, w); + + // not stopped + if (w > 0) v.addWeight(id, w); + } + + if (!v.empty() && !must) { + // unnecessary when normalizing + const double nd = v.size(); + for (BowVector::iterator vit = v.begin(); vit != v.end(); vit++) + vit->second /= nd; + } + + } else // IDF || BINARY + { + for (auto fit = features.begin(); fit < features.end(); ++fit) { + WordId id; + WordValue w; + // w is idf if IDF, or 1 if BINARY + + transform(*fit, id, w); + + // not stopped + if (w > 0) v.addIfNotExist(id, w); + + } // if add_features + } // if m_weighting == ... + + if (must) v.normalize(norm); +} + +// -------------------------------------------------------------------------- + +void Vocabulary::transform(const std::vector> &features, + BowVector &v, FeatureVector &fv, + int levelsup) const { + v.clear(); + fv.clear(); + + if (empty()) // safe for subclasses + { + return; + } + + // normalize + LNorm norm; + bool must = m_scoring_object->mustNormalize(norm); + + if (m_weighting == TF || m_weighting == TF_IDF) { + unsigned int i_feature = 0; + for (auto fit = features.begin(); fit < features.end(); + ++fit, ++i_feature) { + WordId id; + NodeId nid; + WordValue w; + // w is the idf value if TF_IDF, 1 if TF + + transform(*fit, id, w, &nid, levelsup); + + if (w > 0) // not stopped + { + v.addWeight(id, w); + fv.addFeature(nid, i_feature); + } + } + + if (!v.empty() && !must) { + // unnecessary when normalizing + const double nd = v.size(); + for (BowVector::iterator vit = v.begin(); vit != v.end(); vit++) + vit->second /= nd; + } + + } else // IDF || BINARY + { + unsigned int i_feature = 0; + for (auto fit = features.begin(); fit < features.end(); + ++fit, ++i_feature) { + WordId id; + NodeId nid; + WordValue w; + // w is idf if IDF, or 1 if BINARY + + transform(*fit, id, w, &nid, levelsup); + + if (w > 0) // not stopped + { + v.addIfNotExist(id, w); + fv.addFeature(nid, i_feature); + } + } + } // if m_weighting == ... + + if (must) v.normalize(norm); +} + +void Vocabulary::transform(const std::vector &features, BowVector &v, + FeatureVector &fv, int levelsup) const { + v.clear(); + fv.clear(); + + if (empty()) // safe for subclasses + { + return; + } + + // normalize + LNorm norm; + bool must = m_scoring_object->mustNormalize(norm); + + if (m_weighting == TF || m_weighting == TF_IDF) { + unsigned int i_feature = 0; + for (auto fit = features.begin(); fit < features.end(); + ++fit, ++i_feature) { + WordId id; + NodeId nid; + WordValue w; + // w is the idf value if TF_IDF, 1 if TF + + transform(*fit, id, w, &nid, levelsup); + + if (w > 0) // not stopped + { + v.addWeight(id, w); + fv.addFeature(nid, i_feature); + } + } + + if (!v.empty() && !must) { + // unnecessary when normalizing + const double nd = v.size(); + for (BowVector::iterator vit = v.begin(); vit != v.end(); vit++) + vit->second /= nd; + } + + } else // IDF || BINARY + { + unsigned int i_feature = 0; + for (auto fit = features.begin(); fit < features.end(); + ++fit, ++i_feature) { + WordId id; + NodeId nid; + WordValue w; + // w is idf if IDF, or 1 if BINARY + + transform(*fit, id, w, &nid, levelsup); + + if (w > 0) // not stopped + { + v.addIfNotExist(id, w); + fv.addFeature(nid, i_feature); + } + } + } // if m_weighting == ... + + if (must) v.normalize(norm); +} + +// -------------------------------------------------------------------------- + +// -------------------------------------------------------------------------- + +void Vocabulary::transform(const cv::Mat &feature, WordId &id) const { + WordValue weight; + transform(feature, id, weight); +} + +// -------------------------------------------------------------------------- + +void Vocabulary::transform(const std::bitset<256> &feature, WordId &word_id, + WordValue &weight, NodeId *nid, int levelsup) const { + // propagate the feature down the tree + + // level at which the node must be stored in nid, if given + const int nid_level = m_L - levelsup; + if (nid_level <= 0 && nid != NULL) *nid = 0; // root + + NodeId final_id = 0; // root + int current_level = 0; + + do { + ++current_level; + auto const &nodes = m_nodes[final_id].children; + double best_d = std::numeric_limits::max(); + // DescManip::distance(feature, m_nodes[final_id].descriptor); + + for (const auto &id : nodes) { + if (m_nodes[id].descriptor.type() != CV_8U || + m_nodes[id].descriptor.cols != sizeof(std::bitset<256>)) { + std::cerr << "Wrong descriptor type" << std::endl; + std::abort(); + } + + std::bitset<256> *desc = (std::bitset<256> *)m_nodes[id].descriptor.data; + + double d = ((*desc) & feature).count(); + + if (d < best_d) { + best_d = d; + final_id = id; + } + } + + if (nid != NULL && current_level == nid_level) *nid = final_id; + + } while (!m_nodes[final_id].isLeaf()); + + // turn node id into word id + word_id = m_nodes[final_id].word_id; + weight = m_nodes[final_id].weight; +} + +void Vocabulary::transform(const cv::Mat &feature, WordId &word_id, + WordValue &weight, NodeId *nid, int levelsup) const { + // propagate the feature down the tree + + // level at which the node must be stored in nid, if given + const int nid_level = m_L - levelsup; + if (nid_level <= 0 && nid != NULL) *nid = 0; // root + + NodeId final_id = 0; // root + int current_level = 0; + + do { + ++current_level; + auto const &nodes = m_nodes[final_id].children; + double best_d = std::numeric_limits::max(); + // DescManip::distance(feature, m_nodes[final_id].descriptor); + + for (const auto &id : nodes) { + double d = DescManip::distance(feature, m_nodes[id].descriptor); + if (d < best_d) { + best_d = d; + final_id = id; + } + } + + if (nid != NULL && current_level == nid_level) *nid = final_id; + + } while (!m_nodes[final_id].isLeaf()); + + // turn node id into word id + word_id = m_nodes[final_id].word_id; + weight = m_nodes[final_id].weight; +} + +void Vocabulary::transform(const cv::Mat &feature, WordId &word_id, + WordValue &weight) const { + // propagate the feature down the tree + + // level at which the node must be stored in nid, if given + + NodeId final_id = 0; // root + // maximum speed by computing here distance and avoid calling to + // DescManip::distance + + // binary descriptor + // int ntimes=0; + if (feature.type() == CV_8U) { + do { + auto const &nodes = m_nodes[final_id].children; + uint64_t best_d = std::numeric_limits::max(); + int idx = 0; //, bestidx = 0; + for (const auto &id : nodes) { + // compute distance + // std::cout<(); + // for(int i=0;i(0); + // const float *b_ptr=b.ptr(0); + // for(int i = 0; i < a.cols; i ++) + // sqd += (a_ptr[i ] - b_ptr[i ])*(a_ptr[i ] - b_ptr[i ]); + // return sqd; + // } + + // do + // { + // auto const &nodes = m_nodes[final_id].children; + // double best_d = std::numeric_limits::max(); + + // for(const auto &id:nodes) + // { + // double d = DescManip::distance(feature, m_nodes[id].descriptor); + // if(d < best_d) + // { + // best_d = d; + // final_id = id; + // } + // } + // } while( !m_nodes[final_id].isLeaf() ); + + // turn node id into word id + word_id = m_nodes[final_id].word_id; + weight = m_nodes[final_id].weight; +} + +void Vocabulary::transform(const std::bitset<256> &feature, WordId &word_id, + WordValue &weight) const { + // propagate the feature down the tree + + // level at which the node must be stored in nid, if given + + NodeId final_id = 0; // root + // maximum speed by computing here distance and avoid calling to + // DescManip::distance + + // binary descriptor + // int ntimes=0; + if (1) { + do { + auto const &nodes = m_nodes[final_id].children; + uint64_t best_d = std::numeric_limits::max(); + int idx = 0; //, bestidx = 0; + for (const auto &id : nodes) { + // compute distance + // std::cout<)) { + std::cerr << "Wrong descriptor type" << std::endl; + std::abort(); + } + + std::bitset<256> *desc = + (std::bitset<256> *)m_nodes[id].descriptor.data; + + uint64_t dist = ((*desc) & feature).count(); + + if (dist < best_d) { + best_d = dist; + final_id = id; + // bestidx = idx; + } + idx++; + } + // std::cout<(); + // for(int i=0;i(0); + // const float *b_ptr=b.ptr(0); + // for(int i = 0; i < a.cols; i ++) + // sqd += (a_ptr[i ] - b_ptr[i ])*(a_ptr[i ] - b_ptr[i ]); + // return sqd; + // } + + // do + // { + // auto const &nodes = m_nodes[final_id].children; + // double best_d = std::numeric_limits::max(); + + // for(const auto &id:nodes) + // { + // double d = DescManip::distance(feature, m_nodes[id].descriptor); + // if(d < best_d) + // { + // best_d = d; + // final_id = id; + // } + // } + // } while( !m_nodes[final_id].isLeaf() ); + + // turn node id into word id + word_id = m_nodes[final_id].word_id; + weight = m_nodes[final_id].weight; +} + +// -------------------------------------------------------------------------- + +NodeId Vocabulary::getParentNode(WordId wid, int levelsup) const { + NodeId ret = m_words[wid]->id; // node id + while (levelsup > 0 && ret != 0) // ret == 0 --> root + { + --levelsup; + ret = m_nodes[ret].parent; + } + return ret; +} + +// -------------------------------------------------------------------------- + +void Vocabulary::getWordsFromNode(NodeId nid, + std::vector &words) const { + words.clear(); + + if (m_nodes[nid].isLeaf()) { + words.push_back(m_nodes[nid].word_id); + } else { + words.reserve(m_k); // ^1, ^2, ... + + std::vector parents; + parents.push_back(nid); + + while (!parents.empty()) { + NodeId parentid = parents.back(); + parents.pop_back(); + + const std::vector &child_ids = m_nodes[parentid].children; + std::vector::const_iterator cit; + + for (cit = child_ids.begin(); cit != child_ids.end(); ++cit) { + const Node &child_node = m_nodes[*cit]; + + if (child_node.isLeaf()) + words.push_back(child_node.word_id); + else + parents.push_back(*cit); + + } // for each child + } // while !parents.empty + } +} + +// -------------------------------------------------------------------------- + +int Vocabulary::stopWords(double minWeight) { + int c = 0; + for (auto wit = m_words.begin(); wit != m_words.end(); ++wit) { + if ((*wit)->weight < minWeight) { + ++c; + (*wit)->weight = 0; + } + } + return c; +} + +// -------------------------------------------------------------------------- + +void Vocabulary::save(const std::string &filename, + bool binary_compressed) const { + if (filename.find(".yml") == std::string::npos) { + std::ofstream file_out(filename, std::ios::binary); + if (!file_out) + throw std::runtime_error("Vocabulary::saveBinary Could not open file :" + + filename + " for writing"); + toStream(file_out, binary_compressed); + } else { + cv::FileStorage fs(filename.c_str(), cv::FileStorage::WRITE); + if (!fs.isOpened()) throw std::string("Could not open file ") + filename; + save(fs); + } +} + +// -------------------------------------------------------------------------- + +void Vocabulary::load(const std::string &filename) { + // check first if it is a binary file + std::ifstream ifile(filename, std::ios::binary); + if (!ifile) + throw std::runtime_error("Vocabulary::load Could not open file :" + + filename + " for reading"); + uint64_t sig; // magic number describing the file + ifile.read((char *)&sig, sizeof(sig)); + if (sig == 88877711233) { // it is a binary file. read from it + ifile.seekg(0, std::ios::beg); + fromStream(ifile); + + } else { + if (filename.find(".txt") != std::string::npos) { + // read from a text file (used in ORBSLAM2) + load_fromtxt(filename); + } else { + cv::FileStorage fs(filename.c_str(), cv::FileStorage::READ); + if (!fs.isOpened()) throw std::string("Could not open file ") + filename; + this->load(fs); + } + } +} + +void Vocabulary::save(cv::FileStorage &f, const std::string &name) const { + f << name << "{"; + + f << "k" << m_k; + f << "L" << m_L; + f << "scoringType" << m_scoring; + f << "weightingType" << m_weighting; + + // tree + f << "nodes" + << "["; + std::vector parents, children; + std::vector::const_iterator pit; + + parents.push_back(0); // root + + while (!parents.empty()) { + NodeId pid = parents.back(); + parents.pop_back(); + + const Node &parent = m_nodes[pid]; + children = parent.children; + + for (pit = children.begin(); pit != children.end(); pit++) { + const Node &child = m_nodes[*pit]; + std::cout << m_nodes[*pit].id << " "; + + // save node data + f << "{:"; + f << "nodeId" << (int)child.id; + f << "parentId" << (int)pid; + f << "weight" << (double)child.weight; + f << "descriptor" << DescManip::toString(child.descriptor); + f << "}"; + + // add to parent list + if (!child.isLeaf()) { + parents.push_back(*pit); + } + } + } + std::cout << "\n"; + + f << "]"; // nodes + + // words + f << "words" + << "["; + + for (auto wit = m_words.begin(); wit != m_words.end(); wit++) { + WordId id = wit - m_words.begin(); + f << "{:"; + f << "wordId" << (int)id; + f << "nodeId" << (int)(*wit)->id; + f << "}"; + } + + f << "]"; // words + + f << "}"; +} + +void Vocabulary::toStream(std::ostream &out_str, bool compressed) const { + uint64_t sig = 88877711233; // magic number describing the file + out_str.write((char *)&sig, sizeof(sig)); + out_str.write((char *)&compressed, sizeof(compressed)); + uint32_t nnodes = m_nodes.size(); + out_str.write((char *)&nnodes, sizeof(nnodes)); + if (nnodes == 0) return; + // save everything to a stream + std::stringstream aux_stream; + aux_stream.write((char *)&m_k, sizeof(m_k)); + aux_stream.write((char *)&m_L, sizeof(m_L)); + aux_stream.write((char *)&m_scoring, sizeof(m_scoring)); + aux_stream.write((char *)&m_weighting, sizeof(m_weighting)); + // nodes + std::vector parents = {0}; // root + + while (!parents.empty()) { + NodeId pid = parents.back(); + parents.pop_back(); + + const Node &parent = m_nodes[pid]; + + for (auto pit : parent.children) { + const Node &child = m_nodes[pit]; + aux_stream.write((char *)&child.id, sizeof(child.id)); + aux_stream.write((char *)&pid, sizeof(pid)); + aux_stream.write((char *)&child.weight, sizeof(child.weight)); + DescManip::toStream(child.descriptor, aux_stream); + // add to parent list + if (!child.isLeaf()) parents.push_back(pit); + } + } + // words + // save size + uint32_t m_words_size = m_words.size(); + aux_stream.write((char *)&m_words_size, sizeof(m_words_size)); + for (auto wit = m_words.begin(); wit != m_words.end(); wit++) { + WordId id = wit - m_words.begin(); + aux_stream.write((char *)&id, sizeof(id)); + aux_stream.write((char *)&(*wit)->id, sizeof((*wit)->id)); + } + + // now, decide if compress or not + if (compressed) { + qlz_state_compress state_compress; + memset(&state_compress, 0, sizeof(qlz_state_compress)); + // Create output buffer + int chunkSize = 10000; + std::vector compressed(chunkSize + size_t(400), 0); + std::vector input(chunkSize, 0); + int64_t total_size = static_cast(aux_stream.tellp()); + uint64_t total_compress_size = 0; + // calculate how many chunks will be written + uint32_t nChunks = total_size / chunkSize; + if (total_size % chunkSize != 0) nChunks++; + out_str.write((char *)&nChunks, sizeof(nChunks)); + // start compressing the chunks + while (total_size != 0) { + int readSize = chunkSize; + if (total_size < chunkSize) readSize = total_size; + aux_stream.read(&input[0], readSize); + uint64_t compressed_size = + qlz_compress(&input[0], &compressed[0], readSize, &state_compress); + total_size -= readSize; + out_str.write(&compressed[0], compressed_size); + total_compress_size += compressed_size; + } + } else { + out_str << aux_stream.rdbuf(); + } +} + +void Vocabulary::load_fromtxt(const std::string &filename) { + std::ifstream ifile(filename); + if (!ifile) + throw std::runtime_error( + "Vocabulary:: load_fromtxt Could not open file for reading:" + + filename); + int n1, n2; + { + std::string str; + getline(ifile, str); + std::stringstream ss(str); + ss >> m_k >> m_L >> n1 >> n2; + } + if (m_k < 0 || m_k > 20 || m_L < 1 || m_L > 10 || n1 < 0 || n1 > 5 || + n2 < 0 || n2 > 3) + throw std::runtime_error( + "Vocabulary loading failure: This is not a correct text file!"); + + m_scoring = (ScoringType)n1; + m_weighting = (WeightingType)n2; + createScoringObject(); + // nodes + int expected_nodes = + (int)((pow((double)m_k, (double)m_L + 1) - 1) / (m_k - 1)); + m_nodes.reserve(expected_nodes); + + m_words.reserve(pow((double)m_k, (double)m_L + 1)); + + m_nodes.resize(1); + m_nodes[0].id = 0; + + int counter = 0; + while (!ifile.eof()) { + std::string snode; + getline(ifile, snode); + if (counter++ % 100 == 0) std::cerr << "."; + // std::cout<> pid; + m_nodes[nid].parent = pid; + m_nodes[pid].children.push_back(nid); + + int nIsLeaf; + ssnode >> nIsLeaf; + + // read until the end and add to data + std::vector data; + data.reserve(100); + float d; + while (ssnode >> d) data.push_back(d); + // the weight is the last + m_nodes[nid].weight = data.back(); + data.pop_back(); // remove + // the rest, to the descriptor + m_nodes[nid].descriptor.create(1, data.size(), CV_8UC1); + auto ptr = m_nodes[nid].descriptor.ptr(0); + for (auto d : data) *ptr++ = d; + + if (nIsLeaf > 0) { + int wid = m_words.size(); + m_words.resize(wid + 1); + + m_nodes[nid].word_id = wid; + m_words[wid] = &m_nodes[nid]; + } else { + m_nodes[nid].children.reserve(m_k); + } + } +} +void Vocabulary::fromStream(std::istream &str) { + m_words.clear(); + m_nodes.clear(); + uint64_t sig = 0; // magic number describing the file + str.read((char *)&sig, sizeof(sig)); + if (sig != 88877711233) + throw std::runtime_error( + "Vocabulary::fromStream is not of appropriate type"); + bool compressed; + str.read((char *)&compressed, sizeof(compressed)); + uint32_t nnodes; + str.read((char *)&nnodes, sizeof(nnodes)); + if (nnodes == 0) return; + std::stringstream decompressed_stream; + std::istream *_used_str = 0; + if (compressed) { + qlz_state_decompress state_decompress; + memset(&state_decompress, 0, sizeof(qlz_state_decompress)); + int chunkSize = 10000; + std::vector decompressed(chunkSize); + std::vector input(chunkSize + 400); + // read how many chunks are there + uint32_t nChunks; + str.read((char *)&nChunks, sizeof(nChunks)); + for (uint32_t i = 0; i < nChunks; i++) { + str.read(&input[0], 9); + int c = qlz_size_compressed(&input[0]); + str.read(&input[9], c - 9); + size_t d = qlz_decompress(&input[0], &decompressed[0], &state_decompress); + decompressed_stream.write(&decompressed[0], d); + } + _used_str = &decompressed_stream; + } else { + _used_str = &str; + } + + _used_str->read((char *)&m_k, sizeof(m_k)); + _used_str->read((char *)&m_L, sizeof(m_L)); + _used_str->read((char *)&m_scoring, sizeof(m_scoring)); + _used_str->read((char *)&m_weighting, sizeof(m_weighting)); + + createScoringObject(); + m_nodes.resize(nnodes); + m_nodes[0].id = 0; + + for (size_t i = 1; i < m_nodes.size(); ++i) { + NodeId nid; + _used_str->read((char *)&nid, sizeof(NodeId)); + Node &child = m_nodes[nid]; + child.id = nid; + _used_str->read((char *)&child.parent, sizeof(child.parent)); + _used_str->read((char *)&child.weight, sizeof(child.weight)); + DescManip::fromStream(child.descriptor, *_used_str); + m_nodes[child.parent].children.push_back(child.id); + } + // // words + uint32_t m_words_size; + _used_str->read((char *)&m_words_size, sizeof(m_words_size)); + m_words.resize(m_words_size); + for (unsigned int i = 0; i < m_words.size(); ++i) { + WordId wid; + NodeId nid; + _used_str->read((char *)&wid, sizeof(wid)); + _used_str->read((char *)&nid, sizeof(nid)); + m_nodes[nid].word_id = wid; + m_words[wid] = &m_nodes[nid]; + } +} +// -------------------------------------------------------------------------- + +void Vocabulary::load(const cv::FileStorage &fs, const std::string &name) { + m_words.clear(); + m_nodes.clear(); + + cv::FileNode fvoc = fs[name]; + + m_k = (int)fvoc["k"]; + m_L = (int)fvoc["L"]; + m_scoring = (ScoringType)((int)fvoc["scoringType"]); + m_weighting = (WeightingType)((int)fvoc["weightingType"]); + + createScoringObject(); + + // nodes + cv::FileNode fn = fvoc["nodes"]; + + m_nodes.resize(fn.size() + 1); // +1 to include root + m_nodes[0].id = 0; + + for (unsigned int i = 0; i < fn.size(); ++i) { + NodeId nid = (int)fn[i]["nodeId"]; + NodeId pid = (int)fn[i]["parentId"]; + WordValue weight = (WordValue)fn[i]["weight"]; + std::string d = (std::string)fn[i]["descriptor"]; + + m_nodes[nid].id = nid; + m_nodes[nid].parent = pid; + m_nodes[nid].weight = weight; + m_nodes[pid].children.push_back(nid); + + DescManip::fromString(m_nodes[nid].descriptor, d); + } + + // words + fn = fvoc["words"]; + + m_words.resize(fn.size()); + + for (unsigned int i = 0; i < fn.size(); ++i) { + NodeId wid = (int)fn[i]["wordId"]; + NodeId nid = (int)fn[i]["nodeId"]; + + m_nodes[nid].word_id = wid; + m_words[wid] = &m_nodes[nid]; + } +} + +// -------------------------------------------------------------------------- + +/** + * Writes printable information of the vocabulary + * @param os stream to write to + * @param voc + */ + +std::ostream &operator<<(std::ostream &os, const Vocabulary &voc) { + os << "Vocabulary: k = " << voc.getBranchingFactor() + << ", L = " << voc.getDepthLevels() << ", Weighting = "; + + switch (voc.getWeightingType()) { + case TF_IDF: + os << "tf-idf"; + break; + case TF: + os << "tf"; + break; + case IDF: + os << "idf"; + break; + case BINARY: + os << "binary"; + break; + } + + os << ", Scoring = "; + switch (voc.getScoringType()) { + case L1_NORM: + os << "L1-norm"; + break; + case L2_NORM: + os << "L2-norm"; + break; + case CHI_SQUARE: + os << "Chi square distance"; + break; + case KL: + os << "KL-divergence"; + break; + case BHATTACHARYYA: + os << "Bhattacharyya coefficient"; + break; + case DOT_PRODUCT: + os << "Dot product"; + break; + } + + os << ", Number of words = " << voc.size(); + + return os; +} +/** + * @brief Vocabulary::clear + */ +void Vocabulary::clear() { + delete m_scoring_object; + m_scoring_object = 0; + m_nodes.clear(); + m_words.clear(); +} +int Vocabulary::getDescritorSize() const { + if (m_words.size() == 0) + return -1; + else + return m_words[0]->descriptor.cols; +} +int Vocabulary::getDescritorType() const { + if (m_words.size() == 0) + return -1; + else + return m_words[0]->descriptor.type(); +} +} diff --git a/thirdparty/DBoW3/src/Vocabulary.h b/thirdparty/DBoW3/src/Vocabulary.h new file mode 100644 index 0000000..d2966f5 --- /dev/null +++ b/thirdparty/DBoW3/src/Vocabulary.h @@ -0,0 +1,468 @@ +/** + * File: Vocabulary.h + * Date: February 2011 + * Author: Dorian Galvez-Lopez + * Description: templated vocabulary + * License: see the LICENSE.txt file + * + */ + +#ifndef __D_T__VOCABULARY__ +#define __D_T__VOCABULARY__ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "BowVector.h" +#include "FeatureVector.h" +#include "ScoringObject.h" +#include "exports.h" +namespace DBoW3 { +/// Vocabulary +class DBOW_API Vocabulary { + friend class FastSearch; + + public: + /** + * Initiates an empty vocabulary + * @param k branching factor + * @param L depth levels + * @param weighting weighting type + * @param scoring scoring type + */ + Vocabulary(int k = 10, int L = 5, WeightingType weighting = TF_IDF, + ScoringType scoring = L1_NORM); + + /** + * Creates the vocabulary by loading a file + * @param filename + */ + Vocabulary(const std::string &filename); + + /** + * Creates the vocabulary by loading a file + * @param filename + */ + Vocabulary(const char *filename); + + /** + * Copy constructor + * @param voc + */ + Vocabulary(const Vocabulary &voc); + + /** + * Destructor + */ + virtual ~Vocabulary(); + + /** + * Assigns the given vocabulary to this by copying its data and removing + * all the data contained by this vocabulary before + * @param voc + * @return reference to this vocabulary + */ + Vocabulary &operator=(const Vocabulary &voc); + + /** + * Creates a vocabulary from the training features with the already + * defined parameters + * @param training_features + */ + virtual void create( + const std::vector> &training_features); + /** + * Creates a vocabulary from the training features with the already + * defined parameters + * @param training_features. Each row of a matrix is a feature + */ + virtual void create(const std::vector &training_features); + + /** + * Creates a vocabulary from the training features, setting the branching + * factor and the depth levels of the tree + * @param training_features + * @param k branching factor + * @param L depth levels + */ + virtual void create( + const std::vector> &training_features, int k, int L); + + /** + * Creates a vocabulary from the training features, setting the branching + * factor nad the depth levels of the tree, and the weighting and scoring + * schemes + */ + virtual void create( + const std::vector> &training_features, int k, int L, + WeightingType weighting, ScoringType scoring); + + /** + * Returns the number of words in the vocabulary + * @return number of words + */ + virtual inline unsigned int size() const { + return (unsigned int)m_words.size(); + } + + /** + * Returns whether the vocabulary is empty (i.e. it has not been trained) + * @return true iff the vocabulary is empty + */ + virtual inline bool empty() const { return m_words.empty(); } + + /** Clears the vocabulary object + */ + void clear(); + /** + * Transforms a set of descriptores into a bow vector + * @param features + * @param v (out) bow vector of weighted words + */ + virtual void transform(const std::vector &features, + BowVector &v) const; + + virtual void transform(const std::vector> &features, + BowVector &v) const; + + /** + * Transforms a set of descriptores into a bow vector + * @param features, one per row + * @param v (out) bow vector of weighted words + */ + virtual void transform(const cv::Mat &features, BowVector &v) const; + /** + * Transform a set of descriptors into a bow vector and a feature vector + * @param features + * @param v (out) bow vector + * @param fv (out) feature vector of nodes and feature indexes + * @param levelsup levels to go up the vocabulary tree to get the node index + */ + virtual void transform(const std::vector &features, BowVector &v, + FeatureVector &fv, int levelsup) const; + + /** + * Transforms a single feature into a word (without weight) + * @param feature + * @return word id + */ + virtual WordId transform(const cv::Mat &feature) const; + + void transform(const std::vector> &features, BowVector &v, + FeatureVector &fv, int levelsup) const; + + /** + * Returns the score of two vectors + * @param a vector + * @param b vector + * @return score between vectors + * @note the vectors must be already sorted and normalized if necessary + */ + double score(const BowVector &a, const BowVector &b) const { + return m_scoring_object->score(a, b); + } + + /** + * Returns the id of the node that is "levelsup" levels from the word given + * @param wid word id + * @param levelsup 0..L + * @return node id. if levelsup is 0, returns the node id associated to the + * word id + */ + virtual NodeId getParentNode(WordId wid, int levelsup) const; + + /** + * Returns the ids of all the words that are under the given node id, + * by traversing any of the branches that goes down from the node + * @param nid starting node id + * @param words ids of words + */ + void getWordsFromNode(NodeId nid, std::vector &words) const; + + /** + * Returns the branching factor of the tree (k) + * @return k + */ + inline int getBranchingFactor() const { return m_k; } + + /** + * Returns the depth levels of the tree (L) + * @return L + */ + inline int getDepthLevels() const { return m_L; } + + /** + * Returns the real depth levels of the tree on average + * @return average of depth levels of leaves + */ + float getEffectiveLevels() const; + + /** + * Returns the descriptor of a word + * @param wid word id + * @return descriptor + */ + virtual inline cv::Mat getWord(WordId wid) const; + + /** + * Returns the weight of a word + * @param wid word id + * @return weight + */ + virtual inline WordValue getWordWeight(WordId wid) const; + + /** + * Returns the weighting method + * @return weighting method + */ + inline WeightingType getWeightingType() const { return m_weighting; } + + /** + * Returns the scoring method + * @return scoring method + */ + inline ScoringType getScoringType() const { return m_scoring; } + + /** + * Changes the weighting method + * @param type new weighting type + */ + inline void setWeightingType(WeightingType type); + + /** + * Changes the scoring method + * @param type new scoring type + */ + void setScoringType(ScoringType type); + + /** + * Saves the vocabulary into a file. If filename extension contains .yml, + * opencv YALM format is used. Otherwise, binary format is employed + * @param filename + */ + void save(const std::string &filename, bool binary_compressed = true) const; + + /** + * Loads the vocabulary from a file created with save + * @param filename. + */ + void load(const std::string &filename); + + /** + * Saves the vocabulary to a file storage structure + * @param fn node in file storage + */ + virtual void save(cv::FileStorage &fs, + const std::string &name = "vocabulary") const; + + /** + * Loads the vocabulary from a file storage node + * @param fn first node + * @param subname name of the child node of fn where the tree is stored. + * If not given, the fn node is used instead + */ + virtual void load(const cv::FileStorage &fs, + const std::string &name = "vocabulary"); + + /** + * Stops those words whose weight is below minWeight. + * Words are stopped by setting their weight to 0. There are not returned + * later when transforming image features into vectors. + * Note that when using IDF or TF_IDF, the weight is the idf part, which + * is equivalent to -log(f), where f is the frequency of the word + * (f = Ni/N, Ni: number of training images where the word is present, + * N: number of training images). + * Note that the old weight is forgotten, and subsequent calls to this + * function with a lower minWeight have no effect. + * @return number of words stopped now + */ + virtual int stopWords(double minWeight); + + /** Returns the size of the descriptor employed. If the Vocabulary is empty, + * returns -1 + */ + int getDescritorSize() const; + /** Returns the type of the descriptor employed normally(8U_C1, 32F_C1) + */ + int getDescritorType() const; + // io to-from a stream + void toStream(std::ostream &str, bool compressed = true) const; + void fromStream(std::istream &str); + + protected: + /// reference to descriptor + typedef const cv::Mat pDescriptor; + + /// Tree node + struct Node { + /// Node id + NodeId id; + /// Weight if the node is a word + WordValue weight; + /// Children + std::vector children; + /// Parent node (undefined in case of root) + NodeId parent; + /// Node descriptor + cv::Mat descriptor; + + /// Word id if the node is a word + WordId word_id; + + /** + * Empty constructor + */ + Node() : id(0), weight(0), parent(0), word_id(0) {} + + /** + * Constructor + * @param _id node id + */ + Node(NodeId _id) : id(_id), weight(0), parent(0), word_id(0) {} + + /** + * Returns whether the node is a leaf node + * @return true iff the node is a leaf + */ + inline bool isLeaf() const { return children.empty(); } + }; + + protected: + /** + * Creates an instance of the scoring object accoring to m_scoring + */ + void createScoringObject(); + + /** + * Returns a set of pointers to descriptores + * @param training_features all the features + * @param features (out) pointers to the training features + */ + void getFeatures(const std::vector> &training_features, + std::vector &features) const; + + /** + * Returns the word id associated to a feature + * @param feature + * @param id (out) word id + * @param weight (out) word weight + * @param nid (out) if given, id of the node "levelsup" levels up + * @param levelsup + */ + virtual void transform(const cv::Mat &feature, WordId &id, WordValue &weight, + NodeId *nid, int levelsup = 0) const; + /** + * Returns the word id associated to a feature + * @param feature + * @param id (out) word id + * @param weight (out) word weight + * @param nid (out) if given, id of the node "levelsup" levels up + * @param levelsup + */ + virtual void transform(const cv::Mat &feature, WordId &id, + WordValue &weight) const; + + void transform(const std::bitset<256> &feature, WordId &word_id, + WordValue &weight) const; + + virtual void transform(const std::bitset<256> &feature, WordId &word_id, + WordValue &weight, NodeId *nid, int levelsup) const; + + /** + * Returns the word id associated to a feature + * @param feature + * @param id (out) word id + */ + virtual void transform(const cv::Mat &feature, WordId &id) const; + + /** + * Creates a level in the tree, under the parent, by running kmeans with + * a descriptor set, and recursively creates the subsequent levels too + * @param parent_id id of parent node + * @param descriptors descriptors to run the kmeans on + * @param current_level current level in the tree + */ + void HKmeansStep(NodeId parent_id, const std::vector &descriptors, + int current_level); + + /** + * Creates k clusters from the given descriptors with some seeding algorithm. + * @note In this class, kmeans++ is used, but this function should be + * overriden by inherited classes. + */ + virtual void initiateClusters(const std::vector &descriptors, + std::vector &clusters) const; + + /** + * Creates k clusters from the given descriptor sets by running the + * initial step of kmeans++ + * @param descriptors + * @param clusters resulting clusters + */ + void initiateClustersKMpp(const std::vector &descriptors, + std::vector &clusters) const; + + /** + * Create the words of the vocabulary once the tree has been built + */ + void createWords(); + + /** + * Sets the weights of the nodes of tree according to the given features. + * Before calling this function, the nodes and the words must be already + * created (by calling HKmeansStep and createWords) + * @param features + */ + void setNodeWeights(const std::vector> &features); + + /** + * Writes printable information of the vocabulary + * @param os stream to write to + * @param voc + */ + DBOW_API friend std::ostream &operator<<(std::ostream &os, + const Vocabulary &voc); + + /**Loads from ORBSLAM txt files + */ + void load_fromtxt(const std::string &filename); + + protected: + /// Branching factor + int m_k; + + /// Depth levels + int m_L; + + /// Weighting method + WeightingType m_weighting; + + /// Scoring method + ScoringType m_scoring; + + /// Object for computing scores + GeneralScoring *m_scoring_object; + + /// Tree nodes + std::vector m_nodes; + + /// Words of the vocabulary (tree leaves) + /// this condition holds: m_words[wid]->word_id == wid + std::vector m_words; + + public: + // for debug (REMOVE) + inline Node *getNodeWord(uint32_t idx) { return m_words[idx]; } +}; + +} // namespace DBoW3 + +#endif diff --git a/thirdparty/DBoW3/src/exports.h b/thirdparty/DBoW3/src/exports.h new file mode 100644 index 0000000..c324953 --- /dev/null +++ b/thirdparty/DBoW3/src/exports.h @@ -0,0 +1,51 @@ +/***************************** +Copyright 2014 Rafael Muñoz Salinas. All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are +permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this list of + conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, this list + of conditions and the following disclaimer in the documentation and/or other materials + provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY Rafael Muñoz Salinas ''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 Rafael Muñoz Salinas 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. + +The views and conclusions contained in the software and documentation are those of the +authors and should not be interpreted as representing official policies, either expressed +or implied, of Rafael Muñoz Salinas. +********************************/ + + + +#ifndef __DBOW_CORE_TYPES_H__ +#define __DBOW_CORE_TYPES_H__ + +#if !defined _CRT_SECURE_NO_DEPRECATE && _MSC_VER > 1300 +#define _CRT_SECURE_NO_DEPRECATE /* to avoid multiple Visual Studio 2005 warnings */ +#endif + +#if (defined WIN32 || defined _WIN32 || defined WINCE) && defined DBOW_DSO_EXPORTS + #define DBOW_API __declspec(dllexport) + #pragma warning ( disable : 4251 ) //disable warning to templates with dll linkage. + #pragma warning ( disable : 4290 ) //disable warning due to exception specifications. + #pragma warning ( disable : 4996 ) //disable warning regarding unsafe vsprintf. + #pragma warning ( disable : 4244 ) //disable warning convesions with lost of data. + +#else + #define DBOW_API +#endif + + +#define DBOW_VERSION "3.0.0" +#endif diff --git a/thirdparty/DBoW3/src/quicklz.c b/thirdparty/DBoW3/src/quicklz.c new file mode 100644 index 0000000..3742129 --- /dev/null +++ b/thirdparty/DBoW3/src/quicklz.c @@ -0,0 +1,848 @@ +// Fast data compression library +// Copyright (C) 2006-2011 Lasse Mikkel Reinhold +// lar@quicklz.com +// +// QuickLZ can be used for free under the GPL 1, 2 or 3 license (where anything +// released into public must be open source) or under a commercial license if such +// has been acquired (see http://www.quicklz.com/order.html). The commercial license +// does not cover derived or ported versions created by third parties under GPL. + +// 1.5.0 final + +#include "quicklz.h" + +#if QLZ_VERSION_MAJOR != 1 || QLZ_VERSION_MINOR != 5 || QLZ_VERSION_REVISION != 0 + #error quicklz.c and quicklz.h have different versions +#endif + +#if (defined(__X86__) || defined(__i386__) || defined(i386) || defined(_M_IX86) || defined(__386__) || defined(__x86_64__) || defined(_M_X64)) + #define X86X64 +#endif + +#define MINOFFSET 2 +#define UNCONDITIONAL_MATCHLEN 6 +#define UNCOMPRESSED_END 4 +#define CWORD_LEN 4 + +#if QLZ_COMPRESSION_LEVEL == 1 && defined QLZ_PTR_64 && QLZ_STREAMING_BUFFER == 0 + #define OFFSET_BASE source + #define CAST (ui32)(size_t) +#else + #define OFFSET_BASE 0 + #define CAST +#endif + +int qlz_get_setting(int setting) +{ + switch (setting) + { + case 0: return QLZ_COMPRESSION_LEVEL; + case 1: return sizeof(qlz_state_compress); + case 2: return sizeof(qlz_state_decompress); + case 3: return QLZ_STREAMING_BUFFER; +#ifdef QLZ_MEMORY_SAFE + case 6: return 1; +#else + case 6: return 0; +#endif + case 7: return QLZ_VERSION_MAJOR; + case 8: return QLZ_VERSION_MINOR; + case 9: return QLZ_VERSION_REVISION; + } + return -1; +} + +#if QLZ_COMPRESSION_LEVEL == 1 +static int same(const unsigned char *src, size_t n) +{ + while(n > 0 && *(src + n) == *src) + n--; + return n == 0 ? 1 : 0; +} +#endif + +static void reset_table_compress(qlz_state_compress *state) +{ + int i; + for(i = 0; i < QLZ_HASH_VALUES; i++) + { +#if QLZ_COMPRESSION_LEVEL == 1 + state->hash[i].offset = 0; +#else + state->hash_counter[i] = 0; +#endif + } +} + +static void reset_table_decompress(qlz_state_decompress *state) +{ + int i; + (void)state; + (void)i; +#if QLZ_COMPRESSION_LEVEL == 2 + for(i = 0; i < QLZ_HASH_VALUES; i++) + { + state->hash_counter[i] = 0; + } +#endif +} + +static __inline ui32 hash_func(ui32 i) +{ +#if QLZ_COMPRESSION_LEVEL == 2 + return ((i >> 9) ^ (i >> 13) ^ i) & (QLZ_HASH_VALUES - 1); +#else + return ((i >> 12) ^ i) & (QLZ_HASH_VALUES - 1); +#endif +} + +static __inline ui32 fast_read(void const *src, ui32 bytes) +{ +#ifndef X86X64 + unsigned char *p = (unsigned char*)src; + switch (bytes) + { + case 4: + return(*p | *(p + 1) << 8 | *(p + 2) << 16 | *(p + 3) << 24); + case 3: + return(*p | *(p + 1) << 8 | *(p + 2) << 16); + case 2: + return(*p | *(p + 1) << 8); + case 1: + return(*p); + } + return 0; +#else + if (bytes >= 1 && bytes <= 4) + return *((ui32*)src); + else + return 0; +#endif +} + +static __inline ui32 hashat(const unsigned char *src) +{ + ui32 fetch, hash; + fetch = fast_read(src, 3); + hash = hash_func(fetch); + return hash; +} + +static __inline void fast_write(ui32 f, void *dst, size_t bytes) +{ +#ifndef X86X64 + unsigned char *p = (unsigned char*)dst; + + switch (bytes) + { + case 4: + *p = (unsigned char)f; + *(p + 1) = (unsigned char)(f >> 8); + *(p + 2) = (unsigned char)(f >> 16); + *(p + 3) = (unsigned char)(f >> 24); + return; + case 3: + *p = (unsigned char)f; + *(p + 1) = (unsigned char)(f >> 8); + *(p + 2) = (unsigned char)(f >> 16); + return; + case 2: + *p = (unsigned char)f; + *(p + 1) = (unsigned char)(f >> 8); + return; + case 1: + *p = (unsigned char)f; + return; + } +#else + switch (bytes) + { + case 4: + *((ui32*)dst) = f; + return; + case 3: + *((ui32*)dst) = f; + return; + case 2: + *((ui16 *)dst) = (ui16)f; + return; + case 1: + *((unsigned char*)dst) = (unsigned char)f; + return; + } +#endif +} + + +size_t qlz_size_decompressed(const char *source) +{ + ui32 n, r; + n = (((*source) & 2) == 2) ? 4 : 1; + r = fast_read(source + 1 + n, n); + r = r & (0xffffffff >> ((4 - n)*8)); + return r; +} + +size_t qlz_size_compressed(const char *source) +{ + ui32 n, r; + n = (((*source) & 2) == 2) ? 4 : 1; + r = fast_read(source + 1, n); + r = r & (0xffffffff >> ((4 - n)*8)); + return r; +} + +size_t qlz_size_header(const char *source) +{ + size_t n = 2*((((*source) & 2) == 2) ? 4 : 1) + 1; + return n; +} + + +static __inline void memcpy_up(unsigned char *dst, const unsigned char *src, ui32 n) +{ + // Caution if modifying memcpy_up! Overlap of dst and src must be special handled. +#ifndef X86X64 + unsigned char *end = dst + n; + while(dst < end) + { + *dst = *src; + dst++; + src++; + } +#else + ui32 f = 0; + do + { + *(ui32 *)(dst + f) = *(ui32 *)(src + f); + f += MINOFFSET + 1; + } + while (f < n); +#endif +} + +static __inline void update_hash(qlz_state_decompress *state, const unsigned char *s) +{ +#if QLZ_COMPRESSION_LEVEL == 1 + ui32 hash; + hash = hashat(s); + state->hash[hash].offset = s; + state->hash_counter[hash] = 1; +#elif QLZ_COMPRESSION_LEVEL == 2 + ui32 hash; + unsigned char c; + hash = hashat(s); + c = state->hash_counter[hash]; + state->hash[hash].offset[c & (QLZ_POINTERS - 1)] = s; + c++; + state->hash_counter[hash] = c; +#endif + (void)state; + (void)s; +} + +#if QLZ_COMPRESSION_LEVEL <= 2 +static void update_hash_upto(qlz_state_decompress *state, unsigned char **lh, const unsigned char *max) +{ + while(*lh < max) + { + (*lh)++; + update_hash(state, *lh); + } +} +#endif + +static size_t qlz_compress_core(const unsigned char *source, unsigned char *destination, size_t size, qlz_state_compress *state) +{ + const unsigned char *last_byte = source + size - 1; + const unsigned char *src = source; + unsigned char *cword_ptr = destination; + unsigned char *dst = destination + CWORD_LEN; + ui32 cword_val = 1U << 31; + const unsigned char *last_matchstart = last_byte - UNCONDITIONAL_MATCHLEN - UNCOMPRESSED_END; + ui32 fetch = 0; + unsigned int lits = 0; + + (void) lits; + + if(src <= last_matchstart) + fetch = fast_read(src, 3); + + while(src <= last_matchstart) + { + if ((cword_val & 1) == 1) + { + // store uncompressed if compression ratio is too low + if (src > source + (size >> 1) && dst - destination > src - source - ((src - source) >> 5)) + return 0; + + fast_write((cword_val >> 1) | (1U << 31), cword_ptr, CWORD_LEN); + + cword_ptr = dst; + dst += CWORD_LEN; + cword_val = 1U << 31; + fetch = fast_read(src, 3); + } +#if QLZ_COMPRESSION_LEVEL == 1 + { + const unsigned char *o; + ui32 hash, cached; + + hash = hash_func(fetch); + cached = fetch ^ state->hash[hash].cache; + state->hash[hash].cache = fetch; + + o = state->hash[hash].offset + OFFSET_BASE; + state->hash[hash].offset = CAST(src - OFFSET_BASE); + +#ifdef X86X64 + if ((cached & 0xffffff) == 0 && o != OFFSET_BASE && (src - o > MINOFFSET || (src == o + 1 && lits >= 3 && src > source + 3 && same(src - 3, 6)))) + { + if(cached != 0) + { +#else + if (cached == 0 && o != OFFSET_BASE && (src - o > MINOFFSET || (src == o + 1 && lits >= 3 && src > source + 3 && same(src - 3, 6)))) + { + if (*(o + 3) != *(src + 3)) + { +#endif + hash <<= 4; + cword_val = (cword_val >> 1) | (1U << 31); + fast_write((3 - 2) | hash, dst, 2); + src += 3; + dst += 2; + } + else + { + const unsigned char *old_src = src; + size_t matchlen; + hash <<= 4; + + cword_val = (cword_val >> 1) | (1U << 31); + src += 4; + + if(*(o + (src - old_src)) == *src) + { + src++; + if(*(o + (src - old_src)) == *src) + { + size_t q = last_byte - UNCOMPRESSED_END - (src - 5) + 1; + size_t remaining = q > 255 ? 255 : q; + src++; + while(*(o + (src - old_src)) == *src && (size_t)(src - old_src) < remaining) + src++; + } + } + + matchlen = src - old_src; + if (matchlen < 18) + { + fast_write((ui32)(matchlen - 2) | hash, dst, 2); + dst += 2; + } + else + { + fast_write((ui32)(matchlen << 16) | hash, dst, 3); + dst += 3; + } + } + fetch = fast_read(src, 3); + lits = 0; + } + else + { + lits++; + *dst = *src; + src++; + dst++; + cword_val = (cword_val >> 1); +#ifdef X86X64 + fetch = fast_read(src, 3); +#else + fetch = (fetch >> 8 & 0xffff) | (*(src + 2) << 16); +#endif + } + } +#elif QLZ_COMPRESSION_LEVEL >= 2 + { + const unsigned char *o, *offset2; + ui32 hash, matchlen, k, m, best_k = 0; + unsigned char c; + size_t remaining = (last_byte - UNCOMPRESSED_END - src + 1) > 255 ? 255 : (last_byte - UNCOMPRESSED_END - src + 1); + (void)best_k; + + + //hash = hashat(src); + fetch = fast_read(src, 3); + hash = hash_func(fetch); + + c = state->hash_counter[hash]; + + offset2 = state->hash[hash].offset[0]; + if(offset2 < src - MINOFFSET && c > 0 && ((fast_read(offset2, 3) ^ fetch) & 0xffffff) == 0) + { + matchlen = 3; + if(*(offset2 + matchlen) == *(src + matchlen)) + { + matchlen = 4; + while(*(offset2 + matchlen) == *(src + matchlen) && matchlen < remaining) + matchlen++; + } + } + else + matchlen = 0; + for(k = 1; k < QLZ_POINTERS && c > k; k++) + { + o = state->hash[hash].offset[k]; +#if QLZ_COMPRESSION_LEVEL == 3 + if(((fast_read(o, 3) ^ fetch) & 0xffffff) == 0 && o < src - MINOFFSET) +#elif QLZ_COMPRESSION_LEVEL == 2 + if(*(src + matchlen) == *(o + matchlen) && ((fast_read(o, 3) ^ fetch) & 0xffffff) == 0 && o < src - MINOFFSET) +#endif + { + m = 3; + while(*(o + m) == *(src + m) && m < remaining) + m++; +#if QLZ_COMPRESSION_LEVEL == 3 + if ((m > matchlen) || (m == matchlen && o > offset2)) +#elif QLZ_COMPRESSION_LEVEL == 2 + if (m > matchlen) +#endif + { + offset2 = o; + matchlen = m; + best_k = k; + } + } + } + o = offset2; + state->hash[hash].offset[c & (QLZ_POINTERS - 1)] = src; + c++; + state->hash_counter[hash] = c; + +#if QLZ_COMPRESSION_LEVEL == 3 + if(matchlen > 2 && src - o < 131071) + { + ui32 u; + size_t offset = src - o; + + for(u = 1; u < matchlen; u++) + { + hash = hashat(src + u); + c = state->hash_counter[hash]++; + state->hash[hash].offset[c & (QLZ_POINTERS - 1)] = src + u; + } + + cword_val = (cword_val >> 1) | (1U << 31); + src += matchlen; + + if(matchlen == 3 && offset <= 63) + { + *dst = (unsigned char)(offset << 2); + dst++; + } + else if (matchlen == 3 && offset <= 16383) + { + ui32 f = (ui32)((offset << 2) | 1); + fast_write(f, dst, 2); + dst += 2; + } + else if (matchlen <= 18 && offset <= 1023) + { + ui32 f = ((matchlen - 3) << 2) | ((ui32)offset << 6) | 2; + fast_write(f, dst, 2); + dst += 2; + } + + else if(matchlen <= 33) + { + ui32 f = ((matchlen - 2) << 2) | ((ui32)offset << 7) | 3; + fast_write(f, dst, 3); + dst += 3; + } + else + { + ui32 f = ((matchlen - 3) << 7) | ((ui32)offset << 15) | 3; + fast_write(f, dst, 4); + dst += 4; + } + } + else + { + *dst = *src; + src++; + dst++; + cword_val = (cword_val >> 1); + } +#elif QLZ_COMPRESSION_LEVEL == 2 + + if(matchlen > 2) + { + cword_val = (cword_val >> 1) | (1U << 31); + src += matchlen; + + if (matchlen < 10) + { + ui32 f = best_k | ((matchlen - 2) << 2) | (hash << 5); + fast_write(f, dst, 2); + dst += 2; + } + else + { + ui32 f = best_k | (matchlen << 16) | (hash << 5); + fast_write(f, dst, 3); + dst += 3; + } + } + else + { + *dst = *src; + src++; + dst++; + cword_val = (cword_val >> 1); + } +#endif + } +#endif + } + while (src <= last_byte) + { + if ((cword_val & 1) == 1) + { + fast_write((cword_val >> 1) | (1U << 31), cword_ptr, CWORD_LEN); + cword_ptr = dst; + dst += CWORD_LEN; + cword_val = 1U << 31; + } +#if QLZ_COMPRESSION_LEVEL < 3 + if (src <= last_byte - 3) + { +#if QLZ_COMPRESSION_LEVEL == 1 + ui32 hash, fetch; + fetch = fast_read(src, 3); + hash = hash_func(fetch); + state->hash[hash].offset = CAST(src - OFFSET_BASE); + state->hash[hash].cache = fetch; +#elif QLZ_COMPRESSION_LEVEL == 2 + ui32 hash; + unsigned char c; + hash = hashat(src); + c = state->hash_counter[hash]; + state->hash[hash].offset[c & (QLZ_POINTERS - 1)] = src; + c++; + state->hash_counter[hash] = c; +#endif + } +#endif + *dst = *src; + src++; + dst++; + cword_val = (cword_val >> 1); + } + + while((cword_val & 1) != 1) + cword_val = (cword_val >> 1); + + fast_write((cword_val >> 1) | (1U << 31), cword_ptr, CWORD_LEN); + + // min. size must be 9 bytes so that the qlz_size functions can take 9 bytes as argument + return dst - destination < 9 ? 9 : dst - destination; +} + +static size_t qlz_decompress_core(const unsigned char *source, unsigned char *destination, size_t size, qlz_state_decompress *state, const unsigned char *history) +{ + const unsigned char *src = source + qlz_size_header((const char *)source); + unsigned char *dst = destination; + const unsigned char *last_destination_byte = destination + size - 1; + ui32 cword_val = 1; + const unsigned char *last_matchstart = last_destination_byte - UNCONDITIONAL_MATCHLEN - UNCOMPRESSED_END; + unsigned char *last_hashed = destination - 1; + const unsigned char *last_source_byte = source + qlz_size_compressed((const char *)source) - 1; + static const ui32 bitlut[16] = {4, 0, 1, 0, 2, 0, 1, 0, 3, 0, 1, 0, 2, 0, 1, 0}; + + (void) last_source_byte; + (void) last_hashed; + (void) state; + (void) history; + + for(;;) + { + ui32 fetch; + + if (cword_val == 1) + { +#ifdef QLZ_MEMORY_SAFE + if(src + CWORD_LEN - 1 > last_source_byte) + return 0; +#endif + cword_val = fast_read(src, CWORD_LEN); + src += CWORD_LEN; + } + +#ifdef QLZ_MEMORY_SAFE + if(src + 4 - 1 > last_source_byte) + return 0; +#endif + + fetch = fast_read(src, 4); + + if ((cword_val & 1) == 1) + { + ui32 matchlen; + const unsigned char *offset2; + +#if QLZ_COMPRESSION_LEVEL == 1 + ui32 hash; + cword_val = cword_val >> 1; + hash = (fetch >> 4) & 0xfff; + offset2 = (const unsigned char *)(size_t)state->hash[hash].offset; + + if((fetch & 0xf) != 0) + { + matchlen = (fetch & 0xf) + 2; + src += 2; + } + else + { + matchlen = *(src + 2); + src += 3; + } + +#elif QLZ_COMPRESSION_LEVEL == 2 + ui32 hash; + unsigned char c; + cword_val = cword_val >> 1; + hash = (fetch >> 5) & 0x7ff; + c = (unsigned char)(fetch & 0x3); + offset2 = state->hash[hash].offset[c]; + + if((fetch & (28)) != 0) + { + matchlen = ((fetch >> 2) & 0x7) + 2; + src += 2; + } + else + { + matchlen = *(src + 2); + src += 3; + } + +#elif QLZ_COMPRESSION_LEVEL == 3 + ui32 offset; + cword_val = cword_val >> 1; + if ((fetch & 3) == 0) + { + offset = (fetch & 0xff) >> 2; + matchlen = 3; + src++; + } + else if ((fetch & 2) == 0) + { + offset = (fetch & 0xffff) >> 2; + matchlen = 3; + src += 2; + } + else if ((fetch & 1) == 0) + { + offset = (fetch & 0xffff) >> 6; + matchlen = ((fetch >> 2) & 15) + 3; + src += 2; + } + else if ((fetch & 127) != 3) + { + offset = (fetch >> 7) & 0x1ffff; + matchlen = ((fetch >> 2) & 0x1f) + 2; + src += 3; + } + else + { + offset = (fetch >> 15); + matchlen = ((fetch >> 7) & 255) + 3; + src += 4; + } + + offset2 = dst - offset; +#endif + +#ifdef QLZ_MEMORY_SAFE + if(offset2 < history || offset2 > dst - MINOFFSET - 1) + return 0; + + if(matchlen > (ui32)(last_destination_byte - dst - UNCOMPRESSED_END + 1)) + return 0; +#endif + + memcpy_up(dst, offset2, matchlen); + dst += matchlen; + +#if QLZ_COMPRESSION_LEVEL <= 2 + update_hash_upto(state, &last_hashed, dst - matchlen); + last_hashed = dst - 1; +#endif + } + else + { + if (dst < last_matchstart) + { + unsigned int n = bitlut[cword_val & 0xf]; +#ifdef X86X64 + *(ui32 *)dst = *(ui32 *)src; +#else + memcpy_up(dst, src, 4); +#endif + cword_val = cword_val >> n; + dst += n; + src += n; +#if QLZ_COMPRESSION_LEVEL <= 2 + update_hash_upto(state, &last_hashed, dst - 3); +#endif + } + else + { + while(dst <= last_destination_byte) + { + if (cword_val == 1) + { + src += CWORD_LEN; + cword_val = 1U << 31; + } +#ifdef QLZ_MEMORY_SAFE + if(src >= last_source_byte + 1) + return 0; +#endif + *dst = *src; + dst++; + src++; + cword_val = cword_val >> 1; + } + +#if QLZ_COMPRESSION_LEVEL <= 2 + update_hash_upto(state, &last_hashed, last_destination_byte - 3); // todo, use constant +#endif + return size; + } + + } + } +} + +size_t qlz_compress(const void *source, char *destination, size_t size, qlz_state_compress *state) +{ + size_t r; + ui32 compressed; + size_t base; + + if(size == 0 || size > 0xffffffff - 400) + return 0; + + if(size < 216) + base = 3; + else + base = 9; + +#if QLZ_STREAMING_BUFFER > 0 + if (state->stream_counter + size - 1 >= QLZ_STREAMING_BUFFER) +#endif + { + reset_table_compress(state); + r = base + qlz_compress_core((const unsigned char *)source, (unsigned char*)destination + base, size, state); +#if QLZ_STREAMING_BUFFER > 0 + reset_table_compress(state); +#endif + if(r == base) + { + memcpy(destination + base, source, size); + r = size + base; + compressed = 0; + } + else + { + compressed = 1; + } + state->stream_counter = 0; + } +#if QLZ_STREAMING_BUFFER > 0 + else + { + unsigned char *src = state->stream_buffer + state->stream_counter; + + memcpy(src, source, size); + r = base + qlz_compress_core(src, (unsigned char*)destination + base, size, state); + + if(r == base) + { + memcpy(destination + base, src, size); + r = size + base; + compressed = 0; + reset_table_compress(state); + } + else + { + compressed = 1; + } + state->stream_counter += size; + } +#endif + if(base == 3) + { + *destination = (unsigned char)(0 | compressed); + *(destination + 1) = (unsigned char)r; + *(destination + 2) = (unsigned char)size; + } + else + { + *destination = (unsigned char)(2 | compressed); + fast_write((ui32)r, destination + 1, 4); + fast_write((ui32)size, destination + 5, 4); + } + + *destination |= (QLZ_COMPRESSION_LEVEL << 2); + *destination |= (1 << 6); + *destination |= ((QLZ_STREAMING_BUFFER == 0 ? 0 : (QLZ_STREAMING_BUFFER == 100000 ? 1 : (QLZ_STREAMING_BUFFER == 1000000 ? 2 : 3))) << 4); + +// 76543210 +// 01SSLLHC + + return r; +} + +size_t qlz_decompress(const char *source, void *destination, qlz_state_decompress *state) +{ + size_t dsiz = qlz_size_decompressed(source); + +#if QLZ_STREAMING_BUFFER > 0 + if (state->stream_counter + qlz_size_decompressed(source) - 1 >= QLZ_STREAMING_BUFFER) +#endif + { + if((*source & 1) == 1) + { + reset_table_decompress(state); + dsiz = qlz_decompress_core((const unsigned char *)source, (unsigned char *)destination, dsiz, state, (const unsigned char *)destination); + } + else + { + memcpy(destination, source + qlz_size_header(source), dsiz); + } + state->stream_counter = 0; + reset_table_decompress(state); + } +#if QLZ_STREAMING_BUFFER > 0 + else + { + unsigned char *dst = state->stream_buffer + state->stream_counter; + if((*source & 1) == 1) + { + dsiz = qlz_decompress_core((const unsigned char *)source, dst, dsiz, state, (const unsigned char *)state->stream_buffer); + } + else + { + memcpy(dst, source + qlz_size_header(source), dsiz); + reset_table_decompress(state); + } + memcpy(destination, dst, dsiz); + state->stream_counter += dsiz; + } +#endif + return dsiz; +} + diff --git a/thirdparty/DBoW3/src/quicklz.h b/thirdparty/DBoW3/src/quicklz.h new file mode 100644 index 0000000..6a710f1 --- /dev/null +++ b/thirdparty/DBoW3/src/quicklz.h @@ -0,0 +1,150 @@ +#ifndef QLZ_HEADER +#define QLZ_HEADER + +// Fast data compression library +// Copyright (C) 2006-2011 Lasse Mikkel Reinhold +// lar@quicklz.com +// +// QuickLZ can be used for free under the GPL 1, 2 or 3 license (where anything +// released into public must be open source) or under a commercial license if such +// has been acquired (see http://www.quicklz.com/order.html). The commercial license +// does not cover derived or ported versions created by third parties under GPL. + +// You can edit following user settings. Data must be decompressed with the same +// setting of QLZ_COMPRESSION_LEVEL and QLZ_STREAMING_BUFFER as it was compressed +// (see manual). If QLZ_STREAMING_BUFFER > 0, scratch buffers must be initially +// zeroed out (see manual). First #ifndef makes it possible to define settings from +// the outside like the compiler command line. + +// 1.5.0 final + +#ifndef QLZ_COMPRESSION_LEVEL + + // 1 gives fastest compression speed. 3 gives fastest decompression speed and best + // compression ratio. + #define QLZ_COMPRESSION_LEVEL 1 + //#define QLZ_COMPRESSION_LEVEL 2 + //#define QLZ_COMPRESSION_LEVEL 3 + + // If > 0, zero out both states prior to first call to qlz_compress() or qlz_decompress() + // and decompress packets in the same order as they were compressed + #define QLZ_STREAMING_BUFFER 0 + //#define QLZ_STREAMING_BUFFER 100000 + //#define QLZ_STREAMING_BUFFER 1000000 + + // Guarantees that decompression of corrupted data cannot crash. Decreases decompression + // speed 10-20%. Compression speed not affected. + //#define QLZ_MEMORY_SAFE +#endif + +#define QLZ_VERSION_MAJOR 1 +#define QLZ_VERSION_MINOR 5 +#define QLZ_VERSION_REVISION 0 + +// Using size_t, memset() and memcpy() +#include + +// Verify compression level +#if QLZ_COMPRESSION_LEVEL != 1 && QLZ_COMPRESSION_LEVEL != 2 && QLZ_COMPRESSION_LEVEL != 3 +#error QLZ_COMPRESSION_LEVEL must be 1, 2 or 3 +#endif + +typedef unsigned int ui32; +typedef unsigned short int ui16; + +// Decrease QLZ_POINTERS for level 3 to increase compression speed. Do not touch any other values! +#if QLZ_COMPRESSION_LEVEL == 1 +#define QLZ_POINTERS 1 +#define QLZ_HASH_VALUES 4096 +#elif QLZ_COMPRESSION_LEVEL == 2 +#define QLZ_POINTERS 4 +#define QLZ_HASH_VALUES 2048 +#elif QLZ_COMPRESSION_LEVEL == 3 +#define QLZ_POINTERS 16 +#define QLZ_HASH_VALUES 4096 +#endif + +// Detect if pointer size is 64-bit. It's not fatal if some 64-bit target is not detected because this is only for adding an optional 64-bit optimization. +#if defined _LP64 || defined __LP64__ || defined __64BIT__ || _ADDR64 || defined _WIN64 || defined __arch64__ || __WORDSIZE == 64 || (defined __sparc && defined __sparcv9) || defined __x86_64 || defined __amd64 || defined __x86_64__ || defined _M_X64 || defined _M_IA64 || defined __ia64 || defined __IA64__ + #define QLZ_PTR_64 +#endif + +// hash entry +typedef struct +{ +#if QLZ_COMPRESSION_LEVEL == 1 + ui32 cache; +#if defined QLZ_PTR_64 && QLZ_STREAMING_BUFFER == 0 + unsigned int offset; +#else + const unsigned char *offset; +#endif +#else + const unsigned char *offset[QLZ_POINTERS]; +#endif + +} qlz_hash_compress; + +typedef struct +{ +#if QLZ_COMPRESSION_LEVEL == 1 + const unsigned char *offset; +#else + const unsigned char *offset[QLZ_POINTERS]; +#endif +} qlz_hash_decompress; + + +// states +typedef struct +{ + #if QLZ_STREAMING_BUFFER > 0 + unsigned char stream_buffer[QLZ_STREAMING_BUFFER]; + #endif + size_t stream_counter; + qlz_hash_compress hash[QLZ_HASH_VALUES]; + unsigned char hash_counter[QLZ_HASH_VALUES]; +} qlz_state_compress; + + +#if QLZ_COMPRESSION_LEVEL == 1 || QLZ_COMPRESSION_LEVEL == 2 + typedef struct + { +#if QLZ_STREAMING_BUFFER > 0 + unsigned char stream_buffer[QLZ_STREAMING_BUFFER]; +#endif + qlz_hash_decompress hash[QLZ_HASH_VALUES]; + unsigned char hash_counter[QLZ_HASH_VALUES]; + size_t stream_counter; + } qlz_state_decompress; +#elif QLZ_COMPRESSION_LEVEL == 3 + typedef struct + { +#if QLZ_STREAMING_BUFFER > 0 + unsigned char stream_buffer[QLZ_STREAMING_BUFFER]; +#endif +#if QLZ_COMPRESSION_LEVEL <= 2 + qlz_hash_decompress hash[QLZ_HASH_VALUES]; +#endif + size_t stream_counter; + } qlz_state_decompress; +#endif + + +#if defined (__cplusplus) +extern "C" { +#endif + +// Public functions of QuickLZ +size_t qlz_size_decompressed(const char *source); +size_t qlz_size_compressed(const char *source); +size_t qlz_compress(const void *source, char *destination, size_t size, qlz_state_compress *state); +size_t qlz_decompress(const char *source, void *destination, qlz_state_decompress *state); +int qlz_get_setting(int setting); + +#if defined (__cplusplus) +} +#endif + +#endif + diff --git a/thirdparty/DBoW3/src/timers.h b/thirdparty/DBoW3/src/timers.h new file mode 100644 index 0000000..98fd0fc --- /dev/null +++ b/thirdparty/DBoW3/src/timers.h @@ -0,0 +1,159 @@ +#ifndef DBoW3_TIMERS_H +#define DBoW3_TIMERS_H + +#include +#include +#include +#include +namespace DBoW3 { + +// timer +struct ScopeTimer { + std::chrono::high_resolution_clock::time_point begin, end; + + std::string name; + bool use; + enum SCALE { NSEC, MSEC, SEC }; + SCALE sc; + ScopeTimer(std::string name_, bool use_ = true, SCALE _sc = MSEC) { + name = name_; + use = use_; + sc = _sc; + begin = std::chrono::high_resolution_clock::now(); + } + ~ScopeTimer() { + if (use) { + end = std::chrono::high_resolution_clock::now(); + double fact = 1; + std::string str; + switch (sc) { + case NSEC: + fact = 1; + str = "ns"; + break; + case MSEC: + fact = 1e6; + str = "ms"; + break; + case SEC: + fact = 1e9; + str = "s"; + break; + }; + + std::cout << "Time (" << name << ")= " + << double(std::chrono::duration_cast( + end - begin) + .count()) / + fact + << str << std::endl; + ; + } + } +}; + +struct ScopedTimerEvents { + enum SCALE { NSEC, MSEC, SEC }; + SCALE sc; + std::vector vtimes; + std::vector names; + std::string _name; + + ScopedTimerEvents(std::string name = "", bool start = true, + SCALE _sc = MSEC) { + if (start) add("start"); + sc = _sc; + _name = name; + } + + void add(std::string name) { + vtimes.push_back(std::chrono::high_resolution_clock::now()); + names.push_back(name); + } + void addspaces(std::vector &str) { + // get max size + size_t m = -1; + for (auto &s : str) m = std::max(s.size(), m); + for (auto &s : str) { + while (s.size() < m) s.push_back(' '); + } + } + + ~ScopedTimerEvents() { + double fact = 1; + std::string str; + switch (sc) { + case NSEC: + fact = 1; + str = "ns"; + break; + case MSEC: + fact = 1e6; + str = "ms"; + break; + case SEC: + fact = 1e9; + str = "s"; + break; + }; + + add("total"); + addspaces(names); + for (size_t i = 1; i < vtimes.size(); i++) { + std::cout << "Time(" << _name << ")-" << names[i] << " " + << double(std::chrono::duration_cast( + vtimes[i] - vtimes[i - 1]) + .count()) / + fact + << str << " " + << double(std::chrono::duration_cast( + vtimes[i] - vtimes[0]) + .count()) / + fact + << str << std::endl; + } + } +}; + +struct Timer { + enum SCALE { NSEC, MSEC, SEC }; + + std::chrono::high_resolution_clock::time_point _s; + double sum = 0, n = 0; + std::string _name; + Timer() {} + + Timer(std::string name) : _name(name) {} + void setName(std::string name) { _name = name; } + void start() { _s = std::chrono::high_resolution_clock::now(); } + void end() { + auto e = std::chrono::high_resolution_clock::now(); + sum += double( + std::chrono::duration_cast(e - _s).count()); + n++; + } + + void print(SCALE sc = MSEC) { + double fact = 1; + std::string str; + switch (sc) { + case NSEC: + fact = 1; + str = "ns"; + break; + case MSEC: + fact = 1e6; + str = "ms"; + break; + case SEC: + fact = 1e9; + str = "s"; + break; + }; + std::cout << "Time(" << _name << ")= " << (sum / n) / fact << str + << std::endl; + } +}; +} + +#endif diff --git a/thirdparty/Pangolin b/thirdparty/Pangolin new file mode 160000 index 0000000..ad8b5f8 --- /dev/null +++ b/thirdparty/Pangolin @@ -0,0 +1 @@ +Subproject commit ad8b5f83222291c51b4800d5a5873b0e90a0cf81 diff --git a/thirdparty/apriltag/CMakeLists.txt b/thirdparty/apriltag/CMakeLists.txt new file mode 100644 index 0000000..0c1a28e --- /dev/null +++ b/thirdparty/apriltag/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.2) + + +SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fPIC") +SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fPIC") + +#file(GLOB APRILTAG_SRCS "${CMAKE_CURRENT_SOURCE_DIR}/apriltag-2016-12-01/*.c" "${CMAKE_CURRENT_SOURCE_DIR}/apriltag-2016-12-01/common/*.c") +#include_directories(apriltag-2016-12-01) + +include_directories(${OpenCV_INCLUDE_DIR}) + +file(GLOB APRILTAG_SRCS "ethz_apriltag2/src/*.cc") +include_directories(ethz_apriltag2/include) + + +include_directories(../../include) +include_directories(../basalt-headers/include) +include_directories(../basalt-headers/thirdparty/Sophus) + +add_library(apriltag STATIC ${APRILTAG_SRCS} src/apriltag.cpp) + +target_include_directories(apriltag PUBLIC include) +target_link_libraries(apriltag PUBLIC ${OpenCV_LIBS} pangolin) + + diff --git a/thirdparty/apriltag/ethz_apriltag2/CMakeLists.txt b/thirdparty/apriltag/ethz_apriltag2/CMakeLists.txt new file mode 100644 index 0000000..58f985c --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/CMakeLists.txt @@ -0,0 +1,35 @@ +cmake_minimum_required(VERSION 2.8) + +project(ethz_apriltag2) + +find_package(catkin REQUIRED COMPONENTS cmake_modules) +include_directories(${catkin_INCLUDE_DIRS}) + +find_package(Eigen REQUIRED) + +catkin_package( + DEPENDS eigen opencv + INCLUDE_DIRS include ${Eigen_INCLUDE_DIRS} + LIBRARIES ${PROJECT_NAME} +) + +set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} ${PROJECT_SOURCE_DIR}/cmake/) + +find_package(Eigen REQUIRED) +find_package(OpenCV REQUIRED) + +add_definitions(-fPIC -O3) +include_directories(include ${Eigen_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS}) + +#library +file(GLOB SOURCE_FILES "src/*.cc") +add_library(${PROJECT_NAME} ${SOURCE_FILES}) +target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS} ${catkin_LIBRARIES}) + +#demo +if(NOT APPLE) + add_executable(apriltags_demo src/example/apriltags_demo.cpp src/example/Serial.cpp) + target_link_libraries(apriltags_demo ${PROJECT_NAME} v4l2) +endif() + + diff --git a/thirdparty/apriltag/ethz_apriltag2/LICENSE b/thirdparty/apriltag/ethz_apriltag2/LICENSE new file mode 100644 index 0000000..ff17f84 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/LICENSE @@ -0,0 +1,34 @@ + +Copyright (c) 2014, Paul Furgale, Jérôme Maye and Jörn Rehder, Autonomous Systems Lab, + ETH Zurich, Switzerland +Copyright (c) 2014, Thomas Schneider, Skybotix AG, Switzerland +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, +are permitted provided that the following conditions are met: + + Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + All advertising materials mentioning features or use of this software must + display the following acknowledgement: This product includes software developed + by the Autonomous Systems Lab and Skybotix AG. + + Neither the name of the Autonomous Systems Lab and Skybotix AG 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 AUTONOMOUS SYSTEMS LAB AND SKYBOTIX AG ''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 AUTONOMOUS SYSTEMS LAB OR SKYBOTIX AG 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/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Edge.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Edge.h new file mode 100644 index 0000000..34fff13 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Edge.h @@ -0,0 +1,59 @@ +#ifndef EDGE_H +#define EDGE_H + +#include + +#include "apriltags/FloatImage.h" + +namespace AprilTags { + +class FloatImage; +class UnionFindSimple; + +using std::min; +using std::max; + +//! Represents an edge between adjacent pixels in the image. +/*! The edge is encoded by the indices of the two pixels. Edge cost + * is proportional to the difference in local orientations. + */ +class Edge { +public: + static float const minMag; //!< minimum intensity gradient for an edge to be recognized + static float const maxEdgeCost; //!< 30 degrees = maximum acceptable difference in local orientations + static int const WEIGHT_SCALE; // was 10000 + static float const thetaThresh; //!< theta threshold for merging edges + static float const magThresh; //!< magnitude threshold for merging edges + + int pixelIdxA; + int pixelIdxB; + int cost; + + //! Constructor + Edge() : pixelIdxA(), pixelIdxB(), cost() {} + + //! Compare edges based on cost + inline bool operator< (const Edge &other) const { return (cost < other.cost); } + + //! Cost of an edge between two adjacent pixels; -1 if no edge here + /*! An edge exists between adjacent pixels if the magnitude of the + intensity gradient at both pixels is above threshold. The edge + cost is proportional to the difference in the local orientation at + the two pixels. Lower cost is better. A cost of -1 means there + is no edge here (intensity gradien fell below threshold). + */ + static int edgeCost(float theta0, float theta1, float mag1); + + //! Calculates and inserts up to four edges into 'edges', a vector of Edges. + static void calcEdges(float theta0, int x, int y, + const FloatImage& theta, const FloatImage& mag, + std::vector &edges, size_t &nEdges); + + //! Process edges in order of increasing cost, merging clusters if we can do so without exceeding the thetaThresh. + static void mergeEdges(std::vector &edges, UnionFindSimple &uf, float tmin[], float tmax[], float mmin[], float mmax[]); + +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/FloatImage.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/FloatImage.h new file mode 100644 index 0000000..e630ff5 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/FloatImage.h @@ -0,0 +1,61 @@ +#ifndef FLOATIMAGE_H +#define FLOATIMAGE_H + +#include +#include + +namespace DualCoding { + typedef unsigned char uchar; + template class Sketch; +} + +namespace AprilTags { + +//! Represent an image as a vector of floats in [0,1] +class FloatImage { +private: + int width; + int height; + std::vector pixels; + +public: + + //! Default constructor + FloatImage(); + + //! Construct an empty image + FloatImage(int widthArg, int heightArg); + + //! Constructor that copies pixels from an array + FloatImage(int widthArg, int heightArg, const std::vector& pArg); + + FloatImage& operator=(const FloatImage& other); + + float get(int x, int y) const { return pixels[y*width + x]; } + void set(int x, int y, float v) { pixels[y*width + x] = v; } + + int getWidth() const { return width; } + int getHeight() const { return height; } + int getNumFloatImagePixels() const { return width*height; } + const std::vector& getFloatImagePixels() const { return pixels; } + + //! TODO: Fix decimateAvg function. DO NOT USE! + void decimateAvg(); + + //! Rescale all values so that they are between [0,1] + void normalize(); + + void filterFactoredCentered(const std::vector& fhoriz, const std::vector& fvert); + + template + void copyToSketch(DualCoding::Sketch& sketch) { + for (int i = 0; i < getNumFloatImagePixels(); i++) + sketch[i] = (T)(255.0f * getFloatImagePixels()[i]); + } + + void printMinMax() const; +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/GLine2D.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/GLine2D.h new file mode 100644 index 0000000..46d8390 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/GLine2D.h @@ -0,0 +1,74 @@ +#ifndef GLINE2D_H +#define GLINE2D_H + +#include +#include +#include + +#include "apriltags/MathUtil.h" +#include "apriltags/XYWeight.h" + +namespace AprilTags { + +//! A 2D line +class GLine2D { +public: + + //! Create a new line. + GLine2D(); + + //! Create a new line. + /* @param slope the slope + * @param b the y intercept + */ + GLine2D(float slope, float b); + + //! Create a new line. + /* @param dx A change in X corresponding to dy + * @param dy A change in Y corresponding to dx + * @param p A point that the line passes through + */ + GLine2D(float dX, float dY, const std::pair& pt); + + //! Create a new line through two points. + /* @param p1 the first point + * @param p2 the second point + */ + GLine2D(const std::pair& p1, const std::pair& p2); + + //! Get the coordinate of a point (on this line), with zero corresponding to the point + //! on the that is perpendicular toa line passing through the origin and the line. + /* This allows easy computation if one point is between two other points on the line: + * compute the line coordinate of all three points and test if a<=b<=c. This is + * implemented by computing the dot product of the vector 'p' with the + * line's direct unit vector. + */ + float getLineCoordinate(const std::pair& p); + + //! The inverse of getLineCoordinate. + std::pair getPointOfCoordinate(float coord); + + //!Compute the point where two lines intersect, or (-1,0) if the lines are parallel. + std::pair intersectionWith(const GLine2D& line) const; + + static GLine2D lsqFitXYW(const std::vector& xyweights); + + inline float getDx() const { return dx; } + inline float getDy() const { return dy; } + inline float getFirst() const { return p.first; } + inline float getSecond() const { return p.second; } + +protected: + void normalizeSlope(); + void normalizeP(); + +private: + float dx, dy; + std::pair p; //!< A point the line passes through; when normalized, it is the point closest to the origin (hence perpendicular to the line) + bool didNormalizeSlope; + bool didNormalizeP; +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/GLineSegment2D.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/GLineSegment2D.h new file mode 100644 index 0000000..8b55a10 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/GLineSegment2D.h @@ -0,0 +1,31 @@ +#ifndef GLINESEGMENT2D_H +#define GLINESEGMENT2D_H + +#include +#include +#include +#include + +#include "apriltags/GLine2D.h" +#include "apriltags/XYWeight.h" + +namespace AprilTags { + +//! A 2D line with endpoints. +class GLineSegment2D { +public: + GLineSegment2D(const std::pair &p0Arg, const std::pair &p1Arg); + static GLineSegment2D lsqFitXYW(const std::vector& xyweight); + std::pair getP0() const { return p0; } + std::pair getP1() const { return p1; } + +private: + GLine2D line; + std::pair p0; + std::pair p1; + int weight; +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Gaussian.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Gaussian.h new file mode 100644 index 0000000..8d8d46f --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Gaussian.h @@ -0,0 +1,37 @@ +#ifndef GAUSSIAN_H +#define GAUSSIAN_H + +#include +#include + +namespace AprilTags { + +class Gaussian { + +public: + static bool warned; + + //! Returns a Gaussian filter of size n. + /*! @param sigma standard deviation of the Gaussian + * @param n length of the Gaussian (must be odd) + */ + static std::vector makeGaussianFilter(float sigma, int n); + + //! Convolve the input 'a' (which begins at offset aoff and is alen elements in length) with the filter 'f'. + /*! The result is deposited in 'r' at offset 'roff'. f.size() should be odd. + * The output is shifted by -f.size()/2, so that there is no net time delay. + * @param a input vector of pixels + * @param aoff + * @param alen + * @param f + * @param r the resultant array of pixels + * @param roff + */ + static void convolveSymmetricCentered(const std::vector& a, unsigned int aoff, unsigned int alen, + const std::vector& f, std::vector& r, unsigned int roff); + +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/GrayModel.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/GrayModel.h new file mode 100644 index 0000000..baade0b --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/GrayModel.h @@ -0,0 +1,46 @@ +//-*-c++-*- + +#ifndef GRAYMODEL_H +#define GRAYMODEL_H + +#include +#include + +namespace AprilTags { + +//! Fits a grayscale model over an area of pixels. +/*! The model is of the form: c1*x + c2*y + c3*x*y + c4 = value + * + * We use this model to compute spatially-varying thresholds for + * reading bits. + */ +class GrayModel { +public: + GrayModel(); + + void addObservation(float x, float y, float gray); + + inline int getNumObservations() { return nobs; } + + float interpolate(float x, float y); + +private: + void compute(); + +// We're solving Av = b. +// +// For each observation, we add a row to A of the form [x y xy 1] +// and to b of the form gray*[x y xy 1]. v is the vector [c1 c2 c3 c4]. +// +// The least-squares solution to the system is v = inv(A'A)A'b + + Eigen::Matrix4d A; + Eigen::Vector4d v; + Eigen::Vector4d b; + int nobs; + bool dirty; //!< True if we've added an observation and need to recompute v +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Gridder.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Gridder.h new file mode 100644 index 0000000..3798d0e --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Gridder.h @@ -0,0 +1,180 @@ +#ifndef GRIDDER_H +#define GRIDDER_H + +#include +#include +#include + +#include "apriltags/Segment.h" + +namespace AprilTags { + +//! A lookup table in 2D for implementing nearest neighbor. +template +class Gridder { + private: + Gridder(const Gridder&); //!< don't call + Gridder& operator=(const Gridder&); //!< don't call + + struct Cell { + T* object; + Cell *next; + + Cell() : object(NULL), next(NULL) {} + + Cell(const Cell& c) : object(c.object), next(c.next) {} + + // Destructor + ~Cell() { + delete next; + } + + Cell& operator=(const Cell &other) { + if (this == &other) + return *this; + + object = other.object; + next = other.next; + return *this; + } + }; + + //! Initializes Gridder constructor + void gridderInit(float x0Arg, float y0Arg, float x1Arg, float y1Arg, float ppCell) { + width = (int) ((x1Arg - x0Arg)/ppCell + 1); + height = (int) ((y1Arg - y0Arg)/ppCell + 1); + + x1 = x0Arg + ppCell*width; + y1 = y0Arg + ppCell*height; + cells = std::vector< std::vector >(height, std::vector(width,(Cell*)NULL)); + } + + float x0,y0,x1,y1; + int width, height; + float pixelsPerCell; //pixels per cell + std::vector< std::vector > cells; + +public: + Gridder(float x0Arg, float y0Arg, float x1Arg, float y1Arg, float ppCell) + : x0(x0Arg), y0(y0Arg), x1(), y1(), width(), height(), pixelsPerCell(ppCell), + cells() { gridderInit(x0Arg, y0Arg, x1Arg, y1Arg, ppCell); } + + // Destructor + ~Gridder() { + for (unsigned int i = 0; i < cells.size(); i++) { + for (unsigned int j = 0; j < cells[i].size(); j++) + delete cells[i][j]; + } + } + + void add(float x, float y, T* object) { + int ix = (int) ((x - x0)/pixelsPerCell); + int iy = (int) ((y - y0)/pixelsPerCell); + + if (ix>=0 && iy>=0 && ixobject = object; + c->next = cells[iy][ix]; + cells[iy][ix] = c; + // cout << "Gridder placed seg " << o->getId() << " at (" << ix << "," << iy << ")" << endl; + } + } + + // iterator begin(); + // iterator end(); + + //! Iterator for Segment class. + class Iterator { + public: + Iterator(Gridder* grid, float x, float y, float range) + : outer(grid), ix0(), ix1(), iy0(), iy1(), ix(), iy(), c(NULL) { iteratorInit(x,y,range); } + + Iterator(const Iterator& it) + : outer(it.outer), ix0(it.ix0), ix1(it.ix1), iy0(it.iy0), iy1(it.iy1), ix(it.ix), iy(it.iy), c(it.c) {} + + Iterator& operator=(const Iterator& it) { + outer = it.outer; + ix0 = it.ix0; + ix1 = it.ix1; + iy0 = it.iy0; + iy1 = it.iy1; + ix = it.ix; + iy = it.iy; + c = it.c; + } + + bool hasNext() { + if (c == NULL) + findNext(); + return (c != NULL); + } + + T& next() { + T* thisObj = c->object; + findNext(); + return *thisObj; // return Segment + } + + private: + void findNext() { + if (c != NULL) + c = c->next; + if (c != NULL) + return; + + ix++; + while (true) { + if (ix > ix1) { + iy++; + ix = ix0; + } + if (iy > iy1) + break; + + c = outer->cells[iy][ix]; + + if (c != NULL) + break; + ix++; + } + } + + //! Initializes Iterator constructor + void iteratorInit(float x, float y, float range) { + ix0 = (int) ((x - range - outer->x0)/outer->pixelsPerCell); + iy0 = (int) ((y - range - outer->y0)/outer->pixelsPerCell); + + ix1 = (int) ((x + range - outer->x0)/outer->pixelsPerCell); + iy1 = (int) ((y + range - outer->y0)/outer->pixelsPerCell); + + ix0 = std::max(0, ix0); + ix0 = std::min(outer->width-1, ix0); + + ix1 = std::max(0, ix1); + ix1 = std::min(outer->width-1, ix1); + + iy0 = std::max(0, iy0); + iy0 = std::min(outer->height-1, iy0); + + iy1 = std::max(0, iy1); + iy1 = std::min(outer->height-1, iy1); + + ix = ix0; + iy = iy0; + + c = outer->cells[iy][ix]; + } + + Gridder* outer; + int ix0, ix1, iy0, iy1; + int ix, iy; + Cell *c; + }; + + typedef Iterator iterator; + iterator find(float x, float y, float range) { return Iterator(this,x,y,range); } +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Homography33.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Homography33.h new file mode 100644 index 0000000..055f74d --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Homography33.h @@ -0,0 +1,77 @@ +//-*-c++-*- + +#ifndef HOMOGRAPHY33_H +#define HOMOGRAPHY33_H + +#include +#include + +#include + +// NOTE: In Basalt we use homography, since for fisheye-distorted +// images, interpolation is not good enough, resulting in a lot less +// valid detections. At the same time we don't case about speed too +// much. + +// interpolate points instead of using homography +//#define INTERPOLATE +// use stable version of homography recover (opencv, includes refinement step) +#define STABLE_H + +//! Compute 3x3 homography using Direct Linear Transform +/* + * + * DEPRECATED - DEPRECATED - DEPRECATED - DEPRECATED + * + * use TagDetection::getRelativeTransform() instead + * + * + * y = Hx (y = image coordinates in homogeneous coordinates, H = 3x3 + * homography matrix, x = homogeneous 2D world coordinates) + * + * For each point correspondence, constrain y x Hx = 0 (where x is + * cross product). This means that they have the same direction, and + * ignores scale factor. + * + * We rewrite this as Ah = 0, where h is the 9x1 column vector of the + * elements of H. Each point correspondence gives us 3 equations of + * rank 2. The solution h is the minimum right eigenvector of A, + * which we can obtain via SVD, USV' = A. h is the right-most column + * of V'. + * + * We will actually maintain A'A internally, which is 9x9 regardless + * of how many correspondences we're given, and has the same + * eigenvectors as A. + */ +class Homography33 { +public: + //! Constructor + Homography33(const std::pair &opticalCenter); + +#ifdef STABLE_H + void setCorrespondences(const std::vector< std::pair > &srcPts, + const std::vector< std::pair > &dstPts); +#else + void addCorrespondence(float worldx, float worldy, float imagex, float imagey); +#endif + + //! Note that the returned H matrix does not reflect cxy. + Eigen::Matrix3d& getH(); + + const std::pair getCXY() const { return cxy; } + + void compute(); + + std::pair project(float worldx, float worldy); + +private: + std::pair cxy; + Eigen::Matrix fA; + Eigen::Matrix3d H; + bool valid; +#ifdef STABLE_H + std::vector< std::pair > srcPts, dstPts; +#endif +}; + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/MathUtil.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/MathUtil.h new file mode 100644 index 0000000..4779dad --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/MathUtil.h @@ -0,0 +1,69 @@ +//-*-c++-*- + +#ifndef MATHUTIL_H +#define MATHUTIL_H + +#include +#include +#include +#include +#include + +namespace AprilTags { + +std::ostream& operator<<(std::ostream &os, const std::pair &pt); + +//! Miscellaneous math utilities and fast exp functions. +class MathUtil { +public: + + //! Returns the square of a value. + static inline float square(float x) { return x*x; } + + static inline float distance2D(const std::pair &p0, const std::pair &p1) { + float dx = p0.first - p1.first; + float dy = p0.second - p1.second; + return std::sqrt(dx*dx + dy*dy); + } + + //! Returns a result in [-Pi, Pi] + static inline float mod2pi(float vin) { + const float twopi = 2 * (float)M_PI; + const float twopi_inv = 1.f / (2.f * (float)M_PI); + float absv = std::abs(vin); + float q = absv*twopi_inv + 0.5f; + int qi = (int) q; + float r = absv - qi*twopi; + return (vin<0) ? -r : r; + } + + //! Returns a value of v wrapped such that ref and v differ by no more than +/- Pi + static inline float mod2pi(float ref, float v) { return ref + mod2pi(v-ref); } + +// lousy approximation of arctan function, but good enough for our purposes (about 4 degrees) + static inline double fast_atan2(double y, double x) { + double coeff_1 = M_PI/4; + double coeff_2 = 3*coeff_1; + double abs_y = fabs(y)+1e-10; // kludge to prevent 0/0 condition + + double angle; + + if (x >= 0) { + double r = (x - abs_y) / (x + abs_y); + angle = coeff_1 - coeff_1 * r; + } else { + double r = (x + abs_y) / (abs_y - x); + angle = coeff_2 - coeff_1 * r; + } + + if (y < 0) + return -angle; // negate if in quad III or IV + else + return angle; + } + +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Quad.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Quad.h new file mode 100644 index 0000000..ca5c10a --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Quad.h @@ -0,0 +1,72 @@ +#ifndef QUAD_H +#define QUAD_H + +#include +#include + +#include + +#include "apriltags/Homography33.h" + +namespace AprilTags { + +class FloatImage; +class Segment; + +using std::min; +using std::max; + +//! Represents four segments that form a loop, and might be a tag. +class Quad { +public: + static const int minimumEdgeLength = 6; //!< Minimum size of a tag (in pixels) as measured along edges and diagonals + static float const maxQuadAspectRatio; //!< Early pruning of quads with insane ratios. + + //! Constructor + /*! (x,y) are the optical center of the camera, which is + * needed to correctly compute the homography. */ + Quad(const std::vector< std::pair >& p, const std::pair& opticalCenter); + + //! Interpolate given that the lower left corner of the lower left cell is at (-1,-1) and the upper right corner of the upper right cell is at (1,1). + std::pair interpolate(float x, float y); + + //! Same as interpolate, except that the coordinates are interpreted between 0 and 1, instead of -1 and 1. + std::pair interpolate01(float x, float y); + + //! Points for the quad (in pixel coordinates), in counter clockwise order. These points are the intersections of segments. + std::vector< std::pair > quadPoints; + + //! Segments composing this quad + std::vector segments; + + //! Total length (in pixels) of the actual perimeter observed for the quad. + /*! This is in contrast to the geometric perimeter, some of which + * may not have been directly observed but rather inferred by + * intersecting segments. Quads with more observed perimeter are + * preferred over others. */ + float observedPerimeter; + + //! Given that the whole quad spans from (0,0) to (1,1) in "quad space", compute the pixel coordinates for a given point within that quad. + /*! Note that for most of the Quad's existence, we will not know the correct orientation of the tag. */ + Homography33 homography; + + //! Searches through a vector of Segments to form Quads. + /* @param quads any discovered quads will be added to this list + * @param path the segments currently part of the search + * @param parent the first segment in the quad + * @param depth how deep in the search are we? + */ + static void search(const FloatImage& fImage, std::vector& path, + Segment& parent, int depth, std::vector& quads, + const std::pair& opticalCenter); + +#ifdef INTERPOLATE + private: + Eigen::Vector2f p0, p3, p01, p32; +#endif + +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Segment.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Segment.h new file mode 100644 index 0000000..ac76560 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Segment.h @@ -0,0 +1,56 @@ +#ifndef SEGMENT_H +#define SEGMENT_H + +#include +#include + +namespace AprilTags { + +//! Represents a line fit to a set of pixels whose gradients are similiar. +class Segment { +public: + Segment(); + + static int const minimumSegmentSize = 4; //!< Minimum number of pixels in a segment before we'll fit a line to it. + static float const minimumLineLength; //!< In pixels. Calculated based on minimum plausible decoding size for Tag9 family. + + float getX0() const { return x0; } + void setX0(float newValue) { x0 = newValue; } + + float getY0() const { return y0; } + void setY0(float newValue) { y0 = newValue; } + + float getX1() const { return x1; } + void setX1(float newValue) { x1 = newValue; } + + float getY1() const { return y1; } + void setY1(float newValue) { y1 = newValue; } + + float getTheta() const { return theta; } + void setTheta(float newValue) { theta = newValue; } + + float getLength() const { return length; } + void setLength(float newValue) { length = newValue; } + + //! Returns the length of the Segment. + float segmentLength(); + + //! Print endpoint coordinates of this segment. + void printSegment(); + + //! ID of Segment. + int getId() const { return segmentId; } + + std::vector children; + +private: + float x0, y0, x1, y1; + float theta; // gradient direction (points towards white) + float length; // length of line segment in pixels + int segmentId; + static int idCounter; +}; + +} // namsepace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag16h5.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag16h5.h new file mode 100644 index 0000000..ea7f947 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag16h5.h @@ -0,0 +1,41 @@ +/** Tag family with 30 distinct codes. + bits: 16, minimum hamming: 5, minimum complexity: 5 + + Max bits corrected False positive rate + 0 0.045776 % + 1 0.778198 % + 2 6.271362 % + + Generation time: 0.309000 s + + Hamming distance between pairs of codes (accounting for rotation): + + 0 0 + 1 0 + 2 0 + 3 0 + 4 0 + 5 120 + 6 172 + 7 91 + 8 33 + 9 13 + 10 6 + 11 0 + 12 0 + 13 0 + 14 0 + 15 0 + 16 0 +**/ + +#pragma once + +namespace AprilTags { + +const unsigned long long t16h5[] = + { 0x231bLL, 0x2ea5LL, 0x346aLL, 0x45b9LL, 0x79a6LL, 0x7f6bLL, 0xb358LL, 0xe745LL, 0xfe59LL, 0x156dLL, 0x380bLL, 0xf0abLL, 0x0d84LL, 0x4736LL, 0x8c72LL, 0xaf10LL, 0x093cLL, 0x93b4LL, 0xa503LL, 0x468fLL, 0xe137LL, 0x5795LL, 0xdf42LL, 0x1c1dLL, 0xe9dcLL, 0x73adLL, 0xad5fLL, 0xd530LL, 0x07caLL, 0xaf2eLL }; + +static const TagCodes tagCodes16h5 = TagCodes(16, 5, t16h5, sizeof(t16h5)/sizeof(t16h5[0])); + +} diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag16h5_other.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag16h5_other.h new file mode 100644 index 0000000..7657c0c --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag16h5_other.h @@ -0,0 +1,17 @@ +// These codes were generated by TagFamilyGenerator.java from Ed Olson + +// tag16h5Codes : 16 bits, minimum Hamming distance 5, minimum complexity 5 + +#pragma once + +namespace AprilTags { + +const unsigned long long t16h5_other[] = + { 0x231bLL, 0x2ea5LL, 0x346aLL, 0x45b9LL, 0x6857LL, 0x7f6bLL, 0xad93LL, 0xb358LL, + 0xb91dLL, 0xe745LL, 0x156dLL, 0xd3d2LL, 0xdf5cLL, 0x4736LL, 0x8c72LL, 0x5a02LL, + 0xd32bLL, 0x1867LL, 0x468fLL, 0xdc91LL, 0x4940LL, 0xa9edLL, 0x2bd5LL, 0x599aLL, + 0x9009LL, 0x61f6LL, 0x3850LL, 0x8157LL, 0xbfcaLL, 0x987cLL}; + +static const TagCodes tagCodes16h5_other = TagCodes(16, 5, t16h5_other, sizeof(t16h5_other)/sizeof(t16h5_other[0])); + +} diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag25h7.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag25h7.h new file mode 100644 index 0000000..d476133 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag25h7.h @@ -0,0 +1,51 @@ +/** Tag family with 242 distinct codes. + bits: 25, minimum hamming: 7, minimum complexity: 8 + + Max bits corrected False positive rate + 0 0.000721 % + 1 0.018752 % + 2 0.235116 % + 3 1.893914 % + + Generation time: 72.585000 s + + Hamming distance between pairs of codes (accounting for rotation): + + 0 0 + 1 0 + 2 0 + 3 0 + 4 0 + 5 0 + 6 0 + 7 2076 + 8 4161 + 9 5299 + 10 6342 + 11 5526 + 12 3503 + 13 1622 + 14 499 + 15 114 + 16 16 + 17 3 + 18 0 + 19 0 + 20 0 + 21 0 + 22 0 + 23 0 + 24 0 + 25 0 +**/ + +#pragma once + +namespace AprilTags { + +const unsigned long long t25h7[] = + { 0x4b770dLL, 0x11693e6LL, 0x1a599abLL, 0xc3a535LL, 0x152aafaLL, 0xaccd98LL, 0x1cad922LL, 0x2c2fadLL, 0xbb3572LL, 0x14a3b37LL, 0x186524bLL, 0xc99d4cLL, 0x23bfeaLL, 0x141cb74LL, 0x1d0d139LL, 0x1670aebLL, 0x851675LL, 0x150334eLL, 0x6e3ed8LL, 0xfd449dLL, 0xaa55ecLL, 0x1c86176LL, 0x15e9b28LL, 0x7ca6b2LL, 0x147c38bLL, 0x1d6c950LL, 0x8b0e8cLL, 0x11a1451LL, 0x1562b65LL, 0x13f53c8LL, 0xd58d7aLL, 0x829ec9LL, 0xfaccf1LL, 0x136e405LL, 0x7a2f06LL, 0x10934cbLL, 0x16a8b56LL, 0x1a6a26aLL, 0xf85545LL, 0x195c2e4LL, 0x24c8a9LL, 0x12bfc96LL, 0x16813aaLL, 0x1a42abeLL, 0x1573424LL, 0x1044573LL, 0xb156c2LL, 0x5e6811LL, 0x1659bfeLL, 0x1d55a63LL, 0x5bf065LL, 0xe28667LL, 0x1e9ba54LL, 0x17d7c5aLL, 0x1f5aa82LL, 0x1a2bbd1LL, 0x1ae9f9LL, 0x1259e51LL, 0x134062bLL, 0xe1177aLL, 0xed07a8LL, 0x162be24LL, 0x59128bLL, 0x1663e8fLL, 0x1a83cbLL, 0x45bb59LL, 0x189065aLL, 0x4bb370LL, 0x16fb711LL, 0x122c077LL, 0xeca17aLL, 0xdbc1f4LL, 0x88d343LL, 0x58ac5dLL, 0xba02e8LL, 0x1a1d9dLL, 0x1c72eecLL, 0x924bc5LL, 0xdccab3LL, 0x886d15LL, 0x178c965LL, 0x5bc69aLL, 0x1716261LL, 0x174e2ccLL, 0x1ed10f4LL, 0x156aa8LL, 0x3e2a8aLL, 0x2752edLL, 0x153c651LL, 0x1741670LL, 0x765b05LL, 0x119c0bbLL, 0x172a783LL, 0x4faca1LL, 0xf31257LL, 0x12441fcLL, 0x0d3748LL, 0xc21f15LL, 0xac5037LL, 0x180e592LL, 0x7d3210LL, 0xa27187LL, 0x2beeafLL, 0x26ff57LL, 0x690e82LL, 0x77765cLL, 0x1a9e1d7LL, 0x140be1aLL, 0x1aa1e3aLL, 0x1944f5cLL, 0x19b5032LL, 0x169897LL, 0x1068eb9LL, 0xf30dbcLL, 0x106a151LL, 0x1d53e95LL, 0x1348ceeLL, 0xcf4fcaLL, 0x1728bb5LL, 0xdc1eecLL, 0x69e8dbLL, 0x16e1523LL, 0x105fa25LL, 0x18abb0cLL, 0xc4275dLL, 0x6d8e76LL, 0xe8d6dbLL, 0xe16fd7LL, 0x1ac2682LL, 0x77435bLL, 0xa359ddLL, 0x3a9c4eLL, 0x123919aLL, 0x1e25817LL, 0x02a836LL, 0x1545a4LL, 0x1209c8dLL, 0xbb5f69LL, 0x1dc1f02LL, 0x5d5f7eLL, 0x12d0581LL, 0x13786c2LL, 0xe15409LL, 0x1aa3599LL, 0x139aad8LL, 0xb09d2aLL, 0x54488fLL, 0x13c351cLL, 0x976079LL, 0xb25b12LL, 0x1addb34LL, 0x1cb23aeLL, 0x1175738LL, 0x1303bb8LL, 0xd47716LL, 0x188ceeaLL, 0xbaf967LL, 0x1226d39LL, 0x135e99bLL, 0x34adc5LL, 0x2e384dLL, 0x90d3faLL, 0x232713LL, 0x17d49b1LL, 0xaa84d6LL, 0xc2ddf8LL, 0x1665646LL, 0x4f345fLL, 0x2276b1LL, 0x1255dd7LL, 0x16f4cccLL, 0x4aaffcLL, 0xc46da6LL, 0x85c7b3LL, 0x1311fcbLL, 0x9c6c4fLL, 0x187d947LL, 0x8578e4LL, 0xe2bf0bLL, 0xa01b4cLL, 0xa1493bLL, 0x7ad766LL, 0xccfe82LL, 0x1981b5bLL, 0x1cacc85LL, 0x562cdbLL, 0x15b0e78LL, 0x8f66c5LL, 0x3332bfLL, 0x12ce754LL, 0x096a76LL, 0x1d5e3baLL, 0x27ea41LL, 0x14412dfLL, 0x67b9b4LL, 0xdaa51aLL, 0x1dcb17LL, 0x4d4afdLL, 0x6335d5LL, 0xee2334LL, 0x17d4e55LL, 0x1b8b0f0LL, 0x14999e3LL, 0x1513dfaLL, 0x765cf2LL, 0x56af90LL, 0x12e16acLL, 0x1d3d86cLL, 0xff279bLL, 0x18822ddLL, 0x99d478LL, 0x8dc0d2LL, 0x34b666LL, 0xcf9526LL, 0x186443dLL, 0x7a8e29LL, 0x19c6aa5LL, 0x1f2a27dLL, 0x12b2136LL, 0xd0cd0dLL, 0x12cb320LL, 0x17ddb0bLL, 0x05353bLL, 0x15b2cafLL, 0x1e5a507LL, 0x120f1e5LL, 0x114605aLL, 0x14efe4cLL, 0x568134LL, 0x11b9f92LL, 0x174d2a7LL, 0x692b1dLL, 0x39e4feLL, 0xaaff3dLL, 0x96224cLL, 0x13c9f77LL, 0x110ee8fLL, 0xf17beaLL, 0x99fb5dLL, 0x337141LL, 0x02b54dLL, 0x1233a70LL }; + +static const TagCodes tagCodes25h7 = TagCodes(25, 7, t25h7, sizeof(t25h7)/sizeof(t25h7[0])); + +} diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag25h9.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag25h9.h new file mode 100644 index 0000000..90185bb --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag25h9.h @@ -0,0 +1,52 @@ +/** Tag family with 35 distinct codes. + bits: 25, minimum hamming: 9, minimum complexity: 8 + + Max bits corrected False positive rate + 0 0.000104 % + 1 0.002712 % + 2 0.034004 % + 3 0.273913 % + 4 1.593411 % + + Generation time: 31.283000 s + + Hamming distance between pairs of codes (accounting for rotation): + + 0 0 + 1 0 + 2 0 + 3 0 + 4 0 + 5 0 + 6 0 + 7 0 + 8 0 + 9 156 + 10 214 + 11 120 + 12 64 + 13 29 + 14 11 + 15 1 + 16 0 + 17 0 + 18 0 + 19 0 + 20 0 + 21 0 + 22 0 + 23 0 + 24 0 + 25 0 +**/ + +#pragma once + +namespace AprilTags { + +const unsigned long long t25h9[] = + { 0x155cbf1LL, 0x1e4d1b6LL, 0x17b0b68LL, 0x1eac9cdLL, 0x12e14ceLL, 0x3548bbLL, 0x7757e6LL, 0x1065dabLL, 0x1baa2e7LL, 0xdea688LL, 0x81d927LL, 0x51b241LL, 0xdbc8aeLL, 0x1e50e19LL, 0x15819d2LL, 0x16d8282LL, 0x163e035LL, 0x9d9b81LL, 0x173eec4LL, 0xae3a09LL, 0x5f7c51LL, 0x1a137fcLL, 0xdc9562LL, 0x1802e45LL, 0x1c3542cLL, 0x870fa4LL, 0x914709LL, 0x16684f0LL, 0xc8f2a5LL, 0x833ebbLL, 0x59717fLL, 0x13cd050LL, 0xfa0ad1LL, 0x1b763b0LL, 0xb991ceLL }; + +static const TagCodes tagCodes25h9 = TagCodes(25, 9, t25h9, sizeof(t25h9)/sizeof(t25h9[0])); + +} diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h11.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h11.h new file mode 100644 index 0000000..7c7e896 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h11.h @@ -0,0 +1,64 @@ +/** Tag family with 587 distinct codes. + bits: 36, minimum hamming: 11, minimum complexity: 10 + + Max bits corrected False positive rate + 0 0.000001 % + 1 0.000032 % + 2 0.000570 % + 3 0.006669 % + 4 0.056985 % + 5 0.379011 % + + Generation time: 210507.523000 s + + Hamming distance between pairs of codes (accounting for rotation): + + 0 0 + 1 0 + 2 0 + 3 0 + 4 0 + 5 0 + 6 0 + 7 0 + 8 0 + 9 0 + 10 0 + 11 7191 + 12 14401 + 13 20567 + 14 29161 + 15 31975 + 16 29179 + 17 21104 + 18 11447 + 19 4923 + 20 1590 + 21 372 + 22 73 + 23 8 + 24 0 + 25 0 + 26 0 + 27 0 + 28 0 + 29 0 + 30 0 + 31 0 + 32 0 + 33 0 + 34 0 + 35 0 + 36 0 +**/ + +#pragma once + +namespace AprilTags { + +const unsigned long long t36h11[] = + { 0xd5d628584LL, 0xd97f18b49LL, 0xdd280910eLL, 0xe479e9c98LL, 0xebcbca822LL, 0xf31dab3acLL, 0x056a5d085LL, 0x10652e1d4LL, 0x22b1dfeadLL, 0x265ad0472LL, 0x34fe91b86LL, 0x3ff962cd5LL, 0x43a25329aLL, 0x474b4385fLL, 0x4e9d243e9LL, 0x5246149aeLL, 0x5997f5538LL, 0x683bb6c4cLL, 0x6be4a7211LL, 0x7e3158eeaLL, 0x81da494afLL, 0x858339a74LL, 0x8cd51a5feLL, 0x9f21cc2d7LL, 0xa2cabc89cLL, 0xadc58d9ebLL, 0xb16e7dfb0LL, 0xb8c05eb3aLL, 0xd25ef139dLL, 0xd607e1962LL, 0xe4aba3076LL, 0x2dde6a3daLL, 0x43d40c678LL, 0x5620be351LL, 0x64c47fa65LL, 0x686d7002aLL, 0x6c16605efLL, 0x6fbf50bb4LL, 0x8d06d39dcLL, 0x9f53856b5LL, 0xadf746dc9LL, 0xbc9b084ddLL, 0xd290aa77bLL, 0xd9e28b305LL, 0xe4dd5c454LL, 0xfad2fe6f2LL, 0x181a8151aLL, 0x26be42c2eLL, 0x2e10237b8LL, 0x405cd5491LL, 0x7742eab1cLL, 0x85e6ac230LL, 0x8d388cdbaLL, 0x9f853ea93LL, 0xc41ea2445LL, 0xcf1973594LL, 0x14a34a333LL, 0x31eacd15bLL, 0x6c79d2dabLL, 0x73cbb3935LL, 0x89c155bd3LL, 0x8d6a46198LL, 0x91133675dLL, 0xa708d89fbLL, 0xae5ab9585LL, 0xb9558a6d4LL, 0xb98743ab2LL, 0xd6cec68daLL, 0x1506bcaefLL, 0x4becd217aLL, 0x4f95c273fLL, 0x658b649ddLL, 0xa76c4b1b7LL, 0xecf621f56LL, 0x1c8a56a57LL, 0x3628e92baLL, 0x53706c0e2LL, 0x5e6b3d231LL, 0x7809cfa94LL, 0xe97eead6fLL, 0x5af40604aLL, 0x7492988adLL, 0xed5994712LL, 0x5eceaf9edLL, 0x7c1632815LL, 0xc1a0095b4LL, 0xe9e25d52bLL, 0x3a6705419LL, 0xa8333012fLL, 0x4ce5704d0LL, 0x508e60a95LL, 0x877476120LL, 0xa864e950dLL, 0xea45cfce7LL, 0x19da047e8LL, 0x24d4d5937LL, 0x6e079cc9bLL, 0x99f2e11d7LL, 0x33aa50429LL, 0x499ff26c7LL, 0x50f1d3251LL, 0x66e7754efLL, 0x96ad633ceLL, 0x9a5653993LL, 0xaca30566cLL, 0xc298a790aLL, 0x8be44b65dLL, 0xdc68f354bLL, 0x16f7f919bLL, 0x4dde0e826LL, 0xd548cbd9fLL, 0xe0439ceeeLL, 0xfd8b1fd16LL, 0x76521bb7bLL, 0xd92375742LL, 0xcab16d40cLL, 0x730c9dd72LL, 0xad9ba39c2LL, 0xb14493f87LL, 0x52b15651fLL, 0x185409cadLL, 0x77ae2c68dLL, 0x94f5af4b5LL, 0x0a13bad55LL, 0x61ea437cdLL, 0xa022399e2LL, 0x203b163d1LL, 0x7bba8f40eLL, 0x95bc9442dLL, 0x41c0b5358LL, 0x8e9c6cc81LL, 0x0eb549670LL, 0x9da3a0b51LL, 0xd832a67a1LL, 0xdcd4350bcLL, 0x4aa05fdd2LL, 0x60c7bb44eLL, 0x4b358b96cLL, 0x067299b45LL, 0xb9c89b5faLL, 0x6975acaeaLL, 0x62b8f7afaLL, 0x33567c3d7LL, 0xbac139950LL, 0xa5927c62aLL, 0x5c916e6a4LL, 0x260ecb7d5LL, 0x29b7bbd9aLL, 0x903205f26LL, 0xae72270a4LL, 0x3d2ec51a7LL, 0x82ea55324LL, 0x11a6f3427LL, 0x1ca1c4576LL, 0xa40c81aefLL, 0xbddccd730LL, 0x0e617561eLL, 0x969317b0fLL, 0x67f781364LL, 0x610912f96LL, 0xb2549fdfcLL, 0x06e5aaa6bLL, 0xb6c475339LL, 0xc56836a4dLL, 0x844e351ebLL, 0x4647f83b4LL, 0x0908a04f5LL, 0x7f51034c9LL, 0xaee537fcaLL, 0x5e92494baLL, 0xd445808f4LL, 0x28d68b563LL, 0x04d25374bLL, 0x2bc065f65LL, 0x96dc3ea0cLL, 0x4b2ade817LL, 0x07c3fd502LL, 0xe768b5cafLL, 0x17605cf6cLL, 0x182741ee4LL, 0x62846097cLL, 0x72b5ebf80LL, 0x263da6e13LL, 0xfa841bcb5LL, 0x7e45e8c69LL, 0x653c81fa0LL, 0x7443b5e70LL, 0x0a5234afdLL, 0x74756f24eLL, 0x157ebf02aLL, 0x82ef46939LL, 0x80d420264LL, 0x2aeed3e98LL, 0xb0a1dd4f8LL, 0xb5436be13LL, 0x7b7b4b13bLL, 0x1ce80d6d3LL, 0x16c08427dLL, 0xee54462ddLL, 0x1f7644cceLL, 0x9c7b5cc92LL, 0xe369138f8LL, 0x5d5a66e91LL, 0x485d62f49LL, 0xe6e819e94LL, 0xb1f340eb5LL, 0x09d198ce2LL, 0xd60717437LL, 0x0196b856cLL, 0xf0a6173a5LL, 0x12c0e1ec6LL, 0x62b82d5cfLL, 0xad154c067LL, 0xce3778832LL, 0x6b0a7b864LL, 0x4c7686694LL, 0x5058ff3ecLL, 0xd5e21ea23LL, 0x9ff4a76eeLL, 0x9dd981019LL, 0x1bad4d30aLL, 0xc601896d1LL, 0x973439b48LL, 0x1ce7431a8LL, 0x57a8021d6LL, 0xf9dba96e6LL, 0x83a2e4e7cLL, 0x8ea585380LL, 0xaf6c0e744LL, 0x875b73babLL, 0xda34ca901LL, 0x2ab9727efLL, 0xd39f21b9aLL, 0x8a10b742fLL, 0x5f8952dbaLL, 0xf8da71ab0LL, 0xc25f9df96LL, 0x06f8a5d94LL, 0xe42e63e1aLL, 0xb78409d1bLL, 0x792229addLL, 0x5acf8c455LL, 0x2fc29a9b0LL, 0xea486237bLL, 0xb0c9685a0LL, 0x1ad748a47LL, 0x03b4712d5LL, 0xf29216d30LL, 0x8dad65e49LL, 0x0a2cf09ddLL, 0x0b5f174c6LL, 0xe54f57743LL, 0xb9cf54d78LL, 0x4a312a88aLL, 0x27babc962LL, 0xb86897111LL, 0xf2ff6c116LL, 0x82274bd8aLL, 0x97023505eLL, 0x52d46edd1LL, 0x585c1f538LL, 0xbddd00e43LL, 0x5590b74dfLL, 0x729404a1fLL, 0x65320855eLL, 0xd3d4b6956LL, 0x7ae374f14LL, 0x2d7a60e06LL, 0x315cd9b5eLL, 0xfd36b4eacLL, 0xf1df7642bLL, 0x55db27726LL, 0x8f15ebc19LL, 0x992f8c531LL, 0x62dea2a40LL, 0x928275cabLL, 0x69c263cb9LL, 0xa774cca9eLL, 0x266b2110eLL, 0x1b14acbb8LL, 0x624b8a71bLL, 0x1c539406bLL, 0x3086d529bLL, 0x0111dd66eLL, 0x98cd630bfLL, 0x8b9d1ffdcLL, 0x72b2f61e7LL, 0x9ed9d672bLL, 0x96cdd15f3LL, 0x6366c2504LL, 0x6ca9df73aLL, 0xa066d60f0LL, 0xe7a4b8addLL, 0x8264647efLL, 0xaa195bf81LL, 0x9a3db8244LL, 0x014d2df6aLL, 0x0b63265b7LL, 0x2f010de73LL, 0x97e774986LL, 0x248affc29LL, 0xfb57dcd11LL, 0x0b1a7e4d9LL, 0x4bfa2d07dLL, 0x54e5cdf96LL, 0x4c15c1c86LL, 0xcd9c61166LL, 0x499380b2aLL, 0x540308d09LL, 0x8b63fe66fLL, 0xc81aeb35eLL, 0x86fe0bd5cLL, 0xce2480c2aLL, 0x1ab29ee60LL, 0x8048daa15LL, 0xdbfeb2d39LL, 0x567c9858cLL, 0x2b6edc5bcLL, 0x2078fca82LL, 0xadacc22aaLL, 0xb92486f49LL, 0x51fac5964LL, 0x691ee6420LL, 0xf63b3e129LL, 0x39be7e572LL, 0xda2ce6c74LL, 0x20cf17a5cLL, 0xee55f9b6eLL, 0xfb8572726LL, 0xb2c2de548LL, 0xcaa9bce92LL, 0xae9182db3LL, 0x74b6e5bd1LL, 0x137b252afLL, 0x51f686881LL, 0xd672f6c02LL, 0x654146ce4LL, 0xf944bc825LL, 0xe8327f809LL, 0x76a73fd59LL, 0xf79da4cb4LL, 0x956f8099bLL, 0x7b5f2655cLL, 0xd06b114a6LL, 0xd0697ca50LL, 0x27c390797LL, 0xbc61ed9b2LL, 0xcc12dd19bLL, 0xeb7818d2cLL, 0x092fcecdaLL, 0x89ded4ea1LL, 0x256a0ba34LL, 0xb6948e627LL, 0x1ef6b1054LL, 0x8639294a2LL, 0xeda3780a4LL, 0x39ee2af1dLL, 0xcd257edc5LL, 0x2d9d6bc22LL, 0x121d3b47dLL, 0x37e23f8adLL, 0x119f31cf6LL, 0x2c97f4f09LL, 0xd502abfe0LL, 0x10bc3ca77LL, 0x53d7190efLL, 0x90c3e62a6LL, 0x7e9ebf675LL, 0x979ce23d1LL, 0x27f0c98e9LL, 0xeafb4ae59LL, 0x7ca7fe2bdLL, 0x1490ca8f6LL, 0x9123387baLL, 0xb3bc73888LL, 0x3ea87e325LL, 0x4888964aaLL, 0xa0188a6b9LL, 0xcd383c666LL, 0x40029a3fdLL, 0xe1c00ac5cLL, 0x39e6f2b6eLL, 0xde664f622LL, 0xe979a75e8LL, 0x7c6b4c86cLL, 0xfd492e071LL, 0x8fbb35118LL, 0x40b4a09b7LL, 0xaf80bd6daLL, 0x70e0b2521LL, 0x2f5c54d93LL, 0x3f4a118d5LL, 0x09c1897b9LL, 0x079776eacLL, 0x084b00b17LL, 0x3a95ad90eLL, 0x28c544095LL, 0x39d457c05LL, 0x7a3791a78LL, 0xbb770e22eLL, 0x9a822bd6cLL, 0x68a4b1fedLL, 0xa5fd27b3bLL, 0x0c3995b79LL, 0xd1519dff1LL, 0x8e7eee359LL, 0xcd3ca50b1LL, 0xb73b8b793LL, 0x57aca1c43LL, 0xec2655277LL, 0x785a2c1b3LL, 0x75a07985aLL, 0xa4b01eb69LL, 0xa18a11347LL, 0xdb1f28ca3LL, 0x877ec3e25LL, 0x31f6341b8LL, 0x1363a3a4cLL, 0x075d8b9baLL, 0x7ae0792a9LL, 0xa83a21651LL, 0x7f08f9fb5LL, 0x0d0cf73a9LL, 0xb04dcc98eLL, 0xf65c7b0f8LL, 0x65ddaf69aLL, 0x2cf9b86b3LL, 0x14cb51e25LL, 0xf48027b5bLL, 0x0ec26ea8bLL, 0x44bafd45cLL, 0xb12c7c0c4LL, 0x959fd9d82LL, 0xc77c9725aLL, 0x48a22d462LL, 0x8398e8072LL, 0xec89b05ceLL, 0xbb682d4c9LL, 0xe5a86d2ffLL, 0x358f01134LL, 0x8556ddcf6LL, 0x67584b6e2LL, 0x11609439fLL, 0x08488816eLL, 0xaaf1a2c46LL, 0xf879898cfLL, 0x8bbe5e2f7LL, 0x101eee363LL, 0x690f69377LL, 0xf5bd93cd9LL, 0xcea4c2bf6LL, 0x9550be706LL, 0x2c5b38a60LL, 0xe72033547LL, 0x4458b0629LL, 0xee8d9ed41LL, 0xd2f918d72LL, 0x78dc39fd3LL, 0x8212636f6LL, 0x7450a72a7LL, 0xc4f0cf4c6LL, 0x367bcddcdLL, 0xc1caf8cc6LL, 0xa7f5b853dLL, 0x9d536818bLL, 0x535e021b0LL, 0xa7eb8729eLL, 0x422a67b49LL, 0x929e928a6LL, 0x48e8aefccLL, 0xa9897393cLL, 0x5eb81d37eLL, 0x1e80287b7LL, 0x34770d903LL, 0x2eef86728LL, 0x59266ccb6LL, 0x0110bba61LL, 0x1dfd284efLL, 0x447439d1bLL, 0xfece0e599LL, 0x9309f3703LL, 0x80764d1ddLL, 0x353f1e6a0LL, 0x2c1c12dccLL, 0xc1d21b9d7LL, 0x457ee453eLL, 0xd66faf540LL, 0x44831e652LL, 0xcfd49a848LL, 0x9312d4133LL, 0x3f097d3eeLL, 0x8c9ebef7aLL, 0xa99e29e88LL, 0x0e9fab22cLL, 0x4e748f4fbLL, 0xecdee4288LL, 0xabce5f1d0LL, 0xc42f6876cLL, 0x7ed402ea0LL, 0xe5c4242c3LL, 0xd5b2c31aeLL, 0x286863be6LL, 0x160444d94LL, 0x5f0f5808eLL, 0xae3d44b2aLL, 0x9f5c5d109LL, 0x8ad9316d7LL, 0x3422ba064LL, 0x2fed11d56LL, 0xbea6e3e04LL, 0x04b029eecLL, 0x6deed7435LL, 0x3718ce17cLL, 0x55857f5e2LL, 0x2edac7b62LL, 0x085d6c512LL, 0xd6ca88e0fLL, 0x2b7e1fc69LL, 0xa699d5c1bLL, 0xf05ad74deLL, 0x4cf5fb56dLL, 0x5725e07e1LL, 0x72f18a2deLL, 0x1cec52609LL, 0x48534243cLL, 0x2523a4d69LL, 0x35c1b80d1LL, 0xa4d7338a7LL, 0x0db1af012LL, 0xe61a9475dLL, 0x05df03f91LL, 0x97ae260bbLL, 0x32d627fefLL, 0xb640f73c2LL, 0x45a1ac9c6LL, 0x6a2202de1LL, 0x57d3e25f2LL, 0x5aa9f986eLL, 0x0cc859d8aLL, 0xe3ec6cca8LL, 0x54e95e1aeLL, 0x446887b06LL, 0x7516732beLL, 0x3817ac8f5LL, 0x3e26d938cLL, 0xaa81bc235LL, 0xdf387ca1bLL, 0x0f3a3b3f2LL, 0xb4bf69677LL, 0xae21868edLL, 0x81e1d2d9dLL, 0xa0a9ea14cLL, 0x8eee297a9LL, 0x4740c0559LL, 0xe8b141837LL, 0xac69e0a3dLL, 0x9ed83a1e1LL, 0x5edb55ecbLL, 0x07340fe81LL, 0x50dfbc6bfLL, 0x4f583508aLL, 0xcb1fb78bcLL, 0x4025ced2fLL, 0x39791ebecLL, 0x53ee388f1LL, 0x7d6c0bd23LL, 0x93a995fbeLL, 0x8a41728deLL, 0x2fe70e053LL, 0xab3db443aLL, 0x1364edb05LL, 0x47b6eeed6LL, 0x12e71af01LL, 0x52ff83587LL, 0x3a1575dd8LL, 0x3feaa3564LL, 0xeacf78ba7LL, 0x0872b94f8LL, 0xda8ddf9a2LL, 0x9aa920d2bLL, 0x1f350ed36LL, 0x18a5e861fLL, 0x2c35b89c3LL, 0x3347ac48aLL, 0x7f23e022eLL, 0x2459068fbLL, 0xe83be4b73LL }; + +static const TagCodes tagCodes36h11 = TagCodes(36, 11, t36h11, sizeof(t36h11)/sizeof(t36h11[0])); + +} diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h11_other.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h11_other.h new file mode 100644 index 0000000..073aa00 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h11_other.h @@ -0,0 +1,88 @@ +// These codes were generated by TagFamilyGenerator.java from Ed Olson + +// tag36h11Codes : 36 bits, minimum Hamming distance 11, minimum complexity 10 + +#pragma once + +namespace AprilTags { + +const unsigned long long t36h11_other[] = + { 0xd5d628584LL, 0xd97f18b49LL, 0xdd280910eLL, 0xe479e9c98LL, 0xebcbca822LL, 0xf31dab3acLL, 0x056a5d085LL, 0x10652e1d4LL, + 0x17b70ed5eLL, 0x22b1dfeadLL, 0x265ad0472LL, 0x34fe91b86LL, 0x3ff962cd5LL, 0x43a25329aLL, 0x474b4385fLL, 0x4e9d243e9LL, + 0x5246149aeLL, 0x5997f5538LL, 0x683bb6c4cLL, 0x6be4a7211LL, 0x7e3158eeaLL, 0x81da494afLL, 0x858339a74LL, 0x8cd51a5feLL, + 0x9f21cc2d7LL, 0xa2cabc89cLL, 0xadc58d9ebLL, 0xb16e7dfb0LL, 0xb8c05eb3aLL, 0xd25ef139dLL, 0xd607e1962LL, 0xe4aba3076LL, + 0x2dde6a3daLL, 0x43d40c678LL, 0x5620be351LL, 0x64c47fa65LL, 0x686d7002aLL, 0x6c16605efLL, 0x6fbf50bb4LL, 0x8d06d39dcLL, + 0x9baa950f0LL, 0x9f53856b5LL, 0xadf746dc9LL, 0xbc9b084ddLL, 0xd290aa77bLL, 0xd9e28b305LL, 0xe4dd5c454LL, 0xfad2fe6f2LL, + 0x181a8151aLL, 0x26be42c2eLL, 0x2e10237b8LL, 0x405cd5491LL, 0x6ff109f92LL, 0x7742eab1cLL, 0x85e6ac230LL, 0x8d388cdbaLL, + 0x9f853ea93LL, 0xc41ea2445LL, 0xcf1973594LL, 0x14a34a333LL, 0x31eacd15bLL, 0x44377ee34LL, 0x6c79d2dabLL, 0x73cbb3935LL, + 0x89c155bd3LL, 0x8d6a46198LL, 0x91133675dLL, 0xa708d89fbLL, 0xae5ab9585LL, 0xb9558a6d4LL, 0xb98743ab2LL, 0xd6cec68daLL, + 0x1506bcaefLL, 0x4becd217aLL, 0x4f95c273fLL, 0x658b649ddLL, 0xa76c4b1b7LL, 0xecf621f56LL, 0x1c8a56a57LL, 0x3628e92baLL, + 0x53706c0e2LL, 0x7809cfa94LL, 0xc88e77982LL, 0xe97eead6fLL, 0x5af40604aLL, 0xffa6463ebLL, 0x5eceaf9edLL, 0x7c1632815LL, + 0xc1a0095b4LL, 0xe9e25d52bLL, 0x3a6705419LL, 0xa8333012fLL, 0x4ce5704d0LL, 0x508e60a95LL, 0x877476120LL, 0xa864e950dLL, + 0xea45cfce7LL, 0x19da047e8LL, 0x24d4d5937LL, 0x54690a438LL, 0x6e079cc9bLL, 0x99f2e11d7LL, 0x499ff26c7LL, 0x50f1d3251LL, + 0x66e7754efLL, 0x49d1abaa5LL, 0x96ad633ceLL, 0x9a5653993LL, 0xaca30566cLL, 0x8be44b65dLL, 0xb4269f5d4LL, 0xdc68f354bLL, + 0x4dde0e826LL, 0xd548cbd9fLL, 0xfd8b1fd16LL, 0x76521bb7bLL, 0xd1d194bb8LL, 0xd57a8517dLL, 0xd92375742LL, 0xcab16d40cLL, + 0x730c9dd72LL, 0xad9ba39c2LL, 0xb14493f87LL, 0x185409cadLL, 0x77ae2c68dLL, 0x94f5af4b5LL, 0x0a13bad55LL, 0x61ea437cdLL, + 0xa022399e2LL, 0xbd69bc80aLL, 0x203b163d1LL, 0x7bba8f40eLL, 0x784358227LL, 0xc92b728d1LL, 0x92a8cfa02LL, 0x9da3a0b51LL, + 0xdcd4350bcLL, 0x4aa05fdd2LL, 0x60c7bb44eLL, 0x4b358b96cLL, 0x612b2dc0aLL, 0x775289286LL, 0x7ea469e10LL, 0x09e9d0d2cLL, + 0x067299b45LL, 0xb9c89b5faLL, 0x9560f1026LL, 0x62b8f7afaLL, 0xbac139950LL, 0x58b6c4d01LL, 0xa5927c62aLL, 0xe77362e04LL, + 0xf29fed331LL, 0x903205f26LL, 0xc36f2afecLL, 0xae72270a4LL, 0x3d2ec51a7LL, 0x82ea55324LL, 0x1ca1c4576LL, 0xa40c81aefLL, + 0xbddccd730LL, 0x0e617561eLL, 0x585b218faLL, 0x969317b0fLL, 0x588cdacd8LL, 0x67309c3ecLL, 0x8c5f2b938LL, 0x4142f72ddLL, + 0x06e5aaa6bLL, 0x626523aa8LL, 0xb6c475339LL, 0xc56836a4dLL, 0x4647f83b4LL, 0x0908a04f5LL, 0x7862950fbLL, 0xd445808f4LL, + 0x28d68b563LL, 0x04d25374bLL, 0xc8bd52fc0LL, 0x06f5491d5LL, 0x27e5bc5c2LL, 0x2bc065f65LL, 0x96dc3ea0cLL, 0xfdb9fb354LL, + 0x47b3a7630LL, 0xd7372a6abLL, 0x372678c25LL, 0xe768b5cafLL, 0x437d5a886LL, 0x2b091f757LL, 0x91b522cc1LL, 0x62846097cLL, + 0x3aa57f1c1LL, 0x263da6e13LL, 0xfa841bcb5LL, 0x157ebf02aLL, 0xf586e9f93LL, 0xecaf0e8ceLL, 0x82ef46939LL, 0x847d10829LL, + 0x68919e513LL, 0x2aeed3e98LL, 0x11265760cLL, 0x1ce80d6d3LL, 0x0e4c1b374LL, 0x68b0db3e7LL, 0x1c389627aLL, 0xfb79dc26bLL, + 0x9379975a4LL, 0x064ac3391LL, 0x706dfdae2LL, 0x44edfb117LL, 0x86a4f78c8LL, 0xaebd61816LL, 0xf53fd690bLL, 0xb8f91cda2LL, + 0xf0a6173a5LL, 0x12c0e1ec6LL, 0xd1a6e0664LL, 0x6bf37b450LL, 0x62b82d5cfLL, 0xe5f46d153LL, 0x0d1438d4bLL, 0x5af82d134LL, + 0x6ea0ef91fLL, 0x9ff4a76eeLL, 0xde5e56ce1LL, 0xb5c82ed18LL, 0x5b50f279bLL, 0xd7f297fa3LL, 0xef444ad53LL, 0xa8c9a5013LL, + 0x3d300e4f1LL, 0x33fc8fa25LL, 0x43d277c22LL, 0x9d2c1d435LL, 0x5f8952dbaLL, 0xf0cc59103LL, 0xd2f779af6LL, 0xb5e97f461LL, + 0x7f0b3918bLL, 0xe42e63e1aLL, 0x769bc1897LL, 0x97bdee062LL, 0x792229addLL, 0x816ca89bdLL, 0xd41446335LL, 0x3f572b065LL, + 0x2a93af8b0LL, 0xcadde9ac9LL, 0x7176b93c1LL, 0x84b15c29bLL, 0x9b9f9c88fLL, 0x537511febLL, 0xee8891d4fLL, 0x5dc83b096LL, + 0x05bd1b4a0LL, 0x2e073e7ccLL, 0x0b5f174c6LL, 0xb184d5e98LL, 0xd0ef4e74aLL, 0x0ddad25b7LL, 0xbd16e63f6LL, 0x4aa64f025LL, + 0xa252eda74LL, 0xd940d24b4LL, 0x9745a041bLL, 0x055322c79LL, 0x7022f6a83LL, 0xa31416eacLL, 0x96b2880f6LL, 0x48d385322LL, + 0x14d46c8f9LL, 0x11e4d63b7LL, 0x379614f93LL, 0x71eda5cc5LL, 0xaa05e1e39LL, 0xcee09d333LL, 0x52c976570LL, 0x023252178LL, + 0x599fac8f4LL, 0xbb0a48854LL, 0x98cd630bfLL, 0x2d8f6f9a4LL, 0xf5c05a72dLL, 0x9ed9d672bLL, 0x50d8b8ce3LL, 0xe59ac55c8LL, + 0xe09d938a6LL, 0x4ada4f38bLL, 0xbb85a794eLL, 0x5544e5f55LL, 0x9a3db8244LL, 0xe3784e95dLL, 0x796c81d2bLL, 0x6cebb60a1LL, + 0x27b2d55b4LL, 0x6de945a0cLL, 0x4a69d0af9LL, 0x6afea0adfLL, 0x158987899LL, 0x1b528fb48LL, 0x6d183275eLL, 0x73afeed3aLL, + 0x1a7a77a10LL, 0x4be59d2feLL, 0x2ad522b12LL, 0xa82d445fdLL, 0xbbcb59c93LL, 0xe71e94895LL, 0x75b14896fLL, 0xb0afb721aLL, + 0x065d8e6c8LL, 0x372810d9cLL, 0xb77603728LL, 0xad78c1f44LL, 0x90ca91da0LL, 0x2e74184b4LL, 0xc2964c0aaLL, 0xb07f7a899LL, + 0x8ee694eddLL, 0x1ad7caf87LL, 0x2035916c5LL, 0xcd1670631LL, 0x1611c2a77LL, 0x8a1a06962LL, 0xdb970149aLL, 0x5778c6bb4LL, + 0x3fab695feLL, 0x014b9cc35LL, 0x604be4377LL, 0xfd49501f1LL, 0xe2b710c4dLL, 0x6bf7f4a88LL, 0x0adf98124LL, 0xc5ee49adeLL, + 0xe4c34b0eaLL, 0x9b5e0047dLL, 0x4002b5929LL, 0x4e9a35492LL, 0x908aedae9LL, 0xa0bc790edLL, 0xd12b583baLL, 0x431b08264LL, + 0xb7b33afc8LL, 0xd115672f8LL, 0x253296b16LL, 0xbd5e4f6edLL, 0xf1276fc55LL, 0x5feaa426bLL, 0x2d0955cbfLL, 0xcb2ade90eLL, + 0x08b0fe749LL, 0x2709d6730LL, 0x0edc7ec97LL, 0xa7c74d431LL, 0x1536402eaLL, 0x61936f66dLL, 0x7ec973bc9LL, 0xa00a12d3dLL, + 0xc6ed2ccf6LL, 0x8f87c4b9aLL, 0xf049ee52bLL, 0x0d1fa9777LL, 0x85175a497LL, 0x2d917c5c5LL, 0xfc61287b4LL, 0x63ce55156LL, + 0x659cac663LL, 0xbb4b8174fLL, 0x70bd5be0bLL, 0xfb3da5f18LL, 0x917b001e3LL, 0x516870f16LL, 0x03bb5ac33LL, 0x2a510ec0cLL, + 0x07ecd1ae2LL, 0x06642c91aLL, 0xcc7c83662LL, 0xb88d2c60eLL, 0x40d35e87eLL, 0x452f5656eLL, 0xf8c5e5640LL, 0xc68372145LL, + 0x6b61cb49eLL, 0x066ce5035LL, 0x151c05dd0LL, 0xad92f9119LL, 0x8fa874156LL, 0xd7d545982LL, 0x2602c7a8eLL, 0x0d9054ac8LL, + 0xb85332ce0LL, 0xa8e7f583cLL, 0xa2534a713LL, 0x77ce78732LL, 0x6b605c6c5LL, 0x8101603e6LL, 0x9573cd8f0LL, 0xa18bba0abLL, + 0xf5d224ae1LL, 0x9ecb4dfd4LL, 0x2e48c9e03LL, 0x79b4c6ae0LL, 0x60e6b0713LL, 0xea6a8420dLL, 0xa22971a8fLL, 0x605c053fdLL, + 0x57678633aLL, 0xea85c3395LL, 0x7fda1da74LL, 0x9824459caLL, 0xb2eee31f2LL, 0x4a34b0db1LL, 0xb5bbbd933LL, 0x583d9c190LL, + 0xc93e6091cLL, 0xdca7c6e3bLL, 0x214d69b74LL, 0x525894f7fLL, 0x21be0e083LL, 0xf0dbd2784LL, 0x0ffac88d9LL, 0x57f7e33e5LL, + 0x4a7301d85LL, 0x8887af6f6LL, 0x1b8ccb3a1LL, 0x68c1b2878LL, 0x78b6bf950LL, 0x63b9aa851LL, 0x7ed12f23aLL, 0x350eb35b2LL, + 0x561503189LL, 0x3f16ac63cLL, 0xd2fd4b06cLL, 0xa7c49627eLL, 0x36b9f5d0aLL, 0xbca21c149LL, 0xba5bc28efLL, 0xce2c2b89cLL, + 0x776bc0448LL, 0xce170f268LL, 0x8f57303c3LL, 0x74e5fcc9eLL, 0x46de67b7eLL, 0x2b98bd7aaLL, 0xb5c41dc2eLL, 0x12e1e50f8LL, + 0x875f6fcdaLL, 0xf90ea702dLL, 0x7ed051595LL, 0x9d8da07b8LL, 0xbc30d09edLL, 0x77ad8306bLL, 0x82d4a0885LL, 0xf4e1b7a04LL, + 0xb427eabdaLL, 0xdb1b28f5eLL, 0xe5f911de5LL, 0xb8ff4c115LL, 0x3185fbcf4LL, 0xefda16bdfLL, 0xeaa3f6c63LL, 0x9a3f4f520LL, + 0x6317c6e21LL, 0xde1ac8909LL, 0xb962e4d06LL, 0x8a8cc1536LL, 0x0abebf2d5LL, 0x6a3787f5fLL, 0x62cc2622fLL, 0x3196aa59fLL, + 0x9b6816c6bLL, 0x95f398661LL, 0x2b1673eb7LL, 0xc9cf19ba7LL, 0x44394782aLL, 0xd02e2d199LL, 0xe517f16dcLL, 0x433df5666LL, + 0xdbfb6521fLL, 0x6316ed9fbLL, 0x0681b072aLL, 0x24e7e3614LL, 0x3049f22daLL, 0x245b47d67LL, 0x032e59d5dLL, 0x78f512121LL, + 0xf76e98aacLL, 0x20e313ad6LL, 0x9947bd319LL, 0x0719aab9fLL, 0xabe40e6b2LL, 0x9bbec96c6LL, 0xcf05e6446LL, 0xee3c76b79LL, + 0xe9317cc92LL, 0x9bf9aa92bLL, 0x13fe98495LL, 0xd931239a6LL, 0x7264aced9LL, 0x04ed957b4LL, 0xbb7021cbbLL, 0x4609308b5LL, + 0x2d5c52c38LL, 0xceb22ad4fLL, 0x82a47a446LL, 0x04d68909aLL, 0x832cdf368LL, 0x242ed1118LL, 0xd1dda2014LL, 0x901b6a04eLL, + 0x19c1e9514LL, 0x3e9c0c97fLL, 0x1e814bce3LL, 0x55b40b44dLL, 0xeff162399LL, 0x4012da58aLL, 0x1d4d90e43LL, 0x50e79facdLL, + 0x35ef088baLL, 0x774709d00LL, 0xd32e575b3LL, 0x54c5cfff2LL, 0x59bbd73fbLL, 0x3b2dc7e8bLL, 0x13a74d09fLL, 0xc5a21e37fLL, + 0x7aab49b28LL, 0x2793aa17aLL, 0x3a6673575LL, 0x78c27371eLL, 0x1788da29cLL, 0x8b5bb6078LL, 0xa5c506a80LL, 0xc2c487d6aLL, + 0xf238647acLL, 0x601f5e6e2LL, 0x2db5d412aLL, 0xd7c46f24aLL, 0xe4e0b67f5LL, 0xe94793093LL, 0xe07e85846LL, 0xa04f6f205LL, + 0xe47cbc125LL, 0x9022fb419LL, 0xc2127ead8LL, 0xc670f0e63LL, 0xd282518cfLL, 0x63e8d8335LL, 0x2aa63408eLL, 0xb011851aaLL, + 0x2df8c686fLL, 0xa31f8c5f1LL, 0xe8c09cecbLL, 0x4cd645fb9LL, 0xa63b5d9f5LL, 0xd74dd32d6LL, 0xf6869a32aLL, 0xb725dae3eLL, + 0xc5b27c981LL, 0x67d0118b8LL, 0xb3fdb04faLL, 0xf11838f31LL, 0x7e73b5fb9LL, 0x24ec2067aLL, 0x8aaf3bceaLL, 0x04a06dca0LL, + 0x70a03ed6bLL, 0x70dc29b18LL, 0x4d75699a9LL, 0xaedc558d9LL, 0x62590b9afLL, 0x5f9258453LL, 0xf04a9a9ceLL, 0xcd1feb280LL, + 0x7300b05a7LL, 0xadb7ab52cLL, 0x59afeb236LL, 0xf1de62e03LL, 0xf103ba210LL, 0x7cf6472d5LL, 0xf84bf1908LL, 0xa4952dc03LL, + 0x43d506f47LL, 0x8e90eed24LL, 0x9c04974e9LL, 0x953aef583LL, 0x3d839c1bcLL, 0x0348ac64fLL, 0x2a1284fc1LL, 0x9fc565ccdLL, + 0x57118e8c4LL}; + +static const TagCodes tagCodes36h11_other = TagCodes(36, 11, t36h11_other, sizeof(t36h11_other)/sizeof(t36h11_other[0])); + +} diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h9.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h9.h new file mode 100644 index 0000000..c3746f2 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/Tag36h9.h @@ -0,0 +1,63 @@ +/** Tag family with 5329 distinct codes. + bits: 36, minimum hamming: 9, minimum complexity: 10 + + Max bits corrected False positive rate + 0 0.000008 % + 1 0.000287 % + 2 0.005172 % + 3 0.060541 % + 4 0.517333 % + + Generation time: 1121504.896000 s + + Hamming distance between pairs of codes (accounting for rotation): + + 0 0 + 1 0 + 2 0 + 3 0 + 4 0 + 5 0 + 6 0 + 7 0 + 8 0 + 9 88978 + 10 237109 + 11 493264 + 12 979401 + 13 1619560 + 14 2297837 + 15 2681251 + 16 2470697 + 17 1772734 + 18 969816 + 19 406950 + 20 134210 + 21 35419 + 22 7666 + 23 1342 + 24 199 + 25 20 + 26 3 + 27 0 + 28 0 + 29 0 + 30 0 + 31 0 + 32 0 + 33 0 + 34 0 + 35 0 + 36 0 +**/ + +#pragma once + +namespace AprilTags { + +const unsigned long long t36h9[] = + { 0x131b29edaLL, 0x16c41a49fLL, 0x1a6d0aa64LL, 0x1e15fb029LL, 0x21beeb5eeLL, 0x2567dbbb3LL, 0x2910cc178LL, 0x340b9d2c7LL, 0x37b48d88cLL, 0x42af5e9dbLL, 0x4a013f565LL, 0x54fc106b4LL, 0x58a500c79LL, 0x6748c238dLL, 0x6e9aa2f17LL, 0x75ec83aa1LL, 0x799574066LL, 0x7d3e6462bLL, 0x80e754bf0LL, 0x88393577aLL, 0x8be225d3fLL, 0x9a85e7453LL, 0x9e2ed7a18LL, 0xa580b85a2LL, 0xa929a8b67LL, 0xacd29912cLL, 0xb07b896f1LL, 0xb42479cb6LL, 0xbb765a840LL, 0xbf1f4ae05LL, 0xc6712b98fLL, 0xca1a1bf54LL, 0xd514ed0a3LL, 0xd8bddd668LL, 0xf60560490LL, 0xf9ae50a55LL, 0x085212169LL, 0x0bfb0272eLL, 0x1e47b4407LL, 0x294285556LL, 0x2ceb75b1bLL, 0x37e646c6aLL, 0x4a32f8943LL, 0x552dc9a92LL, 0x58d6ba057LL, 0x677a7b76bLL, 0x6b236bd30LL, 0x72754c8baLL, 0x81190dfceLL, 0x84c1fe593LL, 0x886aeeb58LL, 0x8c13df11dLL, 0x970eb026cLL, 0xad045250aLL, 0xb45633094LL, 0xc6a2e4d6dLL, 0xca4bd5332LL, 0xd19db5ebcLL, 0xd546a6481LL, 0xdc988700bLL, 0xe3ea67b95LL, 0xe7935815aLL, 0xeee538ce4LL, 0x0131ea9bdLL, 0x0c2cbbb0cLL, 0x0fd5ac0d1LL, 0x137e9c696LL, 0x17278cc5bLL, 0x22225ddaaLL, 0x2d1d2eef9LL, 0x346f0fa83LL, 0x3f69e0bd2LL, 0x4312d1197LL, 0x4e0da22e6LL, 0x51b6928abLL, 0x590873435LL, 0x5cb1639faLL, 0x605a53fbfLL, 0x67ac34b49LL, 0x6b552510eLL, 0x6efe156d3LL, 0x764ff625dLL, 0x889ca7f36LL, 0x8c45984fbLL, 0x939779085LL, 0x97406964aLL, 0xa5e42ad5eLL, 0xc6d49e14bLL, 0xce267ecd5LL, 0xd9214fe24LL, 0xdcca403e9LL, 0xe7c511538LL, 0xf668d2c4cLL, 0x13b055a74LL, 0x29a5f7d12LL, 0x2d4ee82d7LL, 0x3849b9426LL, 0x3bf2a99ebLL, 0x43448a575LL, 0x46ed7ab3aLL, 0x51e84bc89LL, 0x6b86de4ecLL, 0x6f2fceab1LL, 0x72d8bf076LL, 0x7681af63bLL, 0x852570d4fLL, 0x8c77518d9LL, 0x93c932463LL, 0x9ec4035b2LL, 0xad67c4cc6LL, 0xb110b528bLL, 0xb4b9a5850LL, 0xcaaf47aeeLL, 0xce58380b3LL, 0xd5aa18c3dLL, 0xe0a4e9d8cLL, 0xe44dda351LL, 0xe7f6ca916LL, 0xef48ab4a0LL, 0xf2f19ba65LL, 0xf69a8c02aLL, 0x10391e88dLL, 0x1b33ef9dcLL, 0x262ec0b2bLL, 0x29d7b10f0LL, 0x2d80a16b5LL, 0x312991c7aLL, 0x3c2462dc9LL, 0x437643953LL, 0x521a05067LL, 0x55c2f562cLL, 0x6466b6d40LL, 0x730a78454LL, 0x76b368a19LL, 0x7a5c58fdeLL, 0x7e05495a3LL, 0x85572a12dLL, 0x9051fb27cLL, 0x97a3dbe06LL, 0x9ef5bc990LL, 0xa29eacf55LL, 0xa6479d51aLL, 0xb1426e669LL, 0xb4eb5ec2eLL, 0xb8944f1f3LL, 0xce89f1491LL, 0xd5dbd201bLL, 0xd984c25e0LL, 0xe0d6a316aLL, 0xf32354e43LL, 0xfa75359cdLL, 0x0918f70e1LL, 0x106ad7c6bLL, 0x17bcb87f5LL, 0x22b789944LL, 0x38ad2bbe2LL, 0x4750ed2f6LL, 0x4af9dd8bbLL, 0x6f934126dLL, 0x8931d3ad0LL, 0x8cdac4095LL, 0x9083b465aLL, 0x9b7e857a9LL, 0xa2d066333LL, 0xa679568f8LL, 0xadcb37482LL, 0xb8c6085d1LL, 0xc017e915bLL, 0xc769c9ce5LL, 0xe85a3d0d2LL, 0xec032d697LL, 0xefac1dc5cLL, 0xf3550e221LL, 0xfaa6eedabLL, 0x01f8cf935LL, 0x22e942d22LL, 0x4782a66d4LL, 0x4b2b96c99LL, 0x4ed48725eLL, 0x5d7848972LL, 0x64ca294fcLL, 0x687319ac1LL, 0x6fc4fa64bLL, 0x736deac10LL, 0x7abfcb79aLL, 0x85ba9c8e9LL, 0x89638ceaeLL, 0xa6ab0fcd6LL, 0xaa540029bLL, 0xb1a5e0e25LL, 0xbca0b1f74LL, 0xc049a2539LL, 0xcb4473688LL, 0xceed63c4dLL, 0xd29654212LL, 0xdd9125361LL, 0xe13a15926LL, 0xe88bf64b0LL, 0xec34e6a75LL, 0xfad8a8189LL, 0xfe819874eLL, 0x097c6989dLL, 0x26c3ec6c5LL, 0x2a6cdcc8aLL, 0x2e15cd24fLL, 0x31bebd814LL, 0x4b5d50077LL, 0x5a011178bLL, 0x5daa01d50LL, 0x6c4dc3464LL, 0x6ff6b3a29LL, 0x7748945b3LL, 0x89954628cLL, 0x90e726e16LL, 0xa333d8aefLL, 0xa6dcc90b4LL, 0xc07b5b917LL, 0xc4244bedcLL, 0xcb762ca66LL, 0xd670fdbb5LL, 0xe16bced04LL, 0xf76170fa2LL, 0x14a8f3dcaLL, 0x1bfad4954LL, 0x2a9e96068LL, 0x2e478662dLL, 0x31f076bf2LL, 0x39425777cLL, 0x52e0e9fdfLL, 0x5689da5a4LL, 0x5ddbbb12eLL, 0x68d68c27dLL, 0x94c1d07b9LL, 0x986ac0d7eLL, 0x9fbca1908LL, 0xa36591ecdLL, 0xaab772a57LL, 0xc0ad14cf5LL, 0xcba7e5e44LL, 0xd2f9c69ceLL, 0xd6a2b6f93LL, 0xda4ba7558LL, 0xddf497b1dLL, 0xec9859231LL, 0xfee50af0aLL, 0x0636eba94LL, 0x14daad1a8LL, 0x397410b5aLL, 0x40c5f16e4LL, 0x4817d226eLL, 0x655f55096LL, 0x69084565bLL, 0x94f389b97LL, 0x989c7a15cLL, 0x9fee5ace6LL, 0xaae92be35LL, 0xb98ced549LL, 0xcbd99f222LL, 0xd32b7fdacLL, 0xecca1260fLL, 0xf07302bd4LL, 0x02bfb48adLL, 0x0a1195437LL, 0x0dba859fcLL, 0x18b556b4bLL, 0x2eaaf8de9LL, 0x35fcd9973LL, 0x3d4eba4fdLL, 0x4bf27bc11LL, 0x56ed4cd60LL, 0x61e81deafLL, 0x6939fea39LL, 0x82d89129cLL, 0x917c529b0LL, 0x952542f75LL, 0xa3c904689LL, 0xa771f4c4eLL, 0xb26cc5d9dLL, 0xc4b977a76LL, 0xcfb448bc5LL, 0xdaaf19d14LL, 0xe952db428LL, 0xf44dac577LL, 0x153e1f964LL, 0x278ad163dLL, 0x3285a278cLL, 0x39d783316LL, 0x487b44a2aLL, 0x5e70e6cc8LL, 0x6219d728dLL, 0x696bb7e17LL, 0x746688f66LL, 0x830a4a67aLL, 0x91ae0bd8eLL, 0xa051cd4a2LL, 0xab4c9e5f1LL, 0xb6476f740LL, 0xbd99502caLL, 0xc89421419LL, 0xcc3d119deLL, 0xd737e2b2dLL, 0xe5dba4241LL, 0xf82855f1aLL, 0x156fd8d42LL, 0x1cc1b98ccLL, 0x2b657afe0LL, 0x32b75bb6aLL, 0x36604c12fLL, 0x53a7cef57LL, 0x5ea2a00a6LL, 0x86e4f401dLL, 0x9931a5cf6LL, 0xa42c76e45LL, 0xaf2747f94LL, 0xb67928b1eLL, 0xbdcb096a8LL, 0xc8c5da7f7LL, 0xcc6ecadbcLL, 0xd3c0ab946LL, 0xdebb7ca95LL, 0xe2646d05aLL, 0x11f8a1b5bLL, 0x244553834LL, 0x3de3e6097LL, 0x48deb71e6LL, 0x53d988335LL, 0x5782788faLL, 0x69cf2a5d3LL, 0x71210b15dLL, 0x8716ad3fbLL, 0x9d0c4f699LL, 0xb301f1937LL, 0xc1a5b304bLL, 0x122a5af39LL, 0x2bc8ed79cLL, 0x331ace326LL, 0x4cb960b89LL, 0x540b41713LL, 0x62af02e27LL, 0x6657f33ecLL, 0x6da9d3f76LL, 0xa0e6f903cLL, 0xabe1ca18bLL, 0xaf8aba750LL, 0xc1d76c429LL, 0xc9294cfb3LL, 0xf8bd81ab4LL, 0x0b0a3378dLL, 0x3e4758853LL, 0x5f37cbc40LL, 0x6689ac7caLL, 0x6a329cd8fLL, 0x6ddb8d354LL, 0xb365640f3LL, 0xb70e546b8LL, 0xbe6035242LL, 0xc5b215dccLL, 0xc95b06391LL, 0xcd03f6956LL, 0xd0ace6f1bLL, 0xe6a2891b9LL, 0xf19d5a308LL, 0x128dcd6f5LL, 0x1636bdcbaLL, 0x2c2c5ff58LL, 0x3727310a7LL, 0x5bc094a59LL, 0x5f698501eLL, 0x6312755e3LL, 0x87abd8f95LL, 0x8b54c955aLL, 0x99f88ac6eLL, 0xac453c947LL, 0xc23adebe5LL, 0xd487908beLL, 0xea7d32b5cLL, 0x0072d4dfaLL, 0x07c4b5984LL, 0x12bf86ad3LL, 0x250c387acLL, 0x2c5e19336LL, 0x3b01daa4aLL, 0x50f77cce8LL, 0x54a06d2adLL, 0x58495d872LL, 0x71e7f00d5LL, 0x8434a1daeLL, 0x87dd92373LL, 0xa5251519bLL, 0xb01fe62eaLL, 0xc61588588LL, 0xf952ad64eLL, 0x0f484f8ecLL, 0x253df1b8aLL, 0x28e6e214fLL, 0x4285749b2LL, 0x462e64f77LL, 0x54d22668bLL, 0x5c2407215LL, 0x6ac7c8929LL, 0x80bd6abc7LL, 0x9a5bfd42aLL, 0xa1adddfb4LL, 0xa556ce579LL, 0xb3fa8fc8dLL, 0xc64741966LL, 0xcd99224f0LL, 0xeae0a5318LL, 0xf5db76467LL, 0x306a7c0b7LL, 0x4a090e91aLL, 0x58acd002eLL, 0x6ea2722ccLL, 0xacda684e1LL, 0xcdcadb8ceLL, 0xe7696e131LL, 0xf60d2f845LL, 0x25a164346LL, 0x344525a5aLL, 0x3b97065e4LL, 0x42e8e716eLL, 0x4de3b82bdLL, 0x553598e47LL, 0x5c87799d1LL, 0x6b2b3b0e5LL, 0x8120dd383LL, 0x84c9cd948LL, 0xbf58d3598LL, 0xdca0563c0LL, 0xeeed08099LL, 0x1ad84c5d5LL, 0x46c390b11LL, 0x606223374LL, 0x7a00b5bd7LL, 0xa994ea6d8LL, 0xb0e6cb262LL, 0xce2e4e08aLL, 0x2d56b768cLL, 0x434c5992aLL, 0x643cccd17LL, 0x6f379de66LL, 0x76897e9f0LL, 0x88d6306c9LL, 0xa9c6a3ab6LL, 0xb86a651caLL, 0xd208f7a2dLL, 0x29df804a5LL, 0x646e860f5LL, 0x6f6957244LL, 0x7a6428393LL, 0xa9f85ce94LL, 0xada14d459LL, 0xe830530a9LL, 0x2a1139883LL, 0x4758bc6abLL, 0x8939a2e85LL, 0x8ce29344aLL, 0x908b83a0fLL, 0xadd306837LL, 0xb524e73c1LL, 0xc3c8a8ad5LL, 0x353dc3db0LL, 0x6129082ecLL, 0x687ae8e76LL, 0x771eaa58aLL, 0x94662d3b2LL, 0x9f60fe501LL, 0xd29e235c7LL, 0x147f09da1LL, 0x2322cb4b5LL, 0x406a4e2ddLL, 0x4b651f42cLL, 0x615ac16caLL, 0x68aca2254LL, 0x9840d6d55LL, 0xb9314a142LL, 0xd678ccf6aLL, 0xddcaadaf4LL, 0xf76940357LL, 0x1859b3744LL, 0x1fab942ceLL, 0x2aa66541dLL, 0x4b96d880aLL, 0x5691a9959LL, 0x6c874bbf7LL, 0xae68323d1LL, 0xc0b4e40aaLL, 0xcf58a57beLL, 0xd6aa86348LL, 0xe54e47a5cLL, 0x40cdc0a99LL, 0x5a6c532fcLL, 0x82aea7273LL, 0x94fb58f4cLL, 0xa7480ac25LL, 0xaaf0fb1eaLL, 0xb5ebcc339LL, 0xb994bc8feLL, 0xd3334f161LL, 0xda852fcebLL, 0xe1d710875LL, 0x0dc254db1LL, 0x2760e7614LL, 0x2b09d7bd9LL, 0x3604a8d28LL, 0x61efed264LL, 0x6598dd829LL, 0x6941cddeeLL, 0x98d6028efLL, 0xa3d0d3a3eLL, 0xab22b45c8LL, 0xb27495152LL, 0x06a22d605LL, 0x1545eed19LL, 0x4fd4f4969LL, 0x746e5831bLL, 0x7f692946aLL, 0x955ecb708LL, 0xa4028ce1cLL, 0xab546d9a6LL, 0xb2a64e530LL, 0xc89bf07ceLL, 0xe5e3735f6LL, 0x4162ec633LL, 0x5006add47LL, 0x57588e8d1LL, 0x8a95b3997LL, 0x959084ae6LL, 0xa434461faLL, 0xba29e8498LL, 0xbdd2d8a5dLL, 0x27f6131aeLL, 0x2b9f03773LL, 0x32f0e42fdLL, 0x4194a5a11LL, 0x48e68659bLL, 0x787abb09cLL, 0x7c23ab661LL, 0x83758c1ebLL, 0xaf60d0727LL, 0xd7a32469eLL, 0xe646e5db2LL, 0x0ae049764LL, 0x3e1d6e82aLL, 0x665fc27a1LL, 0x6db1a332bLL, 0x715a938f0LL, 0x750383eb5LL, 0x83a7455c9LL, 0xa0eec83f1LL, 0xb33b7a0caLL, 0xc5882bda3LL, 0xc9311c368LL, 0xccda0c92dLL, 0xe6789f190LL, 0xedca7fd1aLL, 0x1263e36ccLL, 0x19b5c4256LL, 0x2c0275f2fLL, 0x4949f8d57LL, 0x509bd98e1LL, 0xa4c971d94LL, 0xd0b4b62d0LL, 0x079acb95bLL, 0x12959caaaLL, 0x21395e1beLL, 0x33860fe97LL, 0x5f71543d3LL, 0x7566f6671LL, 0x840ab7d85LL, 0x8f0588ed4LL, 0xa4fb2b172LL, 0xb39eec886LL, 0xbe99bd9d5LL, 0xc9948eb24LL, 0xe33321387LL, 0x1a1936a12LL, 0x425b8a989LL, 0x5bfa1d1ecLL, 0xe70dcad2aLL, 0xee5fab8b4LL, 0x4d8814eb6LL, 0x7973593f2LL, 0x9311ebc55LL, 0x21ce89d58LL, 0x5162be859LL, 0x58b49f3e3LL, 0x6eaa41681LL, 0xbb85f8faaLL, 0xd5248b80dLL, 0x4a42970adLL, 0x678a19ed5LL, 0x6b330a49aLL, 0x762ddb5e9LL, 0xa5c2100eaLL, 0xca5b73a9cLL, 0xeb4be6e89LL, 0xf29dc7a13LL, 0xfd9898b62LL, 0x17372b3c5LL, 0x25daecad9LL, 0x556f215daLL, 0x975007db4LL, 0xa5f3c94c8LL, 0xa99cb9a8dLL, 0x0c6e13654LL, 0x29b59647cLL, 0x55a0da9b8LL, 0x7a3a3e36aLL, 0x9781c1192LL, 0x9b2ab1757LL, 0x9ed3a1d1cLL, 0xad7763430LL, 0xcabee6258LL, 0xef5849c0aLL, 0x1eec7e70bLL, 0x4ad7c2c47LL, 0x731a16bbeLL, 0x8566c8897LL, 0xe0e6418d4LL, 0xf332f35adLL, 0x267018673LL, 0x3513d9d87LL, 0x3c65ba911LL, 0x4eb26c5eaLL, 0x56044d174LL, 0x64a80e888LL, 0x7e46a10ebLL, 0xbc7e97300LL, 0x4040642b4LL, 0x43e954879LL, 0x4b3b35403LL, 0xaa639ea05LL, 0x232a9a86aLL, 0x47c3fe21cLL, 0x825303e6cLL, 0xa34377259LL, 0xc433ea646LL, 0xddd27cea9LL, 0xe5245da33LL, 0x0d66b19aaLL, 0x5deb59898LL, 0x653d3a422LL, 0xa37530637LL, 0xb5c1e2310LL, 0xcbb7845aeLL, 0xd6b2556fdLL, 0xeca7f799bLL, 0xfef4a9674LL, 0x06468a1feLL, 0x4f7951562LL, 0x98ac188c6LL, 0xff2662a52LL, 0x0a2133ba1LL, 0x11731472bLL, 0x326387b18LL, 0x3d5e58c67LL, 0x69499d1a3LL, 0x77ed5e8b7LL, 0xb27c64507LL, 0xc4c9161e0LL, 0x11a4cdb09LL, 0x329540ef6LL, 0x572ea48a8LL, 0xa40a5c1d1LL, 0xaf052d320LL, 0xb2ae1d8e5LL, 0xb6570deaaLL, 0xd39e90cd2LL, 0xd74781297LL, 0x157f774acLL, 0x4c658cb37LL, 0xed6edc913LL, 0x0e5f4fd00LL, 0x74d999e8cLL, 0x7c2b7aa16LL, 0xba6370c2bLL, 0x2bd88bf06LL, 0x2f817c4cbLL, 0x750b5326aLL, 0x95fbc6657LL, 0xe6806e545LL, 0x2fb3358a9LL, 0x335c25e6eLL, 0x7c8eed1d2LL, 0xafcc12298LL, 0xb3750285dLL, 0x19ef4c9e9LL, 0x3736cf811LL, 0x3e88b039bLL, 0x582742bfeLL, 0x5f7923788LL, 0x8f0d58289LL, 0x9db11999dLL, 0xa15a09f62LL, 0xaffdcb676LL, 0xc99c5ded9LL, 0xee35c188bLL, 0x376888befLL, 0xa8dda3ecaLL, 0xd4c8e8406LL, 0x0baefda91LL, 0x21a49fd2fLL, 0x3eec22b57LL, 0x797b287a7LL, 0x9a6b9bb94LL, 0xc9ffd0695LL, 0xdc4c8236eLL, 0x37cbfb3abLL, 0x3b74eb970LL, 0x516a8dc0eLL, 0x84a7b2cd4LL, 0xb7e4d7d9aLL, 0xd8d54b187LL, 0x1ab631961LL, 0x1e5f21f26LL, 0x25b102ab0LL, 0xa220eeedaLL, 0x13960a1b5LL, 0x34867d5a2LL, 0x3bd85e12cLL, 0x1ec2946e2LL, 0x26147526cLL, 0x88e5cee33LL, 0xa62d51c5bLL, 0xb12822daaLL, 0xb87a03934LL, 0xcac6b560dLL, 0xce6fa5bd2LL, 0x34e9efd5eLL, 0x3fe4c0eadLL, 0x6f78f59aeLL, 0x76cad6538LL, 0x97bb49925LL, 0xcea15efb0LL, 0xd24a4f575LL, 0xd5f33fb3aLL, 0x01de84076LL, 0x3c6d89cc6LL, 0x4b114b3daLL, 0x6858ce202LL, 0x8949415efLL, 0x9b95f32c8LL, 0xd27c08953LL, 0xd624f8f18LL, 0xd9cde94ddLL, 0x4b43047b8LL, 0x90ccdb557LL, 0xbcb81fa93LL, 0xe4fa73a0aLL, 0x0993d73bcLL, 0x39280bebdLL, 0x89acb3dabLL, 0x90fe94935LL, 0xda315bc99LL, 0xddda4c25eLL, 0x40aba5e25LL, 0xb5c9b16c5LL, 0xb972a1c8aLL, 0xcbbf53963LL, 0xda6315077LL, 0x02a568feeLL, 0x09f749b78LL, 0x1fecebe16LL, 0x2e90ad52aLL, 0x4bd830352LL, 0x5a7bf1a66LL, 0x950af76b6LL, 0xaea989f19LL, 0xf08a706f3LL, 0x201ea51f4LL, 0x23c7957b9LL, 0x4c09e9730LL, 0x5704ba87fLL, 0x77f52dc6cLL, 0xa7896276dLL, 0xb62d23e81LL, 0x0a5abc334LL, 0x623144dacLL, 0x9cc04a9fcLL, 0x242b07f75LL, 0x32cec9689LL, 0xa7ecd4f29LL, 0xc18b6778cLL, 0x07153e52bLL, 0x0e671f0b5LL, 0x8ad70b4dfLL, 0xbe14305a5LL, 0xc1bd20b6aLL, 0xe9ff74ae1LL, 0x4cd0ce6a8LL, 0x62c670946LL, 0x7c65031a9LL, 0x960395a0cLL, 0xafa22826fLL, 0x0eca91871LL, 0x3363f5223LL, 0x5ba64919aLL, 0xd816355c4LL, 0x164e2b7d9LL, 0x2148fc928LL, 0x87c346ab4LL, 0xd49efe3ddLL, 0x9a41b1b6bLL, 0xa193926f5LL, 0xb03753e09LL, 0x37a211382LL, 0x4645d2a96LL, 0x673645e83LL, 0xb411fd7acLL, 0x4a207c439LL, 0x96fc33d62LL, 0x9e4e148ecLL, 0x3f57646c8LL, 0x46a945252LL, 0x81384aea2LL, 0x972ded140LL, 0xa97a9ee19LL, 0xca6b12206LL, 0x29937b808LL, 0x6f1d525a7LL, 0x766f33131LL, 0x177882f0dLL, 0x1eca63a97LL, 0x55b079122LL, 0x8c968e7adLL, 0xb881d2ce9LL, 0xbc2ac32aeLL, 0xd2206554cLL, 0x22a50d43aLL, 0x2d9fde589LL, 0x3fec90262LL, 0x60dd0364fLL, 0xbc5c7c68cLL, 0x64b7acff2LL, 0x9f46b2c42LL, 0x59ee95281LL, 0x6c3b46f5aLL, 0xaa733d16fLL, 0x2a8c19b5eLL, 0x31ddfa6e8LL, 0xb59fc769cLL, 0xf780ade76LL, 0x06246f58aLL, 0x56a917478LL, 0x7047a9cdbLL, 0x91381d0c8LL, 0xda6ae442cLL, 0x61d5a19a5LL, 0xa3b68817fLL, 0xb25a49893LL, 0xc4a6fb56cLL, 0xd6f3ad245LL, 0xde458ddcfLL, 0x1182b2e95LL, 0x2eca35cbdLL, 0x327326282LL, 0x4c11b8ae5LL, 0x570c89c34LL, 0x5ab57a1f9LL, 0xcfd385a99LL, 0xcc5c4e8b2LL, 0xff9973978LL, 0xa7f4a42deLL, 0xdedab9969LL, 0x1d12afb7eLL, 0x74e9385f6LL, 0x99829bfa8LL, 0xc916d0aa9LL, 0xd7ba921bdLL, 0x0af7b7283LL, 0x2f911ac35LL, 0x6dc910e4aLL, 0x8767a36adLL, 0xb352e7be9LL, 0xd4435afd6LL, 0x2c19e3a4eLL, 0x2fc2d4013LL, 0x6a51d9c63LL, 0xea6ab6652LL, 0xf1bc971dcLL, 0xfcb76832bLL, 0x49931fc54LL, 0xa8bb89256LL, 0x3b211791eLL, 0x4272f84a8LL, 0xbee2e48d2LL, 0xd4d886b70LL, 0x2caf0f5e8LL, 0x3b52d0cfcLL, 0x5fec346aeLL, 0x932959774LL, 0x16eb26728LL, 0x76138fd2aLL, 0xd53bf932cLL, 0x9adeacabaLL, 0x3f90ece5bLL, 0x4a8bbdfaaLL, 0x901594d49LL, 0xbfdb82c28LL, 0x17b20b6a0LL, 0x143ad44b9LL, 0x2dd966d1cLL, 0x61168bde2LL, 0xa6a062b81LL, 0xcee2b6af8LL, 0xe8814935bLL, 0x0d1aacd0dLL, 0x7ae6d7a23LL, 0xd2bd6049bLL, 0xe8b302739LL, 0xf3add3888LL, 0x05fa85561LL, 0x567f2d44fLL, 0xdde9ea9c8LL, 0xe192daf8dLL, 0xf7887d22bLL, 0x77a159c1aLL, 0x94e8dca42LL, 0xa38c9e156LL, 0x7b7c035bdLL, 0xc857baee6LL, 0x44c7a7310LL, 0x6d09fb287LL, 0x745bdbe11LL, 0x8a517e0afLL, 0xa79900ed7LL, 0xb66e7b9c9LL, 0xcc641dc67LL, 0x1596e4fcbLL, 0x661b8ceb9LL, 0x8ab4f086bLL, 0xa453830ceLL, 0x8ae6a9c49LL, 0x0ea876bfdLL, 0x3341da5afLL, 0x5f2d1eaebLL, 0xea40cc629LL, 0x5bb5e7904LL, 0xa4e8aec68LL, 0xac3a8f7f2LL, 0xb73560941LL, 0xbade50f06LL, 0xbe87414cbLL, 0xc23031a90LL, 0xcd2b02bdfLL, 0x6a8b623f6LL, 0x6e34529bbLL, 0x8f24c5da8LL, 0x9dc8874bcLL, 0xa17177a81LL, 0xdfa96dc96LL, 0x511e88f71LL, 0x96a85fd10LL, 0xd4e055f25LL, 0xead5f81c3LL, 0x933128b29LL, 0xcdc02e779LL, 0x0fa114f53LL, 0x72726eb1aLL, 0x970bd24ccLL, 0x0880ed7a7LL, 0x973d8b8aaLL, 0xeb6b23d5dLL, 0x1aff5885eLL, 0x1ea848e23LL, 0x29a319f72LL, 0x852292fafLL, 0x88cb83574LL, 0x0c8d50528LL, 0x3126b3edaLL, 0xf320770a3LL, 0x4af6ffb1bLL, 0x4e9ff00e0LL, 0x5d43b17f4LL, 0x733953a92LL, 0x9080d68baLL, 0xa67678b58LL, 0xdd5c8e1e3LL, 0x22e664f82LL, 0x05d09b538LL, 0x14745cc4cLL, 0x8d3b58ab1LL, 0xd66e1fe15LL, 0x40915a566LL, 0x4b8c2b6b5LL, 0x911602454LL, 0xe5439a907LL, 0xe1cc63720LL, 0x5a935f585LL, 0x7431f1de8LL, 0x7b83d2972LL, 0x8dd08464bLL, 0xa76f16eaeLL, 0xde552c539LL, 0x153b41bc4LL, 0x2787f389dLL, 0x98fd0eb78LL, 0xaef2b0e16LL, 0x2b629d240LL, 0x0aa3e3231LL, 0x836adf096LL, 0xb2ff13b97LL, 0xd79877549LL, 0xf888ea936LL, 0x540863973LL, 0x62ac25087LL, 0xc9266f213LL, 0xd42140362LL, 0x877741e17LL, 0x3e7633e91LL, 0x50c2e5b6aLL, 0x12bca8d33LL, 0x758e028faLL, 0x92d585722LL, 0x12ee62111LL, 0xbb4992a77LL, 0xc9ed5418bLL, 0xd4e8252daLL, 0x6af6a3f67LL, 0x76232e494LL, 0xb45b246a9LL, 0xc6a7d6382LL, 0x3bc5e1c22LL, 0x640835b99LL, 0x8c4a89b10LL, 0x8ff37a0d5LL, 0xa2402bdaeLL, 0x437b34f68LL, 0x646ba8355LL, 0x6bbd88edfLL, 0xc39411957LL, 0xcae5f24e1LL, 0xf32846458LL, 0x8cdfb56aaLL, 0x9088a5c6fLL, 0xadd028a97LL, 0xe4b63e122LL, 0x094fa1ad4LL, 0x17f3631e8LL, 0x40677053dLL, 0x0d5c04855LL, 0xa71373aa7LL, 0x0292ecae4LL, 0x1136ae1f8LL, 0x8dd853a00LL, 0xb61aa7977LL, 0x363384366LL, 0x5723f7753LL, 0xf48456f6aLL, 0xdec06e0aaLL, 0x0aabb25e6LL, 0xa80c11dfdLL, 0xf890b9cebLL, 0x3a71a04c5LL, 0x7157b5b50LL, 0xdb7af02a1LL, 0x57eadc6cbLL, 0xac1874b7eLL, 0x3ad512c81LL, 0x2c630a94bLL, 0x87e283988LL, 0x169f21a8bLL, 0x7d196bc17LL, 0x1e22bb9f3LL, 0xd8ca9e032LL, 0x1e862e1afLL, 0xbbe68d9c6LL, 0xce64f8a7dLL, 0x8cb5cb681LL, 0xce96b1e5bLL, 0x057cc74e6LL, 0x64d6e9ec6LL, 0x687fda48bLL, 0xd64c051a1LL, 0x2327bcacaLL, 0x31cb7e1deLL, 0x7afe45542LL, 0x7ea735b07LL, 0xddcf9f109LL, 0x2aab56a32LL, 0x56969af6eLL, 0x029abbe99LL, 0x61c32549bLL, 0x656c15a60LL, 0xcf8f501b1LL, 0xde64caca3LL, 0xf45a6cf41LL, 0x9cb59d8a7LL, 0x5b06704abLL, 0x6d5322184LL, 0xbdd7ca072LL, 0x48eb77bb0LL, 0x4c9468175LL, 0xc55b63fdaLL, 0xd7a815cb3LL, 0x20dadd017LL, 0x6a0da437bLL, 0xea2680d6aLL, 0x19bab586bLL, 0xdbb478a34LL, 0x50d2842d4LL, 0x6350ef38bLL, 0x54dee7055LL, 0x2d000589aLL, 0x4a47886c2LL, 0xad18e2289LL, 0xf9f499bb2LL, 0x1e8dfd564LL, 0x2988ce6b3LL, 0x9afde998eLL, 0x76963f3baLL, 0xebb44ac5aLL, 0xe83d13a73LL, 0x0cd677425LL, 0x52604e1c4LL, 0x9f3c05aedLL, 0xaa36d6c3cLL, 0xbc8388915LL, 0xcb274a029LL, 0x7b06148f7LL, 0xc46a95039LL, 0x9c59fa4a0LL, 0xb9a17d2c8LL, 0x39ba59cb7LL, 0xc4ce077f5LL, 0xf0b94bd31LL, 0x3a1dcc473LL, 0x57654f29bLL, 0x2f866dae0LL, 0x57c8c1a57LL, 0xdb8a8ea0bLL, 0x423691f75LL, 0x66cff5927LL, 0xcd4a3fab3LL, 0xe71a8b6f4LL, 0x21a991344LL, 0x304d52a58LL, 0x6733680e3LL, 0x307f0be36LL, 0xb440d8deaLL, 0xfd73a014eLL, 0x3459b57d9LL, 0x3f5486928LL, 0xe46a39485LL, 0xd9d2daaf2LL, 0xe8a8555e4LL, 0xa35037c23LL, 0xc472643eeLL, 0x239acd9f0LL, 0xb9db05a5bLL, 0xcc27b7734LL, 0x364af1e85LL, 0xc8b08054dLL, 0x8e84ed0b9LL, 0x36e01da1fLL, 0xafa719884LL, 0xbb055d18fLL, 0xf93d533a4LL, 0x6ab26e67fLL, 0xe3796a4e4LL, 0xf21d2bbf8LL, 0x464ac40abLL, 0xe75413e87LL, 0x676cf0876LL, 0xe785cd265LL, 0xdcbcb54f4LL, 0x5cd591ee3LL, 0xb1032a396LL, 0xa9e302beaLL, 0xb886c42feLL, 0x523e33550LL, 0xb50f8d117LL, 0x1b89d72a3LL, 0x1bbb90681LL, 0xf753e60adLL, 0x4f2a6eb25LL, 0x03159c174LL, 0x06be8c739LL, 0xd03be986aLL, 0x0acaef4baLL, 0x7fe8fad5aLL, 0x50867f637LL, 0x78c8d35aeLL, 0x2875e4a9eLL, 0x78fa8c98cLL, 0xac37b1a52LL, 0xb0125b3f5LL, 0xa54943684LL, 0xa1d20c49dLL, 0xd8e9daf06LL, 0xdcc4848a9LL, 0xf6631710cLL, 0x851fb520fLL, 0xa9b918bc1LL, 0xb13cb2b29LL, 0xef74a8d3eLL, 0xf6c6898c8LL, 0xaa1c8b37dLL, 0xb5175c4ccLL, 0x64c46d9bcLL, 0xcee7a810dLL, 0x05cdbd798LL, 0xfb04a5a27LL, 0x73fd5ac6aLL, 0xecc456acfLL, 0x56e791220LL, 0x693442ef9LL, 0xc10acb971LL, 0x44cc98925LL, 0x5ac23abc3LL, 0x7bb2adfb0LL, 0x2064ee351LL, 0x4c81ebc6bLL, 0xaf84fec10LL, 0xa112f68daLL, 0x078d40a66LL, 0xa144afcb8LL, 0xb73a51f56LL, 0xe6ce86a57LL, 0xf94cf1b0eLL, 0x7213ed973LL, 0xfd595488fLL, 0xb45846909LL, 0x1b3603251LL, 0x90540eaf1LL, 0xebd387b2eLL, 0x8933e7345LL, 0xb8c81be46LL, 0x4b2daa50eLL, 0xe13c2919bLL, 0x4c2648864LL, 0xb64982fb5LL, 0xa0e90c8b1LL, 0x5f39df4b5LL, 0xac1596ddeLL, 0xf5485e142LL, 0xc9f2457a0LL, 0x60327d80bLL, 0x225df9db2LL, 0x35a349de1LL, 0xb5bc267d0LL, 0x9c8106729LL, 0xa029f6ceeLL, 0xaecdb8402LL, 0x44dc3708fLL, 0x0e27dade2LL, 0x48b6e0a32LL, 0x9d16322c3LL, 0x5f0ff548cLL, 0x3010ec525LL, 0x0f83eb8f4LL, 0x1e27ad008LL, 0x9345b88a8LL, 0xa24cec778LL, 0x4e510d6a3LL, 0xb8d7ba5b0LL, 0x1f83bdb1aLL, 0x53560e77aLL, 0xed0d7d9ccLL, 0x78b6570a4LL, 0x07a4ae585LL, 0x498594d5fLL, 0x9a0a3cc4dLL, 0xdc1cdc805LL, 0xe717ad954LL, 0xa1bf8ff93LL, 0xb063516a7LL, 0xc6bc66101LL, 0xd93ad11b8LL, 0xe435a2307LL, 0xe7de928ccLL, 0x60a58e731LL, 0x769b309cfLL, 0x0ca9af65cLL, 0x97bd5d19aLL, 0x560e2fd9eLL, 0x1f59d3af1LL, 0xbcebec6e6LL, 0x14f42e53cLL, 0xb62f376f6LL, 0xe31319f88LL, 0x66d4e6f3cLL, 0x6e26c7ac6LL, 0xee3fa44b5LL, 0x80a532b7dLL, 0xe3768c744LL, 0xd15b93e49LL, 0xb09cd9e3aLL, 0x642494ccdLL, 0xf6ed95b51LL, 0x7769e4cfcLL, 0x779b9e0daLL, 0x3995612a3LL, 0xbd572e257LL, 0x0a32e5b80LL, 0x5ae946e4cLL, 0x8e266bf12LL, 0x36819c878LL, 0x41ae26da5LL, 0x0af9caaf8LL, 0x542c91e5cLL, 0x57d582421LL, 0x6a22340faLL, 0xac668d090LL, 0x6e6050259LL, 0xbb3c07b82LL, 0xee792cc48LL, 0xb072efe11LL, 0xbf486a903LL, 0x88940e656LL, 0xa98481a43LL, 0x7a53bf6feLL, 0x40bd57e04LL, 0x2ea25f509LL, 0x745def686LL, 0xc88b87b39LL, 0xc8bd40f17LL, 0x9d356f197LL, 0xf8b4e81d4LL, 0x0b0199eadLL, 0x1d4e4bb86LL, 0x78cdc4bc3LL, 0x54661a5efLL, 0x79313737fLL, 0x3ed3eab0dLL, 0x6f2f04586LL, 0x9b4c01ea0LL, 0x4b2acc76eLL, 0x52e01fab4LL, 0x9c12e6e18LL, 0x2acf84f1bLL, 0xc0de03ba8LL, 0x362dc8826LL, 0x15a0c7bf5LL, 0xd07a63612LL, 0x57e520b8bLL, 0x2c2b95a2dLL, 0x0f47853c1LL, 0x465f53e2aLL, 0xa96266dcfLL, 0xf32a59ccdLL, 0xd6a9bbe1dLL, 0x5e1479396LL, 0x39accedc2LL, 0xbd6e9bd76LL, 0x5ea9a4f30LL, 0x4c8eac635LL, 0xa83fdea50LL, 0xafc3789b8LL, 0x0b42f19f5LL, 0x1dc15caacLL, 0x6acecd7b3LL, 0x135bb74f7LL, 0x3b9e0b46eLL, 0x34af9d0a0LL, 0x76908387aLL, 0xb9384efccLL, 0x4b9ddd694LL, 0x8a078cc87LL, 0xd7aa29528LL, 0x073e5e029LL, 0x24b79a22fLL, 0x3f4ecade8LL, 0xd9063a03aLL, 0xce3d222c9LL, 0x226aba77cLL, 0x93dfd5a57LL, 0xb1bc84419LL, 0xb90e64fa3LL, 0x52f78d5d3LL, 0xbd4c81102LL, 0x2ec19c3ddLL, 0x8352a704cLL, 0xbde1acc9cLL, 0x875f09dcdLL, 0xd49e33eb2LL, 0x5fe39adceLL, 0x638c8b393LL, 0xb099fc09aLL, 0xdc85405d6LL, 0x42ff8a762LL, 0x6ba550e95LL, 0xd9717bbabLL, 0x10894a614LL, 0x5d6501f3dLL, 0x445b9b274LL, 0x89e572013LL, 0x11502f58cLL, 0x533115d66LL, 0x98baecb05LL, 0x95a7280daLL, 0xdfa0d43b6LL, 0xc28b0a96cLL, 0xe7246e31eLL, 0x046bf1146LL, 0x3b52067d1LL, 0x601d23561LL, 0x08dbc6683LL, 0x13d6977d2LL, 0x29cc39a70LL, 0x105f605ebLL, 0x3c4aa4b27LL, 0x736273590LL, 0x985f496feLL, 0xec8ce1bb1LL, 0x9fe2e3666LL, 0x065d2d7f2LL, 0x91d44daecLL, 0xa7c9efd8aLL, 0x3a2f7e452LL, 0x6d9e5c8f6LL, 0xa0db819bcLL, 0xf50919e6fLL, 0x667e3514aLL, 0x9393d0dbaLL, 0x614f4a04aLL, 0x77da17e82LL, 0xc8f3eb90aLL, 0xa4bdfa714LL, 0x967dab7bcLL, 0xf22eddbd7LL, 0x8be64ce29LL, 0xb1dbc12edLL, 0xd6a6de07dLL, 0x690c6c745LL, 0xb5e82406eLL, 0x484db2736LL, 0x46328c061LL, 0xad10489a9LL, 0x9af5500aeLL, 0xd9c271e5dLL, 0xe4bd42facLL, 0x3198fa8d5LL, 0xd9f42b23bLL, 0x7ea66b5dcLL, 0xcf2b134caLL, 0xe1a97e581LL, 0x535052c3aLL, 0x37016e168LL, 0x7cbcfe2e5LL, 0xa1881b075LL, 0x42916ae51LL, 0x884cfafceLL, 0x3bd4b5e61LL, 0x72ec848caLL, 0xb187ed29bLL, 0x279e96e91LL, 0x07434f63eLL, 0xf17f6677eLL, 0x19f373ad3LL, 0x58c095882LL, 0xc315893b1LL, 0x0559e2347LL, 0x38970740dLL, 0xfecee6735LL, 0x2054856bcLL, 0x994d3a8ffLL, 0x9607bcaf6LL, 0xe00168dd2LL, 0x25eeb232dLL, 0x1ece8ab81LL, 0x2ece5cda7LL, 0x82fbf525aLL, 0xb388c80b1LL, 0xf569ae88bLL, 0x8f52d6ebbLL, 0x58d033fecLL, 0xfd827438dLL, 0x3f9513f45LL, 0xf6c5bf39dLL, 0x6491ea0b3LL, 0xebfca762cLL, 0x736764ba5LL, 0xa707fc427LL, 0x44685bc3eLL, 0x3a02b6689LL, 0x5404bb6a8LL, 0xf50e0b484LL, 0x2505b2741LL, 0xb0ae8be19LL, 0xf2c12b9d1LL, 0x46eec3e84LL, 0x053f96a88LL, 0xd5dd1b365LL, 0x2a6e25fd4LL, 0x3911e76e8LL, 0xe1d08a80aLL, 0x39d8cc660LL, 0x3a0a85a3eLL, 0x91e10e4b6LL, 0xf85b58642LL, 0xe2976f782LL, 0x3e16e87bfLL, 0xccd3868c2LL, 0x8f30bc247LL, 0xd51e057a2LL, 0xb839f5136LL, 0x2355cdbddLL, 0xa591a0056LL, 0xfd6828aceLL, 0xca8e761c4LL, 0x435572029LL, 0x7e1631057LL, 0xaa332e971LL, 0xb1b6c88d9LL, 0xaafa138e9LL, 0x92b791b98LL, 0xfd0c856c7LL, 0xe4984a598LL, 0xe121133b1LL, 0xda32a4fe3LL, 0x40dea854dLL, 0xab970e838LL, 0x1d0c29b13LL, 0x454e7da8aLL, 0x039f5068eLL, 0x7c98058d1LL, 0xb37e1af5cLL, 0x6769485abLL, 0x58f740275LL, 0x3fedd95acLL, 0x1f9291d59LL, 0x7b757d552LL, 0x95daf4d2dLL, 0x4930f67e2LL, 0xea3a465beLL, 0xd949a53f7LL, 0x2da8f6c88LL, 0x6117d512cLL, 0x736486e05LL, 0x7e5f57f54LL, 0x689b6f094LL, 0x53093f5b2LL, 0xc107236a6LL, 0x74c097917LL, 0xe28cc262dLL, 0xbaade0e72LL, 0xcd2c4bf29LL, 0x8f260f0f2LL, 0xb79a1c447LL, 0xd2c678b9aLL, 0x5e0bdfab6LL, 0x864e33a2dLL, 0x40f61606cLL, 0x98fe57ec2LL, 0xe5da0f7ebLL, 0x783f9deb3LL, 0x072df5394LL, 0x2f704930bLL, 0x4565eb5a9LL, 0x0f7874274LL, 0x6ea0dd876LL, 0x9e3512377LL, 0xab52d8f50LL, 0x2f14a5f04LL, 0xb6e2d5c39LL, 0x6e1381091LL, 0xe73def6b2LL, 0x93a582d99LL, 0x2d8eab3c9LL, 0x0644f57a8LL, 0xa408c777bLL, 0x0a8311907LL, 0x41cc9974eLL, 0x6a40a6aa3LL, 0xcd43b9a48LL, 0x12cd907e7LL, 0x54ae76fc1LL, 0xb532f10d5LL, 0x6888f2b8aLL, 0xa349b1bb8LL, 0xb2b458244LL, 0x75118dbc9LL, 0xe686a8ea4LL, 0x3e5d3191cLL, 0x6702f804fLL, 0xb3deaf978LL, 0x931ff5969LL, 0xb06778791LL, 0xe81472d94LL, 0x3178f34d6LL, 0x70a987a41LL, 0x5393bdff7LL, 0x8add45e3eLL, 0xf5323996dLL, 0x19fd566fdLL, 0xf1ecbbb64LL, 0x13a413ec9LL, 0xae2268093LL, 0x567d989f9LL, 0xcbff16a55LL, 0x246acb067LL, 0x8b48879afLL, 0x929a68539LL, 0x4d7403f56LL, 0x6aed4015cLL, 0xb82c6a241LL, 0xb10c42a95LL, 0xb4b53305aLL, 0x4ac3b1ce7LL, 0x2722ec68bLL, 0x20c9a9e57LL, 0x493db71acLL, 0xeb3fa52deLL, 0xe8f2c582bLL, 0x32258cb8fLL, 0x89fc15607LL, 0x96213de8aLL, 0x297f6a8a8LL, 0x6bf57cc1cLL, 0xb559fd35eLL, 0xc0868788bLL, 0x09eb07fcdLL, 0xc0e9fa047LL, 0x076c6f13cLL, 0xbf008cd50LL, 0xad1f1cbe8LL, 0x60d890e59LL, 0x98e8fdc18LL, 0xf21b971a2LL, 0x05f612d6bLL, 0x65503574bLL, 0x2e9bd949eLL, 0xed1e65480LL, 0x1cb299f81LL, 0xc164da322LL, 0xfc2599350LL, 0x88c710d7eLL, 0xae27596a8LL, 0xa0adef6c8LL, 0x8b1bbfbe6LL, 0x9a22f3ab6LL, 0xa6481c339LL, 0x4ea34cc9fLL, 0xcb76ab885LL, 0xb0521e4e7LL, 0x3b65cc025LL, 0xbf8b0b795LL, 0xe9297021eLL, 0x70c5e6b75LL, 0x1cca07aa0LL, 0x0e89b8b48LL, 0xee2e712f5LL, 0x0ba7ad4fbLL, 0x21cf08b77LL, 0xeec39ce8fLL, 0x6194c8c7cLL, 0x63544bf4aLL, 0x045d9bd26LL, 0xfd6f2d958LL, 0x5d2cc2af4LL, 0x8cf2b09d3LL, 0xcf68c2d47LL, 0xf218b9402LL, 0x7d5e2031eLL, 0xa2293d0aeLL, 0x819c3c47dLL, 0xaa73bbf8eLL, 0x14c8afabdLL, 0x673e94057LL, 0x6ef3e739dLL, 0x4eca58f28LL, 0x536be7843LL, 0x06c1e92f8LL, 0x44f9df50dLL, 0x4ff4b065cLL, 0x075714e92LL, 0xee4dae1c9LL, 0xb4b7468cfLL, 0xc0dc6f152LL, 0xac42dd9c6LL, 0x799ae449aLL, 0x08ecae137LL, 0x69a2e1629LL, 0xfd32c7425LL, 0xb431b949fLL, 0xfa82751b6LL, 0xe553b7e90LL, 0xd529fbc41LL, 0x457c8eb9dLL, 0xac2892107LL, 0xb034f4e88LL, 0xb7ea481ceLL, 0xd90c74999LL, 0x903d1fdf1LL, 0x73590f785LL, 0xf1250c6c1LL, 0x03a377778LL, 0x751892a53LL, 0x83bc54167LL, 0x8c388c425LL, 0xbf75b14ebLL, 0xc3821426cLL, 0xb5d6f0eaeLL, 0x249bb9f1aLL, 0xe5ac7d4f7LL, 0xdebe0f129LL, 0x5b5fb4931LL, 0x07f9013f6LL, 0x54d4b8d1fLL, 0xeab94d983LL, 0x28f143b98LL, 0x6b6755f0cLL, 0xca0262d29LL, 0x85712a2e0LL, 0x89af4643fLL, 0xa7ef675bdLL, 0xb7285486bLL, 0xc6f66d6b3LL, 0x2dd429ffbLL, 0x9f49452d6LL, 0x396426ce4LL, 0xdeb361fd4LL, 0x4219e7735LL, 0x0debf36ceLL, 0xe4b8d07b6LL, 0xb8402fa95LL, 0x73e0b042aLL, 0xc8d52d855LL, 0x16145793aLL, 0xd15165b13LL, 0x1a842ce77LL, 0x5329c57d0LL, 0x27a1f3a50LL, 0x0abde33e4LL, 0x82309daecLL, 0x396148f44LL, 0xda6a98d20LL, 0x8eeaf1f09LL, 0x6394d9567LL, 0xacc7a08cbLL, 0xd59f203dcLL, 0x9d64c95f4LL, 0x5f9045b9bLL, 0x3f0344f6aLL, 0x1035f53e1LL, 0xd9e50b8f0LL, 0x74635fabaLL, 0x7248393e5LL, 0x25cff4278LL, 0x590d1933eLL, 0x6407ea48dLL, 0xa306c561aLL, 0x1b4064c9aLL, 0x715f397f9LL, 0x6a3f1204dLL, 0x840f5dc8eLL, 0x6350a3c7fLL, 0x12fdb516fLL, 0x9ed847c25LL, 0x38f329633LL, 0x5a470f1dcLL, 0x4ccda51fcLL, 0x666c37a5fLL, 0xc2e44edf2LL, 0xf6e858e30LL, 0x6517f6302LL, 0x53f59bd5dLL, 0xba6fe5ee9LL, 0x25bd77d6eLL, 0xb4dd8862dLL, 0x439a26730LL, 0x85acc62e8LL, 0x56adbd381LL, 0xb3ecb968cLL, 0xb0a73b883LL, 0x7b1d36d0aLL, 0xa3f4b681bLL, 0x02c17ca16LL, 0x98a61167aLL, 0x57ef825d4LL, 0x79436817dLL, 0xd119f0bf5LL, 0x4669b5873LL, 0x0fb5595c6LL, 0x3fad00883LL, 0x3c6782a7aLL, 0xdd70d2856LL, 0x18634ac62LL, 0x235e1bdb1LL, 0x831bb0f4dLL, 0x8edd67014LL, 0x0657f0ad1LL, 0xa41bc2aa4LL, 0xdeaac86f4LL, 0xdbc8bd0a7LL, 0x75b1e56d7LL, 0x51adad8bfLL, 0x5a5b9ef5bLL, 0x6efcffa9cLL, 0xbbd8b73c5LL, 0xf2f085e2eLL, 0x1edbca36aLL, 0x494113d6bLL, 0x1635a8083LL, 0x1ad73699eLL, 0x038d52fa3LL, 0x8b29c98faLL, 0xc5b8cf54aLL, 0x67babd67cLL, 0x76c1f154cLL, 0x7b31c6a89LL, 0x2c6ca1e69LL, 0x25e97560cLL, 0x7a7a8027bLL, 0xae1b17afdLL, 0x5ef280721LL, 0x969f7ad24LL, 0x4e01df55aLL, 0xb47c296e6LL, 0x8d642cea3LL, 0xee4c19773LL, 0x1a375dcafLL, 0x46b7cdd85LL, 0x4e3b67cedLL, 0xa8669f5cdLL, 0x1eaf025a1LL, 0xc9f40d909LL, 0x896f37c41LL, 0xe46154499LL, 0xeb894affaLL, 0x01b0a6676LL, 0xaa3d903baLL, 0x286cffab2LL, 0xd944686d6LL, 0xeb911a3afLL, 0x4029f43d3LL, 0xc111850efLL, 0x5ea39dce4LL, 0x4eab9ae73LL, 0xd083fab30LL, 0xdfc4b7193LL, 0xab6509d4eLL, 0x1d3d977e5LL, 0xc9a52aeccLL, 0x957736e65LL, 0x95daa9621LL, 0xea0841ad4LL, 0xa859146d8LL, 0x0b8de0a5bLL, 0xf252c09b4LL, 0x8172d1273LL, 0xb88a9fcdcLL, 0x6993c1cdeLL, 0xcc96d4c83LL, 0xd1ff48516LL, 0xb1408e507LL, 0x097a8973bLL, 0x7496621e2LL, 0x03b672aa1LL, 0xdc3b03aa2LL, 0xae3498e91LL, 0xcf250c27eLL, 0x6160b091dLL, 0x96c0cb46dLL, 0xced13822cLL, 0x26d97a082LL, 0x8fda2c454LL, 0x9e85bcf1dLL, 0x689845be8LL, 0x06f143755LL, 0x9204f1293LL, 0x1d4a581afLL, 0xbee8d3b25LL, 0x8146094aaLL, 0x349c0af5fLL, 0xb1a8f22d8LL, 0x774ba5a66LL, 0x6ce6004b1LL, 0xf450bda2aLL, 0x930d2dd53LL, 0x68e16cae5LL, 0x8b91631a0LL, 0xb3d3b7117LL, 0x666aa3009LL, 0x5fadee019LL, 0x9de5e422eLL, 0x58bf7fc4bLL, 0xd52f6c075LL, 0x13fc8de24LL, 0xd6eeef343LL, 0x364911d23LL, 0x2d713665eLL, 0xa9e8f1e3dLL, 0x84c231ca6LL, 0xd9e8684afLL, 0xf72feb2d7LL, 0x5ea2d37b9LL, 0xfc66a578cLL, 0x812110a96LL, 0x936dc276fLL, 0x84fbba439LL, 0x17f67469bLL, 0xb7481055eLL, 0x96ecc8d0bLL, 0x8d7fc1aacLL, 0x0ec2f5bcfLL, 0xc24ab0a62LL, 0xd1839dd10LL, 0x8fd470914LL, 0x6cfa90230LL, 0x205091ce5LL, 0xdaf874324LL, 0xf15958133LL, 0x1158fc57fLL, 0xf0cbfb94eLL, 0xca17718c7LL, 0x18b2ac4beLL, 0xa92ecd88fLL, 0x228af528eLL, 0x774db92dbLL, 0x21fd98aa9LL, 0x8e7582062LL, 0xbb59648f4LL, 0xfd9dbd88aLL, 0x389035c96LL, 0x1114c6c97LL, 0xf49428de7LL, 0x669e6fc5cLL, 0x1dd6ea469LL, 0x882bddf98LL, 0xfed7b3728LL, 0x25309a3a8LL, 0xb04c1729bLL, 0xeb3e8f6a7LL, 0x7468cfeeeLL, 0x1a1b7d99aLL, 0x3eb4e134cLL, 0x43566fc67LL, 0xb1e97f8f5LL, 0xdb562afa0LL, 0xedd496057LL, 0x5ccb184a1LL, 0xe3da32613LL, 0x25ecd21cbLL, 0xdedd008f1LL, 0x45ec76617LL, 0x73fab05ddLL, 0xb2645fbd0LL, 0x78cdf82d6LL, 0x66e4b8db9LL, 0xc83017e45LL, 0x86b2a3e27LL, 0xc6dbd66e8LL, 0x00b395b2aLL, 0x1c11ab65bLL, 0x888994c14LL, 0x111ea98c1LL, 0xae86d848dLL, 0x54c6e271eLL, 0xb13ef9ab1LL, 0x2ed93d60fLL, 0xa4efe7205LL, 0xe70286dbdLL, 0xd2cc67dedLL, 0x2b0663021LL, 0x95f851a9fLL, 0xf67ccbbb3LL, 0x267c42225LL, 0x2be4b5ab8LL, 0x8a7fc28d5LL, 0x0e418f889LL, 0x1a34fed2eLL, 0x65590273eLL, 0x574a6cbc4LL, 0x3e0f4cb1dLL, 0xb7cee6cd8LL, 0x5627e4845LL, 0xadfe6d2bdLL, 0x568b57001LL, 0xd4ec7fad7LL, 0xad3f576faLL, 0x497d2eb92LL, 0x0fe6c7298LL, 0x16161faa3LL, 0x16799225fLL, 0xf30a85fe1LL, 0x52f9d455bLL, 0x130a2a42dLL, 0x598c9f522LL, 0x78c55e9f6LL, 0x7646c5b65LL, 0x7a53288e6LL, 0xb2c707e61LL, 0x134b81f75LL, 0x6d76b9855LL, 0x78a343d82LL, 0x2e4df469fLL, 0xf89236748LL, 0xf57e71d1dLL, 0x10dc8784eLL, 0x70fd8f1a6LL, 0x937bcc483LL, 0xf4c72b50fLL, 0x10ba6cbdaLL, 0x077f1ed59LL, 0x66d941739LL, 0x04ceccaeaLL, 0x015795903LL, 0xe53a6a20fLL, 0x3999bbaa0LL, 0x1281bf25dLL, 0x7337f274fLL, 0xcb40345a5LL, 0x68d24d19aLL, 0xd2fd56ca0LL, 0x0d30b94e9LL, 0xbb57cfe9eLL, 0xd74b11569LL, 0xe2db0e252LL, 0x5fe026216LL, 0xb47130e85LL, 0xfe076a9a5LL, 0x9415e9632LL, 0x3367854f5LL, 0x50af0831dLL, 0x49f25332dLL, 0x7739a837bLL, 0x099f36a43LL, 0xc8537be03LL, 0x3e06b323dLL, 0xf9a733bd2LL, 0x312a441acLL, 0x335508febLL, 0x7db227a83LL, 0x3ebb1bcabLL, 0x7a1106873LL, 0x5486d3f20LL, 0xa1628b849LL, 0xb64543ed2LL, 0xe293fabcaLL, 0xd1d512de1LL, 0x47884a21bLL, 0x4a406b83fLL, 0x7aa35466dLL, 0x6542ddf69LL, 0x348c210e9LL, 0x2aed60aacLL, 0xe9d35f24aLL, 0x2bbc14dd9LL, 0xf2891fc9bLL, 0x72a9cba3fLL, 0x409ecd462LL, 0x712ba02b9LL, 0x1b149ab0fLL, 0xaf6b65883LL, 0xf68306512LL, 0x20e84ff13LL, 0x88beaabb1LL, 0x7456d2803LL, 0xa04216d3fLL, 0x83f33226dLL, 0x394a0eb38LL, 0x65670c452LL, 0xa5903ed13LL, 0x473689a3eLL, 0x142b1dd56LL, 0x53bf24a7dLL, 0x88585a655LL, 0xe62c824faLL, 0x1bc6257ddLL, 0x266d228daLL, 0x9d18f806aLL, 0x26a6ab06dLL, 0xb90c39735LL, 0xd844f8c09LL, 0x4ebf14fbbLL, 0x5c720772eLL, 0xe033d46e2LL, 0x2d72fe7c7LL, 0x11878c4b1LL, 0xa075e3992LL, 0xf4dd045d8LL, 0x9caad8759LL, 0xf5b387cbaLL, 0x20dfb6633LL, 0xe7511e0eeLL, 0xc3e9e1225LL, 0xf6d332299LL, 0x43aee9bc2LL, 0x4882318bbLL, 0x958fa25c2LL, 0x6c9dd71f2LL, 0xda71d12bdLL, 0xead515c9fLL, 0x5622a7b24LL, 0xb1a220b61LL, 0x5e3b6d626LL, 0x95533c08fLL, 0xaf093c411LL, 0x364a0f961LL, 0x6dc550b86LL, 0x43cb48cf6LL, 0x01331bd0eLL, 0x55926d59fLL, 0xddfd98223LL, 0x509d0ac32LL, 0xdd3e82660LL, 0x72f15dee6LL, 0x114a5ba53LL, 0x70d637811LL, 0xbf7172408LL, 0xca9dfc935LL, 0x2b082b18aLL, 0x9e227de74LL, 0x084d8797aLL, 0xd91cc5635LL, 0xd9b9c0584LL, 0xe6a5cdd7fLL, 0x606567f3aLL, 0x30121d876LL, 0xed40680fbLL, 0x9e498a0fdLL, 0xf6e6f7aedLL, 0x7bd31c1d5LL, 0x7fadc5b78LL, 0x430399853LL, 0xd6937f64fLL, 0xe9755cec2LL, 0x336f0919eLL, 0x62d953c76LL, 0x6eccc311bLL, 0xa7725ba74LL, 0x6b2ba1f0bLL, 0xd9c680f4eLL, 0x0b4bf20fbLL, 0x7d247fb92LL, 0xe2dfb415bLL, 0xaa41eabb7LL, 0xdde282439LL, 0x19cd98b9bLL, 0xc169b393eLL, 0x7057af26bLL, 0x621760313LL, 0x091e4f51cLL, 0x712e3294dLL, 0xba60f9cb1LL, 0xcac43e693LL, 0x49ba92d03LL, 0x3ec790f69LL, 0x6b4fd03f4LL, 0x1753f131fLL, 0x140e73516LL, 0xb235b7ca5LL, 0x1d27a6723LL, 0x3102222ecLL, 0xc0b75e745LL, 0x3a1b554f9LL, 0xc313dc962LL, 0xa323d6c80LL, 0xccca0aabeLL, 0xa61580a37LL, 0xea4b16079LL, 0x6b2ad79e0LL, 0xb766b661aLL, 0xe22f727d7LL, 0xe4304d5edLL, 0x24376523aLL, 0xf853f00b3LL, 0x6592be5e4LL, 0x553748fb7LL, 0x6852aefbdLL, 0x73e2abca6LL, 0x5fb45c08bLL, 0x635d4c650LL, 0x0e0d2be1eLL, 0x60ee51f29LL, 0x38ddb7390LL, 0xa300f1ae1LL, 0x22efe44a7LL, 0x628bba583LL, 0x4b17ecb5fLL, 0x55c6b9011LL, 0xe1a14bac7LL, 0xe427b3d0dLL, 0x46100dce8LL, 0x04cc2245dLL, 0x84c2e41d8LL, 0x0919dcd26LL, 0x8d1d01822LL, 0x2e26515feLL, 0xf7ab7dae4LL, 0x7768b70ccLL, 0xe94913f18LL, 0x0f3e883dcLL, 0x3b8d3f0d4LL, 0xd67ea41c4LL, 0x99d477e9fLL, 0x3fb10f974LL, 0x02a370e93LL, 0x17768adb2LL, 0xd6329f527LL, 0x3bbc1a712LL, 0x1b052fab8LL, 0x1a4619ef5LL, 0x00b725dfcLL, 0x78f0c547cLL, 0xadbbb4432LL, 0xe1cf5cbdaLL, 0xd70644e69LL, 0xab4cb9d0bLL, 0x5fcd12ef4LL, 0xe396af25dLL, 0x2d9ff9ca3LL, 0x4ef3df84cLL, 0xc7ec94a8fLL, 0x6b18da2f5LL, 0xa63d0badfLL, 0xf91662835LL, 0x3410a9ff6LL, 0x7ed13b24aLL, 0xf95f89732LL, 0xce74b2901LL, 0x695679287LL, 0x4843eb226LL, 0x5a66b2ed6LL, 0xa86cc1f33LL, 0x16d5e7b98LL, 0x748025a14LL, 0x3397dd590LL, 0x7bafeb92aLL, 0xb45584283LL, 0xd54dc6a25LL, 0xaf2e68538LL, 0x220f32a8fLL, 0x44f8b18ddLL, 0x51814c91cLL, 0x8bb4af165LL, 0xbcd6adb56LL, 0x82e4a2e55LL, 0xcd4990ca2LL, 0xef32a23e5LL, 0x688ec9de4LL, 0x2aba4638bLL, 0x16f7382e1LL, 0xbdfe274eaLL, 0x2164acc4bLL, 0xaad044fdaLL, 0x64559f29aLL, 0x5a9c9339eLL, 0x6a0739a2aLL, 0x8f993b732LL, 0xa90de3f6cLL, 0xace88d90fLL, 0x36a7f9cf0LL, 0xdbef65c2bLL, 0x69bb34d8dLL, 0x6f095cd61LL, 0x3bdbd6405LL, 0x34600b852LL, 0x0d1e24fe6LL, 0xcc994f31eLL, 0xccfcc1adaLL, 0x106b721a4LL, 0xad3e751d6LL, 0xab0903242LL, 0xb60ba3746LL, 0xc5b7a191aLL, 0xc7da973a4LL, 0xf45b0747aLL, 0xba92e67a2LL, 0xb93ea5045LL, 0x011d2ac4cLL, 0x564361455LL, 0x420d42485LL, 0x47e0f7889LL, 0x110a80968LL, 0x7a3cec118LL, 0xd058e2ed7LL, 0x1dc9c639aLL, 0x42de0a027LL, 0xe5530907fLL, 0xaffabd8e4LL, 0xb08fe947eLL, 0x5ba33b408LL, 0xd5f80115dLL, 0xe6298c761LL, 0x893b86708LL, 0x85b1d3017LL, 0xf2ac6bc60LL, 0xfa9378384LL, 0x3f538c40bLL, 0x21b0661dcLL, 0xe762b80d4LL, 0x16f6ecbd5LL, 0x1264fca24LL, 0xf39f4e476LL, 0x51cc3b982LL, 0x757c9f748LL, 0x311d200ddLL, 0x2563393cbLL, 0x1b05631cbLL, 0x9a547cea2LL, 0x35fd287a0LL, 0x25460fd6cLL, 0x8d4e23de8LL, 0xd56e01537LL, 0x4714d5bf0LL, 0xce7f93169LL, 0xf16142c02LL, 0xf88939763LL, 0x42b49ee1dLL, 0x8495855f7LL, 0xade7e53e3LL, 0xea99e0abdLL, 0xd5a4abf2aLL, 0xe8868979dLL, 0xde8c25d59LL, 0x24796f2b4LL, 0x588d17a5cLL, 0x23446aa2bLL, 0xd7930a836LL, 0xa1ad628b6LL, 0x8502da9ddLL, 0x1abd85618LL, 0x044a252ffLL, 0xd33f9442dLL, 0x0711e508dLL, 0xb8548f822LL, 0x9298a3af1LL, 0x397d78086LL, 0x26d522fa6LL, 0x744606469LL, 0xab2c1baf4LL, 0x24568a115LL, 0x233bd114bLL, 0x68f7612c8LL, 0x391ef6edfLL, 0x03c6ab744LL, 0xe248dbb72LL, 0x7511dc9f6LL, 0x53309a668LL, 0x5438d7128LL, 0x57e1c76edLL, 0x61c9aec27LL, 0x4b1219026LL, 0x6d5e9cf25LL, 0x2242688caLL, 0xaa10985ffLL, 0x8454ac8ceLL, 0x23a648791LL, 0xb8d396be7LL, 0x482d2fc39LL, 0x62fde8f85LL, 0x84bd1069fLL, 0x1aa1a5303LL, 0x434f3adebLL, 0xc99f3f39aLL, 0x744f1eb68LL, 0x9cd2ca627LL, 0x472428c4eLL, 0xdbacacda0LL, 0x310c6bd3cLL, 0xa84d6d066LL, 0x6ba340d41LL, 0x7aaa74c11LL, 0xe21d5d0f3LL, 0x8e84f07daLL, 0x3b260c654LL, 0xdb704686dLL, 0xf197a1ee9LL, 0xcb4e599d3LL, 0x2c67ff681LL, 0xedaa7c03cLL, 0xb859ffc56LL, 0x320eeccbcLL, 0x8014fbd19LL, 0x32e57039eLL, 0x5e196e0ccLL, 0xa02c0dc84LL, 0x29f06b67aLL, 0xe48da0b64LL, 0x47f4262c5LL, 0x3abc13e2dLL, 0x57afc2c03LL, 0x9437d42b4LL, 0x57f8e9b00LL, 0xd0644255eLL, 0xb9f0e2245LL, 0xf68892060LL, 0x11b4ee7b3LL, 0x26f34a243LL, 0xd92e92d2eLL, 0xc3c36f4d5LL, 0x057a6bc86LL, 0xc1e1d1593LL, 0xf36f11af5LL, 0x926cd9966LL, 0x66fc75705LL, 0x6cc85b754LL, 0x373e56bdbLL, 0x9a7322f5eLL, 0x948cf1650LL, 0x11f57bdd0LL, 0x662314283LL, 0x8e2901cc7LL, 0x9a5dc8cb4LL, 0x3b6718a90LL, 0xfa4d1722eLL, 0x19d6cc9b4LL, 0x0fa2e07ddLL, 0xe0483446fLL, 0xcee973997LL, 0xcab326bedLL, 0x8653a7582LL, 0x07d8331edLL, 0x916db55a5LL, 0xac0cb5513LL, 0x445d66afeLL, 0x265e9d4c8LL, 0x543b1e0b0LL, 0xfc6c649edLL, 0x02a38c5adLL, 0xae31be812LL, 0x46f85eac3LL, 0x38b531dcbLL, 0x046cf24a5LL, 0xf77637b55LL, 0xf07d1c632LL, 0xe05b2f798LL, 0x10d5860e5LL, 0xe42b2bfe6LL, 0xbfc381a12LL, 0xad645382fLL, 0x762a6a152LL, 0x58336fed1LL, 0x5c88f9b4fLL, 0x64b15ddbbLL, 0x9cd938699LL, 0xf3c6c1525LL, 0x2362c53dbLL, 0xd40874c21LL, 0x2fc1763f1LL, 0xfbf6f4b46LL, 0xe9fb3911fLL, 0x692346b6dLL, 0x52e96efe7LL, 0xbe0d16e43LL, 0xcd144ad13LL, 0xd497e4c7bLL, 0x280b58b80LL, 0x443ff1d93LL, 0x2f528c5b5LL, 0x3ef6bb3d4LL, 0xb806de136LL, 0x9600a3394LL, 0x0bdae6a57LL, 0x7ac6bbd4cLL, 0x17364c5c2LL, 0xec5344b46LL, 0x0bf745b8bLL, 0x72718fd17LL, 0xe2fdab406LL, 0x7cc4b8dc2LL, 0x4f5379d4bLL, 0xde49a05e1LL, 0x5e9c05763LL, 0xed58a3866LL, 0x80535dac8LL, 0x6affa7d8eLL, 0x4e7f09edeLL, 0xee0a2e534LL, 0x7519486a6LL, 0xf9b9680f1LL, 0xabbb28449LL, 0x5a2396946LL, 0x7fd4d5522LL, 0x542319779LL, 0x3caf4bd55LL, 0xfd740a695LL, 0x68c96b8cfLL, 0xab1593c1aLL, 0x42b1dc797LL, 0x4acaa2299LL, 0x2e27e9775LL, 0x4f157edc2LL, 0xb068ad203LL, 0x437ad4f84LL, 0xb8e9d6ad6LL, 0xa6439526bLL, 0xbfe227aceLL, 0xd32f46eb2LL, 0x404bfa76fLL, 0xb7beb4e77LL, 0x1874e8369LL, 0x879d23b91LL, 0xd9bf340d9LL, 0x714131397LL, 0x16a00adf1LL, 0xb9b9d414dLL, 0x2631bd706LL, 0xa2a978ee5LL, 0xe8fa34bfcLL, 0xaf9d55a95LL, 0x70a649cbdLL, 0x754fa798dLL, 0x59cf771e8LL, 0x6814b7755LL, 0x36efdafc4LL, 0x305a3225dLL, 0xadf19801bLL, 0xa38bf2a66LL, 0x44de6973fLL, 0x62f4a0894LL, 0xcf4a6f1d9LL, 0x0b358593bLL, 0x18583db29LL, 0x2891984e2LL, 0x7702e90b0LL, 0x91a1e901eLL, 0x64ff5e2d4LL, 0xbf9da6adaLL, 0x02e26d17bLL, 0xf89c04a9aLL, 0x4b43a2412LL, 0x31de98342LL, 0x28c287395LL, 0xc3362e40aLL, 0xe5bc3aa9cLL, 0x9e48f6a06LL, 0x733435bacLL, 0xa43be8cdeLL, 0x5c653248cLL, 0xe2931bdc7LL, 0x02c4795f1LL, 0x62bb96f20LL, 0xb2f43a171LL, 0x19d1f6ab9LL, 0x433ea2164LL, 0x137da589aLL, 0x28fd58e72LL, 0x202d4cb62LL, 0xf03d74c5aLL, 0xf6112a05eLL, 0x1527ce8beLL, 0xd27556017LL, 0xf1bdb3c55LL, 0xc081699a5LL, 0xd8368ef11LL, 0xa1ed747d5LL, 0xd833b1171LL, 0x2e161f79dLL, 0xf2d7a26f4LL, 0xffb902d9aLL, 0x6c62a5731LL, 0x914cff395LL, 0x849a7a32dLL, 0x787d20e5fLL, 0x873080cddLL, 0x902f6862bLL, 0xa2ef2b22aLL, 0xbc6ba2e19LL, 0x27fa8c7e6LL, 0x3b7964fa8LL, 0x99d80b892LL, 0xa9d7ddab8LL, 0x0e6dabf62LL, 0x19b1a3faeLL, 0xdabcaba4bLL, 0x465086a2dLL, 0xaf9290947LL, 0x3f16139c2LL, 0xf5eb1ba13LL, 0x5be4c9d84LL, 0xb491d5edeLL, 0xecb1e1407LL, 0xe2bf4cd78LL, 0xe9ba7bb10LL, 0xbe6954783LL, 0xd3a7b0213LL, 0x50de815b5LL, 0xddc150b2bLL, 0xf83e35e25LL, 0x06bcfeb25LL, 0xd446be9d7LL, 0xb8f07825bLL, 0x0938b9c16LL, 0x5dc6e6ae5LL, 0x3d8adc166LL, 0x6deae71f4LL, 0x748581570LL, 0xf2d14fd9cLL, 0xde56fb4e4LL, 0x23852ee7cLL, 0x7663771e7LL, 0xac04e987fLL, 0x10c77faf2LL, 0x84f4bc3f1LL, 0xb54fd5e6aLL, 0x5b315ef54LL, 0x60cb8bbc5LL, 0xbd8cc9e55LL, 0xab5f55050LL, 0xdddd64553LL, 0x6cd38ade9LL, 0xf0f5ec7b9LL, 0x96da53643LL, 0x3bb39fc6dLL, 0x2b2884ad7LL, 0xaa26a84fcLL, 0x8a2bf56c5LL, 0xb68a4ab27LL, 0x4962ea115LL, 0xd4f9472e3LL, 0x975e4c01dLL, 0xa82cd2570LL, 0xb6433749fLL, 0x7234ae0e6LL, 0x14cbc7db2LL, 0x22d77fb8cLL, 0xac098f788LL, 0x7762cecbbLL, 0x2e715f49fLL, 0xa529f55f9LL, 0x935054846LL, 0x999c0c185LL, 0xf6a94f0b2LL, 0x6bdec8471LL, 0x290d12cf6LL, 0x73b35868bLL, 0x5e9c08e84LL, 0x35d427addLL, 0x4decbf805LL, 0xb1218bb88LL, 0xcf15a8069LL, 0x44d59fe6dLL, 0x48cf866e4LL, 0xd85fca129LL, 0xa81c1e1cfLL, 0x25be310e2LL, 0xe57ab2f62LL, 0x22c1da1d6LL, 0x6a2a71117LL, 0xd60d2eb36LL, 0x3f3f9a2e6LL, 0x6d1c1aeceLL, 0x9b831a4fbLL, 0xd64ba88deLL, 0x968db7b8eLL, 0x073910151LL, 0x3e5d9f584LL, 0x8fdae57c8LL, 0xb0cb58bb5LL, 0x8bc3d58f2LL, 0x01188bb85LL, 0x226c7172eLL, 0xed7f67b04LL, 0x63c7caad8LL, 0xf6768009dLL, 0x06e193e34LL, 0x2021a54f0LL, 0xd4437d532LL, 0x82ce066a3LL, 0x260bfdee8LL, 0x26b0c81ecLL, 0x081503c67LL, 0x18be917a6LL, 0x3aac944feLL, 0x5a91ed08bLL, 0xd93c3ca5eLL, 0x4ba9f608fLL, 0xf9d10ca44LL, 0x314c4dc69LL, 0x8acfdd4a5LL, 0x69e73946dLL, 0xa103f94ebLL, 0xe708b0565LL, 0x4ebcf058fLL, 0x3385e6ce7LL, 0xdbbc1ec39LL, 0xd13c2ddc5LL, 0x3df56eec6LL, 0x50fe589c2LL, 0x5e7f91d57LL, 0x411dc3670LL, 0xa1785375bLL, 0x8d710fdc9LL, 0xe767b052bLL, 0x950939ab0LL, 0x7b7767c17LL, 0x5d24ca58fLL, 0x409e70b9fLL, 0x02d1bc4fbLL, 0xddec53eacLL, 0xa05158be6LL, 0xb64eca239LL, 0x88794e4dbLL, 0x815926d2fLL, 0xa109e873eLL, 0x87b47cdd8LL, 0xc48d8473bLL, 0x4a2e11891LL, 0x355819bd2LL, 0x23f9590faLL, 0x95a7fcb68LL, 0x325115b71LL, 0x42d0b9687LL, 0xc63bd4849LL, 0xe6d873be4LL, 0xf48b66357LL, 0xb29fd2a28LL, 0x5cafd9507LL, 0x09b467b3dLL, 0xe2dae50a2LL, 0x0ba7b7a5eLL, 0x4b2172ec6LL, 0x49795d717LL, 0x6c9495943LL, 0xd257992c1LL, 0x96d7c46d0LL, 0x0266ae09dLL, 0x241b28662LL, 0xc1ee98d9fLL, 0x50132d568LL, 0x07d90455aLL, 0xc2e459355LL, 0x42bdf1a71LL, 0xc662953c6LL, 0x4cfdd40e7LL, 0xd5fe2a905LL, 0x5339ed2bcLL, 0xc9603561cLL, 0x47c64f707LL, 0x8110b2364LL, 0x1b3b324dcLL, 0xc665f1f85LL, 0x74299617eLL, 0x4216c87ecLL, 0xc675906efLL, 0x2dcb4f572LL, 0x6fd55584aLL, 0xa0c4d0932LL, 0x19ab0966bLL, 0x883e192f9LL, 0x5fa021f7bLL, 0x266d2ce3dLL, 0xe90bba30aLL, 0x782bcabc9LL, 0x6d40981e4LL, 0x5b98b080fLL, 0xc21fbb365LL, 0xc574d78d8LL, 0xb2b236f39LL, 0x80cb66e45LL, 0x669c9a05dLL, 0xbd6808275LL, 0x21f8e510aLL, 0x437ba62f1LL, 0xc5224cbd0LL, 0xcb441a4e6LL, 0x59aa067f7LL, 0xa9d51eb53LL, 0xdc294402dLL, 0x33abf8a53LL, 0x2bc9dd944LL, 0xc3f8742bbLL, 0xc72b75bbaLL, 0x17cf5a97cLL, 0x08f42434aLL, 0xec593abdbLL, 0x120a797b7LL, 0x6cdc8ec10LL, 0xd0a686b2dLL, 0x81a4fb9daLL, 0x44facf6b5LL, 0xbec238c25LL, 0x6c12019cdLL, 0x1aac292a8LL, 0xe88bd0a21LL, 0x959a41c81LL, 0x432c2ca9cLL, 0x6c0b7b962LL, 0x385867bd6LL, 0x8068a6bbbLL, 0x09a777181LL, 0xc27d59fe8LL, 0xa04074853LL, 0xa50631657LL, 0xba7b37adaLL, 0xd9872f1e5LL, 0x949f449aaLL, 0xd2aa72df6LL, 0xbcc9608d7LL, 0x93d9a8d7cLL, 0x5e5495818LL, 0xbc9bce5e3LL, 0xc3875ec11LL, 0x97ea32be7LL, 0x41c5a2548LL, 0xe64df88c0LL, 0x2e21d1372LL, 0x0630736adLL, 0x226cdbc75LL, 0x609746f95LL, 0xe7cd6d390LL, 0x3ee9d185aLL, 0xd8cd3e34aLL, 0xab785e407LL, 0x93addebf1LL, 0x854b75025LL, 0x26f1bfd50LL, 0x598394aa7LL, 0xdfdb6840bLL, 0x6ea7a4c78LL, 0x6b4faa965LL, 0xa7aaf424dLL, 0xc694d0ce4LL, 0xfdab0acf7LL, 0x582738889LL, 0xb30ea7f8cLL, 0xc1af8b900LL, 0xe26889dcfLL, 0x5ffd11dedLL, 0xf6b05ad7eLL, 0x35cb9503fLL, 0x8b86f73e2LL, 0x8d467a6b0LL, 0x91f7a7735LL, 0x214693632LL, 0x106d5ff8aLL, 0xb9cdef610LL, 0x3dfafe135LL, 0x0fa5b0ae7LL, 0x26cd7986eLL, 0xc6fd681c8LL, 0x6b4188c58LL, 0xa3ba597e8LL, 0x85f518945LL, 0xf365a0254LL, 0x2048b85bbLL, 0x0f3dcbb35LL, 0xd3e5031cdLL, 0x54de45ec8LL, 0x2af3dc7a2LL, 0xe08932e15LL, 0x7734ac9f1LL, 0x322d852e2LL, 0xcdbdf8b96LL, 0x806696a67LL, 0x8cd4e61e7LL, 0xe057f8856LL, 0x4d9e9613cLL, 0xb82f25c73LL, 0x93c8c49e9LL, 0x7aace1816LL, 0x646f619c5LL, 0x6aae5893aLL, 0x84d48be42LL, 0xe4a98eafdLL, 0xd7f42bcf5LL, 0xa8017604dLL, 0xcd715d0e1LL, 0x11abe3d38LL, 0xacd8e4e30LL, 0x623790ab0LL, 0x39f25ed99LL, 0x8aef091c2LL, 0x7a2574284LL, 0x108cb8578LL, 0xd7a2ea337LL, 0xf13e9edfaLL, 0x5a80a8d14LL, 0x748f6e6fdLL, 0x1e4ba118aLL, 0x546ce5112LL, 0x1703a322aLL, 0x894c63e47LL, 0x3f403b661LL, 0xed4d06757LL, 0x5b9902d5dLL, 0xdf86cd5afLL, 0x1ba88e704LL, 0x4f148ee08LL, 0x1eb0dbaafLL, 0xb377d99a9LL, 0xf480a804bLL, 0x477b4f4eaLL, 0x0a9c8c047LL, 0x7e4c0a8cbLL, 0x4a89583d5LL, 0x6fc78608bLL, 0x7b59965e9LL, 0x7dcaa4585LL, 0x4002e14f6LL, 0x14c436673LL, 0x98ed9cecdLL, 0x092ad5b7fLL, 0x19088d131LL, 0xdec2ae3deLL, 0x3ac6ea320LL, 0x4352c0d48LL, 0x47ad3bfdbLL, 0x469a523c6LL, 0xf529ccb4cLL, 0xf663c29eaLL, 0x9a225604aLL, 0xb71dd41d5LL, 0xee5201d72LL, 0xd06cb9ad0LL, 0x91b427aa0LL, 0x7ef2d044bLL, 0x61bfdd3a2LL, 0x33a4184e7LL, 0xc875c3536LL, 0x5c5e6e999LL, 0x8fb237053LL, 0x2143558aeLL, 0xe77b34bd6LL, 0xe5b1047b3LL, 0x729ad8bb3LL, 0x9d2efdbf2LL, 0x6a5d1a69dLL, 0xeab0c8b69LL, 0x24ced1108LL, 0x9488901ffLL, 0xbf910f4aeLL, 0xf89e416adLL, 0x9eb3973eaLL, 0x9fac35740LL, 0x1fc51212fLL, 0x2a106be25LL, 0xcd5bee55fLL, 0x4b78e174dLL, 0x231194dc2LL, 0xf094cec09LL, 0xbc94ebcb5LL, 0x9980b8913LL, 0xe6cca33c2LL, 0x4bcdb33ddLL, 0x1a6f4e4b9LL, 0x097ead2f2LL, 0x6f4980025LL, 0x7b9d83ee6LL, 0x61ab1d631LL, 0x522dfaa9bLL, 0xd58e68b08LL, 0x6dd894088LL, 0xa43851db8LL, 0xdb3da4317LL, 0xf1d8108b9LL, 0x0257b43cfLL, 0xa36dc4b75LL, 0x586b118aeLL, 0x4d292d0d7LL, 0xd5dd7ec58LL, 0x2961da611LL, 0x8e1eb4d44LL, 0xbdaf4157aLL, 0x783587d64LL, 0xb89073a03LL, 0xf2a98a98dLL, 0x8e6e953bfLL, 0x82728c63aLL, 0x08cf515b3LL, 0x192019a8bLL, 0x199feb37bLL, 0x4747d4de5LL, 0xbad74c26aLL, 0xa3eb1f4ebLL, 0x3a3fe72d5LL, 0xa24fca706LL, 0xac295c820LL, 0xdf8707b04LL, 0x240d933f8LL, 0x40d3afedaLL, 0x08967b352LL, 0xdb5908f2eLL, 0x0eb77e73dLL, 0x55e3af14bLL, 0x7e2af46d7LL, 0x2ad8069f0LL, 0x1c94d9cf8LL, 0xad3fd6707LL, 0xd527d05c1LL, 0x0e9661707LL, 0x5434c8225LL, 0x8b17ffb10LL, 0x6f4bca6ceLL, 0xe3d99b9e9LL, 0xb3f192e96LL, 0x4fe4ae9dbLL, 0x3e986a40dLL, 0xabebc86bdLL, 0xacec35dc8LL, 0xbff455399LL, 0x34ea8a485LL, 0x5c603d944LL, 0xf9228c5d5LL, 0x630b74068LL, 0xcc087e16fLL, 0xdcded3a77LL, 0x18e36b56dLL, 0x745c5e53fLL, 0xe54b21ebfLL, 0x8d71bb6a7LL, 0x804669bd9LL, 0x78a8843b2LL, 0xa841aa4c8LL, 0x7c1721cb9LL, 0x9a83406d5LL, 0xa896c7864LL, 0x04bb0aba5LL, 0x3c11533b6LL, 0x328444d58LL, 0x39bbda023LL, 0x8b36424c7LL, 0xf6120c770LL, 0x185bb28cfLL, 0x28319aaccLL, 0x44125fc8dLL, 0x9bd0b06bbLL, 0x77e3e63c2LL, 0x92cc0d22dLL, 0x6471ce5caLL, 0xa5cd27974LL, 0x821216a59LL, 0xb44bf0674LL, 0x91c306242LL, 0x59ddcc7f6LL, 0x8a49cdd23LL, 0x4126a5129LL, 0x5dae47e63LL, 0x5ae91a769LL, 0x1167709c8LL, 0xf72905476LL, 0x7f714af5bLL, 0xe1156f64eLL, 0xf043af7a7LL, 0xda86cb771LL, 0xefe9556eaLL, 0xe93191d0fLL, 0xc57680df4LL, 0xd6731845aLL, 0x40a0357d5LL, 0x369846e9cLL, 0x55c37b47bLL, 0xc1a35b0faLL, 0x53ac7be90LL, 0x85eb470c0LL, 0x3181486daLL, 0xf0e227153LL, 0x324271b12LL, 0x87850744fLL, 0x2e2d754b1LL, 0xe6eb202ceLL, 0xb0704c7b4LL, 0xa67db8125LL, 0x711fb0e4aLL, 0x37c2d1ce3LL, 0x6aea9caffLL, 0x443334cd8LL, 0x69e4738b4LL, 0x0d0afd5daLL, 0x9ab6c533dLL, 0xcca49a2bbLL, 0xc4d4fb6b6LL, 0x0e4b2ddd7LL, 0xda2509125LL, 0xe9c86da19LL, 0xc7274b59dLL, 0x2f4bbe74dLL, 0x96ac2a725LL, 0x1f30d673dLL, 0x425fd41bdLL, 0xa575e248bLL, 0xa41df8a63LL, 0x850967a78LL, 0x580a6f3fcLL, 0x3e7fa23edLL, 0x77d9a37b4LL, 0xaac2f4828LL, 0xd5afdeeceLL, 0x463bfa5bdLL, 0x8d8c594b4LL, 0xd5c3a4722LL, 0xc26bd81e9LL, 0xa25f27cc7LL, 0xb0a959849LL, 0xed63242d8LL, 0xf2a5d4c2cLL, 0xe55b4628aLL, 0x0b2dd55afLL, 0xc8738d953LL, 0x8a7cef286LL, 0xcc7c48409LL, 0x043816c4bLL, 0x85a74860cLL, 0x48fc51dbcLL, 0xee8237a9fLL, 0xdb101fca7LL, 0xa22651a66LL, 0xe15eb5386LL, 0xd43085b18LL, 0x651931da4LL, 0x9326a183fLL, 0x6f8dab598LL, 0x0e51eac76LL, 0x6e2623406LL, 0x9f935c569LL, 0x99d04350dLL, 0x2bfb7ef17LL, 0x9408845a8LL, 0x36e8c5171LL, 0x8af933fc5LL, 0x36ecec25bLL, 0xc90ec3e5aLL, 0x84942ea05LL, 0xfb5493f14LL, 0xd81204353LL, 0xd5060ecddLL, 0xddfda6095LL, 0x5cafc4e1dLL, 0x7754ff6eaLL, 0xc257672a5LL, 0x27299bc82LL, 0x4ca1520cbLL, 0xe1de3ec8bLL, 0xfb5ab687aLL, 0x88f4cc5feLL, 0x5c83fac92LL, 0x18bdce2abLL, 0x87fa99852LL, 0xeafdac7f7LL, 0xa095e0c0aLL, 0x1de9110e0LL, 0xabee689d5LL, 0x917d79b7aLL, 0xdb13b369aLL, 0x56aa3e642LL, 0xaaaf35e16LL, 0x9c0896962LL, 0x32ed98cd1LL, 0x40befddedLL, 0x733f9f984LL, 0xab7ee7d81LL, 0x38e744727LL, 0x7501364c7LL, 0xfd3421d02LL, 0x8d492864cLL, 0xb25d6c2d9LL, 0xb88708fa4LL, 0x66ca7ea8dLL, 0x53b061dd1LL, 0xbfe629317LL, 0xe48ccc4b2LL, 0x529e75dfaLL, 0x02ce3697aLL, 0xbe76866c4LL, 0xce03c67e3LL, 0x3c79ace12LL, 0xabb5ade8eLL, 0x5510819d4LL, 0x1853d91a5LL, 0xd99655b60LL, 0x47729ddffLL, 0x3c8c5ca2fLL, 0x1b819dd83LL, 0xdacb0ecddLL, 0xbf430f183LL, 0x829af66d3LL, 0xd1e2ca983LL, 0x779105c39LL, 0xb192af0a4LL, 0xd5098a6d7LL, 0x15cb456f1LL, 0x8481b933dLL, 0x409d19fadLL, 0x1f5c2f72dLL, 0x53673e5f5LL, 0x65e6a72eaLL, 0x0527da518LL, 0xeaddf7946LL, 0xb2617eaebLL, 0x691892fb2LL, 0xdcd129f35LL, 0xccb42e6b0LL, 0xdbc331935LL, 0x8867aa36eLL, 0xd7cd26a9cLL, 0x67a19fdc9LL, 0x20952b0aeLL, 0x6026d2e54LL, 0x98963fbd9LL, 0xa8b64c911LL, 0x97fd9f487LL, 0x7d3c848a5LL, 0x147a4c27bLL, 0x18c9cecadLL, 0x046eb72c9LL, 0xc88d38085LL, 0xb25dc1f48LL, 0x61790445dLL, 0xc125e5258LL, 0xfbeb9589bLL, 0xaecade15fLL, 0xda4f86a33LL, 0x6cf66cc43LL, 0xef65417e4LL, 0xdc50e0668LL, 0x8810cbcabLL, 0x4aafd7f97LL, 0x6c5c831a7LL, 0xb83ed224fLL, 0x64f1a00a8LL, 0x8db3c590fLL, 0x68ce5d2c0LL, 0xfd51258d2LL, 0xe2c5eb1b8LL, 0x59df15d2eLL, 0x700ebf57eLL, 0x3be89a8ccLL, 0x47fb46c45LL, 0xa923c0b32LL, 0xd88bac689LL, 0x27683edc8LL, 0x2eba1f952LL, 0x7102542c6LL, 0xd049fa79cLL, 0xcc0622afdLL, 0x693120c6bLL, 0x396461615LL, 0x2f1f4227eLL, 0x26b4bbf9fLL, 0xe8f7a6065LL, 0xecdf103d2LL, 0x708691ac7LL, 0x51941b750LL, 0xd33cd58a4LL, 0x95f2d0890LL, 0x3440d5b9cLL, 0x00afdca84LL, 0x625eae2ccLL, 0x2c36e42d9LL, 0x3f5f89ac8LL, 0x5649578c6LL, 0xbba60ace8LL, 0xe344ddca5LL, 0x128c435deLL, 0x02c52f620LL, 0x4db779c52LL, 0xaac4bcb7fLL, 0xf13e98394LL, 0x696f9e134LL, 0x179733908LL, 0x2c9580b9aLL, 0xa6f7072b9LL, 0x3358704e9LL, 0x7182449f1LL, 0x86eeb1594LL, 0x82b9adb34LL, 0x0ee258afcLL, 0xe122b5e67LL, 0x42ed1c2b8LL, 0x8633f61ceLL, 0xe8e335121LL, 0x525874e76LL, 0x96901dd2dLL, 0xda22fc8e0LL, 0xa72387097LL, 0x4f5d9a9c7LL, 0x88a87c443LL, 0x33b056d4dLL, 0x62d064cf1LL, 0x5e7c243bdLL, 0x18213a370LL, 0xf7bd5923dLL, 0x815aaa9aaLL, 0x84aa0b3ddLL, 0x1ee0819f4LL, 0x847cf7f08LL, 0xf120ded5fLL, 0x9a76c1290LL, 0x082b32d7bLL, 0xc8b59e9fdLL, 0x2d4dff53bLL, 0x293d29fc4LL, 0x08701ab95LL, 0xfd7fab48fLL, 0xf4cbfe2b3LL, 0xcbca4906dLL, 0x99cc8a279LL, 0x34251b504LL, 0x89092fc9aLL, 0x9e1c0ccabLL, 0xf697de846LL, 0x055fce443LL, 0x6b0cad5ecLL, 0x87923cab1LL, 0x8b4e2839fLL, 0x0a44b0122LL, 0xfb3909a5cLL, 0xa16fafee2LL, 0x1778046b8LL, 0xba9808373LL, 0x064852931LL, 0xb79d2dec4LL, 0x50cb67a1bLL, 0xbbfb05d16LL, 0xf0139fad3LL, 0xccbb36e49LL, 0xa2cd25458LL, 0x49343b972LL, 0x112efab27LL, 0x53d9d772cLL, 0x40bda71fbLL, 0xf8e62647eLL, 0xdee732912LL, 0x53500b219LL, 0x7e47a2a14LL, 0xe11cd7fb9LL, 0xfcaca6ec8LL, 0x6c2da7d57LL, 0xd93abceaaLL, 0x01bb3f4bdLL, 0x67dcf76f5LL, 0xb5b63e989LL, 0x5bae6b067LL, 0x9b6eee44bLL, 0xb7f96ef25LL, 0xf4d97b712LL, 0x930dff68aLL, 0xa40a96cf0LL, 0x0d5683834LL, 0x647e13c72LL, 0x2a5c63408LL, 0x395fef00dLL, 0xb4f5afa8aLL, 0x017bfe90bLL, 0xc9042b9b9LL, 0x2c9ad5aa2LL, 0x047a51093LL, 0xea341678cLL, 0x546838991LL, 0x09858cac9LL, 0x6061e2795LL, 0xce7d6ed07LL, 0x91b7626cdLL, 0x5805e4fe9LL, 0x119b5c832LL, 0x954f9e8f1LL, 0x6d1580b55LL, 0xf43091166LL, 0x0d5a7e04dLL, 0xe191d35a4LL, 0xd8ca15468LL, 0x0a708b652LL, 0xcc15b029eLL, 0xff5aa4719LL, 0x8e74f9498LL, 0xf9d92e911LL, 0x477e5d846LL, 0x042650770LL, 0x1e5730dcdLL, 0xa0e8eab0dLL, 0xddce6772eLL, 0x75a090773LL, 0xa19aa8eeeLL, 0xdcfe9d7caLL, 0xa0676c7ceLL, 0x17197c8bdLL, 0xa87af55afLL, 0xe2d1706aaLL, 0xa43dd708eLL, 0x26503e2fdLL, 0x123d37bdfLL, 0x68c7362b6LL, 0xea30ac137LL, 0xb01b70b8bLL, 0xb8d1315dcLL, 0x96824e75cLL, 0x98d141a84LL, 0x74aa24acdLL, 0xb4776887bLL, 0x8fdb27129LL, 0x70d84811dLL, 0xcb8b9f4c1LL, 0xa3a424426LL, 0xdd2531a76LL, 0xb29c389abLL, 0xbd1835e48LL, 0x47f3a453dLL, 0x8dfe4a80aLL, 0xa4b0a36eaLL, 0x4e886ad80LL, 0xe92d00ca8LL, 0xd7c6efc3aLL, 0xa5941aea9LL, 0x161a7aa58LL, 0x9ed69b98eLL, 0x64eda938cLL, 0x5588a6847LL, 0xd92d4a19cLL, 0xc9bd66defLL, 0x95b20c81bLL, 0x3e9ec0a50LL, 0xd957e66f7LL, 0x2251d77faLL, 0xa018cb128LL, 0x50bdb0443LL, 0xebebfa885LL, 0x05eb8892aLL, 0x294e078f1LL, 0x4c54e34b1LL, 0xc2ac1a6c4LL, 0x73e62b579LL, 0x95d24e16fLL, 0xd5edf5b3bLL, 0x9085ee304LL, 0xaa71ceb4eLL, 0xa51325eecLL, 0x2c0bd017dLL, 0xbf7101a25LL, 0x78d932686LL, 0x1bd9f946dLL, 0x4e18c469dLL, 0x61b4f9bd1LL, 0x9cc6aeeb1LL, 0xf457ec40aLL, 0x3a54d40cfLL, 0xf37fd42d2LL, 0xdca9017fdLL, 0x2018fb211LL, 0x0583139a2LL, 0xed794feb9LL, 0x2671f2339LL, 0x0a9dedb42LL, 0x00a59d973LL, 0xeeb0e6dd6LL, 0x27c5e838aLL, 0x15b92ceb6LL, 0xfaa9e1dc9LL, 0x691c2012dLL, 0xa700422f0LL, 0x42ce65421LL, 0xf36c2d8b9LL, 0xdd3255d33LL, 0xf16927235LL, 0xcea8c7ee5LL, 0x8b405217aLL, 0xa937cb21aLL, 0x1972d865eLL, 0x3dd15253aLL, 0x8e12c277eLL, 0x05f4e5ae1LL, 0x5cc68e658LL, 0x43dbcda4bLL, 0xa65e44bd5LL, 0xc2b21acbcLL, 0xd683fcfa5LL, 0x3f6a63ab8LL, 0x07da47408LL, 0xe8b12669eLL, 0x32a0a4644LL, 0xa9825a29cLL, 0x49b66fce0LL, 0xfa9a992ceLL, 0xd2b5fbfd3LL, 0x14a5b69ecLL, 0x74a030edaLL, 0x8e50a8e2fLL, 0x0a95167daLL, 0x80202bd54LL, 0xe8318bbe2LL, 0xa3ab33a01LL, 0xde35c6e5bLL, 0xa1226c83aLL, 0xb6c43aa86LL, 0xedc5e4d1aLL, 0xd5944aa7dLL, 0x478a80992LL, 0x47811cb87LL, 0xb95d85ffcLL, 0xe2360374bLL, 0xa9a9ec186LL, 0x74de32ca5LL, 0x04a66a427LL, 0xd4a65cf9dLL, 0xd8d75502dLL, 0x1c3b585a2LL, 0x795d13255LL, 0xd451f5854LL, 0xc70f36267LL, 0xc29959adeLL, 0x0c5da4711LL, 0x32123feacLL, 0xb7fdbc068LL, 0xae25f20b7LL, 0x25e3e6f31LL, 0x20232ce56LL, 0x74f543f01LL, 0x185cda063LL, 0x97d611476LL, 0x13f15f323LL, 0x173612c01LL, 0x3d616758dLL, 0x4737d01fbLL, 0x0d5d33019LL, 0x259e9f133LL, 0x5eae970d9LL, 0x4ac96e3bbLL, 0x2242e4b5cLL, 0x118f28ce7LL, 0x2f7cbf15dLL, 0x8a7d644e8LL, 0x80ef8b95fLL, 0x1be972336LL, 0xf42d2a60eLL, 0x42a580066LL, 0x9a911767cLL, 0x3a4b9612fLL, 0xdb0f1bbcdLL, 0x3ac93c1b1LL, 0xcfec5c2d1LL, 0x452d01604LL, 0x4f3f3998dLL, 0x8aa4775b3LL, 0x32fd7c6abLL, 0xe3e43832dLL, 0xe774f08a8LL, 0x25b8dcf5cLL, 0xc0f10d6e9LL, 0x23874a0c7LL, 0xc7e7c9c8bLL, 0x6470db895LL, 0x6a458e8d7LL, 0x886e29f3dLL, 0x4b6531365LL, 0x8eccc4bacLL, 0xeed4c9f8fLL, 0x7d0685f48LL, 0xf6e8b9b96LL, 0x524d9bc08LL, 0x8ba35deecLL, 0x127a38c15LL, 0x07d5ce1acLL, 0x8496b0888LL, 0x9589e40e3LL, 0x9f123483fLL, 0x0a7f03598LL, 0x57342da57LL, 0xdbaa17d6dLL, 0x4c068d8f3LL, 0xf76ad5b2fLL, 0xb398e63bcLL, 0x102afd902LL, 0x4877b8bfbLL, 0x790f6c2baLL, 0xc7655b992LL, 0x4e0d5b07dLL, 0xb02afe708LL, 0xa8875d3a1LL, 0x750681812LL, 0x77a9c79abLL, 0x02ad0c854LL, 0xc5cc6924fLL, 0x25e9c88dcLL, 0x877356004LL, 0xc67444a06LL, 0x12d72f8c9LL, 0xffa5a50eeLL, 0x931d865b3LL, 0xd5b7c6e10LL, 0x3d0aa7ef3LL, 0x92ce0cd5eLL, 0xa0f27b9a1LL, 0xd74b04855LL, 0xac4596a59LL, 0xa2b5aa65bLL, 0x88d45ef6dLL, 0x7294cb8a7LL, 0xeec1cb733LL, 0x964498855LL, 0x2279b8adbLL, 0x922c72d48LL, 0xf994172bdLL, 0x3e047e3dcLL, 0x317053d24LL, 0x42c8f55b7LL, 0xfa9d550dcLL, 0x91a2dd669LL, 0xa81f56081LL, 0x3fd3a6c56LL, 0xdf850d00aLL, 0xbe3e03545LL, 0x407ec6fd3LL, 0xbd016301aLL, 0x916a7194fLL, 0x11a49ea87LL, 0xc5d123c1eLL, 0x9a807b6b0LL, 0x0593ba877LL, 0x018d46d49LL, 0xa7a3e5dd0LL, 0x9686fbc5fLL, 0x22769d2b3LL, 0xb1395dd1cLL, 0x77e0a5c9fLL, 0x890a050ceLL, 0x49f50576cLL, 0xb43273783LL, 0xf909f5329LL, 0x9bb92f046LL, 0x4712ca12dLL, 0xe74059b06LL, 0x119424c3bLL, 0x08b0d1ef6LL, 0x636ed63efLL, 0x75fb4b1baLL, 0x64f15c372LL, 0x77d9f6a84LL, 0x007ae9bd7LL, 0xe00da4c99LL, 0x7a5814217LL, 0x117097acdLL, 0x5549740d1LL, 0x9f3aba1e0LL, 0x2ceeb811eLL, 0xed5f8aa13LL, 0x667486d91LL, 0x31472697eLL, 0x71fa40e6cLL, 0x29d3f8dccLL, 0x74e5ff0f1LL, 0xb18e969c0LL, 0x331847353LL, 0x95471db9eLL, 0x9e3816ef2LL, 0xc7bdacb19LL, 0xd33a176c1LL, 0xc15810741LL, 0x230e1a526LL, 0x3e7d17b0bLL, 0xfaf6ae216LL, 0x428e9f5b4LL, 0xbeb6ade2bLL, 0xde276103cLL, 0x6928c5d83LL, 0x685ca40eaLL, 0xc0d875c85LL, 0x8096f3381LL, 0xed453bc21LL, 0xfbda5c809LL, 0xa6542bb1dLL, 0x2e1a744a4LL, 0x9e5a72efdLL, 0xedfee81f2LL, 0xb48280aabLL, 0x7586536ccLL, 0xd46c9ac5bLL, 0x9f228c8e7LL, 0x2137d18f6LL, 0x513747f68LL, 0x88ae16997LL, 0x6e30cdf98LL, 0xa67eea5d4LL, 0x27bf40957LL, 0xf11c7e690LL, 0x25449ebbeLL, 0x0db5bb3b0LL, 0x7d784749aLL, 0x51a7cd63cLL, 0xe23ca5876LL, 0x4cdd52936LL, 0x326eaaa63LL, 0xf8c9d5d50LL, 0x0ed014396LL, 0xcf8a25b81LL, 0x2dbdcc80bLL, 0xc4aa9df2fLL, 0x6f6c2f6dcLL, 0x59e8ef553LL, 0x0f6c484dbLL, 0x9ec72a877LL, 0x2cc4e64caLL, 0x58899d59cLL, 0x0bfe119faLL, 0x8361ac7b7LL, 0xb3615653cLL, 0x541ea167bLL, 0xfdb2fd954LL, 0xcf4fd9d05LL, 0x48f5aab41LL, 0x22d74d9b3LL, 0x9b3270e8fLL, 0x2fff128d0LL, 0xca0170b88LL, 0x6ca810fc5LL, 0x90b6aa826LL, 0xb1b09d138LL, 0x02b238b76LL, 0x98f2254d5LL, 0xbbb2d3652LL, 0x3427c35ceLL, 0xf559d72f4LL, 0xf982e7fd6LL, 0xf102bc341LL, 0xf13b625b0LL, 0xc6f04c475LL, 0x7523d80e8LL, 0x44a0e7ebbLL, 0xafd06e1bdLL, 0x68808e0e5LL, 0x90621d64eLL, 0xe05e5a36cLL, 0x83131c4b6LL, 0x97eb76817LL, 0xd9cc44ff8LL, 0x8b36f9654LL, 0x0245dde9bLL, 0x520e35f6dLL, 0xd4cceb189LL, 0xc2b894013LL, 0xaeb641c96LL, 0x7af4d8aeaLL, 0xad2618e25LL, 0xabe43bbd9LL, 0xef52ec2a3LL, 0xb73c6029fLL, 0x6a3807c97LL, 0xddfb4bd6fLL, 0xf3d8e96d6LL, 0x2aa6fa42aLL, 0x43a2f1918LL, 0x3a90c3595LL, 0x2cd912f20LL, 0x9adc1bd3cLL, 0x7b9ac2f88LL, 0xc5833c0a4LL, 0xbd9b65455LL, 0xcb1c9e7eaLL, 0x63a0524fdLL, 0xf4c384b5aLL, 0xe8e524253LL, 0xc22b11d9fLL, 0x68422fc45LL, 0xa68c0b54cLL, 0x26f6c3e32LL, 0x6d33234ddLL, 0x3249aeef8LL, 0xa44768ab6LL, 0x799b27147LL, 0xc2d133071LL, 0x97db182d3LL, 0x86eb74d4aLL, 0xe937414e1LL, 0xa7a7bb500LL, 0xbb9745c67LL, 0x598c8590cLL, 0x0daa06872LL, 0x1630a0579LL, 0xed748567fLL, 0x985b0f840LL, 0x65fbf1b05LL, 0x2ac24e078LL, 0x8e44e7201LL, 0x73dea54fbLL, 0xec53fc29dLL, 0x17eb2107bLL, 0x0623990cdLL, 0xe8d2b249aLL, 0x3e53f5292LL, 0xb31e481faLL, 0xbd28c91c7LL, 0xc95853493LL, 0x4cf19e5a3LL, 0x13dd03e15LL, 0xe420f8b60LL, 0x0aba216f1LL, 0xfc949ce77LL, 0x12cc4c8b0LL, 0xda1af11cbLL, 0x95e51047dLL, 0x239712b3fLL, 0xdd8c9ff85LL, 0x3b7c11327LL, 0x03706c9cdLL, 0x4a5428a10LL, 0xf9ff29dacLL, 0x6880bb16eLL, 0x39ce35cc3LL, 0x348a6f738LL, 0x481ebd8beLL, 0x312f67693LL, 0x066d19548LL, 0x252c908b8LL, 0x93dd489c4LL, 0x2e916877eLL, 0x4f03ba3ebLL, 0x8332640a5LL, 0xb5418976cLL, 0x43e45adcfLL, 0x5ad03c442LL, 0xc5c651faaLL, 0xe9e22aff4LL, 0xe3e84f5acLL, 0xfa27e6393LL, 0x5c2975ff6LL, 0xeb28706c1LL, 0xbc16eb250LL, 0xb230ff592LL, 0xe01b41ea3LL, 0x550beeb62LL, 0x3acc6d9d9LL, 0xfee57e361LL, 0x0e47f1f33LL, 0xa13c0e131LL, 0x8c28e5a14LL, 0x7d201d0eeLL, 0x72377cd9dLL, 0xc2d4903e8LL, 0xd865c90ceLL, 0x5159115feLL, 0x70d91786dLL, 0xa6859de80LL, 0xfb7b97d08LL, 0x5844a534dLL, 0x902dba777LL, 0x36d28050eLL, 0x01bc8a4f9LL, 0x6c810239dLL, 0x1b8bdbc1dLL, 0xed019746dLL, 0xb2e22db8bLL, 0xce20242c4LL, 0x277835081LL, 0x55c421fe5LL, 0x1c3d0d749LL, 0x26bd653e3LL, 0xd7ed2ff69LL, 0x10c6fc33bLL, 0x9ea03e399LL, 0x5b22ed1a3LL, 0x99ced9f23LL, 0x6ac377418LL, 0x9129d7dd6LL, 0x43ace647bLL, 0x7c4b49f58LL, 0x900ae344aLL, 0x2b8959613LL, 0x47fc08ec9LL, 0x21d67379eLL, 0xd89df08faLL, 0x37d955225LL, 0xcc10979b9LL, 0x6621b1eb7LL, 0x0de2fc4a2LL, 0x745cfaf22LL, 0x8d46a9619LL, 0x61b1ceee4LL, 0x675b9a2bfLL, 0x40058aafaLL, 0x05d25b9c4LL, 0xefcb86566LL, 0xc13e788eeLL, 0xab9e7280bLL, 0xd9306e8d4LL, 0xa266d71b8LL, 0x45995737dLL, 0xea8f02adbLL, 0xb313918c4LL, 0x970f9be58LL, 0xaaf674ce6LL, 0xc7d00b910LL, 0xfa502e688LL, 0x3702f79aeLL, 0xd893b843dLL, 0x0f1e45ddbLL, 0x93c9617a8LL, 0xe14247733LL, 0x43f4cb24cLL, 0xf1b75980eLL, 0xcea5553fbLL, 0x4f4d89e4bLL, 0xd8bfdb958LL, 0xe231a41daLL, 0x60116696aLL, 0x12cdb2096LL, 0x6d0202075LL, 0xb75ae1a2aLL, 0x888d79ea8LL, 0xc7d80e5c6LL, 0x4f21633fdLL, 0x9375ea207LL, 0x84017c66bLL, 0x7ec585495LL, 0x5be0f7c5cLL, 0x14b106f8aLL, 0xba2feec25LL, 0xf12261575LL, 0xd87fc9c27LL, 0x7ffea3372LL, 0xfe6f6a5b2LL, 0x494a627dfLL, 0x73c4f89f4LL, 0xb54156ddbLL, 0x14d501f4eLL, 0xbe50c2ad8LL, 0x76cfa8441LL, 0x2a6832d8fLL, 0x82ed6f577LL, 0x234ee72bdLL, 0x3fe939c14LL, 0xd9aa5f1bfLL, 0x436b7049eLL, 0xe939e6266LL, 0xcab65d44cLL, 0xc6b90201dLL, 0x9dd60ae8cLL, 0x975c2a441LL, 0x3eaa603e5LL, 0x67e5526b2LL, 0xdc57f5beaLL, 0xbca1f74baLL, 0xc3472a0b3LL, 0x74fc1b243LL, 0x4011a3cadLL, 0x688f30527LL, 0x7cb1bd3b6LL, 0xc6172373dLL, 0x1e58a5d3bLL, 0x161e143f2LL, 0x69fecc526LL, 0xedc625028LL, 0x62386857cLL, 0xc65817d6eLL, 0x1c2907aceLL, 0x5f845976aLL, 0xc71a8dc11LL, 0x56431fdb7LL, 0x096c5d1c4LL, 0x7fa1f8582LL, 0x71e278b58LL, 0x50719d063LL, 0x9f166f178LL, 0x503ada677LL, 0x044953c8bLL, 0x3477a905cLL, 0xe18a293adLL, 0x63eb0f954LL, 0x6504fe3f3LL, 0x207477edcLL, 0x45395da2eLL, 0x0d5d3fe02LL, 0xa8b671eabLL, 0x53b890c75LL, 0x21318478dLL, 0x84c15d0ffLL, 0x1163ede85LL, 0xa3d4784cfLL, 0x0e8d78cf3LL, 0x029b52b98LL, 0x31261cfa9LL, 0x8ce517f2fLL, 0xebc01b551LL, 0x55e719687LL, 0x14a334c3eLL, 0x7a18edcf6LL, 0xd2adc5527LL, 0xb9355ca29LL, 0x899223cf7LL, 0xcb97089c8LL, 0xc024cf877LL, 0xb705e424bLL, 0xa8e0142c5LL, 0xd60a133e3LL, 0xfbb712edcLL, 0x90ac40d24LL, 0x80b3aa7bcLL, 0xa0fa4a297LL, 0xa660659ebLL, 0x6270b5e01LL, 0x7875e8d73LL, 0x99b1c9fe5LL, 0x26147c55fLL, 0x494d6032aLL, 0x805c954b3LL, 0x4bc4dc338LL, 0x8d28838b6LL, 0x65f2934e9LL, 0xd2e0ba595LL, 0x2f63fd89cLL, 0x1d468e027LL, 0xae5c50ea9LL, 0x2754729f5LL, 0xb4821c6f9LL, 0x1e2deee48LL, 0x6fd833c89LL, 0xaf7e537b5LL, 0x0f96cbd90LL, 0xf82ef480bLL, 0x906fa3f87LL, 0x621287584LL, 0xf05c6358eLL, 0x5698e95c5LL, 0x105509992LL, 0x0762e2a0eLL, 0x6ffb64722LL, 0x64d6dccbdLL, 0x1b7f83d6bLL, 0x5518fcb18LL, 0x025ee2c96LL, 0x8e78ed132LL, 0xad93d4196LL, 0x8c8750aa2LL, 0x9e3c7b381LL, 0xe5148c631LL, 0x4b38f2617LL, 0x82b98bc77LL, 0x92dcc557cLL, 0x28dc57fd1LL, 0xf912e0c62LL, 0xaac55e599LL, 0x081984b5cLL, 0x93826e871LL, 0xce7abded7LL, 0x414db1e2dLL, 0xef68bda6bLL, 0x47da612d0LL, 0x07b99ba1eLL, 0x8b7872c39LL, 0x3390d271bLL, 0x32f6bc3aeLL, 0x77325c35dLL, 0xff2993b97LL, 0xd811caa67LL, 0xf6610ec51LL, 0xf61101d05LL, 0x9bdf143c8LL, 0x712a1da5fLL, 0x69edb2899LL, 0x918f4b5fdLL, 0x9b70b01edLL, 0xd1d7c1bd4LL, 0x7455d932bLL, 0x53590c39aLL, 0x4021360a9LL, 0x1dc922b31LL, 0xe893c6a98LL, 0x7e274d451LL, 0xb3197bda3LL, 0xe0d039a4cLL, 0xb5bb78bf2LL, 0x3f453821eLL, 0x1ceea1703LL, 0x7e245e4faLL, 0x43dfb0af8LL, 0x56a72aab3LL, 0x4cdc702f9LL, 0x7196ac417LL, 0x185c13ae6LL, 0x72a069055LL, 0xe3b657a99LL, 0xe54143be9LL, 0xb96b8d06aLL, 0xb917bc739LL, 0x075675126LL, 0x667eae736LL, 0xa24735968LL, 0x80cb15f06LL, 0x9084726feLL, 0x9115fce0fLL, 0x4fd117067LL, 0x08ed4302bLL, 0x09d57f52eLL, 0x83b947bd2LL, 0x1b379cbc5LL, 0x6e4f6d6c3LL, 0xf3a45c9a2LL, 0xa6edec8baLL, 0xbfe48b96dLL, 0xa316bb1f0LL, 0x4b02d5449LL, 0xb7c8d6f14LL, 0xf8aab8168LL, 0xbbd63e715LL, 0xff2e5262dLL, 0xe7ce4a45dLL, 0xe69ea1730LL, 0x83a416eb4LL, 0xd131294b9LL, 0x0cff9c21dLL, 0x51f972f8cLL, 0x8aeb661f1LL, 0x79db4388cLL, 0x38d94d7a3LL, 0x8035d996dLL, 0xcaf8d77c6LL, 0x6ccc390e7LL, 0x7510bb2deLL, 0x47570789cLL, 0xbb0f0b128LL, 0xe344866dcLL, 0xf8e8538c5LL, 0xa89fe5639LL, 0x30bf26d3aLL, 0x9903d49fcLL, 0x475e6c8f8LL, 0x7e3d98813LL, 0x5e6f1698dLL, 0xa1304eb9bLL, 0x8662da415LL, 0x5b84b9c39LL, 0x8759f87dbLL, 0x9bc957f53LL, 0xcfafd522dLL, 0xf8fdaa82aLL, 0x3975f695cLL, 0xd9eabbf19LL, 0x054c9e489LL, 0xcebed9ba9LL, 0x3f29c0269LL, 0x280639ce6LL, 0x19a9698ecLL, 0x7e9965582LL, 0x23efea1b4LL, 0x5674b2e35LL, 0x28cfadfadLL, 0xd224628aeLL, 0x1a5857d9fLL, 0x1f2fb59cbLL, 0x45eeca839LL, 0xf57b0db20LL, 0x2cf4d5a09LL, 0x5898bb1b1LL, 0xdce4dd9faLL, 0xb2fed21f2LL, 0x29fcd26a6LL, 0xff1ed7959LL, 0x4582dd7c6LL, 0x94d96dcbcLL, 0x08fcaf998LL, 0xc2150dc02LL, 0xcb725e6feLL, 0x497bf9d00LL, 0x9a07aa199LL, 0x231cc756aLL, 0x8029024e4LL, 0x706c3b697LL, 0x21dab6df9LL, 0x9822ce6c1LL, 0xd9339f82bLL, 0x08588a50cLL, 0xfc592f12bLL, 0x5d0de92e1LL, 0x84cf29460LL, 0x17dd9463eLL, 0xd552a6e3fLL, 0x9921d4023LL, 0x511997b06LL, 0xa7db8d63bLL, 0x7628f7e02LL, 0xb5a70da67LL, 0xb78b26044LL, 0xcc757da90LL, 0xa372fe31fLL, 0xa6d0e7885LL, 0xfdd5c9958LL, 0x22d093093LL, 0xac02463ccLL, 0xb8dc89befLL, 0x0c6ac81d2LL, 0x2453311fdLL, 0x2a4b37046LL, 0x1022902e5LL, 0x09b58f09fLL, 0xdca206ca4LL, 0x8c5443cfeLL, 0xd1bcfda67LL, 0x06156bcbbLL, 0x71826e127LL, 0xd8b00b0eaLL, 0x16d325e74LL, 0xf67b3e901LL, 0xe7d585092LL, 0xc1aa82c54LL, 0x020121d7aLL, 0x836756756LL, 0xed93b03e8LL, 0x25e1b4a2bLL, 0x94279c34fLL, 0xa6130a7fbLL, 0x0cf097151LL, 0x192bb41b7LL, 0x82650ff19LL, 0x222fe2d89LL, 0xf38d6658fLL, 0x0da70ff01LL, 0xd531e4109LL, 0x8fc408d99LL, 0x864f65e98LL, 0x0f552caeaLL, 0xf07941d6eLL, 0x69520b2ccLL, 0x4e19bbdfbLL, 0x201ad85b4LL, 0xa24f492e0LL, 0xf577561a2LL, 0x3ac417bfdLL, 0x2c262d743LL, 0x1a57ae77dLL, 0x9cd8b411cLL, 0xd39c85983LL, 0x11b2afd51LL, 0x249ce5cfbLL, 0xd33548b8eLL, 0x5dd56d7c9LL, 0xa56ee9248LL, 0x425d68e8aLL, 0x10f87e0e9LL, 0xc6b7f55b9LL, 0x359462f78LL, 0xf68d21c1eLL, 0x7611706cdLL, 0x1252d7e37LL, 0xa8bfdb38cLL, 0xe86b4fbd2LL, 0x35a2f972fLL, 0xe3d6ec1c8LL, 0x1b4bc2a9cLL, 0x1daaaa19dLL, 0x2883e99faLL, 0x0deb8b211LL, 0xa3779f2c6LL, 0xe9e6d10a7LL, 0x4ea5c2770LL, 0xec50b1009LL, 0x914f44e74LL, 0x42c94c52eLL, 0xddaeee892LL, 0x77cbea957LL, 0xa1c5404a3LL, 0xbb7add120LL, 0x3a28116d5LL, 0x862e8ec66LL, 0x4ecbec8b1LL, 0x86bbbeb7aLL, 0x09efcbc44LL, 0xa213bc2a8LL, 0xf18dee3d2LL, 0xcfabe895bLL, 0x62d502afdLL, 0xdee6d82c7LL, 0x72e120e31LL, 0xf40d09991LL, 0xdf823444bLL, 0x5265afe71LL, 0x30a0e4dfeLL, 0x5c5c0b7f4LL, 0x4996907d6LL, 0x600c53191LL, 0x01ac06c9aLL, 0x4a53707b6LL, 0xd16ea6a44LL, 0x60be6e211LL, 0x5edf96076LL, 0x6b2e67779LL, 0x93d96e2eeLL, 0x90846d495LL, 0x61eaedc80LL, 0x1e267b96cLL, 0x17530b57dLL, 0x64fa1dd35LL, 0xbbb4c69f5LL, 0xb6323afb6LL, 0xf8d4d766bLL, 0x25e356458LL, 0x53934ceedLL, 0x864225814LL, 0x1c36a7a0fLL, 0x778490a0cLL, 0x5cc616142LL, 0x636654005LL, 0x8f554e490LL, 0x2984db337LL, 0x02ac89bedLL, 0x09a93c224LL, 0xa4a194fe7LL, 0x9a75ab8d8LL, 0x26245c20aLL, 0xa64fd081dLL, 0xfa8cde28aLL, 0x975c3c712LL, 0x8b1ad0475LL, 0xcfa7b1de2LL, 0xf2bdad2edLL, 0x071b918baLL, 0x1eaea2ff4LL, 0x04838c15bLL, 0x599911ed2LL, 0x41ddcd721LL, 0xdb10e3fb5LL, 0x8bbadce41LL, 0xfb483af95LL, 0x919fc8b26LL, 0xe2414e967LL, 0x33632f41aLL, 0x8ef4feed2LL, 0x7288b6a3aLL, 0x8f0db5f29LL, 0x35429b088LL, 0x34b45572bLL, 0x5a4889ae3LL, 0x22ac2efa9LL, 0x49b0e4db7LL, 0x8fd129de6LL, 0x0aaddf60dLL, 0x164d7e181LL, 0xb4c6f0d55LL, 0x8a1d30ab1LL, 0xd69bcbc97LL, 0x84b118674LL, 0x83223f98fLL, 0xa7e49656eLL, 0xb2eaa12b5LL, 0xbbd1fc497LL, 0x8737c574eLL, 0x9c29ec54fLL, 0x48941910cLL, 0x7b5140011LL, 0x14d62b95aLL, 0x004a8bee9LL, 0x17d22cde5LL, 0x779768374LL, 0x41d9d481eLL, 0xdfc61088aLL, 0x8ae83d895LL, 0xefd5a6e97LL, 0x0e9142829LL, 0x684e1983dLL, 0xbd5acb77fLL, 0x2eb9f5998LL, 0x084ad2738LL, 0xca47a6db4LL, 0xb730d9221LL, 0xe1d02dae3LL, 0x1897bbeedLL, 0xae6460eceLL, 0x2ae10dcc2LL, 0x20b562229LL, 0xab5a5963eLL, 0x23f786b94LL, 0x7a1e0be5bLL, 0x0d416a4bdLL, 0xfda34600bLL, 0xea42e3913LL, 0x191c6acd2LL, 0x2cd0c0257LL, 0x3fa745285LL, 0x486a34308LL, 0xd5bc0fc16LL, 0x9c29c1970LL, 0xc748e4213LL, 0x7d894d16dLL, 0x462f9a307LL, 0x93e77fc9bLL, 0x2586ca766LL, 0x7f4843d74LL, 0xc59dfb603LL, 0xcc9f8a977LL, 0xfcd5dbdaaLL, 0xabd042620LL, 0x01e98ed52LL, 0x3723c0ed4LL, 0xbba7a3d47LL, 0x87191e9e5LL, 0x96f863d99LL, 0x52ff61749LL, 0xed5634dceLL, 0x29e089ed4LL, 0xc7840939cLL, 0x710fd2bd7LL, 0xa7bcde8eeLL, 0x6992f5b0eLL, 0x8e43638daLL, 0xa8f8bb730LL, 0xb3ac0121aLL, 0x9a39430a5LL, 0xb400f5406LL, 0xf1fed9cf4LL, 0xecb8eed3dLL, 0xf982961b8LL, 0xd2ca7f580LL, 0xc0ff82a1aLL, 0x472f86bfaLL, 0x6c7819a1aLL, 0xc5fb45b51LL, 0x1e8265bbcLL, 0x992ea46fbLL, 0xeae69326cLL, 0x5cf05b4b0LL, 0x4dba41e1bLL, 0x678b0c87bLL, 0x541dfe46dLL, 0x5c6805370LL, 0xa46d1f411LL, 0x20ca43c25LL, 0xb825728d0LL, 0x60e64b7c3LL, 0x158a87789LL, 0xec8327da8LL, 0x312f31d11LL, 0x44e751abdLL, 0xb86749801LL, 0xf1e21217dLL, 0x1df98766aLL, 0x3b82a6a92LL, 0x813e55a4aLL, 0x425a3e347LL, 0x23d2e0991LL, 0x125b5b7a8LL, 0x299f2386dLL, 0xae87ad90eLL, 0x88d6c80c2LL, 0x505d3e3acLL, 0x8c08d9bf5LL, 0xbc74ec4c7LL, 0xb4b961f43LL, 0xeffd6e25bLL, 0xa34783dd4LL, 0x4b77e81edLL, 0xdae14fb89LL, 0x652a40492LL, 0xb89ac1d1fLL, 0xc326835a3LL, 0x62377a03eLL, 0x073a0bde3LL, 0x63ab6d119LL, 0xa4516da9bLL, 0x7310b4716LL, 0x0eaa5bfd1LL, 0xb2e0c1b7aLL, 0x6b2d91842LL, 0xa71ee6024LL, 0xe96938770LL, 0x94bf95cc1LL, 0x13752cd22LL, 0x0212fadb3LL, 0xa6d81af51LL, 0xdf3594b4eLL, 0x74d16cfeaLL, 0x1c7666313LL, 0xd4d2825d3LL, 0x32ef55c77LL, 0xb41709c57LL, 0x65496705fLL, 0x46c363baaLL, 0xe5d09d8b4LL, 0x4a092d2adLL, 0x1c85dc273LL, 0xb7fd50ec1LL, 0x85898eb2fLL, 0x64e4c723dLL, 0x53d9f5ed1LL, 0x3a557ef3bLL, 0xbb1bf6342LL, 0x5a5ef851bLL, 0x47ad6c0efLL, 0x8fb3984b8LL, 0xde8ad29aaLL, 0xce019b097LL, 0xa2e99fbdaLL, 0x254954e30LL, 0x380afe9d3LL, 0x6ed87890fLL, 0x75c288fadLL, 0xfed4797b1LL, 0x1b19ca486LL, 0x2bddbba6bLL, 0xbda8398a9LL, 0x4b96c12d9LL, 0x74448a4d4LL, 0x84a06a048LL, 0x7be5eb6f5LL, 0xbf1429ebcLL, 0x317cbe9b3LL, 0xda1bfba51LL, 0xf19033d98LL, 0x6692ec390LL, 0x85de73668LL, 0x502e6e128LL, 0x6bf51b707LL, 0x858deeef7LL, 0x231f255c8LL, 0xdc5285120LL, 0x1f7499d35LL, 0x51e562dfbLL, 0xfd31d9e13LL, 0xf56f7abe5LL, 0xbfe2014b4LL, 0xae9e0b0baLL, 0x04ab6818fLL, 0xfc5222cf4LL, 0xe479029b2LL, 0xedac0cbc2LL, 0x3dd056ec8LL, 0x2b3ab1bf3LL, 0x96090fde2LL, 0x7414985b2LL, 0x07c5f1053LL, 0xc912a2b86LL, 0x2238893caLL, 0x0a047b8d4LL, 0x956a79db3LL, 0xc987e2e17LL, 0xa3c23d85aLL, 0x97129d3d4LL, 0x8602ebdf8LL, 0x0c1e5c94aLL, 0x728fa9af1LL, 0x6783b3466LL, 0xd03a47b3fLL, 0x577e66a97LL, 0x064ea8d8fLL, 0xf810556b3LL, 0x550d70ce2LL, 0xeaf8c9627LL, 0xe1c975366LL, 0xb0c0fb42aLL, 0x60b80b9c6LL, 0xe5c4caf80LL, 0x54c8d166bLL, 0xc8f6e29f8LL, 0xb0c391d73LL, 0xc5684f473LL, 0x0812877caLL, 0xd98c3dc0fLL, 0xa530878c2LL, 0x83b26929fLL, 0x473ec8d20LL, 0xfb27d5064LL, 0x790c88e09LL, 0x4fad3f4a3LL, 0xde15f1749LL, 0xc2ba6e2acLL, 0xe52a2cfb9LL, 0xc5797941cLL, 0x383593138LL, 0x7a025b10aLL, 0x92d15a83dLL, 0x3084af2a3LL, 0x6cfe2a38bLL, 0x66973a8f4LL, 0x265dd307bLL, 0x884284f79LL, 0xf04052eb4LL, 0x94b8aaadeLL, 0x0bd36a298LL, 0xe22dd0993LL, 0x30a8178f2LL, 0xef40b3badLL, 0x5fd9521deLL, 0xe323cbc56LL, 0x2dbd84334LL, 0xe7f732978LL, 0xc940d0d9eLL, 0x017e1db0dLL, 0xb30f2898dLL, 0x3a70d4c13LL, 0x6877cc2c7LL, 0xb29c26091LL, 0x86d1b6ba0LL, 0x34790d00aLL, 0xcea3d1c3aLL, 0x609555677LL, 0x47ae0cd43LL, 0x6bc9151d8LL, 0xcd08c96bfLL, 0x2dcf87f90LL, 0x5d38abc7aLL, 0xb53944398LL, 0x5aa36c2c2LL, 0x6dc1a9602LL, 0x3f78a849eLL, 0x9a75bd745LL, 0xcccae769fLL, 0x7bb8bd72bLL, 0x37c8f5b48LL, 0x63307f50eLL, 0xa16e04992LL, 0x461e6f322LL, 0x05c9b0b16LL, 0x125571aceLL, 0xd671fa72fLL, 0x1da08d7dfLL, 0xf75a3b250LL, 0xc3e35da05LL, 0x9debf4cf5LL, 0x568893e81LL, 0x9f45f5a8fLL, 0xd28f36e5fLL, 0x39ed2c299LL, 0x7ec5b28bfLL, 0x726971dbdLL, 0x62a7e6608LL, 0x2465cc620LL, 0x54b82a639LL, 0x16f964b59LL, 0x18afd656aLL, 0xfa45a2401LL, 0xd63e74a3eLL, 0x85c8b9164LL, 0x01c5a5bfbLL, 0x7b406d02cLL, 0x1a6885edaLL, 0xea0f61089LL, 0x3356e4e19LL, 0x954d1c237LL, 0x73894ee02LL, 0x594d206b1LL, 0xa34df0652LL, 0x6627dfb9cLL, 0xe0a8d336fLL, 0xf76b0bf3eLL, 0xf4bcb8c6cLL, 0x9cfee3b2aLL, 0x727af778eLL, 0x2af80ac19LL, 0xa99353076LL, 0xbc1b3a11fLL, 0x055fa22abLL, 0x5bc6b849eLL, 0xa7b5b3826LL, 0x1464c65f1LL, 0xb797e45feLL, 0x06aa7641cLL, 0xd6402bea1LL, 0x69042dc7aLL, 0xc27a84b0fLL, 0xc3e40bc3eLL, 0x5188a9088LL, 0x9ca221e9fLL, 0x2eeb0cf45LL, 0x387326c49LL, 0xc192f116fLL, 0x5b4afe3f7LL, 0x1e2b7028bLL, 0xf315bf477LL, 0x1dfa88408LL, 0x82ede7a9fLL, 0x1daec4b02LL, 0x90b55c4fbLL, 0x1dfa5f446LL, 0x35d8744beLL, 0x9ed16f6c2LL, 0xbe5a98781LL, 0x057cf82b0LL, 0x62c4d6074LL, 0x0e524f153LL, 0x5ad102332LL, 0x5ce554139LL, 0x09b4882e4LL, 0x2f854512bLL, 0x42376f39fLL, 0xbd5b7cd06LL, 0x5f34b8fa2LL, 0xc8dd8867aLL, 0x26ff91debLL, 0x24fc05cf4LL, 0x61e928d08LL, 0xe5ed22480LL, 0x7edcca236LL, 0xbf19c5c5aLL, 0xd876f6600LL, 0x18cc2a06eLL, 0x98f9a0f2dLL, 0x0e46da359LL, 0xf10ca127dLL, 0x4ea58d6c8LL, 0xc5d584facLL, 0x4168b3771LL, 0xf7742c3abLL, 0x3d9e01ab6LL, 0x749603675LL, 0x93d380e27LL, 0x935fbdf99LL, 0x8b004f544LL, 0xf21336ccbLL, 0x55be0a2d7LL, 0x31a272812LL, 0x9356f2104LL, 0x64cd11059LL, 0xb306fab7bLL, 0xc4b4bcecbLL, 0xa44ee754cLL, 0x9c5b95d4aLL, 0xafe82cb14LL, 0xd2802c70aLL, 0x9b067ca08LL, 0xa0d33eadfLL, 0xf82d374e8LL, 0x97608d4c1LL, 0x3c49f7262LL, 0x1f8b8b4b2LL, 0xd49171ea7LL, 0x9abe1e7f5LL, 0x127c694ccLL, 0xad02f7180LL, 0x48dcd2cc8LL, 0x781de93caLL, 0x2593187eeLL, 0xdc2e3515fLL, 0x97535dc18LL, 0x3db5f0785LL, 0xcb73b619dLL, 0x76c0cae0fLL, 0x195f0526dLL, 0x4b0893b28LL, 0xca2151e27LL, 0x0e01526baLL, 0x844d01096LL, 0x96ed3edd6LL, 0xfe1d07fadLL, 0x625d110ecLL, 0xd6e07dc43LL, 0xa0d531bbfLL, 0xed6e29fd3LL, 0x9aa5ff7e9LL, 0x2bf330b23LL, 0xaa905fb48LL, 0x575c3dd88LL, 0xc12a8ea3eLL, 0xa60ce7ea7LL, 0x36e3d46beLL, 0x84a1acf90LL, 0x99315f5efLL, 0x23c5c149eLL, 0xe819f9d2aLL, 0x0327b7f85LL, 0x60878c9fcLL, 0xbbe1b425fLL, 0x5efb57d1aLL, 0xae81e06a3LL, 0xc683416e0LL, 0xa138a207bLL, 0x531a8805dLL, 0x3207cd72bLL, 0x1ffad4babLL, 0xa05d08c41LL, 0xc4ffc6089LL, 0xf6ebda0bcLL, 0xf9c6b0a7bLL, 0x76ac7063fLL, 0xbd7b1a5b1LL, 0xf6e306a3fLL, 0x93f23d425LL, 0xc9834e422LL, 0x73088434aLL, 0xb618f4fe0LL, 0x7affb1ed0LL, 0x8de2b690dLL, 0xe7bbca4f9LL, 0x0e92d2cd5LL, 0xb572af3ddLL, 0xa32f50358LL, 0x97d0aca69LL, 0x4e02a1956LL, 0x489a38814LL, 0x16cde41bfLL, 0xf844bb35bLL, 0xb3cb5e287LL, 0x798ca35d5LL, 0xad78e6952LL, 0x74e3accf5LL, 0x2c2509397LL, 0x9ed3b6e0bLL, 0x382fd5392LL, 0x46b1753ccLL, 0x3f1a79503LL, 0xd511be53cLL, 0x2c0ad700bLL, 0x0c83dab06LL, 0x854c15d1cLL, 0xa27cbb3d7LL, 0xf178f1810LL, 0xaa69504f2LL, 0x619f3c356LL, 0x2a31f3e7cLL, 0xef900e61dLL, 0xdfe8751a9LL, 0x651358e73LL, 0xc825327afLL, 0xbc151fafaLL, 0x876051de6LL, 0x06729eb40LL, 0x75876a783LL, 0x8c76d5474LL, 0x39bd3dd20LL, 0xbbc32223bLL, 0xf8ae91f88LL, 0xe3bbca3d6LL, 0xa0a3ee436LL, 0xf993c8887LL, 0xde8781781LL, 0xc3d26acc2LL, 0xce1748eb0LL, 0x09c49b6abLL, 0xe7ea808f1LL, 0x34d62cf99LL, 0xf0dcc0da8LL, 0x49ca61d07LL, 0x1b930880dLL, 0xdca578c15LL, 0xda7a6a1ceLL, 0x9c3294a82LL, 0xf0874721eLL, 0xa5dc060edLL, 0x23a8939a5LL, 0x6f6c16f02LL, 0x42edd94dcLL, 0x5a74f1432LL, 0xe019cb4ddLL, 0xc2c5b533eLL, 0xecc894724LL, 0xa5cff9f11LL, 0x04a5864abLL, 0xbf6b96bc9LL, 0xd7b3ded99LL, 0x7a9377d6fLL, 0x8a7f9cef2LL, 0xacf09eaadLL, 0x785f73185LL, 0x8904b414bLL, 0xbd5fa7379LL, 0x43ddabc60LL, 0x17f40d8fbLL, 0xcf6903101LL, 0x4cf434f98LL, 0xa97973ef7LL, 0xb3c4ac601LL, 0xc0aad8a1bLL, 0x2150bb64dLL, 0xed72e5ac5LL, 0x131cef825LL, 0x8659cecc4LL, 0xf30a8f072LL, 0x457c90fdaLL, 0xc9df54666LL, 0x68743306fLL, 0x62021b53dLL, 0xf9d7ea28aLL, 0x844e5bcd0LL, 0xfb1a1a1dcLL, 0x1394fd8d2LL, 0xf744f941eLL, 0xc07e65afbLL, 0x84a9e17d6LL, 0x9cd3f1176LL, 0x332e89b30LL, 0xbb9140f2dLL, 0x941e8e334LL, 0x9439f6e24LL, 0x0b89c5739LL, 0x077975e23LL, 0x4317e76cbLL, 0x53f2c5011LL, 0x7826317f7LL, 0xfad95bff5LL, 0x053de8de6LL, 0x856bcf7edLL, 0x77772201bLL, 0x1b15d0bb4LL, 0x42d5df9e2LL, 0xd9c5aea63LL, 0xb4980534aLL, 0x89c348f43LL, 0x3d7300d9bLL, 0x49440d5e1LL, 0xce4694114LL, 0x9e6c19bd7LL, 0xfa1294b28LL, 0xe2b6e790dLL, 0xe4891435cLL, 0x706bb090aLL, 0xc2f74169cLL, 0x9d669a64dLL, 0x4118daf4bLL, 0x5b118d504LL, 0x3f57b597fLL, 0x916e47de1LL, 0xe3b88c4feLL, 0x2af4fd773LL, 0x74664c8dfLL, 0xd66194717LL, 0x90a0baf41LL, 0xcf1f647faLL, 0xea211f2d8LL, 0x75a1f220aLL, 0x9cb63c40dLL, 0x812805a51LL, 0xd5d503690LL, 0x532bc4026LL, 0x021a8d59fLL, 0x5150b9dd3LL, 0x0a2ee41baLL, 0x846fade51LL, 0xc684ba60eLL, 0x3a8f6efd7LL, 0x03e17b682LL, 0x3927db859LL, 0x87b0b1480LL, 0x52536e422LL, 0x946ed17ecLL, 0xa214c62c5LL, 0x4342229d4LL, 0x7cd868ed0LL, 0xf19ba2ab2LL, 0xf8c1c41ccLL, 0x0cc7d69fbLL, 0x3c3911e61LL, 0x18fc07576LL, 0x0846ea988LL, 0x9f86addc8LL, 0xcacea817eLL, 0x975a047cbLL, 0xcc00a9d6cLL, 0x35b095cfdLL, 0x1032b2bd9LL, 0x839311750LL, 0xf61bbb4b8LL, 0xbeddf32a6LL, 0x5db253de6LL, 0xad1c79f1aLL, 0x0943a5b28LL, 0x8574f9b27LL, 0x6cb284742LL, 0x66a469a9aLL, 0x9c9e646b7LL, 0x15e3f3da7LL, 0xa7335e7c1LL, 0x81d5b8c23LL, 0xd3ce4adb1LL, 0xe6c2c0436LL, 0x0c422445aLL, 0x69efe9391LL, 0x6e494fb4bLL, 0x52938a7d8LL, 0x1538c045aLL, 0x86ffd6a31LL, 0x3a7a1eda4LL, 0x6a06881dbLL, 0x0ee1f5cfeLL, 0x7dbd99f14LL, 0x2222f7d4fLL, 0xa092a9546LL, 0x4f6ea12ecLL, 0x786076e0dLL, 0x2025a3e06LL, 0x3f3c67e47LL, 0xeeb2ddb02LL, 0xb1997582fLL, 0x84774c908LL, 0xa94d9c44eLL, 0x687970da3LL, 0x4ac4aaaceLL, 0xaa5b6afcdLL, 0x797cefd6eLL, 0x239edc6f7LL, 0xf6b54c197LL, 0x71141e85aLL, 0x22be2c02bLL, 0xb8343a746LL, 0xbb01b3487LL, 0x2fc5f873dLL, 0x80dbb9d8fLL, 0x749b8643dLL, 0x61163a4efLL, 0x899b02afcLL, 0x6d1359b14LL, 0x0e87bed7eLL, 0x34e646200LL, 0xdb37c86d3LL, 0x4a0cf7e11LL, 0xe33dd1e6eLL, 0x3b788a101LL, 0x06a936d91LL, 0x1ddc58739LL, 0xc92051779LL, 0x838ce51aeLL, 0xa7a3ef32dLL, 0x9f7eb103aLL, 0x36b9802d8LL, 0x65da1e81cLL, 0xea1cf562fLL, 0xa8c63c0ceLL, 0xf6104a32aLL, 0x4c4cf0893LL, 0xd47da0be3LL, 0x80483d254LL, 0xdc6de57b1LL, 0x7fac92c49LL, 0xda1e5f16eLL, 0x4026949bfLL, 0x8e17a9d20LL, 0x12f3419d6LL, 0x4e9089cdfLL, 0xd8f5fc61eLL, 0xdc8f7325bLL, 0x61247ef19LL, 0x0c1d908c9LL, 0x69bd43b4cLL, 0x3f7f5c231LL, 0x91c41e9bdLL, 0xbf844084dLL, 0x05827c577LL, 0xc07d61e65LL, 0x7615c75b6LL, 0x62600d7bbLL, 0x82f62a3faLL, 0x95f7fe291LL, 0x2ea50c1e5LL, 0xc90ae812cLL, 0xc85c79bf6LL, 0x0614cafdaLL, 0x692bc66d5LL, 0x43cae4bbeLL, 0xcc4dd9e12LL, 0x02b1f9181LL, 0xd19a5261cLL, 0xd8e402b96LL, 0x08f730fc6LL, 0x159e9ba29LL, 0xb9413ddabLL, 0xbd296f2feLL, 0x53ae2f38dLL, 0x42e6e15c5LL, 0x5efba4ecfLL, 0x764371efeLL, 0x8b665b2e1LL, 0x542432a00LL, 0xddd7e3c19LL, 0x195083f58LL, 0x7ed57c706LL, 0xb50bbbe8eLL, 0x203d18735LL, 0x2a4c69b07LL, 0xd72e90958LL, 0xcd3c5031bLL, 0x313e2ee85LL, 0xa12fd86c6LL, 0x9009383eaLL, 0xe550f2a4fLL, 0x49ae8c013LL, 0xeba56010aLL, 0xa7210786cLL, 0xfda4a611fLL, 0xcfe525fb0LL, 0xefcaf6ef6LL, 0x23c31fd13LL, 0x3847c5dcdLL, 0x166fd6693LL, 0x06f8ec087LL, 0xa531e0fb4LL, 0x76f9bc318LL, 0xe56c0cb7fLL, 0x51e2d02baLL, 0xb3e8d6022LL, 0x9a20ad5faLL, 0x73af547b7LL, 0x5e6134b2eLL, 0x8582b0e60LL, 0xc8ea6019dLL, 0x281e3763eLL, 0x647d83e97LL, 0x293634305LL, 0x6743c18c0LL, 0x2a01782f9LL, 0xbf49e9eb6LL, 0x05856f3b9LL, 0x634812ac0LL, 0x035cbb63eLL, 0x032540c2aLL, 0xaf358f5e0LL, 0x7826f829fLL, 0xb8c89448bLL, 0xebbe0239dLL, 0x905e5aa89LL, 0x310ddb064LL, 0xb762f118bLL, 0xc9b1a8e31LL, 0xff0661391LL, 0x8a66f999fLL, 0xb3593b7ceLL, 0x9f603a864LL, 0xa23a960efLL, 0xaae9837acLL, 0xc755afc59LL, 0x9c76f21c9LL, 0x39cd67a7fLL, 0x29f1dfa26LL, 0x01a253c9cLL, 0x1d3a11177LL, 0x7f60cd2ddLL, 0x5871af5ddLL, 0xa7d3d617cLL, 0xddbb2b303LL, 0x6c69147baLL, 0x843954b47LL, 0x46cc229a9LL, 0x4eac19c20LL, 0xfb7b51ca4LL, 0x9b7015d5bLL, 0xf2051a917LL, 0xe701d5d53LL, 0x38fd5da8cLL, 0xd3f2acb84LL, 0xba7cb1ebeLL, 0x1f016ea57LL, 0xd63c1250fLL, 0x646f446adLL, 0xc43b287cdLL, 0xdf676c468LL, 0x30f777359LL, 0xb8f10af87LL, 0x88c425335LL, 0x6c9f778aeLL, 0x50da4eebaLL, 0x0690f680aLL, 0xac101a310LL, 0xe603ce909LL, 0xef2918ebeLL, 0x3bb23758aLL, 0x409e4b934LL, 0x74f744bfcLL, 0x64e96d541LL, 0x271bc72c6LL, 0xba27f9edeLL, 0x782a145a1LL, 0x61f275072LL, 0x8c15dac40LL, 0x3431268feLL, 0x9853d7243LL, 0x98ba31d02LL, 0x6d1b5e69cLL, 0xe67d3e6a8LL, 0x3afb9b2d3LL, 0x8aef7d109LL, 0x0e0d77de8LL, 0xdcbaa0356LL, 0x6bc718df0LL, 0x77d6f39faLL, 0x1207d50beLL, 0x68758144aLL, 0x5600bd7f1LL, 0x99722a481LL, 0xbf673f8d1LL, 0x4bf1cce7eLL, 0xd3ee2609bLL, 0x31e9e4c73LL, 0x32a28985bLL, 0x9314656c1LL, 0xcf02f5fdcLL, 0x2748d2cbeLL, 0xeeaa65fcaLL, 0xc9294684aLL, 0x706fb6725LL, 0x32f6c276bLL, 0xe030afe87LL, 0x912b88011LL, 0x2ab7ee1feLL, 0xb04877110LL, 0x474b92b6dLL, 0xaccab7218LL, 0x04c6bb58aLL, 0x0d6777d7cLL, 0x6f6008813LL, 0x1d8da74efLL, 0xd9d905134LL, 0x4ff1a2f68LL, 0x2861d5528LL, 0x4ed66d24dLL, 0x7ee0b92f3LL, 0x0f2979e98LL, 0x36291e9bbLL, 0x0635f0e0bLL, 0x6cf4ea059LL, 0xa20b467b1LL, 0x610cc1d4dLL, 0x2da5cb5fdLL, 0x07553968cLL, 0x844a86803LL, 0xb1d48ccc2LL, 0xbba3fe918LL, 0xae0d869f3LL, 0x7c6a7de9cLL, 0x91f8382f4LL, 0x3014094caLL, 0x8c3a9a5d5LL, 0x69c3f2722LL, 0x8bb38f982LL, 0xb8efcdcdaLL, 0xda51b2ff0LL, 0xcf8e8a44aLL, 0x8158ddc00LL, 0x643ecd9c0LL, 0x5e10383a9LL, 0x24a886e16LL, 0x4ba9db990LL, 0xc8b4e335fLL, 0x8b1c2c0b8LL, 0xfba632127LL, 0x77bb6e51eLL, 0x63142235cLL, 0x7906aa8d6LL, 0x0295334c5LL, 0x30e855681LL, 0x7cc4fc438LL, 0x1cba770b2LL, 0xeb67c65e9LL, 0xbf495ac78LL, 0x250ef8472LL, 0xe918df704LL, 0x9ae42835cLL, 0xba887baddLL, 0x0a9e3a8cdLL, 0x6b4efbb80LL, 0x47e50b225LL, 0x492ddb0bbLL, 0x58bc2506dLL, 0x52aedbb0eLL, 0x51eb43eb4LL, 0xea2d9d116LL, 0x278274efcLL, 0xc013733d6LL, 0xd371949d4LL, 0x8d49ee822LL, 0x30745b332LL, 0xafc18e441LL, 0x0cd9fb4d7LL, 0x582ae0f65LL, 0xcacbd79cbLL, 0x1fe675d20LL, 0xee7117735LL, 0xa7280378fLL, 0xbaf1b5a32LL, 0x0b5d5e9b3LL, 0x44196d9ddLL, 0xd8b6fdafcLL, 0x82450b356LL, 0x8e0a46aa9LL, 0x250b0460eLL, 0x44582149aLL, 0x18a09bc26LL, 0xb26286d64LL, 0xc9e4860ceLL, 0xadfc81dadLL, 0x16506214aLL, 0x038769b15LL, 0xc01b50928LL, 0x151ac514fLL, 0x5492593daLL, 0x5946d5c27LL, 0xab9aed4dfLL, 0xc91cd1da7LL, 0xc3495b589LL, 0x2e962ae83LL, 0xeab920345LL, 0x155b3b617LL, 0x985edf48fLL, 0xe758d6ba3LL, 0x99660780eLL, 0x7b8a41acfLL, 0x6c4f8c59fLL, 0x970c219faLL, 0x5fa614ff0LL, 0xa7b3adda7LL, 0x809edc138LL, 0xb4ee65663LL, 0x6b487e8baLL, 0xa530f957eLL, 0x8a533c79bLL, 0x00d94ff5cLL, 0x9b709ef88LL, 0xd7c38826eLL, 0x0e7bcd688LL, 0x23668c8a0LL, 0x87244e859LL, 0xb1006de44LL, 0x15b37df10LL, 0x801e94f9dLL, 0xbce729ec0LL, 0x17ddf288bLL, 0x4bafecdbdLL, 0x8536977b1LL, 0x6f5ddbf9aLL, 0x23d5da865LL, 0x68e3a57c7LL, 0xfbb7bc650LL, 0xa412fceb2LL, 0x0cb978a6fLL, 0x30b6a7328LL, 0x167252f06LL, 0xe0df087e5LL, 0x022465eb6LL, 0xb580a4f2cLL, 0x0198d1533LL, 0x6e118afbeLL, 0xa3a697b20LL, 0x481fe6809LL, 0xc1cae26f0LL, 0xad006f34bLL, 0xdef609d40LL, 0x18a918f11LL, 0x68a4bf8dfLL, 0x4f8f44a9aLL, 0x4311a21a3LL, 0x53d72ea12LL, 0x51e4bd4d4LL, 0xf2cda5994LL, 0xd575a8336LL, 0x41cf85c53LL, 0x30eda148aLL, 0x907fa024dLL, 0x6e3cf917bLL, 0x470d9c67dLL, 0x73dc15f58LL, 0x708ec5e31LL, 0x83e1f42e8LL, 0xb315ee8bbLL, 0xd6b511041LL, 0xea2405d10LL, 0x8f51802b0LL, 0xb2ab1513bLL, 0xf31e33ae6LL, 0x55a48d565LL, 0x57cd5d243LL, 0xe705530c5LL, 0xf0908bfd5LL, 0x37a4d3e77LL }; + +static const TagCodes tagCodes36h9 = TagCodes(36, 9, t36h9, sizeof(t36h9)/sizeof(t36h9[0])); + +} diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/TagDetection.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/TagDetection.h new file mode 100644 index 0000000..9016f3a --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/TagDetection.h @@ -0,0 +1,99 @@ +#ifndef TAGDETECTION_H +#define TAGDETECTION_H + +#include + +#include "opencv2/opencv.hpp" + +#include +#include + +namespace AprilTags { + +struct TagDetection { + + //! Constructor + TagDetection(); + + //! Constructor for manually creating tags in a world map + TagDetection(int id); + + //! Is the detection good enough? + bool good; + + //! Observed code + long long obsCode; + + //! Matched code + long long code; + + //! What was the ID of the detected tag? + int id; + + //! The hamming distance between the detected code and the true code + int hammingDistance; + + //! How many 90 degree rotations were required to align the code (internal use only) + int rotation; + + /////////////// Fields below are filled in by TagDetector /////////////// + //! Position (in fractional pixel coordinates) of the detection. + /* The points travel counter-clockwise around the target, always + * starting from the same corner of the tag. + */ + std::pair p[4]; + + //! Center of tag in pixel coordinates. + std::pair cxy; + + //! Measured in pixels, how long was the observed perimeter. + /*! Observed perimeter excludes the inferred perimeter which is used to connect incomplete quads. */ + float observedPerimeter; + + //! A 3x3 homography that computes pixel coordinates from tag-relative coordinates. + /* Both the input and output coordinates are 2D homogeneous vectors, with y = Hx. + * 'y' are pixel coordinates, 'x' are tag-relative coordinates. Tag coordinates span + * from (-1,-1) to (1,1). The orientation of the homography reflects the orientation + * of the target. + */ + Eigen::Matrix3d homography; + + //! Orientation in the xy plane + float getXYOrientation() const; + + //! The homography is relative to image center, whose coordinates are below. + std::pair hxy; + + //! Interpolate point given (x,y) is in tag coordinate space from (-1,-1) to (1,1). + std::pair interpolate(float x, float y) const; + + //! Used to eliminate redundant tags + bool overlapsTooMuch(const TagDetection &other) const; + + //! Relative pose of tag with respect to the camera + /* Returns the relative location and orientation of the tag using a + 4x4 homogeneous transformation matrix (see Hartley&Zisserman, + Multi-View Geometry, 2003). Requires knowledge of physical tag + size (side length of black square in meters) as well as camera + calibration (focal length and principal point); Result is in + camera frame (z forward, x right, y down) + */ + Eigen::Matrix4d getRelativeTransform(double tag_size, double fx, double fy, + double px, double py) const; + + //! Recover rotation matrix and translation vector of April tag relative to camera. + // Result is in object frame (x forward, y left, z up) + void getRelativeTranslationRotation(double tag_size, double fx, double fy, double px, double py, + Eigen::Vector3d& trans, Eigen::Matrix3d& rot) const; + + //! Draw the detection within the supplied image, including boarders and tag ID. + void draw(cv::Mat& image) const; + + //! Compare function to sort detections by std::sort + static bool sortByIdCompare (const TagDetection &a, const TagDetection &b) { return (a.id + +#include "opencv2/opencv.hpp" + +#include "apriltags//TagDetection.h" +#include "apriltags//TagFamily.h" +#include "apriltags//FloatImage.h" + +namespace AprilTags { + +class TagDetector { +public: + + const TagFamily thisTagFamily; + + //! Constructor + // note: TagFamily is instantiated here from TagCodes + TagDetector(const TagCodes& tagCodes, const size_t blackBorder=2) : thisTagFamily(tagCodes, blackBorder) {} + + std::vector extractTags(const cv::Mat& image); + +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/TagFamily.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/TagFamily.h new file mode 100644 index 0000000..e54e90e --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/TagFamily.h @@ -0,0 +1,106 @@ +#ifndef TAGFAMILY_H +#define TAGFAMILY_H + +#include +#include +#include +#include +#include + +#include "apriltags//TagDetection.h" +using namespace std; + +namespace AprilTags { + +class TagCodes { +public: + int bits; + int minHammingDistance; + std::vector codes; +public: + TagCodes(int bits, int minHammingDistance, + const unsigned long long* codesA, int num) + : bits(bits), minHammingDistance(minHammingDistance), + codes(codesA, codesA+num) // created vector for all entries of codesA + {} +}; + +//! Generic class for all tag encoding families +class TagFamily { +public: + //! The codes array is not copied internally and so must not be modified externally. + TagFamily(const TagCodes& tagCodes, const size_t blackBorder); + + void setErrorRecoveryBits(int b); + + void setErrorRecoveryFraction(float v); + + /* if the bits in w were arranged in a d*d grid and that grid was + * rotated, what would the new bits in w be? + * The bits are organized like this (for d = 3): + * + * 8 7 6 2 5 8 0 1 2 + * 5 4 3 ==> 1 4 7 ==> 3 4 5 (rotate90 applied twice) + * 2 1 0 0 3 6 6 7 8 + */ + static unsigned long long rotate90(unsigned long long w, int d); + + //! Computes the hamming distance between two unsigned long longs. + static int hammingDistance(unsigned long long a, unsigned long long b); + + //! How many bits are set in the unsigned long long? + static unsigned char popCountReal(unsigned long long w); + + static int popCount(unsigned long long w); + + //! Given an observed tag with code 'rCode', try to recover the id. + /* The corresponding fields of TagDetection will be filled in. */ + void decode(TagDetection& det, unsigned long long rCode) const; + + //! Prints the hamming distances of the tag codes. + void printHammingDistances() const; + + //! Numer of pixels wide of the inner black border. + int blackBorder; + + //! Number of bits in the tag. Must be n^2. + int bits; + + //! Dimension of tag. e.g. for 16 bits, dimension=4. Must be sqrt(bits). + int dimension; + + //! Minimum hamming distance between any two codes. + /* Accounting for rotational ambiguity? The code can recover + * (minHammingDistance-1)/2 bit errors. + */ + int minimumHammingDistance; + + /* The error recovery value determines our position on the ROC + * curve. We will report codes that are within errorRecoveryBits + * of a valid code. Small values mean greater rejection of bogus + * tags (but false negatives). Large values mean aggressive + * reporting of bad tags (but with a corresponding increase in + * false positives). + */ + int errorRecoveryBits; + + //! The array of the codes. The id for a code is its index. + std::vector codes; + + static const int popCountTableShift = 12; + static const unsigned int popCountTableSize = 1 << popCountTableShift; + static unsigned char popCountTable[popCountTableSize]; + + //! Initializes the static popCountTable + static class TableInitializer { + public: + TableInitializer() { + for (unsigned int i = 0; i < TagFamily::popCountTableSize; i++) + TagFamily::popCountTable[i] = TagFamily::popCountReal(i); + } + } initializer; +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/UnionFindSimple.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/UnionFindSimple.h new file mode 100644 index 0000000..841f576 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/UnionFindSimple.h @@ -0,0 +1,41 @@ +#ifndef UNIONFINDSIMPLE_H +#define UNIONFINDSIMPLE_H + +#include + +namespace AprilTags { + +//! Implementation of disjoint set data structure using the union-find algorithm +class UnionFindSimple { + //! Identifies parent ids and sizes. + struct Data { + int id; + int size; + }; + +public: + explicit UnionFindSimple(int maxId) : data(maxId) { + init(); + }; + + int getSetSize(int thisId) { return data[getRepresentative(thisId)].size; } + + int getRepresentative(int thisId); + + //! Returns the id of the merged node. + /* @param aId + * @param bId + */ + int connectNodes(int aId, int bId); + + void printDataVector() const; + +private: + void init(); + + std::vector data; +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/XYWeight.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/XYWeight.h new file mode 100644 index 0000000..064b73d --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/XYWeight.h @@ -0,0 +1,19 @@ +#ifndef XYWeight_H_ +#define XYWeight_H_ + +namespace AprilTags { + +//! Represents a triple holding an x value, y value, and weight value. +struct XYWeight { + float x; + float y; + float weight; + + XYWeight(float xval, float yval, float weightval) : + x(xval), y(yval), weight(weightval) {} + +}; + +} // namespace + +#endif diff --git a/thirdparty/apriltag/ethz_apriltag2/include/apriltags/pch.h b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/pch.h new file mode 100644 index 0000000..1e4f58f --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/include/apriltags/pch.h @@ -0,0 +1,17 @@ +#include "apriltags/Edge.h" +#include "apriltags/FloatImage.h" +#include "apriltags/GLine2D.h" +//#include "apriltags/GLineSegment2D.h" +#include "apriltags/Gaussian.h" +//#include "apriltags/GrayModel.h" +//#include "apriltags/Gridder.h" +#include "apriltags/Homography33.h" +#include "apriltags/MathUtil.h" +//#include "apriltags/Quad.h" +//#include "apriltags/Segment.h" +//#include "apriltags/TagDetection.h" +//#include "apriltags/TagDetector.h" +//#include "apriltags/TagFamily.h" +#include "apriltags/UnionFindSimple.h" +#include "apriltags/XYWeight.h" + diff --git a/thirdparty/apriltag/ethz_apriltag2/package.xml b/thirdparty/apriltag/ethz_apriltag2/package.xml new file mode 100644 index 0000000..4fc8b1c --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/package.xml @@ -0,0 +1,13 @@ + + + ethz_apriltag2 + ethz_apriltag2 + 0.0.1 + Paul Furgale + Paul Furgale + New BSD + catkin + cmake_modules + opencv + eigen2 + diff --git a/thirdparty/apriltag/ethz_apriltag2/src/Edge.cc b/thirdparty/apriltag/ethz_apriltag2/src/Edge.cc new file mode 100644 index 0000000..d2d21d0 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/Edge.cc @@ -0,0 +1,119 @@ +#include "apriltags/Edge.h" +#include "apriltags/FloatImage.h" +#include "apriltags/MathUtil.h" +#include "apriltags/UnionFindSimple.h" + +namespace AprilTags { + +float const Edge::minMag = 0.004f; +float const Edge::maxEdgeCost = 30.f * float(M_PI) / 180.f; +int const Edge::WEIGHT_SCALE = 100; +float const Edge::thetaThresh = 100; +float const Edge::magThresh = 1200; + +int Edge::edgeCost(float theta0, float theta1, float mag1) { + if (mag1 < minMag) // mag0 was checked by the main routine so no need to recheck here + return -1; + + const float thetaErr = std::abs(MathUtil::mod2pi(theta1 - theta0)); + if (thetaErr > maxEdgeCost) + return -1; + + const float normErr = thetaErr / maxEdgeCost; + return (int) (normErr*WEIGHT_SCALE); +} + +void Edge::calcEdges(float theta0, int x, int y, + const FloatImage& theta, const FloatImage& mag, + std::vector &edges, size_t &nEdges) { + int width = theta.getWidth(); + int thisPixel = y*width+x; + + // horizontal edge + int cost1 = edgeCost(theta0, theta.get(x+1,y), mag.get(x+1,y)); + if (cost1 >= 0) { + edges[nEdges].cost = cost1; + edges[nEdges].pixelIdxA = thisPixel; + edges[nEdges].pixelIdxB = y*width+x+1; + ++nEdges; + } + + // vertical edge + int cost2 = edgeCost(theta0, theta.get(x, y+1), mag.get(x,y+1)); + if (cost2 >= 0) { + edges[nEdges].cost = cost2; + edges[nEdges].pixelIdxA = thisPixel; + edges[nEdges].pixelIdxB = (y+1)*width+x; + ++nEdges; + } + + // downward diagonal edge + int cost3 = edgeCost(theta0, theta.get(x+1, y+1), mag.get(x+1,y+1)); + if (cost3 >= 0) { + edges[nEdges].cost = cost3; + edges[nEdges].pixelIdxA = thisPixel; + edges[nEdges].pixelIdxB = (y+1)*width+x+1; + ++nEdges; + } + + // updward diagonal edge + int cost4 = (x == 0) ? -1 : edgeCost(theta0, theta.get(x-1, y+1), mag.get(x-1,y+1)); + if (cost4 >= 0) { + edges[nEdges].cost = cost4; + edges[nEdges].pixelIdxA = thisPixel; + edges[nEdges].pixelIdxB = (y+1)*width+x-1; + ++nEdges; + } +} + +void Edge::mergeEdges(std::vector &edges, UnionFindSimple &uf, + float tmin[], float tmax[], float mmin[], float mmax[]) { + for (size_t i = 0; i < edges.size(); i++) { + int ida = edges[i].pixelIdxA; + int idb = edges[i].pixelIdxB; + + ida = uf.getRepresentative(ida); + idb = uf.getRepresentative(idb); + + if (ida == idb) + continue; + + int sza = uf.getSetSize(ida); + int szb = uf.getSetSize(idb); + + float tmina = tmin[ida], tmaxa = tmax[ida]; + float tminb = tmin[idb], tmaxb = tmax[idb]; + + float costa = (tmaxa-tmina); + float costb = (tmaxb-tminb); + + // bshift will be a multiple of 2pi that aligns the spans of 'b' with 'a' + // so that we can properly take the union of them. + float bshift = MathUtil::mod2pi((tmina+tmaxa)/2, (tminb+tmaxb)/2) - (tminb+tmaxb)/2; + + float tminab = min(tmina, tminb + bshift); + float tmaxab = max(tmaxa, tmaxb + bshift); + + if (tmaxab-tminab > 2*(float)M_PI) // corner case that's probably not too useful to handle correctly, oh well. + tmaxab = tminab + 2*(float)M_PI; + + float mminab = min(mmin[ida], mmin[idb]); + float mmaxab = max(mmax[ida], mmax[idb]); + + // merge these two clusters? + float costab = (tmaxab - tminab); + if (costab <= (min(costa, costb) + Edge::thetaThresh/(sza+szb)) && + (mmaxab-mminab) <= min(mmax[ida]-mmin[ida], mmax[idb]-mmin[idb]) + Edge::magThresh/(sza+szb)) { + + int idab = uf.connectNodes(ida, idb); + + tmin[idab] = tminab; + tmax[idab] = tmaxab; + + mmin[idab] = mminab; + mmax[idab] = mmaxab; + } + } +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/FloatImage.cc b/thirdparty/apriltag/ethz_apriltag2/src/FloatImage.cc new file mode 100644 index 0000000..dba9019 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/FloatImage.cc @@ -0,0 +1,77 @@ +#include "apriltags/FloatImage.h" +#include "apriltags/Gaussian.h" +#include + +namespace AprilTags { + +FloatImage::FloatImage() : width(0), height(0), pixels() {} + +FloatImage::FloatImage(int widthArg, int heightArg) + : width(widthArg), height(heightArg), pixels(widthArg*heightArg) {} + +FloatImage::FloatImage(int widthArg, int heightArg, const std::vector& pArg) + : width(widthArg), height(heightArg), pixels(pArg) {} + +FloatImage& FloatImage::operator=(const FloatImage& other) { + width = other.width; + height = other.height; + if (pixels.size() != other.pixels.size()) + pixels.resize(other.pixels.size()); + pixels = other.pixels; + return *this; +} + +void FloatImage::decimateAvg() { + int nWidth = width/2; + int nHeight = height/2; + + for (int y = 0; y < nHeight; y++) + for (int x = 0; x < nWidth; x++) + pixels[y*nWidth+x] = pixels[(2*y)*width + (2*x)]; + + width = nWidth; + height = nHeight; + pixels.resize(nWidth*nHeight); +} + +void FloatImage::normalize() { + const float maxVal = *max_element(pixels.begin(),pixels.end()); + const float minVal = *min_element(pixels.begin(),pixels.end()); + const float range = maxVal - minVal; + const float rescale = 1 / range; + for ( unsigned int i = 0; i < pixels.size(); i++ ) + pixels[i] = (pixels[i]-minVal) * rescale; +} + +void FloatImage::filterFactoredCentered(const std::vector& fhoriz, const std::vector& fvert) { + // do horizontal + std::vector r(pixels); + + for (int y = 0; y < height; y++) { + Gaussian::convolveSymmetricCentered(pixels, y*width, width, fhoriz, r, y*width); + } + + // do vertical + std::vector tmp(height); // column before convolution + std::vector tmp2(height); // column after convolution + + for (int x = 0; x < width; x++) { + + // copy the column out for locality + for (int y = 0; y < height; y++) + tmp[y] = r[y*width + x]; + + Gaussian::convolveSymmetricCentered(tmp, 0, height, fvert, tmp2, 0); + + for (int y = 0; y < height; y++) + pixels[y*width + x] = tmp2[y]; + } +} + +void FloatImage::printMinMax() const { + std::cout << "Min: " << *min_element(pixels.begin(),pixels.end()) << ", Max: " << *max_element(pixels.begin(),pixels.end()) << std::endl; + //for (int i = 0; i < getNumFloatImagePixels(); i++) + // std::cout << "Index[" << i << "]: " << this->normalize().getFloatImagePixels()[i] << endl; +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/GLine2D.cc b/thirdparty/apriltag/ethz_apriltag2/src/GLine2D.cc new file mode 100644 index 0000000..4bb0926 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/GLine2D.cc @@ -0,0 +1,109 @@ +#include "apriltags/GLine2D.h" + +namespace AprilTags { + +GLine2D::GLine2D() + : dx(0), dy(0), p(0,0), didNormalizeSlope(false), didNormalizeP(false) {} + +GLine2D::GLine2D(float slope, float b) + : dx(1), dy(slope), p(0,b), didNormalizeSlope(false), didNormalizeP(false){} + +GLine2D::GLine2D(float dX, float dY, const std::pair& pt) + : dx(dX), dy(dY), p(pt), didNormalizeSlope(false), didNormalizeP(false) {} + +GLine2D::GLine2D(const std::pair& p1, const std::pair& p2) + : dx(p2.first - p1.first), dy(p2.second - p1.second), p(p1), didNormalizeSlope(false), didNormalizeP(false) {} + +float GLine2D::getLineCoordinate(const std::pair& pt) { + normalizeSlope(); + return pt.first*dx + pt.second*dy; +} + +std::pair GLine2D::getPointOfCoordinate(float coord) { + normalizeP(); + return std::pair(p.first + coord*dx, p.second + coord*dy); +} + +std::pair GLine2D::intersectionWith(const GLine2D& line) const { + float m00 = dx; + float m01 = -line.getDx(); + float m10 = dy; + float m11 = -line.getDy(); + + // determinant of 'm' + float det = m00*m11 - m01*m10; + + // parallel lines? if so, return (-1,0). + if (fabs(det) < 1e-10) + return std::pair(-1,0); + + // inverse of 'm' + float i00 = m11/det; + // float i11 = m00/det; + float i01 = -m01/det; + // float i10 = -m10/det; + + float b00 = line.getFirst() - p.first; + float b10 = line.getSecond() - p.second; + + float x00 = i00*b00 + i01*b10; + + return std::pair(dx*x00+p.first, dy*x00+p.second); +} + +GLine2D GLine2D::lsqFitXYW(const std::vector& xyweights) { + float Cxx=0, Cyy=0, Cxy=0, Ex=0, Ey=0, mXX=0, mYY=0, mXY=0, mX=0, mY=0; + float n=0; + + int idx = 0; + for (unsigned int i = 0; i < xyweights.size(); i++) { + float x = xyweights[i].x; + float y = xyweights[i].y; + float alpha = xyweights[i].weight; + + mY += y*alpha; + mX += x*alpha; + mYY += y*y*alpha; + mXX += x*x*alpha; + mXY += x*y*alpha; + n += alpha; + + idx++; + } + + Ex = mX/n; + Ey = mY/n; + Cxx = mXX/n - MathUtil::square(mX/n); + Cyy = mYY/n - MathUtil::square(mY/n); + Cxy = mXY/n - (mX/n)*(mY/n); + + // find dominant direction via SVD + float phi = 0.5f*std::atan2(-2*Cxy,(Cyy-Cxx)); + // float rho = Ex*cos(phi) + Ey*sin(phi); //why is this needed if he never uses it? + std::pair pts = std::pair(Ex,Ey); + + // compute line parameters + return GLine2D(-std::sin(phi), std::cos(phi), pts); +} + +void GLine2D::normalizeSlope() { + if ( !didNormalizeSlope ) { + float mag = std::sqrt(dx*dx+dy*dy); + dx /= mag; + dy /= mag; + didNormalizeSlope=true; + } +} + +void GLine2D::normalizeP() { + if ( !didNormalizeP ) { + normalizeSlope(); + // we already have a point (P) on the line, and we know the line vector U + // and its perpendicular vector V: so, P'=P.*V *V + float dotprod = -dy*p.first + dx*p.second; + p = std::pair(-dy*dotprod, dx*dotprod); + didNormalizeP = true; + } +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/GLineSegment2D.cc b/thirdparty/apriltag/ethz_apriltag2/src/GLineSegment2D.cc new file mode 100644 index 0000000..2177b48 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/GLineSegment2D.cc @@ -0,0 +1,26 @@ +#include "apriltags/GLineSegment2D.h" +#include + +namespace AprilTags { + +GLineSegment2D::GLineSegment2D(const std::pair& p0Arg, const std::pair& p1Arg) +: line(p0Arg,p1Arg), p0(p0Arg), p1(p1Arg), weight() {} + +GLineSegment2D GLineSegment2D::lsqFitXYW(const std::vector& xyweight) { + GLine2D gline = GLine2D::lsqFitXYW(xyweight); + float maxcoord = -std::numeric_limits::infinity(); + float mincoord = std::numeric_limits::infinity();; + + for (unsigned int i = 0; i < xyweight.size(); i++) { + std::pair p(xyweight[i].x, xyweight[i].y); + float coord = gline.getLineCoordinate(p); + maxcoord = std::max(maxcoord, coord); + mincoord = std::min(mincoord, coord); + } + + std::pair minValue = gline.getPointOfCoordinate(mincoord); + std::pair maxValue = gline.getPointOfCoordinate(maxcoord); + return GLineSegment2D(minValue,maxValue); +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/Gaussian.cc b/thirdparty/apriltag/ethz_apriltag2/src/Gaussian.cc new file mode 100644 index 0000000..52c0ae8 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/Gaussian.cc @@ -0,0 +1,71 @@ +#include "apriltags/Gaussian.h" +#include + +namespace AprilTags { + +bool Gaussian::warned = false; + +std::vector Gaussian::makeGaussianFilter(float sigma, int n) { + std::vector f(n,0.0f); + + if (sigma == 0) { + for (int i = 0; i < n; i++) + f[i] = 0; + f[n/2] = 1; + return f; + } + + double const inv_variance = 1./(2*sigma*sigma); + float sum = 0; + for (int i = 0; i < n; i++) { + int j = i - n/2; + f[i] = (float)std::exp(-j*j * inv_variance); + sum += f[i]; + } + + // normalize the gaussian + for (int i = 0; i < n; i++) + f[i] /= sum; + + return f; +} + +void Gaussian::convolveSymmetricCentered(const std::vector& a, unsigned int aoff, unsigned int alen, + const std::vector& f, std::vector& r, unsigned int roff) { + if ((f.size()&1)== 0 && !warned) { + std::cout<<"convolveSymmetricCentered Warning: filter is not odd length\n"; + warned = true; + } + + for (size_t i = f.size()/2; i < f.size(); i++) { + double acc = 0; + for (size_t j = 0; j < f.size(); j++) { + if ((aoff + i) < j || (aoff + i) >= (alen + j)) + acc += a[aoff] * f[j]; + else + acc += a[aoff + i - j] * f[j]; + } + r[roff + i - f.size()/2] = (float)acc; + } + + for (size_t i = f.size(); i < alen; i++) { + double acc = 0; + for (unsigned int j = 0; j < f.size(); j++) { + acc += a[aoff + i - j] * f[j]; + } + r[roff + i - f.size()/2] = (float)acc; + } + + for (size_t i = alen; i < alen + f.size()/2; i++) { + double acc = 0; + for (size_t j = 0; j < f.size(); j++) { + if ((aoff + i) >= (alen + j) || (aoff + i) < j) + acc += a[aoff + alen - 1] * f[j]; + else + acc += a[aoff + i - j] * f[j]; + } + r[roff + i - f.size()/2] = (float)acc; + } +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/GrayModel.cc b/thirdparty/apriltag/ethz_apriltag2/src/GrayModel.cc new file mode 100644 index 0000000..129d2ec --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/GrayModel.cc @@ -0,0 +1,81 @@ +#include + +#include +#include + +#include "apriltags/GrayModel.h" + +namespace AprilTags { + +GrayModel::GrayModel() : A(), v(), b(), nobs(0), dirty(false) { + A.setZero(); + v.setZero(); + b.setZero(); +} + +void GrayModel::addObservation(float x, float y, float gray) { + float xy = x*y; + + // update only upper-right elements. A'A is symmetric, + // we'll fill the other elements in later. + A(0,0) += x*x; + A(0,1) += x*y; + A(0,2) += x*xy; + A(0,3) += x; + A(1,1) += y*y; + A(1,2) += y*xy; + A(1,3) += y; + A(2,2) += xy*xy; + A(2,3) += xy; + A(3,3) += 1; + + b[0] += x*gray; + b[1] += y*gray; + b[2] += xy*gray; + b[3] += gray; + + nobs++; + dirty = true; +} + +float GrayModel::interpolate(float x, float y) { + if (dirty) compute(); + return v[0]*x + v[1]*y + v[2]*x*y + v[3]; +} + +void GrayModel::compute() { + // we really only need 4 linearly independent observations to fit our answer, but we'll be very + // sensitive to noise if we don't have an over-determined system. Thus, require at least 6 + // observations (or we'll use a constant model below). + + dirty = false; + if (nobs >= 6) { + // make symmetric + Eigen::Matrix4d Ainv; + for (int i = 0; i < 4; i++) + for (int j = i+1; j < 4; j++) + A(j,i) = A(i,j); + + // try { + // Ainv = A.inverse(); + bool invertible; + double det_unused; + A.computeInverseAndDetWithCheck(Ainv, det_unused, invertible); + if (invertible) { + v = Ainv * b; + return; + } + std::cerr << "AprilTags::GrayModel::compute() has underflow in matrix inverse\n"; + // } + // catch (std::underflow_error&) { + // std::cerr << "AprilTags::GrayModel::compute() has underflow in matrix inverse\n"; + // } + } + + // If we get here, either nobs < 6 or the matrix inverse generated + // an underflow, so use a constant model. + v.setZero(); // need the cast to avoid operator= ambiguity wrt. const-ness + v[3] = b[3] / nobs; +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/Homography33.cc b/thirdparty/apriltag/ethz_apriltag2/src/Homography33.cc new file mode 100644 index 0000000..87c906a --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/Homography33.cc @@ -0,0 +1,216 @@ +//-*-c++-*- + +#include + +#include + +#include + +#include "apriltags/Homography33.h" + +Homography33::Homography33(const std::pair &opticalCenter) : cxy(opticalCenter), fA(), H(), valid(false) { + fA.setZero(); + H.setZero(); +} + +Eigen::Matrix3d& Homography33::getH() { + compute(); + return H; +} + +#ifdef STABLE_H +void Homography33::setCorrespondences(const std::vector< std::pair > &sPts, + const std::vector< std::pair > &dPts) { + valid = false; + srcPts = sPts; + dstPts = dPts; +} +#else +void Homography33::addCorrespondence(float worldx, float worldy, float imagex, float imagey) { + valid = false; + imagex -= cxy.first; + imagey -= cxy.second; + + /* Here are the rows of matrix A. We will compute A'*A + * A[3*i+0][3] = -worldxyh[i][0]*imagexy[i][2]; + * A[3*i+0][4] = -worldxyh[i][1]*imagexy[i][2]; + * A[3*i+0][5] = -worldxyh[i][2]*imagexy[i][2]; + * A[3*i+0][6] = worldxyh[i][0]*imagexy[i][1]; + * A[3*i+0][7] = worldxyh[i][1]*imagexy[i][1]; + * A[3*i+0][8] = worldxyh[i][2]*imagexy[i][1]; + * + * A[3*i+1][0] = worldxyh[i][0]*imagexy[i][2]; + * A[3*i+1][1] = worldxyh[i][1]*imagexy[i][2]; + * A[3*i+1][2] = worldxyh[i][2]*imagexy[i][2]; + * A[3*i+1][6] = -worldxyh[i][0]*imagexy[i][0]; + * A[3*i+1][7] = -worldxyh[i][1]*imagexy[i][0]; + * A[3*i+1][8] = -worldxyh[i][2]*imagexy[i][0]; + * + * A[3*i+2][0] = -worldxyh[i][0]*imagexy[i][1]; + * A[3*i+2][1] = -worldxyh[i][1]*imagexy[i][1]; + * A[3*i+2][2] = -worldxyh[i][2]*imagexy[i][1]; + * A[3*i+2][3] = worldxyh[i][0]*imagexy[i][0]; + * A[3*i+2][4] = worldxyh[i][1]*imagexy[i][0]; + * A[3*i+2][5] = worldxyh[i][2]*imagexy[i][0]; + */ + + // only update upper-right. A'A is symmetric, we'll finish the lower left later. + float a03 = -worldx; + float a04 = -worldy; + float a05 = -1; + float a06 = worldx*imagey; + float a07 = worldy*imagey; + float a08 = imagey; + + fA(3, 3) += a03*a03; + fA(3, 4) += a03*a04; + fA(3, 5) += a03*a05; + fA(3, 6) += a03*a06; + fA(3, 7) += a03*a07; + fA(3, 8) += a03*a08; + + fA(4, 4) += a04*a04; + fA(4, 5) += a04*a05; + fA(4, 6) += a04*a06; + fA(4, 7) += a04*a07; + fA(4, 8) += a04*a08; + + fA(5, 5) += a05*a05; + fA(5, 6) += a05*a06; + fA(5, 7) += a05*a07; + fA(5, 8) += a05*a08; + + fA(6, 6) += a06*a06; + fA(6, 7) += a06*a07; + fA(6, 8) += a06*a08; + + fA(7, 7) += a07*a07; + fA(7, 8) += a07*a08; + + fA(8, 8) += a08*a08; + + float a10 = worldx; + float a11 = worldy; + float a12 = 1; + float a16 = -worldx*imagex; + float a17 = -worldy*imagex; + float a18 = -imagex; + + fA(0, 0) += a10*a10; + fA(0, 1) += a10*a11; + fA(0, 2) += a10*a12; + fA(0, 6) += a10*a16; + fA(0, 7) += a10*a17; + fA(0, 8) += a10*a18; + + fA(1, 1) += a11*a11; + fA(1, 2) += a11*a12; + fA(1, 6) += a11*a16; + fA(1, 7) += a11*a17; + fA(1, 8) += a11*a18; + + fA(2, 2) += a12*a12; + fA(2, 6) += a12*a16; + fA(2, 7) += a12*a17; + fA(2, 8) += a12*a18; + + fA(6, 6) += a16*a16; + fA(6, 7) += a16*a17; + fA(6, 8) += a16*a18; + + fA(7, 7) += a17*a17; + fA(7, 8) += a17*a18; + + fA(8, 8) += a18*a18; + + float a20 = -worldx*imagey; + float a21 = -worldy*imagey; + float a22 = -imagey; + float a23 = worldx*imagex; + float a24 = worldy*imagex; + float a25 = imagex; + + fA(0, 0) += a20*a20; + fA(0, 1) += a20*a21; + fA(0, 2) += a20*a22; + fA(0, 3) += a20*a23; + fA(0, 4) += a20*a24; + fA(0, 5) += a20*a25; + + fA(1, 1) += a21*a21; + fA(1, 2) += a21*a22; + fA(1, 3) += a21*a23; + fA(1, 4) += a21*a24; + fA(1, 5) += a21*a25; + + fA(2, 2) += a22*a22; + fA(2, 3) += a22*a23; + fA(2, 4) += a22*a24; + fA(2, 5) += a22*a25; + + fA(3, 3) += a23*a23; + fA(3, 4) += a23*a24; + fA(3, 5) += a23*a25; + + fA(4, 4) += a24*a24; + fA(4, 5) += a24*a25; + + fA(5, 5) += a25*a25; +} +#endif + +#ifdef STABLE_H +void Homography33::compute() { + if ( valid ) return; + + std::vector sPts; + std::vector dPts; + for (int i=0; i<4; i++) { + sPts.push_back(cv::Point2f(srcPts[i].first, srcPts[i].second)); + } + for (int i=0; i<4; i++) { + dPts.push_back(cv::Point2f(dstPts[i].first - cxy.first, dstPts[i].second - cxy.second)); + } + cv::Mat homography = cv::findHomography(sPts, dPts); + for (int c=0; c<3; c++) { + for (int r=0; r<3; r++) { + H(r,c) = homography.at(r,c); + } + } + + valid = true; +} +#else +void Homography33::compute() { + if ( valid ) return; + + // make symmetric + for (int i = 0; i < 9; i++) + for (int j = i+1; j < 9; j++) + fA(j,i) = fA(i,j); + + Eigen::JacobiSVD svd(fA, Eigen::ComputeFullU | Eigen::ComputeFullV); + Eigen::MatrixXd eigV = svd.matrixV(); + + for (int i = 0; i < 3; i++) { + for (int j = 0; j < 3; j++) { + H(i,j) = eigV(i*3+j, eigV.cols()-1); + } + } + + valid = true; +} +#endif + +std::pair Homography33::project(float worldx, float worldy) { + compute(); + + std::pair ixy; + ixy.first = H(0,0)*worldx + H(0,1)*worldy + H(0,2); + ixy.second = H(1,0)*worldx + H(1,1)*worldy + H(1,2); + float z = H(2,0)*worldx + H(2,1)*worldy + H(2,2); + ixy.first = ixy.first/z + cxy.first; + ixy.second = ixy.second/z + cxy.second; + return ixy; +} + diff --git a/thirdparty/apriltag/ethz_apriltag2/src/MathUtil.cc b/thirdparty/apriltag/ethz_apriltag2/src/MathUtil.cc new file mode 100644 index 0000000..8f4adf3 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/MathUtil.cc @@ -0,0 +1,11 @@ +#include "apriltags/MathUtil.h" + +namespace AprilTags{ + +// Output operator for std::pair, useful for debugging +std::ostream& operator<<(std::ostream &os, const std::pair &pt) { + os << pt.first << "," << pt.second; + return os; +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/Quad.cc b/thirdparty/apriltag/ethz_apriltag2/src/Quad.cc new file mode 100644 index 0000000..cc8071d --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/Quad.cc @@ -0,0 +1,159 @@ +#include + +#include "apriltags/FloatImage.h" +#include "apriltags/MathUtil.h" +#include "apriltags/GLine2D.h" +#include "apriltags/Quad.h" +#include "apriltags/Segment.h" + +namespace AprilTags { + +const float Quad::maxQuadAspectRatio = 32; + +Quad::Quad(const std::vector< std::pair >& p, const std::pair& opticalCenter) + : quadPoints(p), segments(), observedPerimeter(), homography(opticalCenter) { +#ifdef STABLE_H + std::vector< std::pair > srcPts; + srcPts.push_back(std::make_pair(-1, -1)); + srcPts.push_back(std::make_pair( 1, -1)); + srcPts.push_back(std::make_pair( 1, 1)); + srcPts.push_back(std::make_pair(-1, 1)); + homography.setCorrespondences(srcPts, p); +#else + homography.addCorrespondence(-1, -1, quadPoints[0].first, quadPoints[0].second); + homography.addCorrespondence( 1, -1, quadPoints[1].first, quadPoints[1].second); + homography.addCorrespondence( 1, 1, quadPoints[2].first, quadPoints[2].second); + homography.addCorrespondence(-1, 1, quadPoints[3].first, quadPoints[3].second); +#endif + +#ifdef INTERPOLATE + p0 = Eigen::Vector2f(p[0].first, p[0].second); + p3 = Eigen::Vector2f(p[3].first, p[3].second); + p01 = (Eigen::Vector2f(p[1].first, p[1].second) - p0); + p32 = (Eigen::Vector2f(p[2].first, p[2].second) - p3); +#endif +} + +std::pair Quad::interpolate(float x, float y) { +#ifdef INTERPOLATE + Eigen::Vector2f r1 = p0 + p01 * (x+1.)/2.; + Eigen::Vector2f r2 = p3 + p32 * (x+1.)/2.; + Eigen::Vector2f r = r1 + (r2-r1) * (y+1)/2; + return std::pair(r(0), r(1)); +#else + return homography.project(x,y); +#endif +} + +std::pair Quad::interpolate01(float x, float y) { + return interpolate(2*x-1, 2*y-1); +} + +void Quad::search(const FloatImage& fImage, std::vector& path, + Segment& parent, int depth, std::vector& quads, + const std::pair& opticalCenter) { + // cout << "Searching segment " << parent.getId() << ", depth=" << depth << ", #children=" << parent.children.size() << endl; + // terminal depth occurs when we've found four segments. + if (depth == 4) { + // cout << "Entered terminal depth" << endl; // debug code + + // Is the first segment the same as the last segment (i.e., a loop?) + if (path[4] == path[0]) { + // the 4 corners of the quad as computed by the intersection of segments. + std::vector< std::pair > p(4); + float calculatedPerimeter = 0; + bool bad = false; + for (int i = 0; i < 4; i++) { + // compute intersections between all the lines. This will give us + // sub-pixel accuracy for the corners of the quad. + GLine2D linea(std::make_pair(path[i]->getX0(),path[i]->getY0()), + std::make_pair(path[i]->getX1(),path[i]->getY1())); + GLine2D lineb(std::make_pair(path[i+1]->getX0(),path[i+1]->getY0()), + std::make_pair(path[i+1]->getX1(),path[i+1]->getY1())); + + p[i] = linea.intersectionWith(lineb); + calculatedPerimeter += path[i]->getLength(); + + // no intersection? Occurs when the lines are almost parallel. + if (p[i].first == -1) + bad = true; + } + // cout << "bad = " << bad << endl; + // eliminate quads that don't form a simply connected loop, i.e., those + // that form an hour glass, or wind the wrong way. + if (!bad) { + float t0 = std::atan2(p[1].second-p[0].second, p[1].first-p[0].first); + float t1 = std::atan2(p[2].second-p[1].second, p[2].first-p[1].first); + float t2 = std::atan2(p[3].second-p[2].second, p[3].first-p[2].first); + float t3 = std::atan2(p[0].second-p[3].second, p[0].first-p[3].first); + + // double ttheta = fmod(t1-t0, 2*M_PI) + fmod(t2-t1, 2*M_PI) + + // fmod(t3-t2, 2*M_PI) + fmod(t0-t3, 2*M_PI); + float ttheta = MathUtil::mod2pi(t1-t0) + MathUtil::mod2pi(t2-t1) + + MathUtil::mod2pi(t3-t2) + MathUtil::mod2pi(t0-t3); + // cout << "ttheta=" << ttheta << endl; + // the magic value is -2*PI. It should be exact, + // but we allow for (lots of) numeric imprecision. + if (ttheta < -7 || ttheta > -5) + bad = true; + } + + if (!bad) { + float d0 = MathUtil::distance2D(p[0], p[1]); + float d1 = MathUtil::distance2D(p[1], p[2]); + float d2 = MathUtil::distance2D(p[2], p[3]); + float d3 = MathUtil::distance2D(p[3], p[0]); + float d4 = MathUtil::distance2D(p[0], p[2]); + float d5 = MathUtil::distance2D(p[1], p[3]); + + // check sizes + if (d0 < Quad::minimumEdgeLength || d1 < Quad::minimumEdgeLength || d2 < Quad::minimumEdgeLength || + d3 < Quad::minimumEdgeLength || d4 < Quad::minimumEdgeLength || d5 < Quad::minimumEdgeLength) { + bad = true; + // cout << "tagsize too small" << endl; + } + + // check aspect ratio + float dmax = max(max(d0,d1), max(d2,d3)); + float dmin = min(min(d0,d1), min(d2,d3)); + + if (dmax > dmin*Quad::maxQuadAspectRatio) { + bad = true; + // cout << "aspect ratio too extreme" << endl; + } + } + + if (!bad) { + Quad q(p, opticalCenter); + q.segments=path; + q.observedPerimeter = calculatedPerimeter; + quads.push_back(q); + } + } + return; + } + + // if (depth >= 1) // debug code + //cout << "depth: " << depth << endl; + + // Not terminal depth. Recurse on any children that obey the correct handedness. + for (unsigned int i = 0; i < parent.children.size(); i++) { + Segment &child = *parent.children[i]; + // cout << " Child " << child.getId() << ": "; + // (handedness was checked when we created the children) + + // we could rediscover each quad 4 times (starting from + // each corner). If we had an arbitrary ordering over + // points, we can eliminate the redundant detections by + // requiring that the first corner have the lowest + // value. We're arbitrarily going to use theta... + if ( child.getTheta() > path[0]->getTheta() ) { + // cout << "theta failed: " << child.getTheta() << " > " << path[0]->getTheta() << endl; + continue; + } + path[depth+1] = &child; + search(fImage, path, child, depth+1, quads, opticalCenter); + } +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/Segment.cc b/thirdparty/apriltag/ethz_apriltag2/src/Segment.cc new file mode 100644 index 0000000..817ed3e --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/Segment.cc @@ -0,0 +1,21 @@ +#include "apriltags/Segment.h" +#include + +namespace AprilTags { + +const float Segment::minimumLineLength = 4; + +Segment::Segment() + : children(), x0(0), y0(0), x1(0), y1(0), theta(0), length(0), segmentId(++idCounter) {} + +float Segment::segmentLength() { + return std::sqrt((x1-x0)*(x1-x0) + (y1-y0)*(y1-y0)); +} + +void Segment::printSegment() { + std::cout <<"("<< x0 <<","<< y0 <<"), "<<"("<< x1 <<","<< y1 <<")" << std::endl; +} + +int Segment::idCounter = 0; + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/TagDetection.cc b/thirdparty/apriltag/ethz_apriltag2/src/TagDetection.cc new file mode 100644 index 0000000..422e493 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/TagDetection.cc @@ -0,0 +1,161 @@ + +#include "opencv2/opencv.hpp" + +#include "apriltags/TagDetection.h" +#include "apriltags/MathUtil.h" + +#ifdef PLATFORM_APERIOS +//missing/broken isnan +namespace std { + static bool isnan(float x) { + const int EXP = 0x7f800000; + const int FRAC = 0x007fffff; + const int y = *((int*)(&x)); + return ((y&EXP)==EXP && (y&FRAC)!=0); + } +} +#endif + +namespace AprilTags { + +TagDetection::TagDetection() + : good(false), obsCode(), code(), id(), hammingDistance(), rotation(), p(), + cxy(), observedPerimeter(), homography(), hxy() { + homography.setZero(); +} + +TagDetection::TagDetection(int _id) + : good(false), obsCode(), code(), id(_id), hammingDistance(), rotation(), p(), + cxy(), observedPerimeter(), homography(), hxy() { + homography.setZero(); +} + +float TagDetection::getXYOrientation() const { + // Because the order of segments in a quad is arbitrary, so is the + // homography's rotation, so we can't determine orientation directly + // from the homography. Instead, use the homography to find two + // bottom corners of a properly oriented tag in pixel coordinates, + // and then compute orientation from that. + std::pair p0 = interpolate(-1,-1); // lower left corner of tag + std::pair p1 = interpolate(1,-1); // lower right corner of tag + float orient = atan2(p1.second - p0.second, p1.first - p0.first); + return ! std::isnan(float(orient)) ? orient : 0.; +} + +std::pair TagDetection::interpolate(float x, float y) const { + float z = homography(2,0)*x + homography(2,1)*y + homography(2,2); + if ( z == 0 ) + return std::pair(0,0); // prevents returning a pair with a -NaN, for which gcc 4.4 flubs isnan + float newx = (homography(0,0)*x + homography(0,1)*y + homography(0,2))/z + hxy.first; + float newy = (homography(1,0)*x + homography(1,1)*y + homography(1,2))/z + hxy.second; + return std::pair(newx,newy); +} + +bool TagDetection::overlapsTooMuch(const TagDetection &other) const { + // Compute a sort of "radius" of the two targets. We'll do this by + // computing the average length of the edges of the quads (in + // pixels). + float radius = + ( MathUtil::distance2D(p[0], p[1]) + + MathUtil::distance2D(p[1], p[2]) + + MathUtil::distance2D(p[2], p[3]) + + MathUtil::distance2D(p[3], p[0]) + + MathUtil::distance2D(other.p[0], other.p[1]) + + MathUtil::distance2D(other.p[1], other.p[2]) + + MathUtil::distance2D(other.p[2], other.p[3]) + + MathUtil::distance2D(other.p[3], other.p[0]) ) / 16.0f; + + // distance (in pixels) between two tag centers + float dist = MathUtil::distance2D(cxy, other.cxy); + + // reject pairs where the distance between centroids is smaller than + // the "radius" of one of the tags. + return ( dist < radius ); +} + +Eigen::Matrix4d TagDetection::getRelativeTransform(double tag_size, double fx, double fy, double px, double py) const { + std::vector objPts; + std::vector imgPts; + double s = tag_size/2.; + objPts.push_back(cv::Point3f(-s,-s, 0)); + objPts.push_back(cv::Point3f( s,-s, 0)); + objPts.push_back(cv::Point3f( s, s, 0)); + objPts.push_back(cv::Point3f(-s, s, 0)); + + std::pair p1 = p[0]; + std::pair p2 = p[1]; + std::pair p3 = p[2]; + std::pair p4 = p[3]; + imgPts.push_back(cv::Point2f(p1.first, p1.second)); + imgPts.push_back(cv::Point2f(p2.first, p2.second)); + imgPts.push_back(cv::Point2f(p3.first, p3.second)); + imgPts.push_back(cv::Point2f(p4.first, p4.second)); + + cv::Mat rvec, tvec; + cv::Matx33f cameraMatrix( + fx, 0, px, + 0, fy, py, + 0, 0, 1); + cv::Vec4f distParam(0,0,0,0); // all 0? + cv::solvePnP(objPts, imgPts, cameraMatrix, distParam, rvec, tvec); + cv::Matx33d r; + cv::Rodrigues(rvec, r); + Eigen::Matrix3d wRo; + wRo << r(0,0), r(0,1), r(0,2), r(1,0), r(1,1), r(1,2), r(2,0), r(2,1), r(2,2); + + Eigen::Matrix4d T; + T.topLeftCorner(3,3) = wRo; + T.col(3).head(3) << tvec.at(0), tvec.at(1), tvec.at(2); + T.row(3) << 0,0,0,1; + + return T; +} + +void TagDetection::getRelativeTranslationRotation(double tag_size, double fx, double fy, double px, double py, + Eigen::Vector3d& trans, Eigen::Matrix3d& rot) const { + Eigen::Matrix4d T = + getRelativeTransform(tag_size, fx, fy, px, py); + + // converting from camera frame (z forward, x right, y down) to + // object frame (x forward, y left, z up) + Eigen::Matrix4d M; + M << + 0, 0, 1, 0, + -1, 0, 0, 0, + 0, -1, 0, 0, + 0, 0, 0, 1; + Eigen::Matrix4d MT = M*T; + // translation vector from camera to the April tag + trans = MT.col(3).head(3); + // orientation of April tag with respect to camera: the camera + // convention makes more sense here, because yaw,pitch,roll then + // naturally agree with the orientation of the object + rot = T.block(0,0,3,3); +} + +// draw one April tag detection on actual image +void TagDetection::draw(cv::Mat& image) const { + // use corner points detected by line intersection + std::pair p1 = p[0]; + std::pair p2 = p[1]; + std::pair p3 = p[2]; + std::pair p4 = p[3]; + + // plot outline + cv::line(image, cv::Point2f(p1.first, p1.second), cv::Point2f(p2.first, p2.second), cv::Scalar(255,0,0,0) ); + cv::line(image, cv::Point2f(p2.first, p2.second), cv::Point2f(p3.first, p3.second), cv::Scalar(0,255,0,0) ); + cv::line(image, cv::Point2f(p3.first, p3.second), cv::Point2f(p4.first, p4.second), cv::Scalar(0,0,255,0) ); + cv::line(image, cv::Point2f(p4.first, p4.second), cv::Point2f(p1.first, p1.second), cv::Scalar(255,0,255,0) ); + + // mark center + cv::circle(image, cv::Point2f(cxy.first, cxy.second), 8, cv::Scalar(0,0,255,0), 2); + + // print ID + std::ostringstream strSt; + strSt << "#" << id; + cv::putText(image, strSt.str(), + cv::Point2f(cxy.first + 10, cxy.second + 10), + cv::FONT_HERSHEY_PLAIN, 1, cv::Scalar(0,0,255)); +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/TagDetector.cc b/thirdparty/apriltag/ethz_apriltag2/src/TagDetector.cc new file mode 100644 index 0000000..7fdbd0a --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/TagDetector.cc @@ -0,0 +1,613 @@ +#include +#include +#include +#include +#include +#include + +#include + +#include "apriltags/Edge.h" +#include "apriltags/FloatImage.h" +#include "apriltags/GLine2D.h" +#include "apriltags/GLineSegment2D.h" +#include "apriltags/Gaussian.h" +#include "apriltags/GrayModel.h" +#include "apriltags/Gridder.h" +#include "apriltags/Homography33.h" +#include "apriltags/MathUtil.h" +#include "apriltags/Quad.h" +#include "apriltags/Segment.h" +#include "apriltags/TagFamily.h" +#include "apriltags/UnionFindSimple.h" +#include "apriltags/XYWeight.h" + +#include "apriltags/TagDetector.h" + +//#define DEBUG_APRIL + +#ifdef DEBUG_APRIL +#include +#include +#endif + +using namespace std; + +namespace AprilTags { + +std::vector TagDetector::extractTags(const cv::Mat &image) { + // convert to internal AprilTags image (todo: slow, change internally to + // OpenCV) + int width = image.cols; + int height = image.rows; + AprilTags::FloatImage fimOrig(width, height); + int i = 0; + for (int y = 0; y < height; y++) { + for (int x = 0; x < width; x++) { + fimOrig.set(x, y, image.data[i] / 255.); + i++; + } + } + std::pair opticalCenter(width / 2, height / 2); + +#ifdef DEBUG_APRIL +#if 0 + { // debug - write + int height_ = fimOrig.getHeight(); + int width_ = fimOrig.getWidth(); + cv::Mat image(height_, width_, CV_8UC3); + { + for (int y=0; y(y, x) = v; + } + } + } + imwrite("out.bmp", image); + } +#endif +#if 0 + FloatImage fimOrig = fimOrig_; + { // debug - read + + cv::Mat image = cv::imread("test.bmp"); + int height_ = fimOrig.getHeight(); + int width_ = fimOrig.getWidth(); + { + for (int y=0; y(y,x); + float val = (float)v(0)/255.; + fimOrig.set(x,y,val); + } + } + } + } +#endif +#endif + + //================================================================ + // Step one: preprocess image (convert to grayscale) and low pass if necessary + + FloatImage fim = fimOrig; + + //! Gaussian smoothing kernel applied to image (0 == no filter). + /*! Used when sampling bits. Filtering is a good idea in cases + * where A) a cheap camera is introducing artifical sharpening, B) + * the bayer pattern is creating artifcats, C) the sensor is very + * noisy and/or has hot/cold pixels. However, filtering makes it + * harder to decode very small tags. Reasonable values are 0, or + * [0.8, 1.5]. + */ + float sigma = 0; + + //! Gaussian smoothing kernel applied to image (0 == no filter). + /*! Used when detecting the outline of the box. It is almost always + * useful to have some filtering, since the loss of small details + * won't hurt. Recommended value = 0.8. The case where sigma == + * segsigma has been optimized to avoid a redundant filter + * operation. + */ + float segSigma = 0.8f; + + if (sigma > 0) { + int filtsz = ((int)max(3.0f, 3 * sigma)) | 1; + std::vector filt = Gaussian::makeGaussianFilter(sigma, filtsz); + fim.filterFactoredCentered(filt, filt); + } + + //================================================================ + // Step two: Compute the local gradient. We store the direction and magnitude. + // This step is quite sensitve to noise, since a few bad theta estimates will + // break up segments, causing us to miss Quads. It is useful to do a Gaussian + // low pass on this step even if we don't want it for encoding. + + FloatImage fimSeg; + if (segSigma > 0) { + if (segSigma == sigma) { + fimSeg = fim; + } else { + // blur anew + int filtsz = ((int)max(3.0f, 3 * segSigma)) | 1; + std::vector filt = Gaussian::makeGaussianFilter(segSigma, filtsz); + fimSeg = fimOrig; + fimSeg.filterFactoredCentered(filt, filt); + } + } else { + fimSeg = fimOrig; + } + + FloatImage fimTheta(fimSeg.getWidth(), fimSeg.getHeight()); + FloatImage fimMag(fimSeg.getWidth(), fimSeg.getHeight()); + + for (int y = 1; y < fimSeg.getHeight() - 1; y++) { + for (int x = 1; x < fimSeg.getWidth() - 1; x++) { + float Ix = fimSeg.get(x + 1, y) - fimSeg.get(x - 1, y); + float Iy = fimSeg.get(x, y + 1) - fimSeg.get(x, y - 1); + + float mag = Ix * Ix + Iy * Iy; +#if 0 // kaess: fast version, but maybe less accurate? + float theta = MathUtil::fast_atan2(Iy, Ix); +#else + float theta = atan2(Iy, Ix); +#endif + + fimTheta.set(x, y, theta); + fimMag.set(x, y, mag); + } + } + +#ifdef DEBUG_APRIL + int height_ = fimSeg.getHeight(); + int width_ = fimSeg.getWidth(); + cv::Mat dbgImage(height_, width_, CV_8UC3); + { + for (int y = 0; y < height_; y++) { + for (int x = 0; x < width_; x++) { + cv::Vec3b v; + // float vf = fimMag.get(x,y); + float vf = fimOrig.get(x, y); + int val = (int)(vf * 255.); + if ((val & 0xffff00) != 0) { + printf("problem... %i\n", val); + } + for (int k = 0; k < 3; k++) { + v(k) = val; + } + dbgImage.at(y, x) = v; + } + } + } +#endif + + //================================================================ + // Step three. Extract edges by grouping pixels with similar + // thetas together. This is a greedy algorithm: we start with + // the most similar pixels. We use 4-connectivity. + UnionFindSimple uf(fimSeg.getWidth() * fimSeg.getHeight()); + + vector edges(width * height * 4); + size_t nEdges = 0; + + // Bounds on the thetas assigned to this group. Note that because + // theta is periodic, these are defined such that the average + // value is contained *within* the interval. + { // limit scope of storage + /* Previously all this was on the stack, but this is 1.2MB for 320x240 + * images + * That's already a problem for OS X (default 512KB thread stack size), + * could be a problem elsewhere for bigger images... so store on heap */ + vector storage( + width * height * + 4); // do all the memory in one big block, exception safe + float *tmin = &storage[width * height * 0]; + float *tmax = &storage[width * height * 1]; + float *mmin = &storage[width * height * 2]; + float *mmax = &storage[width * height * 3]; + + for (int y = 0; y + 1 < height; y++) { + for (int x = 0; x + 1 < width; x++) { + float mag0 = fimMag.get(x, y); + if (mag0 < Edge::minMag) continue; + mmax[y * width + x] = mag0; + mmin[y * width + x] = mag0; + + float theta0 = fimTheta.get(x, y); + tmin[y * width + x] = theta0; + tmax[y * width + x] = theta0; + + // Calculates then adds edges to 'vector edges' + Edge::calcEdges(theta0, x, y, fimTheta, fimMag, edges, nEdges); + + // XXX Would 8 connectivity help for rotated tags? + // Probably not much, so long as input filtering hasn't been disabled. + } + } + + edges.resize(nEdges); + std::stable_sort(edges.begin(), edges.end()); + Edge::mergeEdges(edges, uf, tmin, tmax, mmin, mmax); + } + + //================================================================ + // Step four: Loop over the pixels again, collecting statistics for each + // cluster. + // We will soon fit lines (segments) to these points. + + map > clusters; + for (int y = 0; y + 1 < fimSeg.getHeight(); y++) { + for (int x = 0; x + 1 < fimSeg.getWidth(); x++) { + if (uf.getSetSize(y * fimSeg.getWidth() + x) < + Segment::minimumSegmentSize) + continue; + + int rep = (int)uf.getRepresentative(y * fimSeg.getWidth() + x); + + map >::iterator it = clusters.find(rep); + if (it == clusters.end()) { + clusters[rep] = vector(); + it = clusters.find(rep); + } + vector &points = it->second; + points.push_back(XYWeight(x, y, fimMag.get(x, y))); + } + } + + //================================================================ + // Step five: Loop over the clusters, fitting lines (which we call Segments). + std::vector segments; // used in Step six + std::map >::const_iterator clustersItr; + for (clustersItr = clusters.begin(); clustersItr != clusters.end(); + clustersItr++) { + std::vector points = clustersItr->second; + GLineSegment2D gseg = GLineSegment2D::lsqFitXYW(points); + + // filter short lines + float length = MathUtil::distance2D(gseg.getP0(), gseg.getP1()); + if (length < Segment::minimumLineLength) continue; + + Segment seg; + float dy = gseg.getP1().second - gseg.getP0().second; + float dx = gseg.getP1().first - gseg.getP0().first; + + float tmpTheta = std::atan2(dy, dx); + + seg.setTheta(tmpTheta); + seg.setLength(length); + + // We add an extra semantic to segments: the vector + // p1->p2 will have dark on the left, white on the right. + // To do this, we'll look at every gradient and each one + // will vote for which way they think the gradient should + // go. This is way more retentive than necessary: we + // could probably sample just one point! + + float flip = 0, noflip = 0; + for (unsigned int i = 0; i < points.size(); i++) { + XYWeight xyw = points[i]; + + float theta = fimTheta.get((int)xyw.x, (int)xyw.y); + float mag = fimMag.get((int)xyw.x, (int)xyw.y); + + // err *should* be +M_PI/2 for the correct winding, but if we + // got the wrong winding, it'll be around -M_PI/2. + float err = MathUtil::mod2pi(theta - seg.getTheta()); + + if (err < 0) + noflip += mag; + else + flip += mag; + } + + if (flip > noflip) { + float temp = seg.getTheta() + (float)M_PI; + seg.setTheta(temp); + } + + float dot = dx * std::cos(seg.getTheta()) + dy * std::sin(seg.getTheta()); + if (dot > 0) { + seg.setX0(gseg.getP1().first); + seg.setY0(gseg.getP1().second); + seg.setX1(gseg.getP0().first); + seg.setY1(gseg.getP0().second); + } else { + seg.setX0(gseg.getP0().first); + seg.setY0(gseg.getP0().second); + seg.setX1(gseg.getP1().first); + seg.setY1(gseg.getP1().second); + } + + segments.push_back(seg); + } + +#ifdef DEBUG_APRIL +#if 0 + { + for (vector::iterator it = segments.begin(); it!=segments.end(); it++) { + long int r = random(); + cv::line(dbgImage, + cv::Point2f(it->getX0(), it->getY0()), + cv::Point2f(it->getX1(), it->getY1()), + cv::Scalar(r%0xff,(r%0xff00)>>8,(r%0xff0000)>>16,0) ); + } + } +#endif +#endif + + // Step six: For each segment, find segments that begin where this segment + // ends. + // (We will chain segments together next...) The gridder accelerates the + // search by + // building (essentially) a 2D hash table. + Gridder gridder(0, 0, width, height, 10); + + // add every segment to the hash table according to the position of the + // segment's + // first point. Remember that the first point has a specific meaning due to + // our + // left-hand rule above. + for (unsigned int i = 0; i < segments.size(); i++) { + gridder.add(segments[i].getX0(), segments[i].getY0(), &segments[i]); + } + + // Now, find child segments that begin where each parent segment ends. + for (unsigned i = 0; i < segments.size(); i++) { + Segment &parentseg = segments[i]; + + // compute length of the line segment + GLine2D parentLine( + std::pair(parentseg.getX0(), parentseg.getY0()), + std::pair(parentseg.getX1(), parentseg.getY1())); + + Gridder::iterator iter = gridder.find( + parentseg.getX1(), parentseg.getY1(), 0.5f * parentseg.getLength()); + while (iter.hasNext()) { + Segment &child = iter.next(); + if (MathUtil::mod2pi(child.getTheta() - parentseg.getTheta()) > 0) { + continue; + } + + // compute intersection of points + GLine2D childLine(std::pair(child.getX0(), child.getY0()), + std::pair(child.getX1(), child.getY1())); + + std::pair p = parentLine.intersectionWith(childLine); + if (p.first == -1) { + continue; + } + + float parentDist = MathUtil::distance2D( + p, std::pair(parentseg.getX1(), parentseg.getY1())); + float childDist = MathUtil::distance2D( + p, std::pair(child.getX0(), child.getY0())); + + if (max(parentDist, childDist) > parentseg.getLength()) { + // cout << "intersection too far" << endl; + continue; + } + + // everything's OK, this child is a reasonable successor. + parentseg.children.push_back(&child); + } + } + + //================================================================ + // Step seven: Search all connected segments to see if any form a loop of + // length 4. + // Add those to the quads list. + vector quads; + + vector tmp(5); + for (unsigned int i = 0; i < segments.size(); i++) { + tmp[0] = &segments[i]; + Quad::search(fimOrig, tmp, segments[i], 0, quads, opticalCenter); + } + +#ifdef DEBUG_APRIL + { + for (unsigned int qi = 0; qi < quads.size(); qi++) { + Quad &quad = quads[qi]; + std::pair p1 = quad.quadPoints[0]; + std::pair p2 = quad.quadPoints[1]; + std::pair p3 = quad.quadPoints[2]; + std::pair p4 = quad.quadPoints[3]; + cv::line(dbgImage, cv::Point2f(p1.first, p1.second), + cv::Point2f(p2.first, p2.second), cv::Scalar(0, 0, 255, 0)); + cv::line(dbgImage, cv::Point2f(p2.first, p2.second), + cv::Point2f(p3.first, p3.second), cv::Scalar(0, 0, 255, 0)); + cv::line(dbgImage, cv::Point2f(p3.first, p3.second), + cv::Point2f(p4.first, p4.second), cv::Scalar(0, 0, 255, 0)); + cv::line(dbgImage, cv::Point2f(p4.first, p4.second), + cv::Point2f(p1.first, p1.second), cv::Scalar(0, 0, 255, 0)); + + p1 = quad.interpolate(-1, -1); + p2 = quad.interpolate(-1, 1); + p3 = quad.interpolate(1, 1); + p4 = quad.interpolate(1, -1); + cv::circle(dbgImage, cv::Point2f(p1.first, p1.second), 3, + cv::Scalar(0, 255, 0, 0), 1); + cv::circle(dbgImage, cv::Point2f(p2.first, p2.second), 3, + cv::Scalar(0, 255, 0, 0), 1); + cv::circle(dbgImage, cv::Point2f(p3.first, p3.second), 3, + cv::Scalar(0, 255, 0, 0), 1); + cv::circle(dbgImage, cv::Point2f(p4.first, p4.second), 3, + cv::Scalar(0, 255, 0, 0), 1); + } + cv::imshow("debug_april", dbgImage); + } +#endif + + //================================================================ + // Step eight. Decode the quads. For each quad, we first estimate a + // threshold color to decide between 0 and 1. Then, we read off the + // bits and see if they make sense. + + std::vector detections; + + for (unsigned int qi = 0; qi < quads.size(); qi++) { + Quad &quad = quads[qi]; + + // Find a threshold + GrayModel blackModel, whiteModel; + const int dd = 2 * thisTagFamily.blackBorder + thisTagFamily.dimension; + + for (int iy = -1; iy <= dd; iy++) { + float y = (iy + 0.5f) / dd; + for (int ix = -1; ix <= dd; ix++) { + float x = (ix + 0.5f) / dd; + std::pair pxy = quad.interpolate01(x, y); + int irx = (int)(pxy.first + 0.5); + int iry = (int)(pxy.second + 0.5); + if (irx < 0 || irx >= width || iry < 0 || iry >= height) continue; + float v = fim.get(irx, iry); + if (iy == -1 || iy == dd || ix == -1 || ix == dd) + whiteModel.addObservation(x, y, v); + else if (iy == 0 || iy == (dd - 1) || ix == 0 || ix == (dd - 1)) + blackModel.addObservation(x, y, v); + } + } + + bool bad = false; + unsigned long long tagCode = 0; + for (int iy = thisTagFamily.dimension - 1; iy >= 0; iy--) { + float y = (thisTagFamily.blackBorder + iy + 0.5f) / dd; + for (int ix = 0; ix < thisTagFamily.dimension; ix++) { + float x = (thisTagFamily.blackBorder + ix + 0.5f) / dd; + std::pair pxy = quad.interpolate01(x, y); + int irx = (int)(pxy.first + 0.5); + int iry = (int)(pxy.second + 0.5); + if (irx < 0 || irx >= width || iry < 0 || iry >= height) { + // cout << "*** bad: irx=" << irx << " iry=" << iry << endl; + bad = true; + continue; + } + float threshold = + (blackModel.interpolate(x, y) + whiteModel.interpolate(x, y)) * + 0.5f; + float v = fim.get(irx, iry); + tagCode = tagCode << 1; + if (v > threshold) tagCode |= 1; +#ifdef DEBUG_APRIL + { + if (v > threshold) + cv::circle(dbgImage, cv::Point2f(irx, iry), 1, + cv::Scalar(0, 0, 255, 0), 2); + else + cv::circle(dbgImage, cv::Point2f(irx, iry), 1, + cv::Scalar(0, 255, 0, 0), 2); + } +#endif + } + } + + if (!bad) { + TagDetection thisTagDetection; + thisTagFamily.decode(thisTagDetection, tagCode); + + // compute the homography (and rotate it appropriately) + thisTagDetection.homography = quad.homography.getH(); + thisTagDetection.hxy = quad.homography.getCXY(); + + float c = std::cos(thisTagDetection.rotation * (float)M_PI / 2); + float s = std::sin(thisTagDetection.rotation * (float)M_PI / 2); + Eigen::Matrix3d R; + R.setZero(); + R(0, 0) = R(1, 1) = c; + R(0, 1) = -s; + R(1, 0) = s; + R(2, 2) = 1; + Eigen::Matrix3d tmp; + tmp = thisTagDetection.homography * R; + thisTagDetection.homography = tmp; + + // Rotate points in detection according to decoded + // orientation. Thus the order of the points in the + // detection object can be used to determine the + // orientation of the target. + std::pair bottomLeft = thisTagDetection.interpolate(-1, -1); + int bestRot = -1; + float bestDist = FLT_MAX; + for (int i = 0; i < 4; i++) { + float const dist = + AprilTags::MathUtil::distance2D(bottomLeft, quad.quadPoints[i]); + if (dist < bestDist) { + bestDist = dist; + bestRot = i; + } + } + + for (int i = 0; i < 4; i++) + thisTagDetection.p[i] = quad.quadPoints[(i + bestRot) % 4]; + + if (thisTagDetection.good) { + thisTagDetection.cxy = quad.interpolate01(0.5f, 0.5f); + thisTagDetection.observedPerimeter = quad.observedPerimeter; + detections.push_back(thisTagDetection); + } + } + } + +#ifdef DEBUG_APRIL + { cv::imshow("debug_april", dbgImage); } +#endif + + //================================================================ + // Step nine: Some quads may be detected more than once, due to + // partial occlusion and our aggressive attempts to recover from + // broken lines. When two quads (with the same id) overlap, we will + // keep the one with the lowest error, and if the error is the same, + // the one with the greatest observed perimeter. + + std::vector goodDetections; + + // NOTE: allow multiple non-overlapping detections of the same target. + + for (vector::const_iterator it = detections.begin(); + it != detections.end(); it++) { + const TagDetection &thisTagDetection = *it; + + bool newFeature = true; + + for (unsigned int odidx = 0; odidx < goodDetections.size(); odidx++) { + TagDetection &otherTagDetection = goodDetections[odidx]; + + if (thisTagDetection.id != otherTagDetection.id || + !thisTagDetection.overlapsTooMuch(otherTagDetection)) + continue; + + // There's a conflict. We must pick one to keep. + newFeature = false; + + // This detection is worse than the previous one... just don't use it. + if (thisTagDetection.hammingDistance > otherTagDetection.hammingDistance) + continue; + + // Otherwise, keep the new one if it either has strictly *lower* error, or + // greater perimeter. + if (thisTagDetection.hammingDistance < + otherTagDetection.hammingDistance || + thisTagDetection.observedPerimeter > + otherTagDetection.observedPerimeter) + goodDetections[odidx] = thisTagDetection; + } + + if (newFeature) goodDetections.push_back(thisTagDetection); + } + + // cout << "AprilTags: edges=" << nEdges << " clusters=" << clusters.size() << + // " segments=" << segments.size() + // << " quads=" << quads.size() << " detections=" << detections.size() << + // " unique tags=" << goodDetections.size() << endl; + + return goodDetections; +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/TagFamily.cc b/thirdparty/apriltag/ethz_apriltag2/src/TagFamily.cc new file mode 100644 index 0000000..11065cb --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/TagFamily.cc @@ -0,0 +1,138 @@ +#include + +#include "apriltags/TagFamily.h" + +/** + +// example of instantiation of tag family: + +#include "apriltags/TagFamily.h" +#include "apriltags/Tag36h11.h" +TagFamily *tag36h11 = new TagFamily(tagCodes36h11); + +// available tag families: + +#include "apriltags/Tag16h5.h" +#include "apriltags/Tag16h5_other.h" +#include "apriltags/Tag25h7.h" +#include "apriltags/Tag25h9.h" +#include "apriltags/Tag36h11.h" +#include "apriltags/Tag36h11_other.h" +#include "apriltags/Tag36h9.h" + +*/ + + +namespace AprilTags { + +TagFamily::TagFamily(const TagCodes& tagCodes, const size_t blackBorder) + : blackBorder(blackBorder), bits(tagCodes.bits), dimension((int)std::sqrt((float)bits)), + minimumHammingDistance(tagCodes.minHammingDistance), + errorRecoveryBits(1), codes() { + if ( bits != dimension*dimension ) + cerr << "Error: TagFamily constructor called with bits=" << bits << "; must be a square number!" << endl; + codes = tagCodes.codes; +} + +void TagFamily::setErrorRecoveryBits(int b) { + errorRecoveryBits = b; +} + +void TagFamily::setErrorRecoveryFraction(float v) { + errorRecoveryBits = (int) (((int) (minimumHammingDistance-1)/2)*v); +} + +unsigned long long TagFamily::rotate90(unsigned long long w, int d) { + unsigned long long wr = 0; + const unsigned long long oneLongLong = 1; + + for (int r = d-1; r>=0; r--) { + for (int c = 0; c>= popCountTableShift; + } + return count; +} + +void TagFamily::decode(TagDetection& det, unsigned long long rCode) const { + int bestId = -1; + int bestHamming = INT_MAX; + int bestRotation = 0; + unsigned long long bestCode = 0; + + unsigned long long rCodes[4]; + rCodes[0] = rCode; + rCodes[1] = rotate90(rCodes[0], dimension); + rCodes[2] = rotate90(rCodes[1], dimension); + rCodes[3] = rotate90(rCodes[2], dimension); + + for (unsigned int id = 0; id < codes.size(); id++) { + for (unsigned int rot = 0; rot < 4; rot++) { + int thisHamming = hammingDistance(rCodes[rot], codes[id]); + if (thisHamming < bestHamming) { + bestHamming = thisHamming; + bestRotation = rot; + bestId = id; + bestCode = codes[id]; + } + } + } + det.id = bestId; + det.hammingDistance = bestHamming; + det.rotation = bestRotation; + det.good = (det.hammingDistance <= errorRecoveryBits); + det.obsCode = rCode; + det.code = bestCode; +} + +void TagFamily::printHammingDistances() const { + vector hammings(dimension*dimension+1); + for (unsigned i = 0; i < codes.size(); i++) { + unsigned long long r0 = codes[i]; + unsigned long long r1 = rotate90(r0, dimension); + unsigned long long r2 = rotate90(r1, dimension); + unsigned long long r3 = rotate90(r2, dimension); + for (unsigned int j = i+1; j < codes.size(); j++) { + int d = min(min(hammingDistance(r0, codes[j]), + hammingDistance(r1, codes[j])), + min(hammingDistance(r2, codes[j]), + hammingDistance(r3, codes[j]))); + hammings[d]++; + } + } + + for (unsigned int i = 0; i < hammings.size(); i++) + printf("hammings: %u = %d\n", i, hammings[i]); +} + +unsigned char TagFamily::popCountTable[TagFamily::popCountTableSize]; + +TagFamily::TableInitializer TagFamily::initializer; + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/UnionFindSimple.cc b/thirdparty/apriltag/ethz_apriltag2/src/UnionFindSimple.cc new file mode 100644 index 0000000..cc24a0f --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/UnionFindSimple.cc @@ -0,0 +1,54 @@ +#include "apriltags/UnionFindSimple.h" +#include + +namespace AprilTags { + +int UnionFindSimple::getRepresentative(int thisId) { + // terminal case: a node is its own parent + if (data[thisId].id == thisId) + return thisId; + + // otherwise, recurse... + int root = getRepresentative(data[thisId].id); + + // short circuit the path + data[thisId].id = root; + + return root; +} + +void UnionFindSimple::printDataVector() const { + for (unsigned int i = 0; i < data.size(); i++) + std::cout << "data[" << i << "]: " << " id:" << data[i].id << " size:" << data[i].size << std::endl; +} + +int UnionFindSimple::connectNodes(int aId, int bId) { + int aRoot = getRepresentative(aId); + int bRoot = getRepresentative(bId); + + if (aRoot == bRoot) + return aRoot; + + int asz = data[aRoot].size; + int bsz = data[bRoot].size; + + if (asz > bsz) { + data[bRoot].id = aRoot; + data[aRoot].size += bsz; + return aRoot; + } else { + data[aRoot].id = bRoot; + data[bRoot].size += asz; + return bRoot; + } +} + +void UnionFindSimple::init() { + for (unsigned int i = 0; i < data.size(); i++) { + // everyone is their own cluster of size 1 + data[i].id = i; + data[i].size = 1; + } +} + +} // namespace diff --git a/thirdparty/apriltag/ethz_apriltag2/src/example/CMakeLists.txt b/thirdparty/apriltag/ethz_apriltag2/src/example/CMakeLists.txt new file mode 100644 index 0000000..a19899a --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/example/CMakeLists.txt @@ -0,0 +1,9 @@ +cmake_minimum_required (VERSION 2.6) + +link_libraries(apriltags) + +add_executable(apriltags_demo apriltags_demo.cpp Serial.cpp) +pods_install_executables(apriltags_demo) + +add_executable(imu imu.cpp Serial.cpp) +pods_install_executables(imu) diff --git a/thirdparty/apriltag/ethz_apriltag2/src/example/Serial.cpp b/thirdparty/apriltag/ethz_apriltag2/src/example/Serial.cpp new file mode 100644 index 0000000..a278972 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/example/Serial.cpp @@ -0,0 +1,113 @@ +/** + * @file Serial.cpp + * @brief Simple serial interface, for example to talk to Arduino. + * @author: Michael Kaess + */ + +#include +#include +#include +#include +#include +#include + +#include "Serial.h" + +using namespace std; + + +// open a serial port connection +void Serial::open(const string& port, int rate) { + m_serialPort = ::open(port.c_str(), O_RDWR | O_NOCTTY | O_NDELAY); + if (m_serialPort==-1) { + cout << "Unable to open serial port" << endl; + exit(1); + } + fcntl(m_serialPort, F_SETFL,0); // O_NONBLOCK might be needed for write... + + struct termios port_settings; // structure to store the port settings in + tcgetattr(m_serialPort, &port_settings); // get current settings + + speed_t b; + switch(rate) { + case(9600): + b = B9600; + break; + case(19200): + b = B19200; + break; + case(38400): + b = B38400; + break; + case(115200): + b = B115200; + break; + default: + cout << "Error: Unknown baud rate requested in Serial.open()" << endl; + exit(1); + } + + cfsetispeed(&port_settings, b); // set baud rates + cfsetospeed(&port_settings, b); + + port_settings.c_cflag &= ~PARENB; // set no parity, stop bits, 8 data bits + port_settings.c_cflag &= ~CSTOPB; + port_settings.c_cflag &= ~CSIZE; + port_settings.c_cflag |= CS8; + + tcsetattr(m_serialPort, TCSANOW, &port_settings); // apply the settings to the port +} + +// read a single character +int Serial::read() const { + unsigned char result; + if (::read(m_serialPort, &result, 1) == 1) { + return (int)result; + } else { + return -1; + } +} + +// read until special character up to a maximum number of bytes +string Serial::readBytesUntil(unsigned char until, int max_length) { + string result(max_length, ' '); + int n = 0; + int c; + do { + c = read(); + if (c<0) { // wait for more characters + usleep(100); + } else { + result[n] = (unsigned char)c; + n++; + } + } while ((c != (int)until) && (n < max_length)); + result.resize(n); + return result; +} + +// send a string +void Serial::print(string str) const { + int res = ::write(m_serialPort, str.c_str(), str.length()); +} + +// send an integer +void Serial::print(int num) const { + stringstream stream; + stream << num; + string str = stream.str(); + print(str); +} + +// send a double +void Serial::print(double num) const { + stringstream stream; + stream << num; + string str = stream.str(); + print(str); +} + +// send a float +void Serial::print(float num) const { + print((double)num); +} diff --git a/thirdparty/apriltag/ethz_apriltag2/src/example/Serial.h b/thirdparty/apriltag/ethz_apriltag2/src/example/Serial.h new file mode 100644 index 0000000..635ee87 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/example/Serial.h @@ -0,0 +1,41 @@ +/** + * @file Serial.h + * @brief Simple serial interface, for example to talk to Arduino. + * @author: Michael Kaess + */ + +#pragma once + +#include + + +class Serial { + + int m_serialPort; // file description for the serial port + +public: + + Serial() : m_serialPort(-1) {} + + // open a serial port connection + void open(const std::string& port, int rate = 115200); + + // read a single character + int read() const; + + // read until special character up to a maximum number of bytes + std::string readBytesUntil(unsigned char until, int length = 300); + + // send a string + void print(std::string str) const; + + // send an integer + void print(int num) const; + + // send a double + void print(double num) const; + + // send a float + void print(float num) const; + +}; diff --git a/thirdparty/apriltag/ethz_apriltag2/src/example/apriltags_demo.cpp b/thirdparty/apriltag/ethz_apriltag2/src/example/apriltags_demo.cpp new file mode 100644 index 0000000..919388a --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/example/apriltags_demo.cpp @@ -0,0 +1,453 @@ +/** + * @file april_tags.cpp + * @brief Example application for April tags library + * @author: Michael Kaess + * + * Opens the first available camera (typically a built in camera in a + * laptop) and continuously detects April tags in the incoming + * images. Detections are both visualized in the live image and shown + * in the text console. Optionally allows selecting of a specific + * camera in case multiple ones are present and specifying image + * resolution as long as supported by the camera. Also includes the + * option to send tag detections via a serial port, for example when + * running on a Raspberry Pi that is connected to an Arduino. + */ + +using namespace std; + +#include +#include +#include +#include + +const string usage = "\n" + "Usage:\n" + " apriltags_demo [OPTION...] [deviceID]\n" + "\n" + "Options:\n" + " -h -? Show help options\n" + " -a Arduino (send tag ids over serial port)\n" + " -d disable graphics\n" + " -C Tag family (default 36h11)\n" + " -F Focal length in pixels\n" + " -W Image width (default 640, availability depends on camera)\n" + " -H Image height (default 480, availability depends on camera)\n" + " -S Tag size (square black frame) in meters\n" + " -E Manually set camera exposure (default auto; range 0-10000)\n" + " -G Manually set camera gain (default auto; range 0-255)\n" + " -B Manually set the camera brightness (default 128; range 0-255)\n" + "\n"; + +const string intro = "\n" + "April tags test code\n" + "(C) 2012-2013 Massachusetts Institute of Technology\n" + "Michael Kaess\n" + "\n"; + + +#ifndef __APPLE__ +#define EXPOSURE_CONTROL // only works in Linux +#endif + +#ifdef EXPOSURE_CONTROL +#include +#include +#include +#include +#endif + +// OpenCV library for easy access to USB camera and drawing of images +// on screen +#include "opencv2/opencv.hpp" + +// April tags detector and various families that can be selected by command line option +#include "apriltags/TagDetector.h" +#include "apriltags/Tag16h5.h" +#include "apriltags/Tag25h7.h" +#include "apriltags/Tag25h9.h" +#include "apriltags/Tag36h9.h" +#include "apriltags/Tag36h11.h" + + +// Needed for getopt / command line options processing +#include +extern int optind; +extern char *optarg; + +// For Arduino: locally defined serial port access class +#include "Serial.h" + + +const char* window_name = "apriltags_demo"; + + +// utility function to provide current system time (used below in +// determining frame rate at which images are being processed) +double tic() { + struct timeval t; + gettimeofday(&t, NULL); + return ((double)t.tv_sec + ((double)t.tv_usec)/1000000.); +} + + +#include + +#ifndef PI +const double PI = 3.14159265358979323846; +#endif +const double TWOPI = 2.0*PI; + +/** + * Normalize angle to be within the interval [-pi,pi]. + */ +inline double standardRad(double t) { + if (t >= 0.) { + t = fmod(t+PI, TWOPI) - PI; + } else { + t = fmod(t-PI, -TWOPI) + PI; + } + return t; +} + +void wRo_to_euler(const Eigen::Matrix3d& wRo, double& yaw, double& pitch, double& roll) { + yaw = standardRad(atan2(wRo(1,0), wRo(0,0))); + double c = cos(yaw); + double s = sin(yaw); + pitch = standardRad(atan2(-wRo(2,0), wRo(0,0)*c + wRo(1,0)*s)); + roll = standardRad(atan2(wRo(0,2)*s - wRo(1,2)*c, -wRo(0,1)*s + wRo(1,1)*c)); + } + + +class Demo { + + AprilTags::TagDetector* m_tagDetector; + AprilTags::TagCodes m_tagCodes; + + bool m_draw; // draw image and April tag detections? + bool m_arduino; // send tag detections to serial port? + + int m_width; // image size in pixels + int m_height; + double m_tagSize; // April tag side length in meters of square black frame + double m_fx; // camera focal length in pixels + double m_fy; + double m_px; // camera principal point + double m_py; + + int m_deviceId; // camera id (in case of multiple cameras) + cv::VideoCapture m_cap; + + int m_exposure; + int m_gain; + int m_brightness; + + Serial m_serial; + +public: + + // default constructor + Demo() : + // default settings, most can be modified through command line options (see below) + m_tagDetector(NULL), + m_tagCodes(AprilTags::tagCodes36h11), + + m_draw(true), + m_arduino(false), + + m_width(640), + m_height(480), + m_tagSize(0.166), + m_fx(600), + m_fy(600), + m_px(m_width/2), + m_py(m_height/2), + + m_exposure(-1), + m_gain(-1), + m_brightness(-1), + + m_deviceId(0) + {} + + // changing the tag family + void setTagCodes(string s) { + if (s=="16h5") { + m_tagCodes = AprilTags::tagCodes16h5; + } else if (s=="25h7") { + m_tagCodes = AprilTags::tagCodes25h7; + } else if (s=="25h9") { + m_tagCodes = AprilTags::tagCodes25h9; + } else if (s=="36h9") { + m_tagCodes = AprilTags::tagCodes36h9; + } else if (s=="36h11") { + m_tagCodes = AprilTags::tagCodes36h11; + } else { + cout << "Invalid tag family specified" << endl; + exit(1); + } + } + + // parse command line options to change default behavior + void parseOptions(int argc, char* argv[]) { + int c; + while ((c = getopt(argc, argv, ":h?adC:F:H:S:W:E:G:B:")) != -1) { + // Each option character has to be in the string in getopt(); + // the first colon changes the error character from '?' to ':'; + // a colon after an option means that there is an extra + // parameter to this option; 'W' is a reserved character + switch (c) { + case 'h': + case '?': + cout << intro; + cout << usage; + exit(0); + break; + case 'a': + m_arduino = true; + break; + case 'd': + m_draw = false; + break; + case 'C': + setTagCodes(optarg); + break; + case 'F': + m_fx = atof(optarg); + m_fy = m_fx; + break; + case 'H': + m_height = atoi(optarg); + m_py = m_height/2; + break; + case 'S': + m_tagSize = atof(optarg); + break; + case 'W': + m_width = atoi(optarg); + m_px = m_width/2; + break; + case 'E': +#ifndef EXPOSURE_CONTROL + cout << "Error: Exposure option (-E) not available" << endl; + exit(1); +#endif + m_exposure = atoi(optarg); + break; + case 'G': +#ifndef EXPOSURE_CONTROL + cout << "Error: Gain option (-G) not available" << endl; + exit(1); +#endif + m_gain = atoi(optarg); + break; + case 'B': +#ifndef EXPOSURE_CONTROL + cout << "Error: Brightness option (-B) not available" << endl; + exit(1); +#endif + m_brightness = atoi(optarg); + break; + case ':': // unknown option, from getopt + cout << intro; + cout << usage; + exit(1); + break; + } + } + + if (argc == optind + 1) { + m_deviceId = atoi(argv[optind]); + } + } + + void setup() { + m_tagDetector = new AprilTags::TagDetector(m_tagCodes); + +#ifdef EXPOSURE_CONTROL + // manually setting camera exposure settings; OpenCV/v4l1 doesn't + // support exposure control; so here we manually use v4l2 before + // opening the device via OpenCV; confirmed to work with Logitech + // C270; try exposure=20, gain=100, brightness=150 + + string video_str = "/dev/video0"; + video_str[10] = '0' + m_deviceId; + int device = v4l2_open(video_str.c_str(), O_RDWR | O_NONBLOCK); + + if (m_exposure >= 0) { + // not sure why, but v4l2_set_control() does not work for + // V4L2_CID_EXPOSURE_AUTO... + struct v4l2_control c; + c.id = V4L2_CID_EXPOSURE_AUTO; + c.value = 1; // 1=manual, 3=auto; V4L2_EXPOSURE_AUTO fails... + if (v4l2_ioctl(device, VIDIOC_S_CTRL, &c) != 0) { + cout << "Failed to set... " << strerror(errno) << endl; + } + cout << "exposure: " << m_exposure << endl; + v4l2_set_control(device, V4L2_CID_EXPOSURE_ABSOLUTE, m_exposure*6); + } + if (m_gain >= 0) { + cout << "gain: " << m_gain << endl; + v4l2_set_control(device, V4L2_CID_GAIN, m_gain*256); + } + if (m_brightness >= 0) { + cout << "brightness: " << m_brightness << endl; + v4l2_set_control(device, V4L2_CID_BRIGHTNESS, m_brightness*256); + } + v4l2_close(device); +#endif + + // find and open a USB camera (built in laptop camera, web cam etc) + m_cap = cv::VideoCapture(m_deviceId); + if(!m_cap.isOpened()) { + cerr << "ERROR: Can't find video device " << m_deviceId << "\n"; + exit(1); + } + m_cap.set(CV_CAP_PROP_FRAME_WIDTH, m_width); + m_cap.set(CV_CAP_PROP_FRAME_HEIGHT, m_height); + cout << "Camera successfully opened (ignore error messages above...)" << endl; + cout << "Actual resolution: " + << m_cap.get(CV_CAP_PROP_FRAME_WIDTH) << "x" + << m_cap.get(CV_CAP_PROP_FRAME_HEIGHT) << endl; + + // prepare window for drawing the camera images + if (m_draw) { + cv::namedWindow(window_name, 1); + } + + // optional: prepare serial port for communication with Arduino + if (m_arduino) { + m_serial.open("/dev/ttyACM0"); + } + } + + void print_detection(AprilTags::TagDetection& detection) const { + cout << " Id: " << detection.id + << " (Hamming: " << detection.hammingDistance << ")"; + + // recovering the relative pose of a tag: + + // NOTE: for this to be accurate, it is necessary to use the + // actual camera parameters here as well as the actual tag size + // (m_fx, m_fy, m_px, m_py, m_tagSize) + + Eigen::Vector3d translation; + Eigen::Matrix3d rotation; + detection.getRelativeTranslationRotation(m_tagSize, m_fx, m_fy, m_px, m_py, + translation, rotation); + + Eigen::Matrix3d F; + F << + 1, 0, 0, + 0, -1, 0, + 0, 0, 1; + Eigen::Matrix3d fixed_rot = F*rotation; + double yaw, pitch, roll; + wRo_to_euler(fixed_rot, yaw, pitch, roll); + + cout << " distance=" << translation.norm() + << "m, x=" << translation(0) + << ", y=" << translation(1) + << ", z=" << translation(2) + << ", yaw=" << yaw + << ", pitch=" << pitch + << ", roll=" << roll + << endl; + + // Also note that for SLAM/multi-view application it is better to + // use reprojection error of corner points, because the noise in + // this relative pose is very non-Gaussian; see iSAM source code + // for suitable factors. + } + + // The processing loop where images are retrieved, tags detected, + // and information about detections generated + void loop() { + + cv::Mat image; + cv::Mat image_gray; + + int frame = 0; + double last_t = tic(); + while (true) { + + // capture frame + m_cap >> image; + + // alternative way is to grab, then retrieve; allows for + // multiple grab when processing below frame rate - v4l keeps a + // number of frames buffered, which can lead to significant lag + // m_cap.grab(); + // m_cap.retrieve(image); + + // detect April tags (requires a gray scale image) + cv::cvtColor(image, image_gray, CV_BGR2GRAY); + vector detections = m_tagDetector->extractTags(image_gray); + + // print out each detection + cout << detections.size() << " tags detected:" << endl; + for (int i=0; i 0) { + // only the first detected tag is sent out for now + Eigen::Vector3d translation; + Eigen::Matrix3d rotation; + detections[0].getRelativeTranslationRotation(m_tagSize, m_fx, m_fy, m_px, m_py, + translation, rotation); + m_serial.print(detections[0].id); + m_serial.print(","); + m_serial.print(translation(0)); + m_serial.print(","); + m_serial.print(translation(1)); + m_serial.print(","); + m_serial.print(translation(2)); + m_serial.print("\n"); + } else { + // no tag detected: tag ID = -1 + m_serial.print("-1,0.0,0.0,0.0\n"); + } + } + + // print out the frame rate at which image frames are being processed + frame++; + if (frame % 10 == 0) { + double t = tic(); + cout << " " << 10./(t-last_t) << " fps" << endl; + last_t = t; + } + + // exit if any key is pressed + if (cv::waitKey(1) >= 0) break; + } + } + +}; // Demo + + +// here is were everything begins +int main(int argc, char* argv[]) { + Demo demo; + + // process command line options + demo.parseOptions(argc, argv); + + // setup image source, window for drawing, serial port... + demo.setup(); + + // the actual processing loop where tags are detected and visualized + demo.loop(); + + return 0; +} diff --git a/thirdparty/apriltag/ethz_apriltag2/src/example/arduino_tags/arduino_tags.ino b/thirdparty/apriltag/ethz_apriltag2/src/example/arduino_tags/arduino_tags.ino new file mode 100644 index 0000000..208d888 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/example/arduino_tags/arduino_tags.ino @@ -0,0 +1,40 @@ +/* + ArduinoTag + Turns on an LED whenever Raspberry Pi sees an Apriltag. + + Michael Kaess 04/13 + */ + +// pin number for LED +int led = 9; + +// information about detected tag +int tagId; +float x, y, z; + +// runs once when the program starts +void setup() { + // open serial port + Serial.begin(115200); + // initialize pin as output + pinMode(led, OUTPUT); +} + +// runs over and over again +void loop() { + // check if new data is available + if (Serial.available() > 0) { + tagId = Serial.parseInt(); + x = Serial.parseFloat(); + y = Serial.parseFloat(); + z = Serial.parseFloat(); + Serial.read(); // ignore newline character + if (tagId >= 0) { + digitalWrite(led, HIGH); + } else { + digitalWrite(led, LOW); + } + } + // wait for 20ms before checking again for new data + delay(20); +} diff --git a/thirdparty/apriltag/ethz_apriltag2/src/example/imu.cpp b/thirdparty/apriltag/ethz_apriltag2/src/example/imu.cpp new file mode 100644 index 0000000..d4af157 --- /dev/null +++ b/thirdparty/apriltag/ethz_apriltag2/src/example/imu.cpp @@ -0,0 +1,64 @@ +// Example of reading from ArduIMU (v3) via serial port +// Michael Kaess, May 2013 + +#include +#include +#include +#include + +#include "Serial.h" + +using namespace std; + + +void parse(string s) { + // note that ex (the rotation matrix) and mg? (the magnetormeter + // readings) below are optional, depending on how the ArduIMU was + // configured + + float version; // ArduIMU code version + float gyroX, gyroY, gyroZ; // raw gyroscope values + float accelX, accelY, accelZ; // raw accelerometer values + // int ex[9]; // rotation matrix (scaled by 10^7) + float roll, pitch, yaw; // Euler angles + int imuh; // IMU health + // float mgx, mgy, mgz, mgh; // magnetometer readings + int tow; // GPS time + + // cout << s; + + // try to parse the line + int num = sscanf(s.c_str(), + //"!!!VER:%g,AN0:%g,AN1:%g,AN2:%g,AN3:%g,AN4:%g,AN5:%g,EX0:%i,EX1:%i,EX2:%i,EX3:%i,EX4:%i,EX5:%i,EX6:%i,EX7:%i,EX8:%i,RLL:%g,PCH:%g,YAW:%g,IMUH:%i,TOW:%i***", + "!!!VER:%g,AN0:%g,AN1:%g,AN2:%g,AN3:%g,AN4:%g,AN5:%g,RLL:%g,PCH:%g,YAW:%g,IMUH:%i,TOW:%i", + //"!!!VER:%g,AN0:%g,AN1:%g,AN2:%g,AN3:%g,AN4:%g,AN5:%g,RLL:%g,PCH:%g,YAW:%g,IMUH:%i,MGX:%g,MGY:%g,MGZ:%g,MGH:%g,TOW:%i", + &version, &gyroX, &gyroY, &gyroZ, &accelX, &accelY, &accelZ, + // &ex[0], &ex[1], &ex[2], &ex[3], &ex[4], &ex[5], &ex[6], &ex[7], &ex[8], + &roll, &pitch, &yaw, + &imuh, + // &mgx, &mgy, &mgz, &mgh, + &tow); + + // did we read the correct number of entries, or did the line contain other information? + if (num==12 || num==16 || num==21) { + cout << "Euler angles: " << yaw << "," << pitch << "," << roll << endl; + } else { + // cout << "Could not parse string " << num << endl; + } + +} + + +int main() { + + Serial serial; + serial.open("/dev/ttyUSB0", 38400); // might need to change to your USB port + + // read and parse one line at a time + while (true) { + string s = serial.readBytesUntil('\n'); + parse(s); + } + + return 0; +} diff --git a/thirdparty/apriltag/include/basalt/utils/apriltag.h b/thirdparty/apriltag/include/basalt/utils/apriltag.h new file mode 100644 index 0000000..0a5c60b --- /dev/null +++ b/thirdparty/apriltag/include/basalt/utils/apriltag.h @@ -0,0 +1,30 @@ + +#include +#include +#include + + +namespace basalt { + +struct ApriltagDetectorData; + +class ApriltagDetector { + public: + ApriltagDetector(); + + ~ApriltagDetector(); + + void detectTags(basalt::ManagedImage& img_raw, + Eigen::vector& corners, + std::vector& ids, + std::vector& radii, + Eigen::vector& corners_rejected, + std::vector& ids_rejected, + std::vector& radii_rejected); + + private: + ApriltagDetectorData* data; + }; + +} + diff --git a/thirdparty/apriltag/src/apriltag.cpp b/thirdparty/apriltag/src/apriltag.cpp new file mode 100644 index 0000000..391766d --- /dev/null +++ b/thirdparty/apriltag/src/apriltag.cpp @@ -0,0 +1,249 @@ + +#include + +#include + +#include + +namespace basalt { + +struct ApriltagDetectorData { + ApriltagDetectorData() + : doSubpixRefinement(true), + maxSubpixDisplacement(0), + minTagsForValidObs(4), + minBorderDistance(4.0), + blackTagBorder(2), + _tagCodes(AprilTags::tagCodes36h11) { + _tagDetector = + std::make_shared(_tagCodes, blackTagBorder); + } + + bool doSubpixRefinement; + double + maxSubpixDisplacement; //!< maximum displacement for subpixel refinement. + //!< If 0, only base it on tag size. + unsigned int minTagsForValidObs; + double minBorderDistance; + unsigned int blackTagBorder; + + AprilTags::TagCodes _tagCodes; + std::shared_ptr _tagDetector; + + inline int size() { return 36 * 4; } +}; + +ApriltagDetector::ApriltagDetector() { data = new ApriltagDetectorData; } + +ApriltagDetector::~ApriltagDetector() { delete data; } + +void ApriltagDetector::detectTags( + basalt::ManagedImage& img_raw, + Eigen::vector& corners, std::vector& ids, + std::vector& radii, + Eigen::vector& corners_rejected, + std::vector& ids_rejected, std::vector& radii_rejected) { + corners.clear(); + ids.clear(); + radii.clear(); + corners_rejected.clear(); + ids_rejected.clear(); + radii_rejected.clear(); + + cv::Mat image(img_raw.h, img_raw.w, CV_8U); + + uint8_t* dst = image.ptr(); + const uint16_t* src = img_raw.ptr; + + for (size_t i = 0; i < img_raw.size(); i++) { + dst[i] = (src[i] >> 8); + } + + // detect the tags + std::vector detections = + data->_tagDetector->extractTags(image); + + /* handle the case in which a tag is identified but not all tag + * corners are in the image (all data bits in image but border + * outside). tagCorners should still be okay as apriltag-lib + * extrapolates them, only the subpix refinement will fail + */ + + // min. distance [px] of tag corners from image border (tag is not used if + // violated) + std::vector::iterator iter = detections.begin(); + for (iter = detections.begin(); iter != detections.end();) { + // check all four corners for violation + bool remove = false; + + for (int j = 0; j < 4; j++) { + remove |= iter->p[j].first < data->minBorderDistance; + remove |= iter->p[j].first > + (float)(image.cols) - data->minBorderDistance; // width + remove |= iter->p[j].second < data->minBorderDistance; + remove |= iter->p[j].second > + (float)(image.rows) - data->minBorderDistance; // height + } + + // also remove tags that are flagged as bad + if (iter->good != 1) remove |= true; + + // also remove if the tag ID is out-of-range for this grid (faulty + // detection) + if (iter->id >= (int)data->size() / 4) remove |= true; + + // delete flagged tags + if (remove) { + // delete the tag and advance in list + iter = detections.erase(iter); + } else { + // advance in list + ++iter; + } + } + + // did we find enough tags? + if (detections.size() < data->minTagsForValidObs) return; + + // sort detections by tagId + std::sort(detections.begin(), detections.end(), + AprilTags::TagDetection::sortByIdCompare); + + // check for duplicate tagIds (--> if found: wild Apriltags in image not + // belonging to calibration target) + // (only if we have more than 1 tag...) + if (detections.size() > 1) { + for (unsigned i = 0; i < detections.size() - 1; i++) + if (detections[i].id == detections[i + 1].id) { + std::cerr << "Wild Apriltag detected. Hide them!" << std::endl; + return; + } + } + + // compute search radius for sub-pixel refinement depending on size of tag in + // image + std::vector radiiRaw; + for (unsigned i = 0; i < detections.size(); i++) { + const double minimalRadius = 2.0; + const double percentOfSideLength = 7.5; + const double avgSideLength = + static_cast(detections[i].observedPerimeter) / 4.0; + // use certain percentage of average side length as radius + // subtract 1.0 since this radius is for displacement threshold; Search + // region is slightly larger + radiiRaw.emplace_back(std::max( + minimalRadius, (percentOfSideLength / 100.0 * avgSideLength) - 1.0)); + } + + // convert corners to cv::Mat (4 consecutive corners form one tag) + /// point ordering here + /// 11-----10 15-----14 + /// | TAG 2 | | TAG 3 | + /// 8-------9 12-----13 + /// 3-------2 7-------6 + /// y | TAG 0 | | TAG 1 | + /// ^ 0-------1 4-------5 + /// |-->x + cv::Mat tagCorners(4 * detections.size(), 2, CV_32F); + + for (unsigned i = 0; i < detections.size(); i++) { + for (unsigned j = 0; j < 4; j++) { + tagCorners.at(4 * i + j, 0) = detections[i].p[j].first; + tagCorners.at(4 * i + j, 1) = detections[i].p[j].second; + } + } + + // store a copy of the corner list before subpix refinement + cv::Mat tagCornersRaw = tagCorners.clone(); + + // optional subpixel refinement on all tag corners (four corners each tag) + if (data->doSubpixRefinement) { + for (size_t i = 0; i < detections.size(); i++) { + cv::Mat currentCorners(4, 2, CV_32F); + for (unsigned j = 0; j < 4; j++) { + currentCorners.at(j, 0) = tagCorners.at(4 * i + j, 0); + currentCorners.at(j, 1) = tagCorners.at(4 * i + j, 1); + } + + const int radius = static_cast(std::ceil(radiiRaw[i] + 1.0)); + cv::cornerSubPix( + image, currentCorners, cv::Size(radius, radius), cv::Size(-1, -1), + cv::TermCriteria(cv::TermCriteria::EPS + cv::TermCriteria::MAX_ITER, + 100, 0.01)); + + for (unsigned j = 0; j < 4; j++) { + tagCorners.at(4 * i + j, 0) = currentCorners.at(j, 0); + tagCorners.at(4 * i + j, 1) = currentCorners.at(j, 1); + } + } + } + + // insert the observed points into the correct location of the grid point + // array + /// point ordering + /// 12-----13 14-----15 + /// | TAG 2 | | TAG 3 | + /// 8-------9 10-----11 + /// 4-------5 6-------7 + /// y | TAG 0 | | TAG 1 | + /// ^ 0-------1 2-------3 + /// |-->x + + for (unsigned int i = 0; i < detections.size(); i++) { + // get the tag id + int tagId = detections[i].id; + + // check maximum displacement from subpixel refinement + const double radius = radiiRaw[i]; + const double tagMaxDispl2 = radius * radius; + const double globalMaxDispl2 = + data->maxSubpixDisplacement * data->maxSubpixDisplacement; + const double subpixRefinementThreshold2 = + globalMaxDispl2 > 0 ? std::min(globalMaxDispl2, tagMaxDispl2) + : tagMaxDispl2; + + // add four points per tag + for (int j = 0; j < 4; j++) { + int pointId = (tagId << 2) + j; + + // refined corners + double corner_x = tagCorners.row(4 * i + j).at(0); + double corner_y = tagCorners.row(4 * i + j).at(1); + + // raw corners + double cornerRaw_x = tagCornersRaw.row(4 * i + j).at(0); + double cornerRaw_y = tagCornersRaw.row(4 * i + j).at(1); + + // only add point if the displacement in the subpixel refinement is below + // a given threshold + double subpix_displacement_squarred = + (corner_x - cornerRaw_x) * (corner_x - cornerRaw_x) + + (corner_y - cornerRaw_y) * (corner_y - cornerRaw_y); + + // add all points, but only set active if the point has not moved to far + // in the subpix refinement + + // TODO: We still get a few false positives here, e.g. when the whole + // search region lies on an edge but the actual corner is not included. + // Maybe what we would need to do is actually checking a "corner + // score" vs "edge score" after refinement and discard all corners + // that are not more "cornery" than "edgy". Another possible issue + // might be corners, where (due to fisheye distortion), neighboring + // corners are in the search radius. For those we should check if in + // the radius there is really a clear single maximum in the corner + // score and otherwise discard the corner. + + if (subpix_displacement_squarred <= subpixRefinementThreshold2) { + corners.emplace_back(corner_x, corner_y); + ids.emplace_back(pointId); + radii.emplace_back(radius); + } else { + corners_rejected.emplace_back(corner_x, corner_y); + ids_rejected.emplace_back(pointId); + radii_rejected.emplace_back(radius); + } + } + } +} + +} // namespace basalt diff --git a/thirdparty/basalt-headers b/thirdparty/basalt-headers new file mode 160000 index 0000000..bb7300d --- /dev/null +++ b/thirdparty/basalt-headers @@ -0,0 +1 @@ +Subproject commit bb7300d51f7f5af8988f162e80e9481f27c5b8ed diff --git a/thirdparty/opengv b/thirdparty/opengv new file mode 160000 index 0000000..306a54e --- /dev/null +++ b/thirdparty/opengv @@ -0,0 +1 @@ +Subproject commit 306a54e6c6b94e2048f820cdf77ef5281d4b48ad diff --git a/thirdparty/ros/CMakeLists.txt b/thirdparty/ros/CMakeLists.txt new file mode 100644 index 0000000..7709a5f --- /dev/null +++ b/thirdparty/ros/CMakeLists.txt @@ -0,0 +1,33 @@ +cmake_minimum_required(VERSION 3.2) + + +SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fPIC") +SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fPIC") + +#find_package(catkin REQUIRED COMPONENTS cpp_common roscpp_serialization roscpp_traits rostime roslz4) +find_package(Boost REQUIRED COMPONENTS date_time filesystem program_options regex) +find_package(BZip2 REQUIRED) +find_library(lz4_LIBRARIES NAMES lz4) + +file(GLOB CONSOLE_BRIDGE_SRCS "${CMAKE_CURRENT_SOURCE_DIR}/console_bridge/src/*.cpp") +file(GLOB CPP_COMMON_SRCS "${CMAKE_CURRENT_SOURCE_DIR}/roscpp_core/cpp_common/src/*.cpp") +file(GLOB ROSCPP_SERIALIZATION_SRCS "${CMAKE_CURRENT_SOURCE_DIR}/roscpp_core/roscpp_serialization/src/*.cpp") +file(GLOB ROSTIME_SRCS "${CMAKE_CURRENT_SOURCE_DIR}/roscpp_core/rostime/src/*.cpp") + +file(GLOB ROSBAG_SRCS "${CMAKE_CURRENT_SOURCE_DIR}/ros_comm/tools/rosbag_storage/src/*.cpp") +file(GLOB ROSLZ4_SRCS "${CMAKE_CURRENT_SOURCE_DIR}/ros_comm/utilities/roslz4/src/[a-z]*.c") + +add_library(rosbag STATIC ${ROSBAG_SRCS} ${ROSTIME_SRCS} ${CPP_COMMON_SRCS} ${ROSCPP_SERIALIZATION_SRCS} ${ROSLZ4_SRCS} ${CONSOLE_BRIDGE_SRCS}) + +target_include_directories(rosbag PUBLIC + include + console_bridge/include + roscpp_core/cpp_common/include + roscpp_core/rostime/include + roscpp_core/roscpp_serialization/include + roscpp_core/roscpp_traits/include + ros_comm/utilities/roslz4/include + ros_comm/tools/rosbag_storage/include) + +target_link_libraries(rosbag PUBLIC ${Boost_LIBRARIES} ${BZIP2_LIBRARIES} ${lz4_LIBRARIES}) + diff --git a/thirdparty/ros/console_bridge b/thirdparty/ros/console_bridge new file mode 160000 index 0000000..ad25f73 --- /dev/null +++ b/thirdparty/ros/console_bridge @@ -0,0 +1 @@ +Subproject commit ad25f7307da76be2857545e7e5c2a20727eee542 diff --git a/thirdparty/ros/include/console_bridge_export.h b/thirdparty/ros/include/console_bridge_export.h new file mode 100644 index 0000000..4b3754d --- /dev/null +++ b/thirdparty/ros/include/console_bridge_export.h @@ -0,0 +1,41 @@ + +#ifndef CONSOLE_BRIDGE_DLLAPI_H +#define CONSOLE_BRIDGE_DLLAPI_H + +#ifdef CONSOLE_BRIDGE_STATIC_DEFINE +# define CONSOLE_BRIDGE_DLLAPI +# define CONSOLE_BRIDGE_NO_EXPORT +#else +# ifndef CONSOLE_BRIDGE_DLLAPI +# ifdef console_bridge_EXPORTS + /* We are building this library */ +# define CONSOLE_BRIDGE_DLLAPI __attribute__((visibility("default"))) +# else + /* We are using this library */ +# define CONSOLE_BRIDGE_DLLAPI __attribute__((visibility("default"))) +# endif +# endif + +# ifndef CONSOLE_BRIDGE_NO_EXPORT +# define CONSOLE_BRIDGE_NO_EXPORT __attribute__((visibility("hidden"))) +# endif +#endif + +#ifndef CONSOLE_BRIDGE_DEPRECATED +# define CONSOLE_BRIDGE_DEPRECATED __attribute__ ((__deprecated__)) +#endif + +#ifndef CONSOLE_BRIDGE_DEPRECATED_EXPORT +# define CONSOLE_BRIDGE_DEPRECATED_EXPORT CONSOLE_BRIDGE_DLLAPI CONSOLE_BRIDGE_DEPRECATED +#endif + +#ifndef CONSOLE_BRIDGE_DEPRECATED_NO_EXPORT +# define CONSOLE_BRIDGE_DEPRECATED_NO_EXPORT CONSOLE_BRIDGE_NO_EXPORT CONSOLE_BRIDGE_DEPRECATED +#endif + +#define DEFINE_NO_DEPRECATED 0 +#if DEFINE_NO_DEPRECATED +# define CONSOLE_BRIDGE_NO_DEPRECATED +#endif + +#endif diff --git a/thirdparty/ros/include/geometry_msgs/Accel.h b/thirdparty/ros/include/geometry_msgs/Accel.h new file mode 100644 index 0000000..e721cc3 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Accel.h @@ -0,0 +1,214 @@ +// Generated by gencpp from file geometry_msgs/Accel.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_ACCEL_H +#define GEOMETRY_MSGS_MESSAGE_ACCEL_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct Accel_ +{ + typedef Accel_ Type; + + Accel_() + : linear() + , angular() { + } + Accel_(const ContainerAllocator& _alloc) + : linear(_alloc) + , angular(_alloc) { + (void)_alloc; + } + + + + typedef ::geometry_msgs::Vector3_ _linear_type; + _linear_type linear; + + typedef ::geometry_msgs::Vector3_ _angular_type; + _angular_type angular; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Accel_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Accel_ const> ConstPtr; + +}; // struct Accel_ + +typedef ::geometry_msgs::Accel_ > Accel; + +typedef boost::shared_ptr< ::geometry_msgs::Accel > AccelPtr; +typedef boost::shared_ptr< ::geometry_msgs::Accel const> AccelConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Accel_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Accel_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Accel_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Accel_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Accel_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Accel_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Accel_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Accel_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Accel_ > +{ + static const char* value() + { + return "9f195f881246fdfa2798d1d3eebca84a"; + } + + static const char* value(const ::geometry_msgs::Accel_&) { return value(); } + static const uint64_t static_value1 = 0x9f195f881246fdfaULL; + static const uint64_t static_value2 = 0x2798d1d3eebca84aULL; +}; + +template +struct DataType< ::geometry_msgs::Accel_ > +{ + static const char* value() + { + return "geometry_msgs/Accel"; + } + + static const char* value(const ::geometry_msgs::Accel_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Accel_ > +{ + static const char* value() + { + return "# This expresses acceleration in free space broken into its linear and angular parts.\n\ +Vector3 linear\n\ +Vector3 angular\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::Accel_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Accel_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.linear); + stream.next(m.angular); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Accel_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Accel_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Accel_& v) + { + s << indent << "linear: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.linear); + s << indent << "angular: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.angular); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_ACCEL_H diff --git a/thirdparty/ros/include/geometry_msgs/AccelStamped.h b/thirdparty/ros/include/geometry_msgs/AccelStamped.h new file mode 100644 index 0000000..dd451fd --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/AccelStamped.h @@ -0,0 +1,238 @@ +// Generated by gencpp from file geometry_msgs/AccelStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_ACCELSTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_ACCELSTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct AccelStamped_ +{ + typedef AccelStamped_ Type; + + AccelStamped_() + : header() + , accel() { + } + AccelStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , accel(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Accel_ _accel_type; + _accel_type accel; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::AccelStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::AccelStamped_ const> ConstPtr; + +}; // struct AccelStamped_ + +typedef ::geometry_msgs::AccelStamped_ > AccelStamped; + +typedef boost::shared_ptr< ::geometry_msgs::AccelStamped > AccelStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::AccelStamped const> AccelStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::AccelStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::AccelStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::AccelStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::AccelStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::AccelStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::AccelStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::AccelStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::AccelStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::AccelStamped_ > +{ + static const char* value() + { + return "d8a98a5d81351b6eb0578c78557e7659"; + } + + static const char* value(const ::geometry_msgs::AccelStamped_&) { return value(); } + static const uint64_t static_value1 = 0xd8a98a5d81351b6eULL; + static const uint64_t static_value2 = 0xb0578c78557e7659ULL; +}; + +template +struct DataType< ::geometry_msgs::AccelStamped_ > +{ + static const char* value() + { + return "geometry_msgs/AccelStamped"; + } + + static const char* value(const ::geometry_msgs::AccelStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::AccelStamped_ > +{ + static const char* value() + { + return "# An accel with reference coordinate frame and timestamp\n\ +Header header\n\ +Accel accel\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Accel\n\ +# This expresses acceleration in free space broken into its linear and angular parts.\n\ +Vector3 linear\n\ +Vector3 angular\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::AccelStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::AccelStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.accel); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct AccelStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::AccelStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::AccelStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "accel: "; + s << std::endl; + Printer< ::geometry_msgs::Accel_ >::stream(s, indent + " ", v.accel); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_ACCELSTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/AccelWithCovariance.h b/thirdparty/ros/include/geometry_msgs/AccelWithCovariance.h new file mode 100644 index 0000000..611555f --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/AccelWithCovariance.h @@ -0,0 +1,230 @@ +// Generated by gencpp from file geometry_msgs/AccelWithCovariance.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_ACCELWITHCOVARIANCE_H +#define GEOMETRY_MSGS_MESSAGE_ACCELWITHCOVARIANCE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace geometry_msgs +{ +template +struct AccelWithCovariance_ +{ + typedef AccelWithCovariance_ Type; + + AccelWithCovariance_() + : accel() + , covariance() { + covariance.assign(0.0); + } + AccelWithCovariance_(const ContainerAllocator& _alloc) + : accel(_alloc) + , covariance() { + (void)_alloc; + covariance.assign(0.0); + } + + + + typedef ::geometry_msgs::Accel_ _accel_type; + _accel_type accel; + + typedef boost::array _covariance_type; + _covariance_type covariance; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::AccelWithCovariance_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::AccelWithCovariance_ const> ConstPtr; + +}; // struct AccelWithCovariance_ + +typedef ::geometry_msgs::AccelWithCovariance_ > AccelWithCovariance; + +typedef boost::shared_ptr< ::geometry_msgs::AccelWithCovariance > AccelWithCovariancePtr; +typedef boost::shared_ptr< ::geometry_msgs::AccelWithCovariance const> AccelWithCovarianceConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::AccelWithCovariance_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::AccelWithCovariance_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::AccelWithCovariance_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::AccelWithCovariance_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::AccelWithCovariance_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::AccelWithCovariance_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::AccelWithCovariance_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::AccelWithCovariance_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::AccelWithCovariance_ > +{ + static const char* value() + { + return "ad5a718d699c6be72a02b8d6a139f334"; + } + + static const char* value(const ::geometry_msgs::AccelWithCovariance_&) { return value(); } + static const uint64_t static_value1 = 0xad5a718d699c6be7ULL; + static const uint64_t static_value2 = 0x2a02b8d6a139f334ULL; +}; + +template +struct DataType< ::geometry_msgs::AccelWithCovariance_ > +{ + static const char* value() + { + return "geometry_msgs/AccelWithCovariance"; + } + + static const char* value(const ::geometry_msgs::AccelWithCovariance_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::AccelWithCovariance_ > +{ + static const char* value() + { + return "# This expresses acceleration in free space with uncertainty.\n\ +\n\ +Accel accel\n\ +\n\ +# Row-major representation of the 6x6 covariance matrix\n\ +# The orientation parameters use a fixed-axis representation.\n\ +# In order, the parameters are:\n\ +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\ +float64[36] covariance\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Accel\n\ +# This expresses acceleration in free space broken into its linear and angular parts.\n\ +Vector3 linear\n\ +Vector3 angular\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::AccelWithCovariance_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::AccelWithCovariance_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.accel); + stream.next(m.covariance); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct AccelWithCovariance_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::AccelWithCovariance_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::AccelWithCovariance_& v) + { + s << indent << "accel: "; + s << std::endl; + Printer< ::geometry_msgs::Accel_ >::stream(s, indent + " ", v.accel); + s << indent << "covariance[]" << std::endl; + for (size_t i = 0; i < v.covariance.size(); ++i) + { + s << indent << " covariance[" << i << "]: "; + Printer::stream(s, indent + " ", v.covariance[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_ACCELWITHCOVARIANCE_H diff --git a/thirdparty/ros/include/geometry_msgs/AccelWithCovarianceStamped.h b/thirdparty/ros/include/geometry_msgs/AccelWithCovarianceStamped.h new file mode 100644 index 0000000..4a559a3 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/AccelWithCovarianceStamped.h @@ -0,0 +1,250 @@ +// Generated by gencpp from file geometry_msgs/AccelWithCovarianceStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_ACCELWITHCOVARIANCESTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_ACCELWITHCOVARIANCESTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct AccelWithCovarianceStamped_ +{ + typedef AccelWithCovarianceStamped_ Type; + + AccelWithCovarianceStamped_() + : header() + , accel() { + } + AccelWithCovarianceStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , accel(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::AccelWithCovariance_ _accel_type; + _accel_type accel; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::AccelWithCovarianceStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::AccelWithCovarianceStamped_ const> ConstPtr; + +}; // struct AccelWithCovarianceStamped_ + +typedef ::geometry_msgs::AccelWithCovarianceStamped_ > AccelWithCovarianceStamped; + +typedef boost::shared_ptr< ::geometry_msgs::AccelWithCovarianceStamped > AccelWithCovarianceStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::AccelWithCovarianceStamped const> AccelWithCovarianceStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::AccelWithCovarianceStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::AccelWithCovarianceStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::AccelWithCovarianceStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::AccelWithCovarianceStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::AccelWithCovarianceStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::AccelWithCovarianceStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::AccelWithCovarianceStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::AccelWithCovarianceStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::AccelWithCovarianceStamped_ > +{ + static const char* value() + { + return "96adb295225031ec8d57fb4251b0a886"; + } + + static const char* value(const ::geometry_msgs::AccelWithCovarianceStamped_&) { return value(); } + static const uint64_t static_value1 = 0x96adb295225031ecULL; + static const uint64_t static_value2 = 0x8d57fb4251b0a886ULL; +}; + +template +struct DataType< ::geometry_msgs::AccelWithCovarianceStamped_ > +{ + static const char* value() + { + return "geometry_msgs/AccelWithCovarianceStamped"; + } + + static const char* value(const ::geometry_msgs::AccelWithCovarianceStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::AccelWithCovarianceStamped_ > +{ + static const char* value() + { + return "# This represents an estimated accel with reference coordinate frame and timestamp.\n\ +Header header\n\ +AccelWithCovariance accel\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/AccelWithCovariance\n\ +# This expresses acceleration in free space with uncertainty.\n\ +\n\ +Accel accel\n\ +\n\ +# Row-major representation of the 6x6 covariance matrix\n\ +# The orientation parameters use a fixed-axis representation.\n\ +# In order, the parameters are:\n\ +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\ +float64[36] covariance\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Accel\n\ +# This expresses acceleration in free space broken into its linear and angular parts.\n\ +Vector3 linear\n\ +Vector3 angular\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::AccelWithCovarianceStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::AccelWithCovarianceStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.accel); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct AccelWithCovarianceStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::AccelWithCovarianceStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::AccelWithCovarianceStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "accel: "; + s << std::endl; + Printer< ::geometry_msgs::AccelWithCovariance_ >::stream(s, indent + " ", v.accel); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_ACCELWITHCOVARIANCESTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/Inertia.h b/thirdparty/ros/include/geometry_msgs/Inertia.h new file mode 100644 index 0000000..7b66083 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Inertia.h @@ -0,0 +1,273 @@ +// Generated by gencpp from file geometry_msgs/Inertia.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_INERTIA_H +#define GEOMETRY_MSGS_MESSAGE_INERTIA_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace geometry_msgs +{ +template +struct Inertia_ +{ + typedef Inertia_ Type; + + Inertia_() + : m(0.0) + , com() + , ixx(0.0) + , ixy(0.0) + , ixz(0.0) + , iyy(0.0) + , iyz(0.0) + , izz(0.0) { + } + Inertia_(const ContainerAllocator& _alloc) + : m(0.0) + , com(_alloc) + , ixx(0.0) + , ixy(0.0) + , ixz(0.0) + , iyy(0.0) + , iyz(0.0) + , izz(0.0) { + (void)_alloc; + } + + + + typedef double _m_type; + _m_type m; + + typedef ::geometry_msgs::Vector3_ _com_type; + _com_type com; + + typedef double _ixx_type; + _ixx_type ixx; + + typedef double _ixy_type; + _ixy_type ixy; + + typedef double _ixz_type; + _ixz_type ixz; + + typedef double _iyy_type; + _iyy_type iyy; + + typedef double _iyz_type; + _iyz_type iyz; + + typedef double _izz_type; + _izz_type izz; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Inertia_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Inertia_ const> ConstPtr; + +}; // struct Inertia_ + +typedef ::geometry_msgs::Inertia_ > Inertia; + +typedef boost::shared_ptr< ::geometry_msgs::Inertia > InertiaPtr; +typedef boost::shared_ptr< ::geometry_msgs::Inertia const> InertiaConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Inertia_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Inertia_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Inertia_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Inertia_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Inertia_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Inertia_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Inertia_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Inertia_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Inertia_ > +{ + static const char* value() + { + return "1d26e4bb6c83ff141c5cf0d883c2b0fe"; + } + + static const char* value(const ::geometry_msgs::Inertia_&) { return value(); } + static const uint64_t static_value1 = 0x1d26e4bb6c83ff14ULL; + static const uint64_t static_value2 = 0x1c5cf0d883c2b0feULL; +}; + +template +struct DataType< ::geometry_msgs::Inertia_ > +{ + static const char* value() + { + return "geometry_msgs/Inertia"; + } + + static const char* value(const ::geometry_msgs::Inertia_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Inertia_ > +{ + static const char* value() + { + return "# Mass [kg]\n\ +float64 m\n\ +\n\ +# Center of mass [m]\n\ +geometry_msgs/Vector3 com\n\ +\n\ +# Inertia Tensor [kg-m^2]\n\ +# | ixx ixy ixz |\n\ +# I = | ixy iyy iyz |\n\ +# | ixz iyz izz |\n\ +float64 ixx\n\ +float64 ixy\n\ +float64 ixz\n\ +float64 iyy\n\ +float64 iyz\n\ +float64 izz\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::Inertia_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Inertia_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.m); + stream.next(m.com); + stream.next(m.ixx); + stream.next(m.ixy); + stream.next(m.ixz); + stream.next(m.iyy); + stream.next(m.iyz); + stream.next(m.izz); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Inertia_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Inertia_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Inertia_& v) + { + s << indent << "m: "; + Printer::stream(s, indent + " ", v.m); + s << indent << "com: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.com); + s << indent << "ixx: "; + Printer::stream(s, indent + " ", v.ixx); + s << indent << "ixy: "; + Printer::stream(s, indent + " ", v.ixy); + s << indent << "ixz: "; + Printer::stream(s, indent + " ", v.ixz); + s << indent << "iyy: "; + Printer::stream(s, indent + " ", v.iyy); + s << indent << "iyz: "; + Printer::stream(s, indent + " ", v.iyz); + s << indent << "izz: "; + Printer::stream(s, indent + " ", v.izz); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_INERTIA_H diff --git a/thirdparty/ros/include/geometry_msgs/InertiaStamped.h b/thirdparty/ros/include/geometry_msgs/InertiaStamped.h new file mode 100644 index 0000000..3b2e2c6 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/InertiaStamped.h @@ -0,0 +1,250 @@ +// Generated by gencpp from file geometry_msgs/InertiaStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_INERTIASTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_INERTIASTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct InertiaStamped_ +{ + typedef InertiaStamped_ Type; + + InertiaStamped_() + : header() + , inertia() { + } + InertiaStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , inertia(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Inertia_ _inertia_type; + _inertia_type inertia; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::InertiaStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::InertiaStamped_ const> ConstPtr; + +}; // struct InertiaStamped_ + +typedef ::geometry_msgs::InertiaStamped_ > InertiaStamped; + +typedef boost::shared_ptr< ::geometry_msgs::InertiaStamped > InertiaStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::InertiaStamped const> InertiaStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::InertiaStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::InertiaStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::InertiaStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::InertiaStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::InertiaStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::InertiaStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::InertiaStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::InertiaStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::InertiaStamped_ > +{ + static const char* value() + { + return "ddee48caeab5a966c5e8d166654a9ac7"; + } + + static const char* value(const ::geometry_msgs::InertiaStamped_&) { return value(); } + static const uint64_t static_value1 = 0xddee48caeab5a966ULL; + static const uint64_t static_value2 = 0xc5e8d166654a9ac7ULL; +}; + +template +struct DataType< ::geometry_msgs::InertiaStamped_ > +{ + static const char* value() + { + return "geometry_msgs/InertiaStamped"; + } + + static const char* value(const ::geometry_msgs::InertiaStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::InertiaStamped_ > +{ + static const char* value() + { + return "Header header\n\ +Inertia inertia\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Inertia\n\ +# Mass [kg]\n\ +float64 m\n\ +\n\ +# Center of mass [m]\n\ +geometry_msgs/Vector3 com\n\ +\n\ +# Inertia Tensor [kg-m^2]\n\ +# | ixx ixy ixz |\n\ +# I = | ixy iyy iyz |\n\ +# | ixz iyz izz |\n\ +float64 ixx\n\ +float64 ixy\n\ +float64 ixz\n\ +float64 iyy\n\ +float64 iyz\n\ +float64 izz\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::InertiaStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::InertiaStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.inertia); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct InertiaStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::InertiaStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::InertiaStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "inertia: "; + s << std::endl; + Printer< ::geometry_msgs::Inertia_ >::stream(s, indent + " ", v.inertia); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_INERTIASTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/Point.h b/thirdparty/ros/include/geometry_msgs/Point.h new file mode 100644 index 0000000..da5933d --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Point.h @@ -0,0 +1,206 @@ +// Generated by gencpp from file geometry_msgs/Point.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POINT_H +#define GEOMETRY_MSGS_MESSAGE_POINT_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace geometry_msgs +{ +template +struct Point_ +{ + typedef Point_ Type; + + Point_() + : x(0.0) + , y(0.0) + , z(0.0) { + } + Point_(const ContainerAllocator& _alloc) + : x(0.0) + , y(0.0) + , z(0.0) { + (void)_alloc; + } + + + + typedef double _x_type; + _x_type x; + + typedef double _y_type; + _y_type y; + + typedef double _z_type; + _z_type z; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Point_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Point_ const> ConstPtr; + +}; // struct Point_ + +typedef ::geometry_msgs::Point_ > Point; + +typedef boost::shared_ptr< ::geometry_msgs::Point > PointPtr; +typedef boost::shared_ptr< ::geometry_msgs::Point const> PointConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Point_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Point_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Point_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Point_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Point_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Point_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Point_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Point_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Point_ > +{ + static const char* value() + { + return "4a842b65f413084dc2b10fb484ea7f17"; + } + + static const char* value(const ::geometry_msgs::Point_&) { return value(); } + static const uint64_t static_value1 = 0x4a842b65f413084dULL; + static const uint64_t static_value2 = 0xc2b10fb484ea7f17ULL; +}; + +template +struct DataType< ::geometry_msgs::Point_ > +{ + static const char* value() + { + return "geometry_msgs/Point"; + } + + static const char* value(const ::geometry_msgs::Point_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Point_ > +{ + static const char* value() + { + return "# This contains the position of a point in free space\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::Point_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Point_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.x); + stream.next(m.y); + stream.next(m.z); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Point_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Point_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Point_& v) + { + s << indent << "x: "; + Printer::stream(s, indent + " ", v.x); + s << indent << "y: "; + Printer::stream(s, indent + " ", v.y); + s << indent << "z: "; + Printer::stream(s, indent + " ", v.z); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POINT_H diff --git a/thirdparty/ros/include/geometry_msgs/Point32.h b/thirdparty/ros/include/geometry_msgs/Point32.h new file mode 100644 index 0000000..6fa1aa1 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Point32.h @@ -0,0 +1,213 @@ +// Generated by gencpp from file geometry_msgs/Point32.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POINT32_H +#define GEOMETRY_MSGS_MESSAGE_POINT32_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace geometry_msgs +{ +template +struct Point32_ +{ + typedef Point32_ Type; + + Point32_() + : x(0.0) + , y(0.0) + , z(0.0) { + } + Point32_(const ContainerAllocator& _alloc) + : x(0.0) + , y(0.0) + , z(0.0) { + (void)_alloc; + } + + + + typedef float _x_type; + _x_type x; + + typedef float _y_type; + _y_type y; + + typedef float _z_type; + _z_type z; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Point32_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Point32_ const> ConstPtr; + +}; // struct Point32_ + +typedef ::geometry_msgs::Point32_ > Point32; + +typedef boost::shared_ptr< ::geometry_msgs::Point32 > Point32Ptr; +typedef boost::shared_ptr< ::geometry_msgs::Point32 const> Point32ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Point32_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Point32_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Point32_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Point32_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Point32_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Point32_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Point32_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Point32_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Point32_ > +{ + static const char* value() + { + return "cc153912f1453b708d221682bc23d9ac"; + } + + static const char* value(const ::geometry_msgs::Point32_&) { return value(); } + static const uint64_t static_value1 = 0xcc153912f1453b70ULL; + static const uint64_t static_value2 = 0x8d221682bc23d9acULL; +}; + +template +struct DataType< ::geometry_msgs::Point32_ > +{ + static const char* value() + { + return "geometry_msgs/Point32"; + } + + static const char* value(const ::geometry_msgs::Point32_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Point32_ > +{ + static const char* value() + { + return "# This contains the position of a point in free space(with 32 bits of precision).\n\ +# It is recommeded to use Point wherever possible instead of Point32. \n\ +# \n\ +# This recommendation is to promote interoperability. \n\ +#\n\ +# This message is designed to take up less space when sending\n\ +# lots of points at once, as in the case of a PointCloud. \n\ +\n\ +float32 x\n\ +float32 y\n\ +float32 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::Point32_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Point32_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.x); + stream.next(m.y); + stream.next(m.z); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Point32_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Point32_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Point32_& v) + { + s << indent << "x: "; + Printer::stream(s, indent + " ", v.x); + s << indent << "y: "; + Printer::stream(s, indent + " ", v.y); + s << indent << "z: "; + Printer::stream(s, indent + " ", v.z); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POINT32_H diff --git a/thirdparty/ros/include/geometry_msgs/PointStamped.h b/thirdparty/ros/include/geometry_msgs/PointStamped.h new file mode 100644 index 0000000..4a037e6 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/PointStamped.h @@ -0,0 +1,226 @@ +// Generated by gencpp from file geometry_msgs/PointStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POINTSTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_POINTSTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct PointStamped_ +{ + typedef PointStamped_ Type; + + PointStamped_() + : header() + , point() { + } + PointStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , point(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Point_ _point_type; + _point_type point; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::PointStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::PointStamped_ const> ConstPtr; + +}; // struct PointStamped_ + +typedef ::geometry_msgs::PointStamped_ > PointStamped; + +typedef boost::shared_ptr< ::geometry_msgs::PointStamped > PointStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::PointStamped const> PointStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::PointStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::PointStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::PointStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::PointStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::PointStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::PointStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PointStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PointStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::PointStamped_ > +{ + static const char* value() + { + return "c63aecb41bfdfd6b7e1fac37c7cbe7bf"; + } + + static const char* value(const ::geometry_msgs::PointStamped_&) { return value(); } + static const uint64_t static_value1 = 0xc63aecb41bfdfd6bULL; + static const uint64_t static_value2 = 0x7e1fac37c7cbe7bfULL; +}; + +template +struct DataType< ::geometry_msgs::PointStamped_ > +{ + static const char* value() + { + return "geometry_msgs/PointStamped"; + } + + static const char* value(const ::geometry_msgs::PointStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::PointStamped_ > +{ + static const char* value() + { + return "# This represents a Point with reference coordinate frame and timestamp\n\ +Header header\n\ +Point point\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Point\n\ +# This contains the position of a point in free space\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::PointStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::PointStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.point); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct PointStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::PointStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::PointStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "point: "; + s << std::endl; + Printer< ::geometry_msgs::Point_ >::stream(s, indent + " ", v.point); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POINTSTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/Polygon.h b/thirdparty/ros/include/geometry_msgs/Polygon.h new file mode 100644 index 0000000..1a82282 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Polygon.h @@ -0,0 +1,209 @@ +// Generated by gencpp from file geometry_msgs/Polygon.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POLYGON_H +#define GEOMETRY_MSGS_MESSAGE_POLYGON_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace geometry_msgs +{ +template +struct Polygon_ +{ + typedef Polygon_ Type; + + Polygon_() + : points() { + } + Polygon_(const ContainerAllocator& _alloc) + : points(_alloc) { + (void)_alloc; + } + + + + typedef std::vector< ::geometry_msgs::Point32_ , typename ContainerAllocator::template rebind< ::geometry_msgs::Point32_ >::other > _points_type; + _points_type points; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Polygon_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Polygon_ const> ConstPtr; + +}; // struct Polygon_ + +typedef ::geometry_msgs::Polygon_ > Polygon; + +typedef boost::shared_ptr< ::geometry_msgs::Polygon > PolygonPtr; +typedef boost::shared_ptr< ::geometry_msgs::Polygon const> PolygonConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Polygon_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Polygon_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Polygon_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Polygon_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::Polygon_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Polygon_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Polygon_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Polygon_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Polygon_ > +{ + static const char* value() + { + return "cd60a26494a087f577976f0329fa120e"; + } + + static const char* value(const ::geometry_msgs::Polygon_&) { return value(); } + static const uint64_t static_value1 = 0xcd60a26494a087f5ULL; + static const uint64_t static_value2 = 0x77976f0329fa120eULL; +}; + +template +struct DataType< ::geometry_msgs::Polygon_ > +{ + static const char* value() + { + return "geometry_msgs/Polygon"; + } + + static const char* value(const ::geometry_msgs::Polygon_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Polygon_ > +{ + static const char* value() + { + return "#A specification of a polygon where the first and last points are assumed to be connected\n\ +Point32[] points\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Point32\n\ +# This contains the position of a point in free space(with 32 bits of precision).\n\ +# It is recommeded to use Point wherever possible instead of Point32. \n\ +# \n\ +# This recommendation is to promote interoperability. \n\ +#\n\ +# This message is designed to take up less space when sending\n\ +# lots of points at once, as in the case of a PointCloud. \n\ +\n\ +float32 x\n\ +float32 y\n\ +float32 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::Polygon_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Polygon_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.points); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Polygon_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Polygon_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Polygon_& v) + { + s << indent << "points[]" << std::endl; + for (size_t i = 0; i < v.points.size(); ++i) + { + s << indent << " points[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::geometry_msgs::Point32_ >::stream(s, indent + " ", v.points[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POLYGON_H diff --git a/thirdparty/ros/include/geometry_msgs/PolygonStamped.h b/thirdparty/ros/include/geometry_msgs/PolygonStamped.h new file mode 100644 index 0000000..45f0b5d --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/PolygonStamped.h @@ -0,0 +1,238 @@ +// Generated by gencpp from file geometry_msgs/PolygonStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POLYGONSTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_POLYGONSTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct PolygonStamped_ +{ + typedef PolygonStamped_ Type; + + PolygonStamped_() + : header() + , polygon() { + } + PolygonStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , polygon(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Polygon_ _polygon_type; + _polygon_type polygon; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::PolygonStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::PolygonStamped_ const> ConstPtr; + +}; // struct PolygonStamped_ + +typedef ::geometry_msgs::PolygonStamped_ > PolygonStamped; + +typedef boost::shared_ptr< ::geometry_msgs::PolygonStamped > PolygonStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::PolygonStamped const> PolygonStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::PolygonStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::PolygonStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::PolygonStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::PolygonStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::PolygonStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::PolygonStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PolygonStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PolygonStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::PolygonStamped_ > +{ + static const char* value() + { + return "c6be8f7dc3bee7fe9e8d296070f53340"; + } + + static const char* value(const ::geometry_msgs::PolygonStamped_&) { return value(); } + static const uint64_t static_value1 = 0xc6be8f7dc3bee7feULL; + static const uint64_t static_value2 = 0x9e8d296070f53340ULL; +}; + +template +struct DataType< ::geometry_msgs::PolygonStamped_ > +{ + static const char* value() + { + return "geometry_msgs/PolygonStamped"; + } + + static const char* value(const ::geometry_msgs::PolygonStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::PolygonStamped_ > +{ + static const char* value() + { + return "# This represents a Polygon with reference coordinate frame and timestamp\n\ +Header header\n\ +Polygon polygon\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Polygon\n\ +#A specification of a polygon where the first and last points are assumed to be connected\n\ +Point32[] points\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Point32\n\ +# This contains the position of a point in free space(with 32 bits of precision).\n\ +# It is recommeded to use Point wherever possible instead of Point32. \n\ +# \n\ +# This recommendation is to promote interoperability. \n\ +#\n\ +# This message is designed to take up less space when sending\n\ +# lots of points at once, as in the case of a PointCloud. \n\ +\n\ +float32 x\n\ +float32 y\n\ +float32 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::PolygonStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::PolygonStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.polygon); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct PolygonStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::PolygonStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::PolygonStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "polygon: "; + s << std::endl; + Printer< ::geometry_msgs::Polygon_ >::stream(s, indent + " ", v.polygon); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POLYGONSTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/Pose.h b/thirdparty/ros/include/geometry_msgs/Pose.h new file mode 100644 index 0000000..8e6a610 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Pose.h @@ -0,0 +1,217 @@ +// Generated by gencpp from file geometry_msgs/Pose.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POSE_H +#define GEOMETRY_MSGS_MESSAGE_POSE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct Pose_ +{ + typedef Pose_ Type; + + Pose_() + : position() + , orientation() { + } + Pose_(const ContainerAllocator& _alloc) + : position(_alloc) + , orientation(_alloc) { + (void)_alloc; + } + + + + typedef ::geometry_msgs::Point_ _position_type; + _position_type position; + + typedef ::geometry_msgs::Quaternion_ _orientation_type; + _orientation_type orientation; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Pose_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Pose_ const> ConstPtr; + +}; // struct Pose_ + +typedef ::geometry_msgs::Pose_ > Pose; + +typedef boost::shared_ptr< ::geometry_msgs::Pose > PosePtr; +typedef boost::shared_ptr< ::geometry_msgs::Pose const> PoseConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Pose_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Pose_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Pose_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Pose_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Pose_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Pose_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Pose_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Pose_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Pose_ > +{ + static const char* value() + { + return "e45d45a5a1ce597b249e23fb30fc871f"; + } + + static const char* value(const ::geometry_msgs::Pose_&) { return value(); } + static const uint64_t static_value1 = 0xe45d45a5a1ce597bULL; + static const uint64_t static_value2 = 0x249e23fb30fc871fULL; +}; + +template +struct DataType< ::geometry_msgs::Pose_ > +{ + static const char* value() + { + return "geometry_msgs/Pose"; + } + + static const char* value(const ::geometry_msgs::Pose_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Pose_ > +{ + static const char* value() + { + return "# A representation of pose in free space, composed of position and orientation. \n\ +Point position\n\ +Quaternion orientation\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Point\n\ +# This contains the position of a point in free space\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +"; + } + + static const char* value(const ::geometry_msgs::Pose_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Pose_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.position); + stream.next(m.orientation); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Pose_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Pose_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Pose_& v) + { + s << indent << "position: "; + s << std::endl; + Printer< ::geometry_msgs::Point_ >::stream(s, indent + " ", v.position); + s << indent << "orientation: "; + s << std::endl; + Printer< ::geometry_msgs::Quaternion_ >::stream(s, indent + " ", v.orientation); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POSE_H diff --git a/thirdparty/ros/include/geometry_msgs/Pose2D.h b/thirdparty/ros/include/geometry_msgs/Pose2D.h new file mode 100644 index 0000000..041fe13 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Pose2D.h @@ -0,0 +1,207 @@ +// Generated by gencpp from file geometry_msgs/Pose2D.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POSE2D_H +#define GEOMETRY_MSGS_MESSAGE_POSE2D_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace geometry_msgs +{ +template +struct Pose2D_ +{ + typedef Pose2D_ Type; + + Pose2D_() + : x(0.0) + , y(0.0) + , theta(0.0) { + } + Pose2D_(const ContainerAllocator& _alloc) + : x(0.0) + , y(0.0) + , theta(0.0) { + (void)_alloc; + } + + + + typedef double _x_type; + _x_type x; + + typedef double _y_type; + _y_type y; + + typedef double _theta_type; + _theta_type theta; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Pose2D_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Pose2D_ const> ConstPtr; + +}; // struct Pose2D_ + +typedef ::geometry_msgs::Pose2D_ > Pose2D; + +typedef boost::shared_ptr< ::geometry_msgs::Pose2D > Pose2DPtr; +typedef boost::shared_ptr< ::geometry_msgs::Pose2D const> Pose2DConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Pose2D_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Pose2D_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Pose2D_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Pose2D_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Pose2D_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Pose2D_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Pose2D_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Pose2D_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Pose2D_ > +{ + static const char* value() + { + return "938fa65709584ad8e77d238529be13b8"; + } + + static const char* value(const ::geometry_msgs::Pose2D_&) { return value(); } + static const uint64_t static_value1 = 0x938fa65709584ad8ULL; + static const uint64_t static_value2 = 0xe77d238529be13b8ULL; +}; + +template +struct DataType< ::geometry_msgs::Pose2D_ > +{ + static const char* value() + { + return "geometry_msgs/Pose2D"; + } + + static const char* value(const ::geometry_msgs::Pose2D_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Pose2D_ > +{ + static const char* value() + { + return "# This expresses a position and orientation on a 2D manifold.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 theta\n\ +"; + } + + static const char* value(const ::geometry_msgs::Pose2D_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Pose2D_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.x); + stream.next(m.y); + stream.next(m.theta); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Pose2D_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Pose2D_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Pose2D_& v) + { + s << indent << "x: "; + Printer::stream(s, indent + " ", v.x); + s << indent << "y: "; + Printer::stream(s, indent + " ", v.y); + s << indent << "theta: "; + Printer::stream(s, indent + " ", v.theta); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POSE2D_H diff --git a/thirdparty/ros/include/geometry_msgs/PoseArray.h b/thirdparty/ros/include/geometry_msgs/PoseArray.h new file mode 100644 index 0000000..2f77767 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/PoseArray.h @@ -0,0 +1,248 @@ +// Generated by gencpp from file geometry_msgs/PoseArray.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POSEARRAY_H +#define GEOMETRY_MSGS_MESSAGE_POSEARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct PoseArray_ +{ + typedef PoseArray_ Type; + + PoseArray_() + : header() + , poses() { + } + PoseArray_(const ContainerAllocator& _alloc) + : header(_alloc) + , poses(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef std::vector< ::geometry_msgs::Pose_ , typename ContainerAllocator::template rebind< ::geometry_msgs::Pose_ >::other > _poses_type; + _poses_type poses; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::PoseArray_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::PoseArray_ const> ConstPtr; + +}; // struct PoseArray_ + +typedef ::geometry_msgs::PoseArray_ > PoseArray; + +typedef boost::shared_ptr< ::geometry_msgs::PoseArray > PoseArrayPtr; +typedef boost::shared_ptr< ::geometry_msgs::PoseArray const> PoseArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::PoseArray_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::PoseArray_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::PoseArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::PoseArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::PoseArray_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::PoseArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PoseArray_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PoseArray_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::PoseArray_ > +{ + static const char* value() + { + return "916c28c5764443f268b296bb671b9d97"; + } + + static const char* value(const ::geometry_msgs::PoseArray_&) { return value(); } + static const uint64_t static_value1 = 0x916c28c5764443f2ULL; + static const uint64_t static_value2 = 0x68b296bb671b9d97ULL; +}; + +template +struct DataType< ::geometry_msgs::PoseArray_ > +{ + static const char* value() + { + return "geometry_msgs/PoseArray"; + } + + static const char* value(const ::geometry_msgs::PoseArray_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::PoseArray_ > +{ + static const char* value() + { + return "# An array of poses with a header for global reference.\n\ +\n\ +Header header\n\ +\n\ +Pose[] poses\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Pose\n\ +# A representation of pose in free space, composed of position and orientation. \n\ +Point position\n\ +Quaternion orientation\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Point\n\ +# This contains the position of a point in free space\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +"; + } + + static const char* value(const ::geometry_msgs::PoseArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::PoseArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.poses); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct PoseArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::PoseArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::PoseArray_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "poses[]" << std::endl; + for (size_t i = 0; i < v.poses.size(); ++i) + { + s << indent << " poses[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::geometry_msgs::Pose_ >::stream(s, indent + " ", v.poses[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POSEARRAY_H diff --git a/thirdparty/ros/include/geometry_msgs/PoseStamped.h b/thirdparty/ros/include/geometry_msgs/PoseStamped.h new file mode 100644 index 0000000..f476a10 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/PoseStamped.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file geometry_msgs/PoseStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POSESTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_POSESTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct PoseStamped_ +{ + typedef PoseStamped_ Type; + + PoseStamped_() + : header() + , pose() { + } + PoseStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , pose(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Pose_ _pose_type; + _pose_type pose; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::PoseStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::PoseStamped_ const> ConstPtr; + +}; // struct PoseStamped_ + +typedef ::geometry_msgs::PoseStamped_ > PoseStamped; + +typedef boost::shared_ptr< ::geometry_msgs::PoseStamped > PoseStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::PoseStamped const> PoseStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::PoseStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::PoseStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::PoseStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::PoseStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::PoseStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::PoseStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PoseStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PoseStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::PoseStamped_ > +{ + static const char* value() + { + return "d3812c3cbc69362b77dc0b19b345f8f5"; + } + + static const char* value(const ::geometry_msgs::PoseStamped_&) { return value(); } + static const uint64_t static_value1 = 0xd3812c3cbc69362bULL; + static const uint64_t static_value2 = 0x77dc0b19b345f8f5ULL; +}; + +template +struct DataType< ::geometry_msgs::PoseStamped_ > +{ + static const char* value() + { + return "geometry_msgs/PoseStamped"; + } + + static const char* value(const ::geometry_msgs::PoseStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::PoseStamped_ > +{ + static const char* value() + { + return "# A Pose with reference coordinate frame and timestamp\n\ +Header header\n\ +Pose pose\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Pose\n\ +# A representation of pose in free space, composed of position and orientation. \n\ +Point position\n\ +Quaternion orientation\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Point\n\ +# This contains the position of a point in free space\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +"; + } + + static const char* value(const ::geometry_msgs::PoseStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::PoseStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.pose); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct PoseStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::PoseStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::PoseStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "pose: "; + s << std::endl; + Printer< ::geometry_msgs::Pose_ >::stream(s, indent + " ", v.pose); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POSESTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/PoseWithCovariance.h b/thirdparty/ros/include/geometry_msgs/PoseWithCovariance.h new file mode 100644 index 0000000..4382743 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/PoseWithCovariance.h @@ -0,0 +1,233 @@ +// Generated by gencpp from file geometry_msgs/PoseWithCovariance.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POSEWITHCOVARIANCE_H +#define GEOMETRY_MSGS_MESSAGE_POSEWITHCOVARIANCE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace geometry_msgs +{ +template +struct PoseWithCovariance_ +{ + typedef PoseWithCovariance_ Type; + + PoseWithCovariance_() + : pose() + , covariance() { + covariance.assign(0.0); + } + PoseWithCovariance_(const ContainerAllocator& _alloc) + : pose(_alloc) + , covariance() { + (void)_alloc; + covariance.assign(0.0); + } + + + + typedef ::geometry_msgs::Pose_ _pose_type; + _pose_type pose; + + typedef boost::array _covariance_type; + _covariance_type covariance; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::PoseWithCovariance_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::PoseWithCovariance_ const> ConstPtr; + +}; // struct PoseWithCovariance_ + +typedef ::geometry_msgs::PoseWithCovariance_ > PoseWithCovariance; + +typedef boost::shared_ptr< ::geometry_msgs::PoseWithCovariance > PoseWithCovariancePtr; +typedef boost::shared_ptr< ::geometry_msgs::PoseWithCovariance const> PoseWithCovarianceConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::PoseWithCovariance_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::PoseWithCovariance_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::PoseWithCovariance_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::PoseWithCovariance_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::PoseWithCovariance_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::PoseWithCovariance_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PoseWithCovariance_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::PoseWithCovariance_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::PoseWithCovariance_ > +{ + static const char* value() + { + return "c23e848cf1b7533a8d7c259073a97e6f"; + } + + static const char* value(const ::geometry_msgs::PoseWithCovariance_&) { return value(); } + static const uint64_t static_value1 = 0xc23e848cf1b7533aULL; + static const uint64_t static_value2 = 0x8d7c259073a97e6fULL; +}; + +template +struct DataType< ::geometry_msgs::PoseWithCovariance_ > +{ + static const char* value() + { + return "geometry_msgs/PoseWithCovariance"; + } + + static const char* value(const ::geometry_msgs::PoseWithCovariance_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::PoseWithCovariance_ > +{ + static const char* value() + { + return "# This represents a pose in free space with uncertainty.\n\ +\n\ +Pose pose\n\ +\n\ +# Row-major representation of the 6x6 covariance matrix\n\ +# The orientation parameters use a fixed-axis representation.\n\ +# In order, the parameters are:\n\ +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\ +float64[36] covariance\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Pose\n\ +# A representation of pose in free space, composed of position and orientation. \n\ +Point position\n\ +Quaternion orientation\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Point\n\ +# This contains the position of a point in free space\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +"; + } + + static const char* value(const ::geometry_msgs::PoseWithCovariance_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::PoseWithCovariance_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.pose); + stream.next(m.covariance); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct PoseWithCovariance_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::PoseWithCovariance_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::PoseWithCovariance_& v) + { + s << indent << "pose: "; + s << std::endl; + Printer< ::geometry_msgs::Pose_ >::stream(s, indent + " ", v.pose); + s << indent << "covariance[]" << std::endl; + for (size_t i = 0; i < v.covariance.size(); ++i) + { + s << indent << " covariance[" << i << "]: "; + Printer::stream(s, indent + " ", v.covariance[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POSEWITHCOVARIANCE_H diff --git a/thirdparty/ros/include/geometry_msgs/PoseWithCovarianceStamped.h b/thirdparty/ros/include/geometry_msgs/PoseWithCovarianceStamped.h new file mode 100644 index 0000000..6662115 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/PoseWithCovarianceStamped.h @@ -0,0 +1,254 @@ +// Generated by gencpp from file geometry_msgs/PoseWithCovarianceStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_POSEWITHCOVARIANCESTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_POSEWITHCOVARIANCESTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct PoseWithCovarianceStamped_ +{ + typedef PoseWithCovarianceStamped_ Type; + + PoseWithCovarianceStamped_() + : header() + , pose() { + } + PoseWithCovarianceStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , pose(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::PoseWithCovariance_ _pose_type; + _pose_type pose; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::PoseWithCovarianceStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::PoseWithCovarianceStamped_ const> ConstPtr; + +}; // struct PoseWithCovarianceStamped_ + +typedef ::geometry_msgs::PoseWithCovarianceStamped_ > PoseWithCovarianceStamped; + +typedef boost::shared_ptr< ::geometry_msgs::PoseWithCovarianceStamped > PoseWithCovarianceStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::PoseWithCovarianceStamped const> PoseWithCovarianceStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::PoseWithCovarianceStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::PoseWithCovarianceStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::PoseWithCovarianceStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::PoseWithCovarianceStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::PoseWithCovarianceStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::PoseWithCovarianceStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PoseWithCovarianceStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::PoseWithCovarianceStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::PoseWithCovarianceStamped_ > +{ + static const char* value() + { + return "953b798c0f514ff060a53a3498ce6246"; + } + + static const char* value(const ::geometry_msgs::PoseWithCovarianceStamped_&) { return value(); } + static const uint64_t static_value1 = 0x953b798c0f514ff0ULL; + static const uint64_t static_value2 = 0x60a53a3498ce6246ULL; +}; + +template +struct DataType< ::geometry_msgs::PoseWithCovarianceStamped_ > +{ + static const char* value() + { + return "geometry_msgs/PoseWithCovarianceStamped"; + } + + static const char* value(const ::geometry_msgs::PoseWithCovarianceStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::PoseWithCovarianceStamped_ > +{ + static const char* value() + { + return "# This expresses an estimated pose with a reference coordinate frame and timestamp\n\ +\n\ +Header header\n\ +PoseWithCovariance pose\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/PoseWithCovariance\n\ +# This represents a pose in free space with uncertainty.\n\ +\n\ +Pose pose\n\ +\n\ +# Row-major representation of the 6x6 covariance matrix\n\ +# The orientation parameters use a fixed-axis representation.\n\ +# In order, the parameters are:\n\ +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\ +float64[36] covariance\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Pose\n\ +# A representation of pose in free space, composed of position and orientation. \n\ +Point position\n\ +Quaternion orientation\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Point\n\ +# This contains the position of a point in free space\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +"; + } + + static const char* value(const ::geometry_msgs::PoseWithCovarianceStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::PoseWithCovarianceStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.pose); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct PoseWithCovarianceStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::PoseWithCovarianceStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::PoseWithCovarianceStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "pose: "; + s << std::endl; + Printer< ::geometry_msgs::PoseWithCovariance_ >::stream(s, indent + " ", v.pose); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_POSEWITHCOVARIANCESTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/Quaternion.h b/thirdparty/ros/include/geometry_msgs/Quaternion.h new file mode 100644 index 0000000..8085528 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Quaternion.h @@ -0,0 +1,216 @@ +// Generated by gencpp from file geometry_msgs/Quaternion.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_QUATERNION_H +#define GEOMETRY_MSGS_MESSAGE_QUATERNION_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace geometry_msgs +{ +template +struct Quaternion_ +{ + typedef Quaternion_ Type; + + Quaternion_() + : x(0.0) + , y(0.0) + , z(0.0) + , w(0.0) { + } + Quaternion_(const ContainerAllocator& _alloc) + : x(0.0) + , y(0.0) + , z(0.0) + , w(0.0) { + (void)_alloc; + } + + + + typedef double _x_type; + _x_type x; + + typedef double _y_type; + _y_type y; + + typedef double _z_type; + _z_type z; + + typedef double _w_type; + _w_type w; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Quaternion_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Quaternion_ const> ConstPtr; + +}; // struct Quaternion_ + +typedef ::geometry_msgs::Quaternion_ > Quaternion; + +typedef boost::shared_ptr< ::geometry_msgs::Quaternion > QuaternionPtr; +typedef boost::shared_ptr< ::geometry_msgs::Quaternion const> QuaternionConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Quaternion_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Quaternion_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Quaternion_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Quaternion_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Quaternion_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Quaternion_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Quaternion_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Quaternion_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Quaternion_ > +{ + static const char* value() + { + return "a779879fadf0160734f906b8c19c7004"; + } + + static const char* value(const ::geometry_msgs::Quaternion_&) { return value(); } + static const uint64_t static_value1 = 0xa779879fadf01607ULL; + static const uint64_t static_value2 = 0x34f906b8c19c7004ULL; +}; + +template +struct DataType< ::geometry_msgs::Quaternion_ > +{ + static const char* value() + { + return "geometry_msgs/Quaternion"; + } + + static const char* value(const ::geometry_msgs::Quaternion_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Quaternion_ > +{ + static const char* value() + { + return "# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +"; + } + + static const char* value(const ::geometry_msgs::Quaternion_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Quaternion_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.x); + stream.next(m.y); + stream.next(m.z); + stream.next(m.w); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Quaternion_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Quaternion_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Quaternion_& v) + { + s << indent << "x: "; + Printer::stream(s, indent + " ", v.x); + s << indent << "y: "; + Printer::stream(s, indent + " ", v.y); + s << indent << "z: "; + Printer::stream(s, indent + " ", v.z); + s << indent << "w: "; + Printer::stream(s, indent + " ", v.w); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_QUATERNION_H diff --git a/thirdparty/ros/include/geometry_msgs/QuaternionStamped.h b/thirdparty/ros/include/geometry_msgs/QuaternionStamped.h new file mode 100644 index 0000000..e40ef5a --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/QuaternionStamped.h @@ -0,0 +1,229 @@ +// Generated by gencpp from file geometry_msgs/QuaternionStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_QUATERNIONSTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_QUATERNIONSTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct QuaternionStamped_ +{ + typedef QuaternionStamped_ Type; + + QuaternionStamped_() + : header() + , quaternion() { + } + QuaternionStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , quaternion(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Quaternion_ _quaternion_type; + _quaternion_type quaternion; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::QuaternionStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::QuaternionStamped_ const> ConstPtr; + +}; // struct QuaternionStamped_ + +typedef ::geometry_msgs::QuaternionStamped_ > QuaternionStamped; + +typedef boost::shared_ptr< ::geometry_msgs::QuaternionStamped > QuaternionStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::QuaternionStamped const> QuaternionStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::QuaternionStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::QuaternionStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::QuaternionStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::QuaternionStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::QuaternionStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::QuaternionStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::QuaternionStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::QuaternionStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::QuaternionStamped_ > +{ + static const char* value() + { + return "e57f1e547e0e1fd13504588ffc8334e2"; + } + + static const char* value(const ::geometry_msgs::QuaternionStamped_&) { return value(); } + static const uint64_t static_value1 = 0xe57f1e547e0e1fd1ULL; + static const uint64_t static_value2 = 0x3504588ffc8334e2ULL; +}; + +template +struct DataType< ::geometry_msgs::QuaternionStamped_ > +{ + static const char* value() + { + return "geometry_msgs/QuaternionStamped"; + } + + static const char* value(const ::geometry_msgs::QuaternionStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::QuaternionStamped_ > +{ + static const char* value() + { + return "# This represents an orientation with reference coordinate frame and timestamp.\n\ +\n\ +Header header\n\ +Quaternion quaternion\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +"; + } + + static const char* value(const ::geometry_msgs::QuaternionStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::QuaternionStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.quaternion); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct QuaternionStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::QuaternionStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::QuaternionStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "quaternion: "; + s << std::endl; + Printer< ::geometry_msgs::Quaternion_ >::stream(s, indent + " ", v.quaternion); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_QUATERNIONSTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/Transform.h b/thirdparty/ros/include/geometry_msgs/Transform.h new file mode 100644 index 0000000..aa3b340 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Transform.h @@ -0,0 +1,223 @@ +// Generated by gencpp from file geometry_msgs/Transform.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_TRANSFORM_H +#define GEOMETRY_MSGS_MESSAGE_TRANSFORM_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct Transform_ +{ + typedef Transform_ Type; + + Transform_() + : translation() + , rotation() { + } + Transform_(const ContainerAllocator& _alloc) + : translation(_alloc) + , rotation(_alloc) { + (void)_alloc; + } + + + + typedef ::geometry_msgs::Vector3_ _translation_type; + _translation_type translation; + + typedef ::geometry_msgs::Quaternion_ _rotation_type; + _rotation_type rotation; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Transform_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Transform_ const> ConstPtr; + +}; // struct Transform_ + +typedef ::geometry_msgs::Transform_ > Transform; + +typedef boost::shared_ptr< ::geometry_msgs::Transform > TransformPtr; +typedef boost::shared_ptr< ::geometry_msgs::Transform const> TransformConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Transform_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Transform_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Transform_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Transform_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Transform_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Transform_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Transform_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Transform_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Transform_ > +{ + static const char* value() + { + return "ac9eff44abf714214112b05d54a3cf9b"; + } + + static const char* value(const ::geometry_msgs::Transform_&) { return value(); } + static const uint64_t static_value1 = 0xac9eff44abf71421ULL; + static const uint64_t static_value2 = 0x4112b05d54a3cf9bULL; +}; + +template +struct DataType< ::geometry_msgs::Transform_ > +{ + static const char* value() + { + return "geometry_msgs/Transform"; + } + + static const char* value(const ::geometry_msgs::Transform_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Transform_ > +{ + static const char* value() + { + return "# This represents the transform between two coordinate frames in free space.\n\ +\n\ +Vector3 translation\n\ +Quaternion rotation\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +"; + } + + static const char* value(const ::geometry_msgs::Transform_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Transform_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.translation); + stream.next(m.rotation); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Transform_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Transform_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Transform_& v) + { + s << indent << "translation: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.translation); + s << indent << "rotation: "; + s << std::endl; + Printer< ::geometry_msgs::Quaternion_ >::stream(s, indent + " ", v.rotation); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_TRANSFORM_H diff --git a/thirdparty/ros/include/geometry_msgs/TransformStamped.h b/thirdparty/ros/include/geometry_msgs/TransformStamped.h new file mode 100644 index 0000000..7e2ac71 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/TransformStamped.h @@ -0,0 +1,262 @@ +// Generated by gencpp from file geometry_msgs/TransformStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_TRANSFORMSTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_TRANSFORMSTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct TransformStamped_ +{ + typedef TransformStamped_ Type; + + TransformStamped_() + : header() + , child_frame_id() + , transform() { + } + TransformStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , child_frame_id(_alloc) + , transform(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _child_frame_id_type; + _child_frame_id_type child_frame_id; + + typedef ::geometry_msgs::Transform_ _transform_type; + _transform_type transform; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::TransformStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::TransformStamped_ const> ConstPtr; + +}; // struct TransformStamped_ + +typedef ::geometry_msgs::TransformStamped_ > TransformStamped; + +typedef boost::shared_ptr< ::geometry_msgs::TransformStamped > TransformStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::TransformStamped const> TransformStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::TransformStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::TransformStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::TransformStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::TransformStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::TransformStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::TransformStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::TransformStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::TransformStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::TransformStamped_ > +{ + static const char* value() + { + return "b5764a33bfeb3588febc2682852579b0"; + } + + static const char* value(const ::geometry_msgs::TransformStamped_&) { return value(); } + static const uint64_t static_value1 = 0xb5764a33bfeb3588ULL; + static const uint64_t static_value2 = 0xfebc2682852579b0ULL; +}; + +template +struct DataType< ::geometry_msgs::TransformStamped_ > +{ + static const char* value() + { + return "geometry_msgs/TransformStamped"; + } + + static const char* value(const ::geometry_msgs::TransformStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::TransformStamped_ > +{ + static const char* value() + { + return "# This expresses a transform from coordinate frame header.frame_id\n\ +# to the coordinate frame child_frame_id\n\ +#\n\ +# This message is mostly used by the \n\ +# tf package. \n\ +# See its documentation for more information.\n\ +\n\ +Header header\n\ +string child_frame_id # the frame id of the child frame\n\ +Transform transform\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Transform\n\ +# This represents the transform between two coordinate frames in free space.\n\ +\n\ +Vector3 translation\n\ +Quaternion rotation\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +"; + } + + static const char* value(const ::geometry_msgs::TransformStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::TransformStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.child_frame_id); + stream.next(m.transform); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct TransformStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::TransformStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::TransformStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "child_frame_id: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.child_frame_id); + s << indent << "transform: "; + s << std::endl; + Printer< ::geometry_msgs::Transform_ >::stream(s, indent + " ", v.transform); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_TRANSFORMSTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/Twist.h b/thirdparty/ros/include/geometry_msgs/Twist.h new file mode 100644 index 0000000..6cb41a3 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Twist.h @@ -0,0 +1,214 @@ +// Generated by gencpp from file geometry_msgs/Twist.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_TWIST_H +#define GEOMETRY_MSGS_MESSAGE_TWIST_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct Twist_ +{ + typedef Twist_ Type; + + Twist_() + : linear() + , angular() { + } + Twist_(const ContainerAllocator& _alloc) + : linear(_alloc) + , angular(_alloc) { + (void)_alloc; + } + + + + typedef ::geometry_msgs::Vector3_ _linear_type; + _linear_type linear; + + typedef ::geometry_msgs::Vector3_ _angular_type; + _angular_type angular; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Twist_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Twist_ const> ConstPtr; + +}; // struct Twist_ + +typedef ::geometry_msgs::Twist_ > Twist; + +typedef boost::shared_ptr< ::geometry_msgs::Twist > TwistPtr; +typedef boost::shared_ptr< ::geometry_msgs::Twist const> TwistConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Twist_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Twist_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Twist_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Twist_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Twist_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Twist_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Twist_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Twist_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Twist_ > +{ + static const char* value() + { + return "9f195f881246fdfa2798d1d3eebca84a"; + } + + static const char* value(const ::geometry_msgs::Twist_&) { return value(); } + static const uint64_t static_value1 = 0x9f195f881246fdfaULL; + static const uint64_t static_value2 = 0x2798d1d3eebca84aULL; +}; + +template +struct DataType< ::geometry_msgs::Twist_ > +{ + static const char* value() + { + return "geometry_msgs/Twist"; + } + + static const char* value(const ::geometry_msgs::Twist_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Twist_ > +{ + static const char* value() + { + return "# This expresses velocity in free space broken into its linear and angular parts.\n\ +Vector3 linear\n\ +Vector3 angular\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::Twist_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Twist_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.linear); + stream.next(m.angular); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Twist_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Twist_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Twist_& v) + { + s << indent << "linear: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.linear); + s << indent << "angular: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.angular); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_TWIST_H diff --git a/thirdparty/ros/include/geometry_msgs/TwistStamped.h b/thirdparty/ros/include/geometry_msgs/TwistStamped.h new file mode 100644 index 0000000..2f542e2 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/TwistStamped.h @@ -0,0 +1,238 @@ +// Generated by gencpp from file geometry_msgs/TwistStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_TWISTSTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_TWISTSTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct TwistStamped_ +{ + typedef TwistStamped_ Type; + + TwistStamped_() + : header() + , twist() { + } + TwistStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , twist(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Twist_ _twist_type; + _twist_type twist; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::TwistStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::TwistStamped_ const> ConstPtr; + +}; // struct TwistStamped_ + +typedef ::geometry_msgs::TwistStamped_ > TwistStamped; + +typedef boost::shared_ptr< ::geometry_msgs::TwistStamped > TwistStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::TwistStamped const> TwistStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::TwistStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::TwistStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::TwistStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::TwistStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::TwistStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::TwistStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::TwistStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::TwistStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::TwistStamped_ > +{ + static const char* value() + { + return "98d34b0043a2093cf9d9345ab6eef12e"; + } + + static const char* value(const ::geometry_msgs::TwistStamped_&) { return value(); } + static const uint64_t static_value1 = 0x98d34b0043a2093cULL; + static const uint64_t static_value2 = 0xf9d9345ab6eef12eULL; +}; + +template +struct DataType< ::geometry_msgs::TwistStamped_ > +{ + static const char* value() + { + return "geometry_msgs/TwistStamped"; + } + + static const char* value(const ::geometry_msgs::TwistStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::TwistStamped_ > +{ + static const char* value() + { + return "# A twist with reference coordinate frame and timestamp\n\ +Header header\n\ +Twist twist\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Twist\n\ +# This expresses velocity in free space broken into its linear and angular parts.\n\ +Vector3 linear\n\ +Vector3 angular\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::TwistStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::TwistStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.twist); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct TwistStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::TwistStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::TwistStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "twist: "; + s << std::endl; + Printer< ::geometry_msgs::Twist_ >::stream(s, indent + " ", v.twist); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_TWISTSTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/TwistWithCovariance.h b/thirdparty/ros/include/geometry_msgs/TwistWithCovariance.h new file mode 100644 index 0000000..912656a --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/TwistWithCovariance.h @@ -0,0 +1,230 @@ +// Generated by gencpp from file geometry_msgs/TwistWithCovariance.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_TWISTWITHCOVARIANCE_H +#define GEOMETRY_MSGS_MESSAGE_TWISTWITHCOVARIANCE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace geometry_msgs +{ +template +struct TwistWithCovariance_ +{ + typedef TwistWithCovariance_ Type; + + TwistWithCovariance_() + : twist() + , covariance() { + covariance.assign(0.0); + } + TwistWithCovariance_(const ContainerAllocator& _alloc) + : twist(_alloc) + , covariance() { + (void)_alloc; + covariance.assign(0.0); + } + + + + typedef ::geometry_msgs::Twist_ _twist_type; + _twist_type twist; + + typedef boost::array _covariance_type; + _covariance_type covariance; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::TwistWithCovariance_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::TwistWithCovariance_ const> ConstPtr; + +}; // struct TwistWithCovariance_ + +typedef ::geometry_msgs::TwistWithCovariance_ > TwistWithCovariance; + +typedef boost::shared_ptr< ::geometry_msgs::TwistWithCovariance > TwistWithCovariancePtr; +typedef boost::shared_ptr< ::geometry_msgs::TwistWithCovariance const> TwistWithCovarianceConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::TwistWithCovariance_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::TwistWithCovariance_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::TwistWithCovariance_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::TwistWithCovariance_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::TwistWithCovariance_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::TwistWithCovariance_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::TwistWithCovariance_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::TwistWithCovariance_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::TwistWithCovariance_ > +{ + static const char* value() + { + return "1fe8a28e6890a4cc3ae4c3ca5c7d82e6"; + } + + static const char* value(const ::geometry_msgs::TwistWithCovariance_&) { return value(); } + static const uint64_t static_value1 = 0x1fe8a28e6890a4ccULL; + static const uint64_t static_value2 = 0x3ae4c3ca5c7d82e6ULL; +}; + +template +struct DataType< ::geometry_msgs::TwistWithCovariance_ > +{ + static const char* value() + { + return "geometry_msgs/TwistWithCovariance"; + } + + static const char* value(const ::geometry_msgs::TwistWithCovariance_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::TwistWithCovariance_ > +{ + static const char* value() + { + return "# This expresses velocity in free space with uncertainty.\n\ +\n\ +Twist twist\n\ +\n\ +# Row-major representation of the 6x6 covariance matrix\n\ +# The orientation parameters use a fixed-axis representation.\n\ +# In order, the parameters are:\n\ +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\ +float64[36] covariance\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Twist\n\ +# This expresses velocity in free space broken into its linear and angular parts.\n\ +Vector3 linear\n\ +Vector3 angular\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::TwistWithCovariance_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::TwistWithCovariance_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.twist); + stream.next(m.covariance); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct TwistWithCovariance_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::TwistWithCovariance_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::TwistWithCovariance_& v) + { + s << indent << "twist: "; + s << std::endl; + Printer< ::geometry_msgs::Twist_ >::stream(s, indent + " ", v.twist); + s << indent << "covariance[]" << std::endl; + for (size_t i = 0; i < v.covariance.size(); ++i) + { + s << indent << " covariance[" << i << "]: "; + Printer::stream(s, indent + " ", v.covariance[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_TWISTWITHCOVARIANCE_H diff --git a/thirdparty/ros/include/geometry_msgs/TwistWithCovarianceStamped.h b/thirdparty/ros/include/geometry_msgs/TwistWithCovarianceStamped.h new file mode 100644 index 0000000..107a806 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/TwistWithCovarianceStamped.h @@ -0,0 +1,250 @@ +// Generated by gencpp from file geometry_msgs/TwistWithCovarianceStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_TWISTWITHCOVARIANCESTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_TWISTWITHCOVARIANCESTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct TwistWithCovarianceStamped_ +{ + typedef TwistWithCovarianceStamped_ Type; + + TwistWithCovarianceStamped_() + : header() + , twist() { + } + TwistWithCovarianceStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , twist(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::TwistWithCovariance_ _twist_type; + _twist_type twist; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::TwistWithCovarianceStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::TwistWithCovarianceStamped_ const> ConstPtr; + +}; // struct TwistWithCovarianceStamped_ + +typedef ::geometry_msgs::TwistWithCovarianceStamped_ > TwistWithCovarianceStamped; + +typedef boost::shared_ptr< ::geometry_msgs::TwistWithCovarianceStamped > TwistWithCovarianceStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::TwistWithCovarianceStamped const> TwistWithCovarianceStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::TwistWithCovarianceStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::TwistWithCovarianceStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::TwistWithCovarianceStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::TwistWithCovarianceStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::TwistWithCovarianceStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::TwistWithCovarianceStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::TwistWithCovarianceStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::TwistWithCovarianceStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::TwistWithCovarianceStamped_ > +{ + static const char* value() + { + return "8927a1a12fb2607ceea095b2dc440a96"; + } + + static const char* value(const ::geometry_msgs::TwistWithCovarianceStamped_&) { return value(); } + static const uint64_t static_value1 = 0x8927a1a12fb2607cULL; + static const uint64_t static_value2 = 0xeea095b2dc440a96ULL; +}; + +template +struct DataType< ::geometry_msgs::TwistWithCovarianceStamped_ > +{ + static const char* value() + { + return "geometry_msgs/TwistWithCovarianceStamped"; + } + + static const char* value(const ::geometry_msgs::TwistWithCovarianceStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::TwistWithCovarianceStamped_ > +{ + static const char* value() + { + return "# This represents an estimated twist with reference coordinate frame and timestamp.\n\ +Header header\n\ +TwistWithCovariance twist\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/TwistWithCovariance\n\ +# This expresses velocity in free space with uncertainty.\n\ +\n\ +Twist twist\n\ +\n\ +# Row-major representation of the 6x6 covariance matrix\n\ +# The orientation parameters use a fixed-axis representation.\n\ +# In order, the parameters are:\n\ +# (x, y, z, rotation about X axis, rotation about Y axis, rotation about Z axis)\n\ +float64[36] covariance\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Twist\n\ +# This expresses velocity in free space broken into its linear and angular parts.\n\ +Vector3 linear\n\ +Vector3 angular\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::TwistWithCovarianceStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::TwistWithCovarianceStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.twist); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct TwistWithCovarianceStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::TwistWithCovarianceStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::TwistWithCovarianceStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "twist: "; + s << std::endl; + Printer< ::geometry_msgs::TwistWithCovariance_ >::stream(s, indent + " ", v.twist); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_TWISTWITHCOVARIANCESTAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/Vector3.h b/thirdparty/ros/include/geometry_msgs/Vector3.h new file mode 100644 index 0000000..7dbb6e9 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Vector3.h @@ -0,0 +1,212 @@ +// Generated by gencpp from file geometry_msgs/Vector3.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_VECTOR3_H +#define GEOMETRY_MSGS_MESSAGE_VECTOR3_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace geometry_msgs +{ +template +struct Vector3_ +{ + typedef Vector3_ Type; + + Vector3_() + : x(0.0) + , y(0.0) + , z(0.0) { + } + Vector3_(const ContainerAllocator& _alloc) + : x(0.0) + , y(0.0) + , z(0.0) { + (void)_alloc; + } + + + + typedef double _x_type; + _x_type x; + + typedef double _y_type; + _y_type y; + + typedef double _z_type; + _z_type z; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Vector3_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Vector3_ const> ConstPtr; + +}; // struct Vector3_ + +typedef ::geometry_msgs::Vector3_ > Vector3; + +typedef boost::shared_ptr< ::geometry_msgs::Vector3 > Vector3Ptr; +typedef boost::shared_ptr< ::geometry_msgs::Vector3 const> Vector3ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Vector3_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Vector3_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Vector3_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Vector3_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Vector3_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Vector3_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Vector3_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Vector3_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Vector3_ > +{ + static const char* value() + { + return "4a842b65f413084dc2b10fb484ea7f17"; + } + + static const char* value(const ::geometry_msgs::Vector3_&) { return value(); } + static const uint64_t static_value1 = 0x4a842b65f413084dULL; + static const uint64_t static_value2 = 0xc2b10fb484ea7f17ULL; +}; + +template +struct DataType< ::geometry_msgs::Vector3_ > +{ + static const char* value() + { + return "geometry_msgs/Vector3"; + } + + static const char* value(const ::geometry_msgs::Vector3_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Vector3_ > +{ + static const char* value() + { + return "# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::Vector3_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Vector3_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.x); + stream.next(m.y); + stream.next(m.z); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Vector3_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Vector3_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Vector3_& v) + { + s << indent << "x: "; + Printer::stream(s, indent + " ", v.x); + s << indent << "y: "; + Printer::stream(s, indent + " ", v.y); + s << indent << "z: "; + Printer::stream(s, indent + " ", v.z); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_VECTOR3_H diff --git a/thirdparty/ros/include/geometry_msgs/Vector3Stamped.h b/thirdparty/ros/include/geometry_msgs/Vector3Stamped.h new file mode 100644 index 0000000..4502761 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Vector3Stamped.h @@ -0,0 +1,232 @@ +// Generated by gencpp from file geometry_msgs/Vector3Stamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_VECTOR3STAMPED_H +#define GEOMETRY_MSGS_MESSAGE_VECTOR3STAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct Vector3Stamped_ +{ + typedef Vector3Stamped_ Type; + + Vector3Stamped_() + : header() + , vector() { + } + Vector3Stamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , vector(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Vector3_ _vector_type; + _vector_type vector; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Vector3Stamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Vector3Stamped_ const> ConstPtr; + +}; // struct Vector3Stamped_ + +typedef ::geometry_msgs::Vector3Stamped_ > Vector3Stamped; + +typedef boost::shared_ptr< ::geometry_msgs::Vector3Stamped > Vector3StampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::Vector3Stamped const> Vector3StampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Vector3Stamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Vector3Stamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Vector3Stamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Vector3Stamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::Vector3Stamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Vector3Stamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Vector3Stamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Vector3Stamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Vector3Stamped_ > +{ + static const char* value() + { + return "7b324c7325e683bf02a9b14b01090ec7"; + } + + static const char* value(const ::geometry_msgs::Vector3Stamped_&) { return value(); } + static const uint64_t static_value1 = 0x7b324c7325e683bfULL; + static const uint64_t static_value2 = 0x02a9b14b01090ec7ULL; +}; + +template +struct DataType< ::geometry_msgs::Vector3Stamped_ > +{ + static const char* value() + { + return "geometry_msgs/Vector3Stamped"; + } + + static const char* value(const ::geometry_msgs::Vector3Stamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Vector3Stamped_ > +{ + static const char* value() + { + return "# This represents a Vector3 with reference coordinate frame and timestamp\n\ +Header header\n\ +Vector3 vector\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::Vector3Stamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Vector3Stamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.vector); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Vector3Stamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Vector3Stamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Vector3Stamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "vector: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.vector); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_VECTOR3STAMPED_H diff --git a/thirdparty/ros/include/geometry_msgs/Wrench.h b/thirdparty/ros/include/geometry_msgs/Wrench.h new file mode 100644 index 0000000..499b647 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/Wrench.h @@ -0,0 +1,215 @@ +// Generated by gencpp from file geometry_msgs/Wrench.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_WRENCH_H +#define GEOMETRY_MSGS_MESSAGE_WRENCH_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct Wrench_ +{ + typedef Wrench_ Type; + + Wrench_() + : force() + , torque() { + } + Wrench_(const ContainerAllocator& _alloc) + : force(_alloc) + , torque(_alloc) { + (void)_alloc; + } + + + + typedef ::geometry_msgs::Vector3_ _force_type; + _force_type force; + + typedef ::geometry_msgs::Vector3_ _torque_type; + _torque_type torque; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::Wrench_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::Wrench_ const> ConstPtr; + +}; // struct Wrench_ + +typedef ::geometry_msgs::Wrench_ > Wrench; + +typedef boost::shared_ptr< ::geometry_msgs::Wrench > WrenchPtr; +typedef boost::shared_ptr< ::geometry_msgs::Wrench const> WrenchConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::Wrench_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::Wrench_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::Wrench_ > + : TrueType + { }; + +template +struct IsFixedSize< ::geometry_msgs::Wrench_ const> + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Wrench_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::Wrench_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::Wrench_ > + : FalseType + { }; + +template +struct HasHeader< ::geometry_msgs::Wrench_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::geometry_msgs::Wrench_ > +{ + static const char* value() + { + return "4f539cf138b23283b520fd271b567936"; + } + + static const char* value(const ::geometry_msgs::Wrench_&) { return value(); } + static const uint64_t static_value1 = 0x4f539cf138b23283ULL; + static const uint64_t static_value2 = 0xb520fd271b567936ULL; +}; + +template +struct DataType< ::geometry_msgs::Wrench_ > +{ + static const char* value() + { + return "geometry_msgs/Wrench"; + } + + static const char* value(const ::geometry_msgs::Wrench_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::Wrench_ > +{ + static const char* value() + { + return "# This represents force in free space, separated into\n\ +# its linear and angular parts.\n\ +Vector3 force\n\ +Vector3 torque\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::Wrench_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::Wrench_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.force); + stream.next(m.torque); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Wrench_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::Wrench_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::Wrench_& v) + { + s << indent << "force: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.force); + s << indent << "torque: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.torque); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_WRENCH_H diff --git a/thirdparty/ros/include/geometry_msgs/WrenchStamped.h b/thirdparty/ros/include/geometry_msgs/WrenchStamped.h new file mode 100644 index 0000000..a07dc97 --- /dev/null +++ b/thirdparty/ros/include/geometry_msgs/WrenchStamped.h @@ -0,0 +1,239 @@ +// Generated by gencpp from file geometry_msgs/WrenchStamped.msg +// DO NOT EDIT! + + +#ifndef GEOMETRY_MSGS_MESSAGE_WRENCHSTAMPED_H +#define GEOMETRY_MSGS_MESSAGE_WRENCHSTAMPED_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace geometry_msgs +{ +template +struct WrenchStamped_ +{ + typedef WrenchStamped_ Type; + + WrenchStamped_() + : header() + , wrench() { + } + WrenchStamped_(const ContainerAllocator& _alloc) + : header(_alloc) + , wrench(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Wrench_ _wrench_type; + _wrench_type wrench; + + + + + + typedef boost::shared_ptr< ::geometry_msgs::WrenchStamped_ > Ptr; + typedef boost::shared_ptr< ::geometry_msgs::WrenchStamped_ const> ConstPtr; + +}; // struct WrenchStamped_ + +typedef ::geometry_msgs::WrenchStamped_ > WrenchStamped; + +typedef boost::shared_ptr< ::geometry_msgs::WrenchStamped > WrenchStampedPtr; +typedef boost::shared_ptr< ::geometry_msgs::WrenchStamped const> WrenchStampedConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::geometry_msgs::WrenchStamped_ & v) +{ +ros::message_operations::Printer< ::geometry_msgs::WrenchStamped_ >::stream(s, "", v); +return s; +} + +} // namespace geometry_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/tmp/binarydeb/ros-kinetic-geometry-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::geometry_msgs::WrenchStamped_ > + : FalseType + { }; + +template +struct IsFixedSize< ::geometry_msgs::WrenchStamped_ const> + : FalseType + { }; + +template +struct IsMessage< ::geometry_msgs::WrenchStamped_ > + : TrueType + { }; + +template +struct IsMessage< ::geometry_msgs::WrenchStamped_ const> + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::WrenchStamped_ > + : TrueType + { }; + +template +struct HasHeader< ::geometry_msgs::WrenchStamped_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::geometry_msgs::WrenchStamped_ > +{ + static const char* value() + { + return "d78d3cb249ce23087ade7e7d0c40cfa7"; + } + + static const char* value(const ::geometry_msgs::WrenchStamped_&) { return value(); } + static const uint64_t static_value1 = 0xd78d3cb249ce2308ULL; + static const uint64_t static_value2 = 0x7ade7e7d0c40cfa7ULL; +}; + +template +struct DataType< ::geometry_msgs::WrenchStamped_ > +{ + static const char* value() + { + return "geometry_msgs/WrenchStamped"; + } + + static const char* value(const ::geometry_msgs::WrenchStamped_&) { return value(); } +}; + +template +struct Definition< ::geometry_msgs::WrenchStamped_ > +{ + static const char* value() + { + return "# A wrench with reference coordinate frame and timestamp\n\ +Header header\n\ +Wrench wrench\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Wrench\n\ +# This represents force in free space, separated into\n\ +# its linear and angular parts.\n\ +Vector3 force\n\ +Vector3 torque\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::geometry_msgs::WrenchStamped_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::geometry_msgs::WrenchStamped_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.wrench); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct WrenchStamped_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::geometry_msgs::WrenchStamped_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::geometry_msgs::WrenchStamped_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "wrench: "; + s << std::endl; + Printer< ::geometry_msgs::Wrench_ >::stream(s, indent + " ", v.wrench); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // GEOMETRY_MSGS_MESSAGE_WRENCHSTAMPED_H diff --git a/thirdparty/ros/include/sensor_msgs/BatteryState.h b/thirdparty/ros/include/sensor_msgs/BatteryState.h new file mode 100644 index 0000000..9e8a83c --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/BatteryState.h @@ -0,0 +1,428 @@ +// Generated by gencpp from file sensor_msgs/BatteryState.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_BATTERYSTATE_H +#define SENSOR_MSGS_MESSAGE_BATTERYSTATE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct BatteryState_ +{ + typedef BatteryState_ Type; + + BatteryState_() + : header() + , voltage(0.0) + , current(0.0) + , charge(0.0) + , capacity(0.0) + , design_capacity(0.0) + , percentage(0.0) + , power_supply_status(0) + , power_supply_health(0) + , power_supply_technology(0) + , present(false) + , cell_voltage() + , location() + , serial_number() { + } + BatteryState_(const ContainerAllocator& _alloc) + : header(_alloc) + , voltage(0.0) + , current(0.0) + , charge(0.0) + , capacity(0.0) + , design_capacity(0.0) + , percentage(0.0) + , power_supply_status(0) + , power_supply_health(0) + , power_supply_technology(0) + , present(false) + , cell_voltage(_alloc) + , location(_alloc) + , serial_number(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef float _voltage_type; + _voltage_type voltage; + + typedef float _current_type; + _current_type current; + + typedef float _charge_type; + _charge_type charge; + + typedef float _capacity_type; + _capacity_type capacity; + + typedef float _design_capacity_type; + _design_capacity_type design_capacity; + + typedef float _percentage_type; + _percentage_type percentage; + + typedef uint8_t _power_supply_status_type; + _power_supply_status_type power_supply_status; + + typedef uint8_t _power_supply_health_type; + _power_supply_health_type power_supply_health; + + typedef uint8_t _power_supply_technology_type; + _power_supply_technology_type power_supply_technology; + + typedef uint8_t _present_type; + _present_type present; + + typedef std::vector::other > _cell_voltage_type; + _cell_voltage_type cell_voltage; + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _location_type; + _location_type location; + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _serial_number_type; + _serial_number_type serial_number; + + + + enum { + POWER_SUPPLY_STATUS_UNKNOWN = 0u, + POWER_SUPPLY_STATUS_CHARGING = 1u, + POWER_SUPPLY_STATUS_DISCHARGING = 2u, + POWER_SUPPLY_STATUS_NOT_CHARGING = 3u, + POWER_SUPPLY_STATUS_FULL = 4u, + POWER_SUPPLY_HEALTH_UNKNOWN = 0u, + POWER_SUPPLY_HEALTH_GOOD = 1u, + POWER_SUPPLY_HEALTH_OVERHEAT = 2u, + POWER_SUPPLY_HEALTH_DEAD = 3u, + POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4u, + POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5u, + POWER_SUPPLY_HEALTH_COLD = 6u, + POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7u, + POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8u, + POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0u, + POWER_SUPPLY_TECHNOLOGY_NIMH = 1u, + POWER_SUPPLY_TECHNOLOGY_LION = 2u, + POWER_SUPPLY_TECHNOLOGY_LIPO = 3u, + POWER_SUPPLY_TECHNOLOGY_LIFE = 4u, + POWER_SUPPLY_TECHNOLOGY_NICD = 5u, + POWER_SUPPLY_TECHNOLOGY_LIMN = 6u, + }; + + + typedef boost::shared_ptr< ::sensor_msgs::BatteryState_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::BatteryState_ const> ConstPtr; + +}; // struct BatteryState_ + +typedef ::sensor_msgs::BatteryState_ > BatteryState; + +typedef boost::shared_ptr< ::sensor_msgs::BatteryState > BatteryStatePtr; +typedef boost::shared_ptr< ::sensor_msgs::BatteryState const> BatteryStateConstPtr; + +// constants requiring out of line definition + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::BatteryState_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::BatteryState_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::BatteryState_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::BatteryState_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::BatteryState_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::BatteryState_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::BatteryState_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::BatteryState_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::BatteryState_ > +{ + static const char* value() + { + return "476f837fa6771f6e16e3bf4ef96f8770"; + } + + static const char* value(const ::sensor_msgs::BatteryState_&) { return value(); } + static const uint64_t static_value1 = 0x476f837fa6771f6eULL; + static const uint64_t static_value2 = 0x16e3bf4ef96f8770ULL; +}; + +template +struct DataType< ::sensor_msgs::BatteryState_ > +{ + static const char* value() + { + return "sensor_msgs/BatteryState"; + } + + static const char* value(const ::sensor_msgs::BatteryState_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::BatteryState_ > +{ + static const char* value() + { + return "\n\ +# Constants are chosen to match the enums in the linux kernel\n\ +# defined in include/linux/power_supply.h as of version 3.7\n\ +# The one difference is for style reasons the constants are\n\ +# all uppercase not mixed case.\n\ +\n\ +# Power supply status constants\n\ +uint8 POWER_SUPPLY_STATUS_UNKNOWN = 0\n\ +uint8 POWER_SUPPLY_STATUS_CHARGING = 1\n\ +uint8 POWER_SUPPLY_STATUS_DISCHARGING = 2\n\ +uint8 POWER_SUPPLY_STATUS_NOT_CHARGING = 3\n\ +uint8 POWER_SUPPLY_STATUS_FULL = 4\n\ +\n\ +# Power supply health constants\n\ +uint8 POWER_SUPPLY_HEALTH_UNKNOWN = 0\n\ +uint8 POWER_SUPPLY_HEALTH_GOOD = 1\n\ +uint8 POWER_SUPPLY_HEALTH_OVERHEAT = 2\n\ +uint8 POWER_SUPPLY_HEALTH_DEAD = 3\n\ +uint8 POWER_SUPPLY_HEALTH_OVERVOLTAGE = 4\n\ +uint8 POWER_SUPPLY_HEALTH_UNSPEC_FAILURE = 5\n\ +uint8 POWER_SUPPLY_HEALTH_COLD = 6\n\ +uint8 POWER_SUPPLY_HEALTH_WATCHDOG_TIMER_EXPIRE = 7\n\ +uint8 POWER_SUPPLY_HEALTH_SAFETY_TIMER_EXPIRE = 8\n\ +\n\ +# Power supply technology (chemistry) constants\n\ +uint8 POWER_SUPPLY_TECHNOLOGY_UNKNOWN = 0\n\ +uint8 POWER_SUPPLY_TECHNOLOGY_NIMH = 1\n\ +uint8 POWER_SUPPLY_TECHNOLOGY_LION = 2\n\ +uint8 POWER_SUPPLY_TECHNOLOGY_LIPO = 3\n\ +uint8 POWER_SUPPLY_TECHNOLOGY_LIFE = 4\n\ +uint8 POWER_SUPPLY_TECHNOLOGY_NICD = 5\n\ +uint8 POWER_SUPPLY_TECHNOLOGY_LIMN = 6\n\ +\n\ +Header header\n\ +float32 voltage # Voltage in Volts (Mandatory)\n\ +float32 current # Negative when discharging (A) (If unmeasured NaN)\n\ +float32 charge # Current charge in Ah (If unmeasured NaN)\n\ +float32 capacity # Capacity in Ah (last full capacity) (If unmeasured NaN)\n\ +float32 design_capacity # Capacity in Ah (design capacity) (If unmeasured NaN)\n\ +float32 percentage # Charge percentage on 0 to 1 range (If unmeasured NaN)\n\ +uint8 power_supply_status # The charging status as reported. Values defined above\n\ +uint8 power_supply_health # The battery health metric. Values defined above\n\ +uint8 power_supply_technology # The battery chemistry. Values defined above\n\ +bool present # True if the battery is present\n\ +\n\ +float32[] cell_voltage # An array of individual cell voltages for each cell in the pack\n\ + # If individual voltages unknown but number of cells known set each to NaN\n\ +string location # The location into which the battery is inserted. (slot number or plug)\n\ +string serial_number # The best approximation of the battery serial number\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::BatteryState_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::BatteryState_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.voltage); + stream.next(m.current); + stream.next(m.charge); + stream.next(m.capacity); + stream.next(m.design_capacity); + stream.next(m.percentage); + stream.next(m.power_supply_status); + stream.next(m.power_supply_health); + stream.next(m.power_supply_technology); + stream.next(m.present); + stream.next(m.cell_voltage); + stream.next(m.location); + stream.next(m.serial_number); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct BatteryState_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::BatteryState_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::BatteryState_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "voltage: "; + Printer::stream(s, indent + " ", v.voltage); + s << indent << "current: "; + Printer::stream(s, indent + " ", v.current); + s << indent << "charge: "; + Printer::stream(s, indent + " ", v.charge); + s << indent << "capacity: "; + Printer::stream(s, indent + " ", v.capacity); + s << indent << "design_capacity: "; + Printer::stream(s, indent + " ", v.design_capacity); + s << indent << "percentage: "; + Printer::stream(s, indent + " ", v.percentage); + s << indent << "power_supply_status: "; + Printer::stream(s, indent + " ", v.power_supply_status); + s << indent << "power_supply_health: "; + Printer::stream(s, indent + " ", v.power_supply_health); + s << indent << "power_supply_technology: "; + Printer::stream(s, indent + " ", v.power_supply_technology); + s << indent << "present: "; + Printer::stream(s, indent + " ", v.present); + s << indent << "cell_voltage[]" << std::endl; + for (size_t i = 0; i < v.cell_voltage.size(); ++i) + { + s << indent << " cell_voltage[" << i << "]: "; + Printer::stream(s, indent + " ", v.cell_voltage[i]); + } + s << indent << "location: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.location); + s << indent << "serial_number: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.serial_number); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_BATTERYSTATE_H diff --git a/thirdparty/ros/include/sensor_msgs/CameraInfo.h b/thirdparty/ros/include/sensor_msgs/CameraInfo.h new file mode 100644 index 0000000..7ac7278 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/CameraInfo.h @@ -0,0 +1,467 @@ +// Generated by gencpp from file sensor_msgs/CameraInfo.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_CAMERAINFO_H +#define SENSOR_MSGS_MESSAGE_CAMERAINFO_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace sensor_msgs +{ +template +struct CameraInfo_ +{ + typedef CameraInfo_ Type; + + CameraInfo_() + : header() + , height(0) + , width(0) + , distortion_model() + , D() + , K() + , R() + , P() + , binning_x(0) + , binning_y(0) + , roi() { + K.assign(0.0); + + R.assign(0.0); + + P.assign(0.0); + } + CameraInfo_(const ContainerAllocator& _alloc) + : header(_alloc) + , height(0) + , width(0) + , distortion_model(_alloc) + , D(_alloc) + , K() + , R() + , P() + , binning_x(0) + , binning_y(0) + , roi(_alloc) { + (void)_alloc; + K.assign(0.0); + + R.assign(0.0); + + P.assign(0.0); + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef uint32_t _height_type; + _height_type height; + + typedef uint32_t _width_type; + _width_type width; + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _distortion_model_type; + _distortion_model_type distortion_model; + + typedef std::vector::other > _D_type; + _D_type D; + + typedef boost::array _K_type; + _K_type K; + + typedef boost::array _R_type; + _R_type R; + + typedef boost::array _P_type; + _P_type P; + + typedef uint32_t _binning_x_type; + _binning_x_type binning_x; + + typedef uint32_t _binning_y_type; + _binning_y_type binning_y; + + typedef ::sensor_msgs::RegionOfInterest_ _roi_type; + _roi_type roi; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::CameraInfo_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::CameraInfo_ const> ConstPtr; + +}; // struct CameraInfo_ + +typedef ::sensor_msgs::CameraInfo_ > CameraInfo; + +typedef boost::shared_ptr< ::sensor_msgs::CameraInfo > CameraInfoPtr; +typedef boost::shared_ptr< ::sensor_msgs::CameraInfo const> CameraInfoConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::CameraInfo_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::CameraInfo_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::CameraInfo_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::CameraInfo_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::CameraInfo_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::CameraInfo_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::CameraInfo_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::CameraInfo_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::CameraInfo_ > +{ + static const char* value() + { + return "c9a58c1b0b154e0e6da7578cb991d214"; + } + + static const char* value(const ::sensor_msgs::CameraInfo_&) { return value(); } + static const uint64_t static_value1 = 0xc9a58c1b0b154e0eULL; + static const uint64_t static_value2 = 0x6da7578cb991d214ULL; +}; + +template +struct DataType< ::sensor_msgs::CameraInfo_ > +{ + static const char* value() + { + return "sensor_msgs/CameraInfo"; + } + + static const char* value(const ::sensor_msgs::CameraInfo_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::CameraInfo_ > +{ + static const char* value() + { + return "# This message defines meta information for a camera. It should be in a\n\ +# camera namespace on topic \"camera_info\" and accompanied by up to five\n\ +# image topics named:\n\ +#\n\ +# image_raw - raw data from the camera driver, possibly Bayer encoded\n\ +# image - monochrome, distorted\n\ +# image_color - color, distorted\n\ +# image_rect - monochrome, rectified\n\ +# image_rect_color - color, rectified\n\ +#\n\ +# The image_pipeline contains packages (image_proc, stereo_image_proc)\n\ +# for producing the four processed image topics from image_raw and\n\ +# camera_info. The meaning of the camera parameters are described in\n\ +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n\ +#\n\ +# The image_geometry package provides a user-friendly interface to\n\ +# common operations using this meta information. If you want to, e.g.,\n\ +# project a 3d point into image coordinates, we strongly recommend\n\ +# using image_geometry.\n\ +#\n\ +# If the camera is uncalibrated, the matrices D, K, R, P should be left\n\ +# zeroed out. In particular, clients may assume that K[0] == 0.0\n\ +# indicates an uncalibrated camera.\n\ +\n\ +#######################################################################\n\ +# Image acquisition info #\n\ +#######################################################################\n\ +\n\ +# Time of image acquisition, camera coordinate frame ID\n\ +Header header # Header timestamp should be acquisition time of image\n\ + # Header frame_id should be optical frame of camera\n\ + # origin of frame should be optical center of camera\n\ + # +x should point to the right in the image\n\ + # +y should point down in the image\n\ + # +z should point into the plane of the image\n\ +\n\ +\n\ +#######################################################################\n\ +# Calibration Parameters #\n\ +#######################################################################\n\ +# These are fixed during camera calibration. Their values will be the #\n\ +# same in all messages until the camera is recalibrated. Note that #\n\ +# self-calibrating systems may \"recalibrate\" frequently. #\n\ +# #\n\ +# The internal parameters can be used to warp a raw (distorted) image #\n\ +# to: #\n\ +# 1. An undistorted image (requires D and K) #\n\ +# 2. A rectified image (requires D, K, R) #\n\ +# The projection matrix P projects 3D points into the rectified image.#\n\ +#######################################################################\n\ +\n\ +# The image dimensions with which the camera was calibrated. Normally\n\ +# this will be the full camera resolution in pixels.\n\ +uint32 height\n\ +uint32 width\n\ +\n\ +# The distortion model used. Supported models are listed in\n\ +# sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n\ +# simple model of radial and tangential distortion - is sufficient.\n\ +string distortion_model\n\ +\n\ +# The distortion parameters, size depending on the distortion model.\n\ +# For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\n\ +float64[] D\n\ +\n\ +# Intrinsic camera matrix for the raw (distorted) images.\n\ +# [fx 0 cx]\n\ +# K = [ 0 fy cy]\n\ +# [ 0 0 1]\n\ +# Projects 3D points in the camera coordinate frame to 2D pixel\n\ +# coordinates using the focal lengths (fx, fy) and principal point\n\ +# (cx, cy).\n\ +float64[9] K # 3x3 row-major matrix\n\ +\n\ +# Rectification matrix (stereo cameras only)\n\ +# A rotation matrix aligning the camera coordinate system to the ideal\n\ +# stereo image plane so that epipolar lines in both stereo images are\n\ +# parallel.\n\ +float64[9] R # 3x3 row-major matrix\n\ +\n\ +# Projection/camera matrix\n\ +# [fx' 0 cx' Tx]\n\ +# P = [ 0 fy' cy' Ty]\n\ +# [ 0 0 1 0]\n\ +# By convention, this matrix specifies the intrinsic (camera) matrix\n\ +# of the processed (rectified) image. That is, the left 3x3 portion\n\ +# is the normal camera intrinsic matrix for the rectified image.\n\ +# It projects 3D points in the camera coordinate frame to 2D pixel\n\ +# coordinates using the focal lengths (fx', fy') and principal point\n\ +# (cx', cy') - these may differ from the values in K.\n\ +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n\ +# also have R = the identity and P[1:3,1:3] = K.\n\ +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n\ +# position of the optical center of the second camera in the first\n\ +# camera's frame. We assume Tz = 0 so both cameras are in the same\n\ +# stereo image plane. The first camera always has Tx = Ty = 0. For\n\ +# the right (second) camera of a horizontal stereo pair, Ty = 0 and\n\ +# Tx = -fx' * B, where B is the baseline between the cameras.\n\ +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n\ +# the rectified image is given by:\n\ +# [u v w]' = P * [X Y Z 1]'\n\ +# x = u / w\n\ +# y = v / w\n\ +# This holds for both images of a stereo pair.\n\ +float64[12] P # 3x4 row-major matrix\n\ +\n\ +\n\ +#######################################################################\n\ +# Operational Parameters #\n\ +#######################################################################\n\ +# These define the image region actually captured by the camera #\n\ +# driver. Although they affect the geometry of the output image, they #\n\ +# may be changed freely without recalibrating the camera. #\n\ +#######################################################################\n\ +\n\ +# Binning refers here to any camera setting which combines rectangular\n\ +# neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n\ +# resolution of the output image to\n\ +# (width / binning_x) x (height / binning_y).\n\ +# The default values binning_x = binning_y = 0 is considered the same\n\ +# as binning_x = binning_y = 1 (no subsampling).\n\ +uint32 binning_x\n\ +uint32 binning_y\n\ +\n\ +# Region of interest (subwindow of full camera resolution), given in\n\ +# full resolution (unbinned) image coordinates. A particular ROI\n\ +# always denotes the same window of pixels on the camera sensor,\n\ +# regardless of binning settings.\n\ +# The default setting of roi (all values 0) is considered the same as\n\ +# full resolution (roi.width = width, roi.height = height).\n\ +RegionOfInterest roi\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: sensor_msgs/RegionOfInterest\n\ +# This message is used to specify a region of interest within an image.\n\ +#\n\ +# When used to specify the ROI setting of the camera when the image was\n\ +# taken, the height and width fields should either match the height and\n\ +# width fields for the associated image; or height = width = 0\n\ +# indicates that the full resolution image was captured.\n\ +\n\ +uint32 x_offset # Leftmost pixel of the ROI\n\ + # (0 if the ROI includes the left edge of the image)\n\ +uint32 y_offset # Topmost pixel of the ROI\n\ + # (0 if the ROI includes the top edge of the image)\n\ +uint32 height # Height of ROI\n\ +uint32 width # Width of ROI\n\ +\n\ +# True if a distinct rectified ROI should be calculated from the \"raw\"\n\ +# ROI in this message. Typically this should be False if the full image\n\ +# is captured (ROI not used), and True if a subwindow is captured (ROI\n\ +# used).\n\ +bool do_rectify\n\ +"; + } + + static const char* value(const ::sensor_msgs::CameraInfo_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::CameraInfo_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.height); + stream.next(m.width); + stream.next(m.distortion_model); + stream.next(m.D); + stream.next(m.K); + stream.next(m.R); + stream.next(m.P); + stream.next(m.binning_x); + stream.next(m.binning_y); + stream.next(m.roi); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct CameraInfo_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::CameraInfo_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::CameraInfo_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "height: "; + Printer::stream(s, indent + " ", v.height); + s << indent << "width: "; + Printer::stream(s, indent + " ", v.width); + s << indent << "distortion_model: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.distortion_model); + s << indent << "D[]" << std::endl; + for (size_t i = 0; i < v.D.size(); ++i) + { + s << indent << " D[" << i << "]: "; + Printer::stream(s, indent + " ", v.D[i]); + } + s << indent << "K[]" << std::endl; + for (size_t i = 0; i < v.K.size(); ++i) + { + s << indent << " K[" << i << "]: "; + Printer::stream(s, indent + " ", v.K[i]); + } + s << indent << "R[]" << std::endl; + for (size_t i = 0; i < v.R.size(); ++i) + { + s << indent << " R[" << i << "]: "; + Printer::stream(s, indent + " ", v.R[i]); + } + s << indent << "P[]" << std::endl; + for (size_t i = 0; i < v.P.size(); ++i) + { + s << indent << " P[" << i << "]: "; + Printer::stream(s, indent + " ", v.P[i]); + } + s << indent << "binning_x: "; + Printer::stream(s, indent + " ", v.binning_x); + s << indent << "binning_y: "; + Printer::stream(s, indent + " ", v.binning_y); + s << indent << "roi: "; + s << std::endl; + Printer< ::sensor_msgs::RegionOfInterest_ >::stream(s, indent + " ", v.roi); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_CAMERAINFO_H diff --git a/thirdparty/ros/include/sensor_msgs/ChannelFloat32.h b/thirdparty/ros/include/sensor_msgs/ChannelFloat32.h new file mode 100644 index 0000000..d599c7a --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/ChannelFloat32.h @@ -0,0 +1,222 @@ +// Generated by gencpp from file sensor_msgs/ChannelFloat32.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_CHANNELFLOAT32_H +#define SENSOR_MSGS_MESSAGE_CHANNELFLOAT32_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace sensor_msgs +{ +template +struct ChannelFloat32_ +{ + typedef ChannelFloat32_ Type; + + ChannelFloat32_() + : name() + , values() { + } + ChannelFloat32_(const ContainerAllocator& _alloc) + : name(_alloc) + , values(_alloc) { + (void)_alloc; + } + + + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _name_type; + _name_type name; + + typedef std::vector::other > _values_type; + _values_type values; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::ChannelFloat32_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::ChannelFloat32_ const> ConstPtr; + +}; // struct ChannelFloat32_ + +typedef ::sensor_msgs::ChannelFloat32_ > ChannelFloat32; + +typedef boost::shared_ptr< ::sensor_msgs::ChannelFloat32 > ChannelFloat32Ptr; +typedef boost::shared_ptr< ::sensor_msgs::ChannelFloat32 const> ChannelFloat32ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::ChannelFloat32_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::ChannelFloat32_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::ChannelFloat32_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::ChannelFloat32_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::ChannelFloat32_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::ChannelFloat32_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::ChannelFloat32_ > + : FalseType + { }; + +template +struct HasHeader< ::sensor_msgs::ChannelFloat32_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::sensor_msgs::ChannelFloat32_ > +{ + static const char* value() + { + return "3d40139cdd33dfedcb71ffeeeb42ae7f"; + } + + static const char* value(const ::sensor_msgs::ChannelFloat32_&) { return value(); } + static const uint64_t static_value1 = 0x3d40139cdd33dfedULL; + static const uint64_t static_value2 = 0xcb71ffeeeb42ae7fULL; +}; + +template +struct DataType< ::sensor_msgs::ChannelFloat32_ > +{ + static const char* value() + { + return "sensor_msgs/ChannelFloat32"; + } + + static const char* value(const ::sensor_msgs::ChannelFloat32_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::ChannelFloat32_ > +{ + static const char* value() + { + return "# This message is used by the PointCloud message to hold optional data\n\ +# associated with each point in the cloud. The length of the values\n\ +# array should be the same as the length of the points array in the\n\ +# PointCloud, and each value should be associated with the corresponding\n\ +# point.\n\ +\n\ +# Channel names in existing practice include:\n\ +# \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ +# This is opposite to usual conventions but remains for\n\ +# historical reasons. The newer PointCloud2 message has no\n\ +# such problem.\n\ +# \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ +# (R,G,B) values packed into the least significant 24 bits,\n\ +# in order.\n\ +# \"intensity\" - laser or pixel intensity.\n\ +# \"distance\"\n\ +\n\ +# The channel name should give semantics of the channel (e.g.\n\ +# \"intensity\" instead of \"value\").\n\ +string name\n\ +\n\ +# The values array should be 1-1 with the elements of the associated\n\ +# PointCloud.\n\ +float32[] values\n\ +"; + } + + static const char* value(const ::sensor_msgs::ChannelFloat32_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::ChannelFloat32_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.name); + stream.next(m.values); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct ChannelFloat32_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::ChannelFloat32_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::ChannelFloat32_& v) + { + s << indent << "name: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.name); + s << indent << "values[]" << std::endl; + for (size_t i = 0; i < v.values.size(); ++i) + { + s << indent << " values[" << i << "]: "; + Printer::stream(s, indent + " ", v.values[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_CHANNELFLOAT32_H diff --git a/thirdparty/ros/include/sensor_msgs/CompressedImage.h b/thirdparty/ros/include/sensor_msgs/CompressedImage.h new file mode 100644 index 0000000..ffed790 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/CompressedImage.h @@ -0,0 +1,239 @@ +// Generated by gencpp from file sensor_msgs/CompressedImage.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_COMPRESSEDIMAGE_H +#define SENSOR_MSGS_MESSAGE_COMPRESSEDIMAGE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct CompressedImage_ +{ + typedef CompressedImage_ Type; + + CompressedImage_() + : header() + , format() + , data() { + } + CompressedImage_(const ContainerAllocator& _alloc) + : header(_alloc) + , format(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _format_type; + _format_type format; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::CompressedImage_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::CompressedImage_ const> ConstPtr; + +}; // struct CompressedImage_ + +typedef ::sensor_msgs::CompressedImage_ > CompressedImage; + +typedef boost::shared_ptr< ::sensor_msgs::CompressedImage > CompressedImagePtr; +typedef boost::shared_ptr< ::sensor_msgs::CompressedImage const> CompressedImageConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::CompressedImage_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::CompressedImage_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::CompressedImage_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::CompressedImage_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::CompressedImage_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::CompressedImage_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::CompressedImage_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::CompressedImage_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::CompressedImage_ > +{ + static const char* value() + { + return "8f7a12909da2c9d3332d540a0977563f"; + } + + static const char* value(const ::sensor_msgs::CompressedImage_&) { return value(); } + static const uint64_t static_value1 = 0x8f7a12909da2c9d3ULL; + static const uint64_t static_value2 = 0x332d540a0977563fULL; +}; + +template +struct DataType< ::sensor_msgs::CompressedImage_ > +{ + static const char* value() + { + return "sensor_msgs/CompressedImage"; + } + + static const char* value(const ::sensor_msgs::CompressedImage_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::CompressedImage_ > +{ + static const char* value() + { + return "# This message contains a compressed image\n\ +\n\ +Header header # Header timestamp should be acquisition time of image\n\ + # Header frame_id should be optical frame of camera\n\ + # origin of frame should be optical center of cameara\n\ + # +x should point to the right in the image\n\ + # +y should point down in the image\n\ + # +z should point into to plane of the image\n\ +\n\ +string format # Specifies the format of the data\n\ + # Acceptable values:\n\ + # jpeg, png\n\ +uint8[] data # Compressed image buffer\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::CompressedImage_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::CompressedImage_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.format); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct CompressedImage_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::CompressedImage_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::CompressedImage_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "format: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.format); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_COMPRESSEDIMAGE_H diff --git a/thirdparty/ros/include/sensor_msgs/FluidPressure.h b/thirdparty/ros/include/sensor_msgs/FluidPressure.h new file mode 100644 index 0000000..98cec3f --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/FluidPressure.h @@ -0,0 +1,233 @@ +// Generated by gencpp from file sensor_msgs/FluidPressure.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_FLUIDPRESSURE_H +#define SENSOR_MSGS_MESSAGE_FLUIDPRESSURE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct FluidPressure_ +{ + typedef FluidPressure_ Type; + + FluidPressure_() + : header() + , fluid_pressure(0.0) + , variance(0.0) { + } + FluidPressure_(const ContainerAllocator& _alloc) + : header(_alloc) + , fluid_pressure(0.0) + , variance(0.0) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef double _fluid_pressure_type; + _fluid_pressure_type fluid_pressure; + + typedef double _variance_type; + _variance_type variance; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::FluidPressure_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::FluidPressure_ const> ConstPtr; + +}; // struct FluidPressure_ + +typedef ::sensor_msgs::FluidPressure_ > FluidPressure; + +typedef boost::shared_ptr< ::sensor_msgs::FluidPressure > FluidPressurePtr; +typedef boost::shared_ptr< ::sensor_msgs::FluidPressure const> FluidPressureConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::FluidPressure_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::FluidPressure_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::FluidPressure_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::FluidPressure_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::FluidPressure_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::FluidPressure_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::FluidPressure_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::FluidPressure_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::FluidPressure_ > +{ + static const char* value() + { + return "804dc5cea1c5306d6a2eb80b9833befe"; + } + + static const char* value(const ::sensor_msgs::FluidPressure_&) { return value(); } + static const uint64_t static_value1 = 0x804dc5cea1c5306dULL; + static const uint64_t static_value2 = 0x6a2eb80b9833befeULL; +}; + +template +struct DataType< ::sensor_msgs::FluidPressure_ > +{ + static const char* value() + { + return "sensor_msgs/FluidPressure"; + } + + static const char* value(const ::sensor_msgs::FluidPressure_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::FluidPressure_ > +{ + static const char* value() + { + return " # Single pressure reading. This message is appropriate for measuring the\n\ + # pressure inside of a fluid (air, water, etc). This also includes\n\ + # atmospheric or barometric pressure.\n\ +\n\ + # This message is not appropriate for force/pressure contact sensors.\n\ +\n\ + Header header # timestamp of the measurement\n\ + # frame_id is the location of the pressure sensor\n\ +\n\ + float64 fluid_pressure # Absolute pressure reading in Pascals.\n\ +\n\ + float64 variance # 0 is interpreted as variance unknown\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::FluidPressure_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::FluidPressure_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.fluid_pressure); + stream.next(m.variance); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct FluidPressure_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::FluidPressure_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::FluidPressure_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "fluid_pressure: "; + Printer::stream(s, indent + " ", v.fluid_pressure); + s << indent << "variance: "; + Printer::stream(s, indent + " ", v.variance); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_FLUIDPRESSURE_H diff --git a/thirdparty/ros/include/sensor_msgs/Illuminance.h b/thirdparty/ros/include/sensor_msgs/Illuminance.h new file mode 100644 index 0000000..ad98737 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/Illuminance.h @@ -0,0 +1,242 @@ +// Generated by gencpp from file sensor_msgs/Illuminance.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_ILLUMINANCE_H +#define SENSOR_MSGS_MESSAGE_ILLUMINANCE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct Illuminance_ +{ + typedef Illuminance_ Type; + + Illuminance_() + : header() + , illuminance(0.0) + , variance(0.0) { + } + Illuminance_(const ContainerAllocator& _alloc) + : header(_alloc) + , illuminance(0.0) + , variance(0.0) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef double _illuminance_type; + _illuminance_type illuminance; + + typedef double _variance_type; + _variance_type variance; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::Illuminance_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::Illuminance_ const> ConstPtr; + +}; // struct Illuminance_ + +typedef ::sensor_msgs::Illuminance_ > Illuminance; + +typedef boost::shared_ptr< ::sensor_msgs::Illuminance > IlluminancePtr; +typedef boost::shared_ptr< ::sensor_msgs::Illuminance const> IlluminanceConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Illuminance_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::Illuminance_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::Illuminance_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::Illuminance_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::Illuminance_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::Illuminance_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Illuminance_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Illuminance_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::Illuminance_ > +{ + static const char* value() + { + return "8cf5febb0952fca9d650c3d11a81a188"; + } + + static const char* value(const ::sensor_msgs::Illuminance_&) { return value(); } + static const uint64_t static_value1 = 0x8cf5febb0952fca9ULL; + static const uint64_t static_value2 = 0xd650c3d11a81a188ULL; +}; + +template +struct DataType< ::sensor_msgs::Illuminance_ > +{ + static const char* value() + { + return "sensor_msgs/Illuminance"; + } + + static const char* value(const ::sensor_msgs::Illuminance_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::Illuminance_ > +{ + static const char* value() + { + return " # Single photometric illuminance measurement. Light should be assumed to be\n\ + # measured along the sensor's x-axis (the area of detection is the y-z plane).\n\ + # The illuminance should have a 0 or positive value and be received with\n\ + # the sensor's +X axis pointing toward the light source.\n\ +\n\ + # Photometric illuminance is the measure of the human eye's sensitivity of the\n\ + # intensity of light encountering or passing through a surface.\n\ +\n\ + # All other Photometric and Radiometric measurements should\n\ + # not use this message.\n\ + # This message cannot represent:\n\ + # Luminous intensity (candela/light source output)\n\ + # Luminance (nits/light output per area)\n\ + # Irradiance (watt/area), etc.\n\ +\n\ + Header header # timestamp is the time the illuminance was measured\n\ + # frame_id is the location and direction of the reading\n\ +\n\ + float64 illuminance # Measurement of the Photometric Illuminance in Lux.\n\ +\n\ + float64 variance # 0 is interpreted as variance unknown\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::Illuminance_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::Illuminance_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.illuminance); + stream.next(m.variance); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Illuminance_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::Illuminance_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::Illuminance_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "illuminance: "; + Printer::stream(s, indent + " ", v.illuminance); + s << indent << "variance: "; + Printer::stream(s, indent + " ", v.variance); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_ILLUMINANCE_H diff --git a/thirdparty/ros/include/sensor_msgs/Image.h b/thirdparty/ros/include/sensor_msgs/Image.h new file mode 100644 index 0000000..e6f17df --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/Image.h @@ -0,0 +1,285 @@ +// Generated by gencpp from file sensor_msgs/Image.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_IMAGE_H +#define SENSOR_MSGS_MESSAGE_IMAGE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct Image_ +{ + typedef Image_ Type; + + Image_() + : header() + , height(0) + , width(0) + , encoding() + , is_bigendian(0) + , step(0) + , data() { + } + Image_(const ContainerAllocator& _alloc) + : header(_alloc) + , height(0) + , width(0) + , encoding(_alloc) + , is_bigendian(0) + , step(0) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef uint32_t _height_type; + _height_type height; + + typedef uint32_t _width_type; + _width_type width; + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _encoding_type; + _encoding_type encoding; + + typedef uint8_t _is_bigendian_type; + _is_bigendian_type is_bigendian; + + typedef uint32_t _step_type; + _step_type step; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::Image_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::Image_ const> ConstPtr; + +}; // struct Image_ + +typedef ::sensor_msgs::Image_ > Image; + +typedef boost::shared_ptr< ::sensor_msgs::Image > ImagePtr; +typedef boost::shared_ptr< ::sensor_msgs::Image const> ImageConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Image_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::Image_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::Image_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::Image_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::Image_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::Image_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Image_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Image_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::Image_ > +{ + static const char* value() + { + return "060021388200f6f0f447d0fcd9c64743"; + } + + static const char* value(const ::sensor_msgs::Image_&) { return value(); } + static const uint64_t static_value1 = 0x060021388200f6f0ULL; + static const uint64_t static_value2 = 0xf447d0fcd9c64743ULL; +}; + +template +struct DataType< ::sensor_msgs::Image_ > +{ + static const char* value() + { + return "sensor_msgs/Image"; + } + + static const char* value(const ::sensor_msgs::Image_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::Image_ > +{ + static const char* value() + { + return "# This message contains an uncompressed image\n\ +# (0, 0) is at top-left corner of image\n\ +#\n\ +\n\ +Header header # Header timestamp should be acquisition time of image\n\ + # Header frame_id should be optical frame of camera\n\ + # origin of frame should be optical center of cameara\n\ + # +x should point to the right in the image\n\ + # +y should point down in the image\n\ + # +z should point into to plane of the image\n\ + # If the frame_id here and the frame_id of the CameraInfo\n\ + # message associated with the image conflict\n\ + # the behavior is undefined\n\ +\n\ +uint32 height # image height, that is, number of rows\n\ +uint32 width # image width, that is, number of columns\n\ +\n\ +# The legal values for encoding are in file src/image_encodings.cpp\n\ +# If you want to standardize a new string format, join\n\ +# ros-users@lists.sourceforge.net and send an email proposing a new encoding.\n\ +\n\ +string encoding # Encoding of pixels -- channel meaning, ordering, size\n\ + # taken from the list of strings in include/sensor_msgs/image_encodings.h\n\ +\n\ +uint8 is_bigendian # is this data bigendian?\n\ +uint32 step # Full row length in bytes\n\ +uint8[] data # actual matrix data, size is (step * rows)\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::Image_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::Image_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.height); + stream.next(m.width); + stream.next(m.encoding); + stream.next(m.is_bigendian); + stream.next(m.step); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Image_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::Image_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::Image_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "height: "; + Printer::stream(s, indent + " ", v.height); + s << indent << "width: "; + Printer::stream(s, indent + " ", v.width); + s << indent << "encoding: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.encoding); + s << indent << "is_bigendian: "; + Printer::stream(s, indent + " ", v.is_bigendian); + s << indent << "step: "; + Printer::stream(s, indent + " ", v.step); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_IMAGE_H diff --git a/thirdparty/ros/include/sensor_msgs/Imu.h b/thirdparty/ros/include/sensor_msgs/Imu.h new file mode 100644 index 0000000..013043c --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/Imu.h @@ -0,0 +1,328 @@ +// Generated by gencpp from file sensor_msgs/Imu.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_IMU_H +#define SENSOR_MSGS_MESSAGE_IMU_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include + +namespace sensor_msgs +{ +template +struct Imu_ +{ + typedef Imu_ Type; + + Imu_() + : header() + , orientation() + , orientation_covariance() + , angular_velocity() + , angular_velocity_covariance() + , linear_acceleration() + , linear_acceleration_covariance() { + orientation_covariance.assign(0.0); + + angular_velocity_covariance.assign(0.0); + + linear_acceleration_covariance.assign(0.0); + } + Imu_(const ContainerAllocator& _alloc) + : header(_alloc) + , orientation(_alloc) + , orientation_covariance() + , angular_velocity(_alloc) + , angular_velocity_covariance() + , linear_acceleration(_alloc) + , linear_acceleration_covariance() { + (void)_alloc; + orientation_covariance.assign(0.0); + + angular_velocity_covariance.assign(0.0); + + linear_acceleration_covariance.assign(0.0); + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Quaternion_ _orientation_type; + _orientation_type orientation; + + typedef boost::array _orientation_covariance_type; + _orientation_covariance_type orientation_covariance; + + typedef ::geometry_msgs::Vector3_ _angular_velocity_type; + _angular_velocity_type angular_velocity; + + typedef boost::array _angular_velocity_covariance_type; + _angular_velocity_covariance_type angular_velocity_covariance; + + typedef ::geometry_msgs::Vector3_ _linear_acceleration_type; + _linear_acceleration_type linear_acceleration; + + typedef boost::array _linear_acceleration_covariance_type; + _linear_acceleration_covariance_type linear_acceleration_covariance; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::Imu_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::Imu_ const> ConstPtr; + +}; // struct Imu_ + +typedef ::sensor_msgs::Imu_ > Imu; + +typedef boost::shared_ptr< ::sensor_msgs::Imu > ImuPtr; +typedef boost::shared_ptr< ::sensor_msgs::Imu const> ImuConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Imu_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::Imu_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::Imu_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::Imu_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::Imu_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::Imu_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Imu_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Imu_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::Imu_ > +{ + static const char* value() + { + return "6a62c6daae103f4ff57a132d6f95cec2"; + } + + static const char* value(const ::sensor_msgs::Imu_&) { return value(); } + static const uint64_t static_value1 = 0x6a62c6daae103f4fULL; + static const uint64_t static_value2 = 0xf57a132d6f95cec2ULL; +}; + +template +struct DataType< ::sensor_msgs::Imu_ > +{ + static const char* value() + { + return "sensor_msgs/Imu"; + } + + static const char* value(const ::sensor_msgs::Imu_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::Imu_ > +{ + static const char* value() + { + return "# This is a message to hold data from an IMU (Inertial Measurement Unit)\n\ +#\n\ +# Accelerations should be in m/s^2 (not in g's), and rotational velocity should be in rad/sec\n\ +#\n\ +# If the covariance of the measurement is known, it should be filled in (if all you know is the \n\ +# variance of each measurement, e.g. from the datasheet, just put those along the diagonal)\n\ +# A covariance matrix of all zeros will be interpreted as \"covariance unknown\", and to use the\n\ +# data a covariance will have to be assumed or gotten from some other source\n\ +#\n\ +# If you have no estimate for one of the data elements (e.g. your IMU doesn't produce an orientation \n\ +# estimate), please set element 0 of the associated covariance matrix to -1\n\ +# If you are interpreting this message, please check for a value of -1 in the first element of each \n\ +# covariance matrix, and disregard the associated estimate.\n\ +\n\ +Header header\n\ +\n\ +geometry_msgs/Quaternion orientation\n\ +float64[9] orientation_covariance # Row major about x, y, z axes\n\ +\n\ +geometry_msgs/Vector3 angular_velocity\n\ +float64[9] angular_velocity_covariance # Row major about x, y, z axes\n\ +\n\ +geometry_msgs/Vector3 linear_acceleration\n\ +float64[9] linear_acceleration_covariance # Row major x, y z \n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::sensor_msgs::Imu_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::Imu_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.orientation); + stream.next(m.orientation_covariance); + stream.next(m.angular_velocity); + stream.next(m.angular_velocity_covariance); + stream.next(m.linear_acceleration); + stream.next(m.linear_acceleration_covariance); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Imu_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::Imu_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::Imu_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "orientation: "; + s << std::endl; + Printer< ::geometry_msgs::Quaternion_ >::stream(s, indent + " ", v.orientation); + s << indent << "orientation_covariance[]" << std::endl; + for (size_t i = 0; i < v.orientation_covariance.size(); ++i) + { + s << indent << " orientation_covariance[" << i << "]: "; + Printer::stream(s, indent + " ", v.orientation_covariance[i]); + } + s << indent << "angular_velocity: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.angular_velocity); + s << indent << "angular_velocity_covariance[]" << std::endl; + for (size_t i = 0; i < v.angular_velocity_covariance.size(); ++i) + { + s << indent << " angular_velocity_covariance[" << i << "]: "; + Printer::stream(s, indent + " ", v.angular_velocity_covariance[i]); + } + s << indent << "linear_acceleration: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.linear_acceleration); + s << indent << "linear_acceleration_covariance[]" << std::endl; + for (size_t i = 0; i < v.linear_acceleration_covariance.size(); ++i) + { + s << indent << " linear_acceleration_covariance[" << i << "]: "; + Printer::stream(s, indent + " ", v.linear_acceleration_covariance[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_IMU_H diff --git a/thirdparty/ros/include/sensor_msgs/JointState.h b/thirdparty/ros/include/sensor_msgs/JointState.h new file mode 100644 index 0000000..5aef117 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/JointState.h @@ -0,0 +1,280 @@ +// Generated by gencpp from file sensor_msgs/JointState.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_JOINTSTATE_H +#define SENSOR_MSGS_MESSAGE_JOINTSTATE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct JointState_ +{ + typedef JointState_ Type; + + JointState_() + : header() + , name() + , position() + , velocity() + , effort() { + } + JointState_(const ContainerAllocator& _alloc) + : header(_alloc) + , name(_alloc) + , position(_alloc) + , velocity(_alloc) + , effort(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef std::vector, typename ContainerAllocator::template rebind::other > , typename ContainerAllocator::template rebind, typename ContainerAllocator::template rebind::other > >::other > _name_type; + _name_type name; + + typedef std::vector::other > _position_type; + _position_type position; + + typedef std::vector::other > _velocity_type; + _velocity_type velocity; + + typedef std::vector::other > _effort_type; + _effort_type effort; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::JointState_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::JointState_ const> ConstPtr; + +}; // struct JointState_ + +typedef ::sensor_msgs::JointState_ > JointState; + +typedef boost::shared_ptr< ::sensor_msgs::JointState > JointStatePtr; +typedef boost::shared_ptr< ::sensor_msgs::JointState const> JointStateConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::JointState_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::JointState_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::JointState_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::JointState_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::JointState_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::JointState_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::JointState_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::JointState_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::JointState_ > +{ + static const char* value() + { + return "3066dcd76a6cfaef579bd0f34173e9fd"; + } + + static const char* value(const ::sensor_msgs::JointState_&) { return value(); } + static const uint64_t static_value1 = 0x3066dcd76a6cfaefULL; + static const uint64_t static_value2 = 0x579bd0f34173e9fdULL; +}; + +template +struct DataType< ::sensor_msgs::JointState_ > +{ + static const char* value() + { + return "sensor_msgs/JointState"; + } + + static const char* value(const ::sensor_msgs::JointState_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::JointState_ > +{ + static const char* value() + { + return "# This is a message that holds data to describe the state of a set of torque controlled joints. \n\ +#\n\ +# The state of each joint (revolute or prismatic) is defined by:\n\ +# * the position of the joint (rad or m),\n\ +# * the velocity of the joint (rad/s or m/s) and \n\ +# * the effort that is applied in the joint (Nm or N).\n\ +#\n\ +# Each joint is uniquely identified by its name\n\ +# The header specifies the time at which the joint states were recorded. All the joint states\n\ +# in one message have to be recorded at the same time.\n\ +#\n\ +# This message consists of a multiple arrays, one for each part of the joint state. \n\ +# The goal is to make each of the fields optional. When e.g. your joints have no\n\ +# effort associated with them, you can leave the effort array empty. \n\ +#\n\ +# All arrays in this message should have the same size, or be empty.\n\ +# This is the only way to uniquely associate the joint name with the correct\n\ +# states.\n\ +\n\ +\n\ +Header header\n\ +\n\ +string[] name\n\ +float64[] position\n\ +float64[] velocity\n\ +float64[] effort\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::JointState_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::JointState_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.name); + stream.next(m.position); + stream.next(m.velocity); + stream.next(m.effort); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct JointState_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::JointState_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::JointState_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "name[]" << std::endl; + for (size_t i = 0; i < v.name.size(); ++i) + { + s << indent << " name[" << i << "]: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.name[i]); + } + s << indent << "position[]" << std::endl; + for (size_t i = 0; i < v.position.size(); ++i) + { + s << indent << " position[" << i << "]: "; + Printer::stream(s, indent + " ", v.position[i]); + } + s << indent << "velocity[]" << std::endl; + for (size_t i = 0; i < v.velocity.size(); ++i) + { + s << indent << " velocity[" << i << "]: "; + Printer::stream(s, indent + " ", v.velocity[i]); + } + s << indent << "effort[]" << std::endl; + for (size_t i = 0; i < v.effort.size(); ++i) + { + s << indent << " effort[" << i << "]: "; + Printer::stream(s, indent + " ", v.effort[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_JOINTSTATE_H diff --git a/thirdparty/ros/include/sensor_msgs/Joy.h b/thirdparty/ros/include/sensor_msgs/Joy.h new file mode 100644 index 0000000..78e2754 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/Joy.h @@ -0,0 +1,234 @@ +// Generated by gencpp from file sensor_msgs/Joy.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_JOY_H +#define SENSOR_MSGS_MESSAGE_JOY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct Joy_ +{ + typedef Joy_ Type; + + Joy_() + : header() + , axes() + , buttons() { + } + Joy_(const ContainerAllocator& _alloc) + : header(_alloc) + , axes(_alloc) + , buttons(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef std::vector::other > _axes_type; + _axes_type axes; + + typedef std::vector::other > _buttons_type; + _buttons_type buttons; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::Joy_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::Joy_ const> ConstPtr; + +}; // struct Joy_ + +typedef ::sensor_msgs::Joy_ > Joy; + +typedef boost::shared_ptr< ::sensor_msgs::Joy > JoyPtr; +typedef boost::shared_ptr< ::sensor_msgs::Joy const> JoyConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Joy_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::Joy_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::Joy_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::Joy_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::Joy_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::Joy_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Joy_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Joy_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::Joy_ > +{ + static const char* value() + { + return "5a9ea5f83505693b71e785041e67a8bb"; + } + + static const char* value(const ::sensor_msgs::Joy_&) { return value(); } + static const uint64_t static_value1 = 0x5a9ea5f83505693bULL; + static const uint64_t static_value2 = 0x71e785041e67a8bbULL; +}; + +template +struct DataType< ::sensor_msgs::Joy_ > +{ + static const char* value() + { + return "sensor_msgs/Joy"; + } + + static const char* value(const ::sensor_msgs::Joy_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::Joy_ > +{ + static const char* value() + { + return "# Reports the state of a joysticks axes and buttons.\n\ +Header header # timestamp in the header is the time the data is received from the joystick\n\ +float32[] axes # the axes measurements from a joystick\n\ +int32[] buttons # the buttons measurements from a joystick \n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::Joy_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::Joy_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.axes); + stream.next(m.buttons); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Joy_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::Joy_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::Joy_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "axes[]" << std::endl; + for (size_t i = 0; i < v.axes.size(); ++i) + { + s << indent << " axes[" << i << "]: "; + Printer::stream(s, indent + " ", v.axes[i]); + } + s << indent << "buttons[]" << std::endl; + for (size_t i = 0; i < v.buttons.size(); ++i) + { + s << indent << " buttons[" << i << "]: "; + Printer::stream(s, indent + " ", v.buttons[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_JOY_H diff --git a/thirdparty/ros/include/sensor_msgs/JoyFeedback.h b/thirdparty/ros/include/sensor_msgs/JoyFeedback.h new file mode 100644 index 0000000..fa5df07 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/JoyFeedback.h @@ -0,0 +1,228 @@ +// Generated by gencpp from file sensor_msgs/JoyFeedback.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_JOYFEEDBACK_H +#define SENSOR_MSGS_MESSAGE_JOYFEEDBACK_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace sensor_msgs +{ +template +struct JoyFeedback_ +{ + typedef JoyFeedback_ Type; + + JoyFeedback_() + : type(0) + , id(0) + , intensity(0.0) { + } + JoyFeedback_(const ContainerAllocator& _alloc) + : type(0) + , id(0) + , intensity(0.0) { + (void)_alloc; + } + + + + typedef uint8_t _type_type; + _type_type type; + + typedef uint8_t _id_type; + _id_type id; + + typedef float _intensity_type; + _intensity_type intensity; + + + + enum { + TYPE_LED = 0u, + TYPE_RUMBLE = 1u, + TYPE_BUZZER = 2u, + }; + + + typedef boost::shared_ptr< ::sensor_msgs::JoyFeedback_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::JoyFeedback_ const> ConstPtr; + +}; // struct JoyFeedback_ + +typedef ::sensor_msgs::JoyFeedback_ > JoyFeedback; + +typedef boost::shared_ptr< ::sensor_msgs::JoyFeedback > JoyFeedbackPtr; +typedef boost::shared_ptr< ::sensor_msgs::JoyFeedback const> JoyFeedbackConstPtr; + +// constants requiring out of line definition + + + + + + + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::JoyFeedback_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::JoyFeedback_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::JoyFeedback_ > + : TrueType + { }; + +template +struct IsFixedSize< ::sensor_msgs::JoyFeedback_ const> + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::JoyFeedback_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::JoyFeedback_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::JoyFeedback_ > + : FalseType + { }; + +template +struct HasHeader< ::sensor_msgs::JoyFeedback_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::sensor_msgs::JoyFeedback_ > +{ + static const char* value() + { + return "f4dcd73460360d98f36e55ee7f2e46f1"; + } + + static const char* value(const ::sensor_msgs::JoyFeedback_&) { return value(); } + static const uint64_t static_value1 = 0xf4dcd73460360d98ULL; + static const uint64_t static_value2 = 0xf36e55ee7f2e46f1ULL; +}; + +template +struct DataType< ::sensor_msgs::JoyFeedback_ > +{ + static const char* value() + { + return "sensor_msgs/JoyFeedback"; + } + + static const char* value(const ::sensor_msgs::JoyFeedback_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::JoyFeedback_ > +{ + static const char* value() + { + return "# Declare of the type of feedback\n\ +uint8 TYPE_LED = 0\n\ +uint8 TYPE_RUMBLE = 1\n\ +uint8 TYPE_BUZZER = 2\n\ +\n\ +uint8 type\n\ +\n\ +# This will hold an id number for each type of each feedback.\n\ +# Example, the first led would be id=0, the second would be id=1\n\ +uint8 id\n\ +\n\ +# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is\n\ +# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on.\n\ +float32 intensity\n\ +\n\ +"; + } + + static const char* value(const ::sensor_msgs::JoyFeedback_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::JoyFeedback_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.type); + stream.next(m.id); + stream.next(m.intensity); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct JoyFeedback_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::JoyFeedback_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::JoyFeedback_& v) + { + s << indent << "type: "; + Printer::stream(s, indent + " ", v.type); + s << indent << "id: "; + Printer::stream(s, indent + " ", v.id); + s << indent << "intensity: "; + Printer::stream(s, indent + " ", v.intensity); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_JOYFEEDBACK_H diff --git a/thirdparty/ros/include/sensor_msgs/JoyFeedbackArray.h b/thirdparty/ros/include/sensor_msgs/JoyFeedbackArray.h new file mode 100644 index 0000000..5debaf4 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/JoyFeedbackArray.h @@ -0,0 +1,212 @@ +// Generated by gencpp from file sensor_msgs/JoyFeedbackArray.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_JOYFEEDBACKARRAY_H +#define SENSOR_MSGS_MESSAGE_JOYFEEDBACKARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct JoyFeedbackArray_ +{ + typedef JoyFeedbackArray_ Type; + + JoyFeedbackArray_() + : array() { + } + JoyFeedbackArray_(const ContainerAllocator& _alloc) + : array(_alloc) { + (void)_alloc; + } + + + + typedef std::vector< ::sensor_msgs::JoyFeedback_ , typename ContainerAllocator::template rebind< ::sensor_msgs::JoyFeedback_ >::other > _array_type; + _array_type array; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::JoyFeedbackArray_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::JoyFeedbackArray_ const> ConstPtr; + +}; // struct JoyFeedbackArray_ + +typedef ::sensor_msgs::JoyFeedbackArray_ > JoyFeedbackArray; + +typedef boost::shared_ptr< ::sensor_msgs::JoyFeedbackArray > JoyFeedbackArrayPtr; +typedef boost::shared_ptr< ::sensor_msgs::JoyFeedbackArray const> JoyFeedbackArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::JoyFeedbackArray_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::JoyFeedbackArray_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::JoyFeedbackArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::JoyFeedbackArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::JoyFeedbackArray_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::JoyFeedbackArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::JoyFeedbackArray_ > + : FalseType + { }; + +template +struct HasHeader< ::sensor_msgs::JoyFeedbackArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::sensor_msgs::JoyFeedbackArray_ > +{ + static const char* value() + { + return "cde5730a895b1fc4dee6f91b754b213d"; + } + + static const char* value(const ::sensor_msgs::JoyFeedbackArray_&) { return value(); } + static const uint64_t static_value1 = 0xcde5730a895b1fc4ULL; + static const uint64_t static_value2 = 0xdee6f91b754b213dULL; +}; + +template +struct DataType< ::sensor_msgs::JoyFeedbackArray_ > +{ + static const char* value() + { + return "sensor_msgs/JoyFeedbackArray"; + } + + static const char* value(const ::sensor_msgs::JoyFeedbackArray_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::JoyFeedbackArray_ > +{ + static const char* value() + { + return "# This message publishes values for multiple feedback at once. \n\ +JoyFeedback[] array\n\ +================================================================================\n\ +MSG: sensor_msgs/JoyFeedback\n\ +# Declare of the type of feedback\n\ +uint8 TYPE_LED = 0\n\ +uint8 TYPE_RUMBLE = 1\n\ +uint8 TYPE_BUZZER = 2\n\ +\n\ +uint8 type\n\ +\n\ +# This will hold an id number for each type of each feedback.\n\ +# Example, the first led would be id=0, the second would be id=1\n\ +uint8 id\n\ +\n\ +# Intensity of the feedback, from 0.0 to 1.0, inclusive. If device is\n\ +# actually binary, driver should treat 0<=x<0.5 as off, 0.5<=x<=1 as on.\n\ +float32 intensity\n\ +\n\ +"; + } + + static const char* value(const ::sensor_msgs::JoyFeedbackArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::JoyFeedbackArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.array); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct JoyFeedbackArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::JoyFeedbackArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::JoyFeedbackArray_& v) + { + s << indent << "array[]" << std::endl; + for (size_t i = 0; i < v.array.size(); ++i) + { + s << indent << " array[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::sensor_msgs::JoyFeedback_ >::stream(s, indent + " ", v.array[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_JOYFEEDBACKARRAY_H diff --git a/thirdparty/ros/include/sensor_msgs/LaserEcho.h b/thirdparty/ros/include/sensor_msgs/LaserEcho.h new file mode 100644 index 0000000..fb5dfdb --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/LaserEcho.h @@ -0,0 +1,195 @@ +// Generated by gencpp from file sensor_msgs/LaserEcho.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_LASERECHO_H +#define SENSOR_MSGS_MESSAGE_LASERECHO_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace sensor_msgs +{ +template +struct LaserEcho_ +{ + typedef LaserEcho_ Type; + + LaserEcho_() + : echoes() { + } + LaserEcho_(const ContainerAllocator& _alloc) + : echoes(_alloc) { + (void)_alloc; + } + + + + typedef std::vector::other > _echoes_type; + _echoes_type echoes; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::LaserEcho_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::LaserEcho_ const> ConstPtr; + +}; // struct LaserEcho_ + +typedef ::sensor_msgs::LaserEcho_ > LaserEcho; + +typedef boost::shared_ptr< ::sensor_msgs::LaserEcho > LaserEchoPtr; +typedef boost::shared_ptr< ::sensor_msgs::LaserEcho const> LaserEchoConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::LaserEcho_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::LaserEcho_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::LaserEcho_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::LaserEcho_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::LaserEcho_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::LaserEcho_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::LaserEcho_ > + : FalseType + { }; + +template +struct HasHeader< ::sensor_msgs::LaserEcho_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::sensor_msgs::LaserEcho_ > +{ + static const char* value() + { + return "8bc5ae449b200fba4d552b4225586696"; + } + + static const char* value(const ::sensor_msgs::LaserEcho_&) { return value(); } + static const uint64_t static_value1 = 0x8bc5ae449b200fbaULL; + static const uint64_t static_value2 = 0x4d552b4225586696ULL; +}; + +template +struct DataType< ::sensor_msgs::LaserEcho_ > +{ + static const char* value() + { + return "sensor_msgs/LaserEcho"; + } + + static const char* value(const ::sensor_msgs::LaserEcho_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::LaserEcho_ > +{ + static const char* value() + { + return "# This message is a submessage of MultiEchoLaserScan and is not intended\n\ +# to be used separately.\n\ +\n\ +float32[] echoes # Multiple values of ranges or intensities.\n\ + # Each array represents data from the same angle increment.\n\ +"; + } + + static const char* value(const ::sensor_msgs::LaserEcho_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::LaserEcho_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.echoes); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct LaserEcho_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::LaserEcho_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::LaserEcho_& v) + { + s << indent << "echoes[]" << std::endl; + for (size_t i = 0; i < v.echoes.size(); ++i) + { + s << indent << " echoes[" << i << "]: "; + Printer::stream(s, indent + " ", v.echoes[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_LASERECHO_H diff --git a/thirdparty/ros/include/sensor_msgs/LaserScan.h b/thirdparty/ros/include/sensor_msgs/LaserScan.h new file mode 100644 index 0000000..ca9dd5d --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/LaserScan.h @@ -0,0 +1,315 @@ +// Generated by gencpp from file sensor_msgs/LaserScan.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_LASERSCAN_H +#define SENSOR_MSGS_MESSAGE_LASERSCAN_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct LaserScan_ +{ + typedef LaserScan_ Type; + + LaserScan_() + : header() + , angle_min(0.0) + , angle_max(0.0) + , angle_increment(0.0) + , time_increment(0.0) + , scan_time(0.0) + , range_min(0.0) + , range_max(0.0) + , ranges() + , intensities() { + } + LaserScan_(const ContainerAllocator& _alloc) + : header(_alloc) + , angle_min(0.0) + , angle_max(0.0) + , angle_increment(0.0) + , time_increment(0.0) + , scan_time(0.0) + , range_min(0.0) + , range_max(0.0) + , ranges(_alloc) + , intensities(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef float _angle_min_type; + _angle_min_type angle_min; + + typedef float _angle_max_type; + _angle_max_type angle_max; + + typedef float _angle_increment_type; + _angle_increment_type angle_increment; + + typedef float _time_increment_type; + _time_increment_type time_increment; + + typedef float _scan_time_type; + _scan_time_type scan_time; + + typedef float _range_min_type; + _range_min_type range_min; + + typedef float _range_max_type; + _range_max_type range_max; + + typedef std::vector::other > _ranges_type; + _ranges_type ranges; + + typedef std::vector::other > _intensities_type; + _intensities_type intensities; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::LaserScan_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::LaserScan_ const> ConstPtr; + +}; // struct LaserScan_ + +typedef ::sensor_msgs::LaserScan_ > LaserScan; + +typedef boost::shared_ptr< ::sensor_msgs::LaserScan > LaserScanPtr; +typedef boost::shared_ptr< ::sensor_msgs::LaserScan const> LaserScanConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::LaserScan_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::LaserScan_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::LaserScan_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::LaserScan_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::LaserScan_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::LaserScan_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::LaserScan_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::LaserScan_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::LaserScan_ > +{ + static const char* value() + { + return "90c7ef2dc6895d81024acba2ac42f369"; + } + + static const char* value(const ::sensor_msgs::LaserScan_&) { return value(); } + static const uint64_t static_value1 = 0x90c7ef2dc6895d81ULL; + static const uint64_t static_value2 = 0x024acba2ac42f369ULL; +}; + +template +struct DataType< ::sensor_msgs::LaserScan_ > +{ + static const char* value() + { + return "sensor_msgs/LaserScan"; + } + + static const char* value(const ::sensor_msgs::LaserScan_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::LaserScan_ > +{ + static const char* value() + { + return "# Single scan from a planar laser range-finder\n\ +#\n\ +# If you have another ranging device with different behavior (e.g. a sonar\n\ +# array), please find or create a different message, since applications\n\ +# will make fairly laser-specific assumptions about this data\n\ +\n\ +Header header # timestamp in the header is the acquisition time of \n\ + # the first ray in the scan.\n\ + #\n\ + # in frame frame_id, angles are measured around \n\ + # the positive Z axis (counterclockwise, if Z is up)\n\ + # with zero angle being forward along the x axis\n\ + \n\ +float32 angle_min # start angle of the scan [rad]\n\ +float32 angle_max # end angle of the scan [rad]\n\ +float32 angle_increment # angular distance between measurements [rad]\n\ +\n\ +float32 time_increment # time between measurements [seconds] - if your scanner\n\ + # is moving, this will be used in interpolating position\n\ + # of 3d points\n\ +float32 scan_time # time between scans [seconds]\n\ +\n\ +float32 range_min # minimum range value [m]\n\ +float32 range_max # maximum range value [m]\n\ +\n\ +float32[] ranges # range data [m] (Note: values < range_min or > range_max should be discarded)\n\ +float32[] intensities # intensity data [device-specific units]. If your\n\ + # device does not provide intensities, please leave\n\ + # the array empty.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::LaserScan_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::LaserScan_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.angle_min); + stream.next(m.angle_max); + stream.next(m.angle_increment); + stream.next(m.time_increment); + stream.next(m.scan_time); + stream.next(m.range_min); + stream.next(m.range_max); + stream.next(m.ranges); + stream.next(m.intensities); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct LaserScan_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::LaserScan_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::LaserScan_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "angle_min: "; + Printer::stream(s, indent + " ", v.angle_min); + s << indent << "angle_max: "; + Printer::stream(s, indent + " ", v.angle_max); + s << indent << "angle_increment: "; + Printer::stream(s, indent + " ", v.angle_increment); + s << indent << "time_increment: "; + Printer::stream(s, indent + " ", v.time_increment); + s << indent << "scan_time: "; + Printer::stream(s, indent + " ", v.scan_time); + s << indent << "range_min: "; + Printer::stream(s, indent + " ", v.range_min); + s << indent << "range_max: "; + Printer::stream(s, indent + " ", v.range_max); + s << indent << "ranges[]" << std::endl; + for (size_t i = 0; i < v.ranges.size(); ++i) + { + s << indent << " ranges[" << i << "]: "; + Printer::stream(s, indent + " ", v.ranges[i]); + } + s << indent << "intensities[]" << std::endl; + for (size_t i = 0; i < v.intensities.size(); ++i) + { + s << indent << " intensities[" << i << "]: "; + Printer::stream(s, indent + " ", v.intensities[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_LASERSCAN_H diff --git a/thirdparty/ros/include/sensor_msgs/MagneticField.h b/thirdparty/ros/include/sensor_msgs/MagneticField.h new file mode 100644 index 0000000..a1b1106 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/MagneticField.h @@ -0,0 +1,264 @@ +// Generated by gencpp from file sensor_msgs/MagneticField.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_MAGNETICFIELD_H +#define SENSOR_MSGS_MESSAGE_MAGNETICFIELD_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace sensor_msgs +{ +template +struct MagneticField_ +{ + typedef MagneticField_ Type; + + MagneticField_() + : header() + , magnetic_field() + , magnetic_field_covariance() { + magnetic_field_covariance.assign(0.0); + } + MagneticField_(const ContainerAllocator& _alloc) + : header(_alloc) + , magnetic_field(_alloc) + , magnetic_field_covariance() { + (void)_alloc; + magnetic_field_covariance.assign(0.0); + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::geometry_msgs::Vector3_ _magnetic_field_type; + _magnetic_field_type magnetic_field; + + typedef boost::array _magnetic_field_covariance_type; + _magnetic_field_covariance_type magnetic_field_covariance; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::MagneticField_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::MagneticField_ const> ConstPtr; + +}; // struct MagneticField_ + +typedef ::sensor_msgs::MagneticField_ > MagneticField; + +typedef boost::shared_ptr< ::sensor_msgs::MagneticField > MagneticFieldPtr; +typedef boost::shared_ptr< ::sensor_msgs::MagneticField const> MagneticFieldConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::MagneticField_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::MagneticField_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::MagneticField_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::MagneticField_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::MagneticField_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::MagneticField_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::MagneticField_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::MagneticField_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::MagneticField_ > +{ + static const char* value() + { + return "2f3b0b43eed0c9501de0fa3ff89a45aa"; + } + + static const char* value(const ::sensor_msgs::MagneticField_&) { return value(); } + static const uint64_t static_value1 = 0x2f3b0b43eed0c950ULL; + static const uint64_t static_value2 = 0x1de0fa3ff89a45aaULL; +}; + +template +struct DataType< ::sensor_msgs::MagneticField_ > +{ + static const char* value() + { + return "sensor_msgs/MagneticField"; + } + + static const char* value(const ::sensor_msgs::MagneticField_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::MagneticField_ > +{ + static const char* value() + { + return " # Measurement of the Magnetic Field vector at a specific location.\n\ +\n\ + # If the covariance of the measurement is known, it should be filled in\n\ + # (if all you know is the variance of each measurement, e.g. from the datasheet,\n\ + #just put those along the diagonal)\n\ + # A covariance matrix of all zeros will be interpreted as \"covariance unknown\",\n\ + # and to use the data a covariance will have to be assumed or gotten from some\n\ + # other source\n\ +\n\ +\n\ + Header header # timestamp is the time the\n\ + # field was measured\n\ + # frame_id is the location and orientation\n\ + # of the field measurement\n\ +\n\ + geometry_msgs/Vector3 magnetic_field # x, y, and z components of the\n\ + # field vector in Tesla\n\ + # If your sensor does not output 3 axes,\n\ + # put NaNs in the components not reported.\n\ +\n\ + float64[9] magnetic_field_covariance # Row major about x, y, z axes\n\ + # 0 is interpreted as variance unknown\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +"; + } + + static const char* value(const ::sensor_msgs::MagneticField_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::MagneticField_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.magnetic_field); + stream.next(m.magnetic_field_covariance); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct MagneticField_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::MagneticField_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::MagneticField_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "magnetic_field: "; + s << std::endl; + Printer< ::geometry_msgs::Vector3_ >::stream(s, indent + " ", v.magnetic_field); + s << indent << "magnetic_field_covariance[]" << std::endl; + for (size_t i = 0; i < v.magnetic_field_covariance.size(); ++i) + { + s << indent << " magnetic_field_covariance[" << i << "]: "; + Printer::stream(s, indent + " ", v.magnetic_field_covariance[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_MAGNETICFIELD_H diff --git a/thirdparty/ros/include/sensor_msgs/MultiDOFJointState.h b/thirdparty/ros/include/sensor_msgs/MultiDOFJointState.h new file mode 100644 index 0000000..7bec3f7 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/MultiDOFJointState.h @@ -0,0 +1,330 @@ +// Generated by gencpp from file sensor_msgs/MultiDOFJointState.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_MULTIDOFJOINTSTATE_H +#define SENSOR_MSGS_MESSAGE_MULTIDOFJOINTSTATE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include + +namespace sensor_msgs +{ +template +struct MultiDOFJointState_ +{ + typedef MultiDOFJointState_ Type; + + MultiDOFJointState_() + : header() + , joint_names() + , transforms() + , twist() + , wrench() { + } + MultiDOFJointState_(const ContainerAllocator& _alloc) + : header(_alloc) + , joint_names(_alloc) + , transforms(_alloc) + , twist(_alloc) + , wrench(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef std::vector, typename ContainerAllocator::template rebind::other > , typename ContainerAllocator::template rebind, typename ContainerAllocator::template rebind::other > >::other > _joint_names_type; + _joint_names_type joint_names; + + typedef std::vector< ::geometry_msgs::Transform_ , typename ContainerAllocator::template rebind< ::geometry_msgs::Transform_ >::other > _transforms_type; + _transforms_type transforms; + + typedef std::vector< ::geometry_msgs::Twist_ , typename ContainerAllocator::template rebind< ::geometry_msgs::Twist_ >::other > _twist_type; + _twist_type twist; + + typedef std::vector< ::geometry_msgs::Wrench_ , typename ContainerAllocator::template rebind< ::geometry_msgs::Wrench_ >::other > _wrench_type; + _wrench_type wrench; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::MultiDOFJointState_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::MultiDOFJointState_ const> ConstPtr; + +}; // struct MultiDOFJointState_ + +typedef ::sensor_msgs::MultiDOFJointState_ > MultiDOFJointState; + +typedef boost::shared_ptr< ::sensor_msgs::MultiDOFJointState > MultiDOFJointStatePtr; +typedef boost::shared_ptr< ::sensor_msgs::MultiDOFJointState const> MultiDOFJointStateConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::MultiDOFJointState_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::MultiDOFJointState_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::MultiDOFJointState_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::MultiDOFJointState_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::MultiDOFJointState_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::MultiDOFJointState_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::MultiDOFJointState_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::MultiDOFJointState_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::MultiDOFJointState_ > +{ + static const char* value() + { + return "690f272f0640d2631c305eeb8301e59d"; + } + + static const char* value(const ::sensor_msgs::MultiDOFJointState_&) { return value(); } + static const uint64_t static_value1 = 0x690f272f0640d263ULL; + static const uint64_t static_value2 = 0x1c305eeb8301e59dULL; +}; + +template +struct DataType< ::sensor_msgs::MultiDOFJointState_ > +{ + static const char* value() + { + return "sensor_msgs/MultiDOFJointState"; + } + + static const char* value(const ::sensor_msgs::MultiDOFJointState_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::MultiDOFJointState_ > +{ + static const char* value() + { + return "# Representation of state for joints with multiple degrees of freedom, \n\ +# following the structure of JointState.\n\ +#\n\ +# It is assumed that a joint in a system corresponds to a transform that gets applied \n\ +# along the kinematic chain. For example, a planar joint (as in URDF) is 3DOF (x, y, yaw)\n\ +# and those 3DOF can be expressed as a transformation matrix, and that transformation\n\ +# matrix can be converted back to (x, y, yaw)\n\ +#\n\ +# Each joint is uniquely identified by its name\n\ +# The header specifies the time at which the joint states were recorded. All the joint states\n\ +# in one message have to be recorded at the same time.\n\ +#\n\ +# This message consists of a multiple arrays, one for each part of the joint state. \n\ +# The goal is to make each of the fields optional. When e.g. your joints have no\n\ +# wrench associated with them, you can leave the wrench array empty. \n\ +#\n\ +# All arrays in this message should have the same size, or be empty.\n\ +# This is the only way to uniquely associate the joint name with the correct\n\ +# states.\n\ +\n\ +Header header\n\ +\n\ +string[] joint_names\n\ +geometry_msgs/Transform[] transforms\n\ +geometry_msgs/Twist[] twist\n\ +geometry_msgs/Wrench[] wrench\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Transform\n\ +# This represents the transform between two coordinate frames in free space.\n\ +\n\ +Vector3 translation\n\ +Quaternion rotation\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Vector3\n\ +# This represents a vector in free space. \n\ +# It is only meant to represent a direction. Therefore, it does not\n\ +# make sense to apply a translation to it (e.g., when applying a \n\ +# generic rigid transformation to a Vector3, tf2 will only apply the\n\ +# rotation). If you want your data to be translatable too, use the\n\ +# geometry_msgs/Point message instead.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +================================================================================\n\ +MSG: geometry_msgs/Quaternion\n\ +# This represents an orientation in free space in quaternion form.\n\ +\n\ +float64 x\n\ +float64 y\n\ +float64 z\n\ +float64 w\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Twist\n\ +# This expresses velocity in free space broken into its linear and angular parts.\n\ +Vector3 linear\n\ +Vector3 angular\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Wrench\n\ +# This represents force in free space, separated into\n\ +# its linear and angular parts.\n\ +Vector3 force\n\ +Vector3 torque\n\ +"; + } + + static const char* value(const ::sensor_msgs::MultiDOFJointState_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::MultiDOFJointState_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.joint_names); + stream.next(m.transforms); + stream.next(m.twist); + stream.next(m.wrench); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct MultiDOFJointState_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::MultiDOFJointState_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::MultiDOFJointState_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "joint_names[]" << std::endl; + for (size_t i = 0; i < v.joint_names.size(); ++i) + { + s << indent << " joint_names[" << i << "]: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.joint_names[i]); + } + s << indent << "transforms[]" << std::endl; + for (size_t i = 0; i < v.transforms.size(); ++i) + { + s << indent << " transforms[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::geometry_msgs::Transform_ >::stream(s, indent + " ", v.transforms[i]); + } + s << indent << "twist[]" << std::endl; + for (size_t i = 0; i < v.twist.size(); ++i) + { + s << indent << " twist[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::geometry_msgs::Twist_ >::stream(s, indent + " ", v.twist[i]); + } + s << indent << "wrench[]" << std::endl; + for (size_t i = 0; i < v.wrench.size(); ++i) + { + s << indent << " wrench[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::geometry_msgs::Wrench_ >::stream(s, indent + " ", v.wrench[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_MULTIDOFJOINTSTATE_H diff --git a/thirdparty/ros/include/sensor_msgs/MultiEchoLaserScan.h b/thirdparty/ros/include/sensor_msgs/MultiEchoLaserScan.h new file mode 100644 index 0000000..4e03934 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/MultiEchoLaserScan.h @@ -0,0 +1,330 @@ +// Generated by gencpp from file sensor_msgs/MultiEchoLaserScan.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_MULTIECHOLASERSCAN_H +#define SENSOR_MSGS_MESSAGE_MULTIECHOLASERSCAN_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +namespace sensor_msgs +{ +template +struct MultiEchoLaserScan_ +{ + typedef MultiEchoLaserScan_ Type; + + MultiEchoLaserScan_() + : header() + , angle_min(0.0) + , angle_max(0.0) + , angle_increment(0.0) + , time_increment(0.0) + , scan_time(0.0) + , range_min(0.0) + , range_max(0.0) + , ranges() + , intensities() { + } + MultiEchoLaserScan_(const ContainerAllocator& _alloc) + : header(_alloc) + , angle_min(0.0) + , angle_max(0.0) + , angle_increment(0.0) + , time_increment(0.0) + , scan_time(0.0) + , range_min(0.0) + , range_max(0.0) + , ranges(_alloc) + , intensities(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef float _angle_min_type; + _angle_min_type angle_min; + + typedef float _angle_max_type; + _angle_max_type angle_max; + + typedef float _angle_increment_type; + _angle_increment_type angle_increment; + + typedef float _time_increment_type; + _time_increment_type time_increment; + + typedef float _scan_time_type; + _scan_time_type scan_time; + + typedef float _range_min_type; + _range_min_type range_min; + + typedef float _range_max_type; + _range_max_type range_max; + + typedef std::vector< ::sensor_msgs::LaserEcho_ , typename ContainerAllocator::template rebind< ::sensor_msgs::LaserEcho_ >::other > _ranges_type; + _ranges_type ranges; + + typedef std::vector< ::sensor_msgs::LaserEcho_ , typename ContainerAllocator::template rebind< ::sensor_msgs::LaserEcho_ >::other > _intensities_type; + _intensities_type intensities; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan_ const> ConstPtr; + +}; // struct MultiEchoLaserScan_ + +typedef ::sensor_msgs::MultiEchoLaserScan_ > MultiEchoLaserScan; + +typedef boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan > MultiEchoLaserScanPtr; +typedef boost::shared_ptr< ::sensor_msgs::MultiEchoLaserScan const> MultiEchoLaserScanConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::MultiEchoLaserScan_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::MultiEchoLaserScan_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::MultiEchoLaserScan_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::MultiEchoLaserScan_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::MultiEchoLaserScan_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::MultiEchoLaserScan_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::MultiEchoLaserScan_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::MultiEchoLaserScan_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::MultiEchoLaserScan_ > +{ + static const char* value() + { + return "6fefb0c6da89d7c8abe4b339f5c2f8fb"; + } + + static const char* value(const ::sensor_msgs::MultiEchoLaserScan_&) { return value(); } + static const uint64_t static_value1 = 0x6fefb0c6da89d7c8ULL; + static const uint64_t static_value2 = 0xabe4b339f5c2f8fbULL; +}; + +template +struct DataType< ::sensor_msgs::MultiEchoLaserScan_ > +{ + static const char* value() + { + return "sensor_msgs/MultiEchoLaserScan"; + } + + static const char* value(const ::sensor_msgs::MultiEchoLaserScan_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::MultiEchoLaserScan_ > +{ + static const char* value() + { + return "# Single scan from a multi-echo planar laser range-finder\n\ +#\n\ +# If you have another ranging device with different behavior (e.g. a sonar\n\ +# array), please find or create a different message, since applications\n\ +# will make fairly laser-specific assumptions about this data\n\ +\n\ +Header header # timestamp in the header is the acquisition time of \n\ + # the first ray in the scan.\n\ + #\n\ + # in frame frame_id, angles are measured around \n\ + # the positive Z axis (counterclockwise, if Z is up)\n\ + # with zero angle being forward along the x axis\n\ + \n\ +float32 angle_min # start angle of the scan [rad]\n\ +float32 angle_max # end angle of the scan [rad]\n\ +float32 angle_increment # angular distance between measurements [rad]\n\ +\n\ +float32 time_increment # time between measurements [seconds] - if your scanner\n\ + # is moving, this will be used in interpolating position\n\ + # of 3d points\n\ +float32 scan_time # time between scans [seconds]\n\ +\n\ +float32 range_min # minimum range value [m]\n\ +float32 range_max # maximum range value [m]\n\ +\n\ +LaserEcho[] ranges # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded)\n\ + # +Inf measurements are out of range\n\ + # -Inf measurements are too close to determine exact distance.\n\ +LaserEcho[] intensities # intensity data [device-specific units]. If your\n\ + # device does not provide intensities, please leave\n\ + # the array empty.\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: sensor_msgs/LaserEcho\n\ +# This message is a submessage of MultiEchoLaserScan and is not intended\n\ +# to be used separately.\n\ +\n\ +float32[] echoes # Multiple values of ranges or intensities.\n\ + # Each array represents data from the same angle increment.\n\ +"; + } + + static const char* value(const ::sensor_msgs::MultiEchoLaserScan_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::MultiEchoLaserScan_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.angle_min); + stream.next(m.angle_max); + stream.next(m.angle_increment); + stream.next(m.time_increment); + stream.next(m.scan_time); + stream.next(m.range_min); + stream.next(m.range_max); + stream.next(m.ranges); + stream.next(m.intensities); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct MultiEchoLaserScan_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::MultiEchoLaserScan_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::MultiEchoLaserScan_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "angle_min: "; + Printer::stream(s, indent + " ", v.angle_min); + s << indent << "angle_max: "; + Printer::stream(s, indent + " ", v.angle_max); + s << indent << "angle_increment: "; + Printer::stream(s, indent + " ", v.angle_increment); + s << indent << "time_increment: "; + Printer::stream(s, indent + " ", v.time_increment); + s << indent << "scan_time: "; + Printer::stream(s, indent + " ", v.scan_time); + s << indent << "range_min: "; + Printer::stream(s, indent + " ", v.range_min); + s << indent << "range_max: "; + Printer::stream(s, indent + " ", v.range_max); + s << indent << "ranges[]" << std::endl; + for (size_t i = 0; i < v.ranges.size(); ++i) + { + s << indent << " ranges[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::sensor_msgs::LaserEcho_ >::stream(s, indent + " ", v.ranges[i]); + } + s << indent << "intensities[]" << std::endl; + for (size_t i = 0; i < v.intensities.size(); ++i) + { + s << indent << " intensities[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::sensor_msgs::LaserEcho_ >::stream(s, indent + " ", v.intensities[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_MULTIECHOLASERSCAN_H diff --git a/thirdparty/ros/include/sensor_msgs/NavSatFix.h b/thirdparty/ros/include/sensor_msgs/NavSatFix.h new file mode 100644 index 0000000..019c09f --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/NavSatFix.h @@ -0,0 +1,347 @@ +// Generated by gencpp from file sensor_msgs/NavSatFix.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_NAVSATFIX_H +#define SENSOR_MSGS_MESSAGE_NAVSATFIX_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace sensor_msgs +{ +template +struct NavSatFix_ +{ + typedef NavSatFix_ Type; + + NavSatFix_() + : header() + , status() + , latitude(0.0) + , longitude(0.0) + , altitude(0.0) + , position_covariance() + , position_covariance_type(0) { + position_covariance.assign(0.0); + } + NavSatFix_(const ContainerAllocator& _alloc) + : header(_alloc) + , status(_alloc) + , latitude(0.0) + , longitude(0.0) + , altitude(0.0) + , position_covariance() + , position_covariance_type(0) { + (void)_alloc; + position_covariance.assign(0.0); + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ::sensor_msgs::NavSatStatus_ _status_type; + _status_type status; + + typedef double _latitude_type; + _latitude_type latitude; + + typedef double _longitude_type; + _longitude_type longitude; + + typedef double _altitude_type; + _altitude_type altitude; + + typedef boost::array _position_covariance_type; + _position_covariance_type position_covariance; + + typedef uint8_t _position_covariance_type_type; + _position_covariance_type_type position_covariance_type; + + + + enum { + COVARIANCE_TYPE_UNKNOWN = 0u, + COVARIANCE_TYPE_APPROXIMATED = 1u, + COVARIANCE_TYPE_DIAGONAL_KNOWN = 2u, + COVARIANCE_TYPE_KNOWN = 3u, + }; + + + typedef boost::shared_ptr< ::sensor_msgs::NavSatFix_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::NavSatFix_ const> ConstPtr; + +}; // struct NavSatFix_ + +typedef ::sensor_msgs::NavSatFix_ > NavSatFix; + +typedef boost::shared_ptr< ::sensor_msgs::NavSatFix > NavSatFixPtr; +typedef boost::shared_ptr< ::sensor_msgs::NavSatFix const> NavSatFixConstPtr; + +// constants requiring out of line definition + + + + + + + + + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::NavSatFix_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::NavSatFix_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::NavSatFix_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::NavSatFix_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::NavSatFix_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::NavSatFix_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::NavSatFix_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::NavSatFix_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::NavSatFix_ > +{ + static const char* value() + { + return "2d3a8cd499b9b4a0249fb98fd05cfa48"; + } + + static const char* value(const ::sensor_msgs::NavSatFix_&) { return value(); } + static const uint64_t static_value1 = 0x2d3a8cd499b9b4a0ULL; + static const uint64_t static_value2 = 0x249fb98fd05cfa48ULL; +}; + +template +struct DataType< ::sensor_msgs::NavSatFix_ > +{ + static const char* value() + { + return "sensor_msgs/NavSatFix"; + } + + static const char* value(const ::sensor_msgs::NavSatFix_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::NavSatFix_ > +{ + static const char* value() + { + return "# Navigation Satellite fix for any Global Navigation Satellite System\n\ +#\n\ +# Specified using the WGS 84 reference ellipsoid\n\ +\n\ +# header.stamp specifies the ROS time for this measurement (the\n\ +# corresponding satellite time may be reported using the\n\ +# sensor_msgs/TimeReference message).\n\ +#\n\ +# header.frame_id is the frame of reference reported by the satellite\n\ +# receiver, usually the location of the antenna. This is a\n\ +# Euclidean frame relative to the vehicle, not a reference\n\ +# ellipsoid.\n\ +Header header\n\ +\n\ +# satellite fix status information\n\ +NavSatStatus status\n\ +\n\ +# Latitude [degrees]. Positive is north of equator; negative is south.\n\ +float64 latitude\n\ +\n\ +# Longitude [degrees]. Positive is east of prime meridian; negative is west.\n\ +float64 longitude\n\ +\n\ +# Altitude [m]. Positive is above the WGS 84 ellipsoid\n\ +# (quiet NaN if no altitude is available).\n\ +float64 altitude\n\ +\n\ +# Position covariance [m^2] defined relative to a tangential plane\n\ +# through the reported position. The components are East, North, and\n\ +# Up (ENU), in row-major order.\n\ +#\n\ +# Beware: this coordinate system exhibits singularities at the poles.\n\ +\n\ +float64[9] position_covariance\n\ +\n\ +# If the covariance of the fix is known, fill it in completely. If the\n\ +# GPS receiver provides the variance of each measurement, put them\n\ +# along the diagonal. If only Dilution of Precision is available,\n\ +# estimate an approximate covariance from that.\n\ +\n\ +uint8 COVARIANCE_TYPE_UNKNOWN = 0\n\ +uint8 COVARIANCE_TYPE_APPROXIMATED = 1\n\ +uint8 COVARIANCE_TYPE_DIAGONAL_KNOWN = 2\n\ +uint8 COVARIANCE_TYPE_KNOWN = 3\n\ +\n\ +uint8 position_covariance_type\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: sensor_msgs/NavSatStatus\n\ +# Navigation Satellite fix status for any Global Navigation Satellite System\n\ +\n\ +# Whether to output an augmented fix is determined by both the fix\n\ +# type and the last time differential corrections were received. A\n\ +# fix is valid when status >= STATUS_FIX.\n\ +\n\ +int8 STATUS_NO_FIX = -1 # unable to fix position\n\ +int8 STATUS_FIX = 0 # unaugmented fix\n\ +int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation\n\ +int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation\n\ +\n\ +int8 status\n\ +\n\ +# Bits defining which Global Navigation Satellite System signals were\n\ +# used by the receiver.\n\ +\n\ +uint16 SERVICE_GPS = 1\n\ +uint16 SERVICE_GLONASS = 2\n\ +uint16 SERVICE_COMPASS = 4 # includes BeiDou.\n\ +uint16 SERVICE_GALILEO = 8\n\ +\n\ +uint16 service\n\ +"; + } + + static const char* value(const ::sensor_msgs::NavSatFix_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::NavSatFix_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.status); + stream.next(m.latitude); + stream.next(m.longitude); + stream.next(m.altitude); + stream.next(m.position_covariance); + stream.next(m.position_covariance_type); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct NavSatFix_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::NavSatFix_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::NavSatFix_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "status: "; + s << std::endl; + Printer< ::sensor_msgs::NavSatStatus_ >::stream(s, indent + " ", v.status); + s << indent << "latitude: "; + Printer::stream(s, indent + " ", v.latitude); + s << indent << "longitude: "; + Printer::stream(s, indent + " ", v.longitude); + s << indent << "altitude: "; + Printer::stream(s, indent + " ", v.altitude); + s << indent << "position_covariance[]" << std::endl; + for (size_t i = 0; i < v.position_covariance.size(); ++i) + { + s << indent << " position_covariance[" << i << "]: "; + Printer::stream(s, indent + " ", v.position_covariance[i]); + } + s << indent << "position_covariance_type: "; + Printer::stream(s, indent + " ", v.position_covariance_type); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_NAVSATFIX_H diff --git a/thirdparty/ros/include/sensor_msgs/NavSatStatus.h b/thirdparty/ros/include/sensor_msgs/NavSatStatus.h new file mode 100644 index 0000000..4702295 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/NavSatStatus.h @@ -0,0 +1,242 @@ +// Generated by gencpp from file sensor_msgs/NavSatStatus.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_NAVSATSTATUS_H +#define SENSOR_MSGS_MESSAGE_NAVSATSTATUS_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace sensor_msgs +{ +template +struct NavSatStatus_ +{ + typedef NavSatStatus_ Type; + + NavSatStatus_() + : status(0) + , service(0) { + } + NavSatStatus_(const ContainerAllocator& _alloc) + : status(0) + , service(0) { + (void)_alloc; + } + + + + typedef int8_t _status_type; + _status_type status; + + typedef uint16_t _service_type; + _service_type service; + + + + enum { + STATUS_NO_FIX = -1, + STATUS_FIX = 0, + STATUS_SBAS_FIX = 1, + STATUS_GBAS_FIX = 2, + SERVICE_GPS = 1u, + SERVICE_GLONASS = 2u, + SERVICE_COMPASS = 4u, + SERVICE_GALILEO = 8u, + }; + + + typedef boost::shared_ptr< ::sensor_msgs::NavSatStatus_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::NavSatStatus_ const> ConstPtr; + +}; // struct NavSatStatus_ + +typedef ::sensor_msgs::NavSatStatus_ > NavSatStatus; + +typedef boost::shared_ptr< ::sensor_msgs::NavSatStatus > NavSatStatusPtr; +typedef boost::shared_ptr< ::sensor_msgs::NavSatStatus const> NavSatStatusConstPtr; + +// constants requiring out of line definition + + + + + + + + + + + + + + + + + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::NavSatStatus_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::NavSatStatus_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::NavSatStatus_ > + : TrueType + { }; + +template +struct IsFixedSize< ::sensor_msgs::NavSatStatus_ const> + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::NavSatStatus_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::NavSatStatus_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::NavSatStatus_ > + : FalseType + { }; + +template +struct HasHeader< ::sensor_msgs::NavSatStatus_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::sensor_msgs::NavSatStatus_ > +{ + static const char* value() + { + return "331cdbddfa4bc96ffc3b9ad98900a54c"; + } + + static const char* value(const ::sensor_msgs::NavSatStatus_&) { return value(); } + static const uint64_t static_value1 = 0x331cdbddfa4bc96fULL; + static const uint64_t static_value2 = 0xfc3b9ad98900a54cULL; +}; + +template +struct DataType< ::sensor_msgs::NavSatStatus_ > +{ + static const char* value() + { + return "sensor_msgs/NavSatStatus"; + } + + static const char* value(const ::sensor_msgs::NavSatStatus_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::NavSatStatus_ > +{ + static const char* value() + { + return "# Navigation Satellite fix status for any Global Navigation Satellite System\n\ +\n\ +# Whether to output an augmented fix is determined by both the fix\n\ +# type and the last time differential corrections were received. A\n\ +# fix is valid when status >= STATUS_FIX.\n\ +\n\ +int8 STATUS_NO_FIX = -1 # unable to fix position\n\ +int8 STATUS_FIX = 0 # unaugmented fix\n\ +int8 STATUS_SBAS_FIX = 1 # with satellite-based augmentation\n\ +int8 STATUS_GBAS_FIX = 2 # with ground-based augmentation\n\ +\n\ +int8 status\n\ +\n\ +# Bits defining which Global Navigation Satellite System signals were\n\ +# used by the receiver.\n\ +\n\ +uint16 SERVICE_GPS = 1\n\ +uint16 SERVICE_GLONASS = 2\n\ +uint16 SERVICE_COMPASS = 4 # includes BeiDou.\n\ +uint16 SERVICE_GALILEO = 8\n\ +\n\ +uint16 service\n\ +"; + } + + static const char* value(const ::sensor_msgs::NavSatStatus_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::NavSatStatus_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.status); + stream.next(m.service); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct NavSatStatus_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::NavSatStatus_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::NavSatStatus_& v) + { + s << indent << "status: "; + Printer::stream(s, indent + " ", v.status); + s << indent << "service: "; + Printer::stream(s, indent + " ", v.service); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_NAVSATSTATUS_H diff --git a/thirdparty/ros/include/sensor_msgs/PointCloud.h b/thirdparty/ros/include/sensor_msgs/PointCloud.h new file mode 100644 index 0000000..654cdbd --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/PointCloud.h @@ -0,0 +1,290 @@ +// Generated by gencpp from file sensor_msgs/PointCloud.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_POINTCLOUD_H +#define SENSOR_MSGS_MESSAGE_POINTCLOUD_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include + +namespace sensor_msgs +{ +template +struct PointCloud_ +{ + typedef PointCloud_ Type; + + PointCloud_() + : header() + , points() + , channels() { + } + PointCloud_(const ContainerAllocator& _alloc) + : header(_alloc) + , points(_alloc) + , channels(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef std::vector< ::geometry_msgs::Point32_ , typename ContainerAllocator::template rebind< ::geometry_msgs::Point32_ >::other > _points_type; + _points_type points; + + typedef std::vector< ::sensor_msgs::ChannelFloat32_ , typename ContainerAllocator::template rebind< ::sensor_msgs::ChannelFloat32_ >::other > _channels_type; + _channels_type channels; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::PointCloud_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::PointCloud_ const> ConstPtr; + +}; // struct PointCloud_ + +typedef ::sensor_msgs::PointCloud_ > PointCloud; + +typedef boost::shared_ptr< ::sensor_msgs::PointCloud > PointCloudPtr; +typedef boost::shared_ptr< ::sensor_msgs::PointCloud const> PointCloudConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::PointCloud_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::PointCloud_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::PointCloud_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::PointCloud_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::PointCloud_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::PointCloud_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::PointCloud_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::PointCloud_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::PointCloud_ > +{ + static const char* value() + { + return "d8e9c3f5afbdd8a130fd1d2763945fca"; + } + + static const char* value(const ::sensor_msgs::PointCloud_&) { return value(); } + static const uint64_t static_value1 = 0xd8e9c3f5afbdd8a1ULL; + static const uint64_t static_value2 = 0x30fd1d2763945fcaULL; +}; + +template +struct DataType< ::sensor_msgs::PointCloud_ > +{ + static const char* value() + { + return "sensor_msgs/PointCloud"; + } + + static const char* value(const ::sensor_msgs::PointCloud_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::PointCloud_ > +{ + static const char* value() + { + return "# This message holds a collection of 3d points, plus optional additional\n\ +# information about each point.\n\ +\n\ +# Time of sensor data acquisition, coordinate frame ID.\n\ +Header header\n\ +\n\ +# Array of 3d points. Each Point32 should be interpreted as a 3d point\n\ +# in the frame given in the header.\n\ +geometry_msgs/Point32[] points\n\ +\n\ +# Each channel should have the same number of elements as points array,\n\ +# and the data in each channel should correspond 1:1 with each point.\n\ +# Channel names in common practice are listed in ChannelFloat32.msg.\n\ +ChannelFloat32[] channels\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: geometry_msgs/Point32\n\ +# This contains the position of a point in free space(with 32 bits of precision).\n\ +# It is recommeded to use Point wherever possible instead of Point32. \n\ +# \n\ +# This recommendation is to promote interoperability. \n\ +#\n\ +# This message is designed to take up less space when sending\n\ +# lots of points at once, as in the case of a PointCloud. \n\ +\n\ +float32 x\n\ +float32 y\n\ +float32 z\n\ +================================================================================\n\ +MSG: sensor_msgs/ChannelFloat32\n\ +# This message is used by the PointCloud message to hold optional data\n\ +# associated with each point in the cloud. The length of the values\n\ +# array should be the same as the length of the points array in the\n\ +# PointCloud, and each value should be associated with the corresponding\n\ +# point.\n\ +\n\ +# Channel names in existing practice include:\n\ +# \"u\", \"v\" - row and column (respectively) in the left stereo image.\n\ +# This is opposite to usual conventions but remains for\n\ +# historical reasons. The newer PointCloud2 message has no\n\ +# such problem.\n\ +# \"rgb\" - For point clouds produced by color stereo cameras. uint8\n\ +# (R,G,B) values packed into the least significant 24 bits,\n\ +# in order.\n\ +# \"intensity\" - laser or pixel intensity.\n\ +# \"distance\"\n\ +\n\ +# The channel name should give semantics of the channel (e.g.\n\ +# \"intensity\" instead of \"value\").\n\ +string name\n\ +\n\ +# The values array should be 1-1 with the elements of the associated\n\ +# PointCloud.\n\ +float32[] values\n\ +"; + } + + static const char* value(const ::sensor_msgs::PointCloud_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::PointCloud_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.points); + stream.next(m.channels); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct PointCloud_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::PointCloud_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::PointCloud_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "points[]" << std::endl; + for (size_t i = 0; i < v.points.size(); ++i) + { + s << indent << " points[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::geometry_msgs::Point32_ >::stream(s, indent + " ", v.points[i]); + } + s << indent << "channels[]" << std::endl; + for (size_t i = 0; i < v.channels.size(); ++i) + { + s << indent << " channels[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::sensor_msgs::ChannelFloat32_ >::stream(s, indent + " ", v.channels[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_POINTCLOUD_H diff --git a/thirdparty/ros/include/sensor_msgs/PointCloud2.h b/thirdparty/ros/include/sensor_msgs/PointCloud2.h new file mode 100644 index 0000000..cf95217 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/PointCloud2.h @@ -0,0 +1,326 @@ +// Generated by gencpp from file sensor_msgs/PointCloud2.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_POINTCLOUD2_H +#define SENSOR_MSGS_MESSAGE_POINTCLOUD2_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include +#include + +namespace sensor_msgs +{ +template +struct PointCloud2_ +{ + typedef PointCloud2_ Type; + + PointCloud2_() + : header() + , height(0) + , width(0) + , fields() + , is_bigendian(false) + , point_step(0) + , row_step(0) + , data() + , is_dense(false) { + } + PointCloud2_(const ContainerAllocator& _alloc) + : header(_alloc) + , height(0) + , width(0) + , fields(_alloc) + , is_bigendian(false) + , point_step(0) + , row_step(0) + , data(_alloc) + , is_dense(false) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef uint32_t _height_type; + _height_type height; + + typedef uint32_t _width_type; + _width_type width; + + typedef std::vector< ::sensor_msgs::PointField_ , typename ContainerAllocator::template rebind< ::sensor_msgs::PointField_ >::other > _fields_type; + _fields_type fields; + + typedef uint8_t _is_bigendian_type; + _is_bigendian_type is_bigendian; + + typedef uint32_t _point_step_type; + _point_step_type point_step; + + typedef uint32_t _row_step_type; + _row_step_type row_step; + + typedef std::vector::other > _data_type; + _data_type data; + + typedef uint8_t _is_dense_type; + _is_dense_type is_dense; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::PointCloud2_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::PointCloud2_ const> ConstPtr; + +}; // struct PointCloud2_ + +typedef ::sensor_msgs::PointCloud2_ > PointCloud2; + +typedef boost::shared_ptr< ::sensor_msgs::PointCloud2 > PointCloud2Ptr; +typedef boost::shared_ptr< ::sensor_msgs::PointCloud2 const> PointCloud2ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::PointCloud2_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::PointCloud2_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::PointCloud2_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::PointCloud2_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::PointCloud2_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::PointCloud2_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::PointCloud2_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::PointCloud2_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::PointCloud2_ > +{ + static const char* value() + { + return "1158d486dd51d683ce2f1be655c3c181"; + } + + static const char* value(const ::sensor_msgs::PointCloud2_&) { return value(); } + static const uint64_t static_value1 = 0x1158d486dd51d683ULL; + static const uint64_t static_value2 = 0xce2f1be655c3c181ULL; +}; + +template +struct DataType< ::sensor_msgs::PointCloud2_ > +{ + static const char* value() + { + return "sensor_msgs/PointCloud2"; + } + + static const char* value(const ::sensor_msgs::PointCloud2_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::PointCloud2_ > +{ + static const char* value() + { + return "# This message holds a collection of N-dimensional points, which may\n\ +# contain additional information such as normals, intensity, etc. The\n\ +# point data is stored as a binary blob, its layout described by the\n\ +# contents of the \"fields\" array.\n\ +\n\ +# The point cloud data may be organized 2d (image-like) or 1d\n\ +# (unordered). Point clouds organized as 2d images may be produced by\n\ +# camera depth sensors such as stereo or time-of-flight.\n\ +\n\ +# Time of sensor data acquisition, and the coordinate frame ID (for 3d\n\ +# points).\n\ +Header header\n\ +\n\ +# 2D structure of the point cloud. If the cloud is unordered, height is\n\ +# 1 and width is the length of the point cloud.\n\ +uint32 height\n\ +uint32 width\n\ +\n\ +# Describes the channels and their layout in the binary data blob.\n\ +PointField[] fields\n\ +\n\ +bool is_bigendian # Is this data bigendian?\n\ +uint32 point_step # Length of a point in bytes\n\ +uint32 row_step # Length of a row in bytes\n\ +uint8[] data # Actual point data, size is (row_step*height)\n\ +\n\ +bool is_dense # True if there are no invalid points\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: sensor_msgs/PointField\n\ +# This message holds the description of one point entry in the\n\ +# PointCloud2 message format.\n\ +uint8 INT8 = 1\n\ +uint8 UINT8 = 2\n\ +uint8 INT16 = 3\n\ +uint8 UINT16 = 4\n\ +uint8 INT32 = 5\n\ +uint8 UINT32 = 6\n\ +uint8 FLOAT32 = 7\n\ +uint8 FLOAT64 = 8\n\ +\n\ +string name # Name of field\n\ +uint32 offset # Offset from start of point struct\n\ +uint8 datatype # Datatype enumeration, see above\n\ +uint32 count # How many elements in the field\n\ +"; + } + + static const char* value(const ::sensor_msgs::PointCloud2_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::PointCloud2_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.height); + stream.next(m.width); + stream.next(m.fields); + stream.next(m.is_bigendian); + stream.next(m.point_step); + stream.next(m.row_step); + stream.next(m.data); + stream.next(m.is_dense); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct PointCloud2_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::PointCloud2_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::PointCloud2_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "height: "; + Printer::stream(s, indent + " ", v.height); + s << indent << "width: "; + Printer::stream(s, indent + " ", v.width); + s << indent << "fields[]" << std::endl; + for (size_t i = 0; i < v.fields.size(); ++i) + { + s << indent << " fields[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::sensor_msgs::PointField_ >::stream(s, indent + " ", v.fields[i]); + } + s << indent << "is_bigendian: "; + Printer::stream(s, indent + " ", v.is_bigendian); + s << indent << "point_step: "; + Printer::stream(s, indent + " ", v.point_step); + s << indent << "row_step: "; + Printer::stream(s, indent + " ", v.row_step); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + s << indent << "is_dense: "; + Printer::stream(s, indent + " ", v.is_dense); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_POINTCLOUD2_H diff --git a/thirdparty/ros/include/sensor_msgs/PointField.h b/thirdparty/ros/include/sensor_msgs/PointField.h new file mode 100644 index 0000000..4d55f27 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/PointField.h @@ -0,0 +1,251 @@ +// Generated by gencpp from file sensor_msgs/PointField.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_POINTFIELD_H +#define SENSOR_MSGS_MESSAGE_POINTFIELD_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace sensor_msgs +{ +template +struct PointField_ +{ + typedef PointField_ Type; + + PointField_() + : name() + , offset(0) + , datatype(0) + , count(0) { + } + PointField_(const ContainerAllocator& _alloc) + : name(_alloc) + , offset(0) + , datatype(0) + , count(0) { + (void)_alloc; + } + + + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _name_type; + _name_type name; + + typedef uint32_t _offset_type; + _offset_type offset; + + typedef uint8_t _datatype_type; + _datatype_type datatype; + + typedef uint32_t _count_type; + _count_type count; + + + + enum { + INT8 = 1u, + UINT8 = 2u, + INT16 = 3u, + UINT16 = 4u, + INT32 = 5u, + UINT32 = 6u, + FLOAT32 = 7u, + FLOAT64 = 8u, + }; + + + typedef boost::shared_ptr< ::sensor_msgs::PointField_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::PointField_ const> ConstPtr; + +}; // struct PointField_ + +typedef ::sensor_msgs::PointField_ > PointField; + +typedef boost::shared_ptr< ::sensor_msgs::PointField > PointFieldPtr; +typedef boost::shared_ptr< ::sensor_msgs::PointField const> PointFieldConstPtr; + +// constants requiring out of line definition + + + + + + + + + + + + + + + + + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::PointField_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::PointField_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::PointField_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::PointField_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::PointField_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::PointField_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::PointField_ > + : FalseType + { }; + +template +struct HasHeader< ::sensor_msgs::PointField_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::sensor_msgs::PointField_ > +{ + static const char* value() + { + return "268eacb2962780ceac86cbd17e328150"; + } + + static const char* value(const ::sensor_msgs::PointField_&) { return value(); } + static const uint64_t static_value1 = 0x268eacb2962780ceULL; + static const uint64_t static_value2 = 0xac86cbd17e328150ULL; +}; + +template +struct DataType< ::sensor_msgs::PointField_ > +{ + static const char* value() + { + return "sensor_msgs/PointField"; + } + + static const char* value(const ::sensor_msgs::PointField_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::PointField_ > +{ + static const char* value() + { + return "# This message holds the description of one point entry in the\n\ +# PointCloud2 message format.\n\ +uint8 INT8 = 1\n\ +uint8 UINT8 = 2\n\ +uint8 INT16 = 3\n\ +uint8 UINT16 = 4\n\ +uint8 INT32 = 5\n\ +uint8 UINT32 = 6\n\ +uint8 FLOAT32 = 7\n\ +uint8 FLOAT64 = 8\n\ +\n\ +string name # Name of field\n\ +uint32 offset # Offset from start of point struct\n\ +uint8 datatype # Datatype enumeration, see above\n\ +uint32 count # How many elements in the field\n\ +"; + } + + static const char* value(const ::sensor_msgs::PointField_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::PointField_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.name); + stream.next(m.offset); + stream.next(m.datatype); + stream.next(m.count); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct PointField_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::PointField_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::PointField_& v) + { + s << indent << "name: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.name); + s << indent << "offset: "; + Printer::stream(s, indent + " ", v.offset); + s << indent << "datatype: "; + Printer::stream(s, indent + " ", v.datatype); + s << indent << "count: "; + Printer::stream(s, indent + " ", v.count); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_POINTFIELD_H diff --git a/thirdparty/ros/include/sensor_msgs/Range.h b/thirdparty/ros/include/sensor_msgs/Range.h new file mode 100644 index 0000000..d46e6ac --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/Range.h @@ -0,0 +1,293 @@ +// Generated by gencpp from file sensor_msgs/Range.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_RANGE_H +#define SENSOR_MSGS_MESSAGE_RANGE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct Range_ +{ + typedef Range_ Type; + + Range_() + : header() + , radiation_type(0) + , field_of_view(0.0) + , min_range(0.0) + , max_range(0.0) + , range(0.0) { + } + Range_(const ContainerAllocator& _alloc) + : header(_alloc) + , radiation_type(0) + , field_of_view(0.0) + , min_range(0.0) + , max_range(0.0) + , range(0.0) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef uint8_t _radiation_type_type; + _radiation_type_type radiation_type; + + typedef float _field_of_view_type; + _field_of_view_type field_of_view; + + typedef float _min_range_type; + _min_range_type min_range; + + typedef float _max_range_type; + _max_range_type max_range; + + typedef float _range_type; + _range_type range; + + + + enum { + ULTRASOUND = 0u, + INFRARED = 1u, + }; + + + typedef boost::shared_ptr< ::sensor_msgs::Range_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::Range_ const> ConstPtr; + +}; // struct Range_ + +typedef ::sensor_msgs::Range_ > Range; + +typedef boost::shared_ptr< ::sensor_msgs::Range > RangePtr; +typedef boost::shared_ptr< ::sensor_msgs::Range const> RangeConstPtr; + +// constants requiring out of line definition + + + + + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Range_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::Range_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::Range_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::Range_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::Range_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::Range_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Range_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Range_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::Range_ > +{ + static const char* value() + { + return "c005c34273dc426c67a020a87bc24148"; + } + + static const char* value(const ::sensor_msgs::Range_&) { return value(); } + static const uint64_t static_value1 = 0xc005c34273dc426cULL; + static const uint64_t static_value2 = 0x67a020a87bc24148ULL; +}; + +template +struct DataType< ::sensor_msgs::Range_ > +{ + static const char* value() + { + return "sensor_msgs/Range"; + } + + static const char* value(const ::sensor_msgs::Range_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::Range_ > +{ + static const char* value() + { + return "# Single range reading from an active ranger that emits energy and reports\n\ +# one range reading that is valid along an arc at the distance measured. \n\ +# This message is not appropriate for laser scanners. See the LaserScan\n\ +# message if you are working with a laser scanner.\n\ +\n\ +# This message also can represent a fixed-distance (binary) ranger. This\n\ +# sensor will have min_range===max_range===distance of detection.\n\ +# These sensors follow REP 117 and will output -Inf if the object is detected\n\ +# and +Inf if the object is outside of the detection range.\n\ +\n\ +Header header # timestamp in the header is the time the ranger\n\ + # returned the distance reading\n\ +\n\ +# Radiation type enums\n\ +# If you want a value added to this list, send an email to the ros-users list\n\ +uint8 ULTRASOUND=0\n\ +uint8 INFRARED=1\n\ +\n\ +uint8 radiation_type # the type of radiation used by the sensor\n\ + # (sound, IR, etc) [enum]\n\ +\n\ +float32 field_of_view # the size of the arc that the distance reading is\n\ + # valid for [rad]\n\ + # the object causing the range reading may have\n\ + # been anywhere within -field_of_view/2 and\n\ + # field_of_view/2 at the measured range. \n\ + # 0 angle corresponds to the x-axis of the sensor.\n\ +\n\ +float32 min_range # minimum range value [m]\n\ +float32 max_range # maximum range value [m]\n\ + # Fixed distance rangers require min_range==max_range\n\ +\n\ +float32 range # range data [m]\n\ + # (Note: values < range_min or > range_max\n\ + # should be discarded)\n\ + # Fixed distance rangers only output -Inf or +Inf.\n\ + # -Inf represents a detection within fixed distance.\n\ + # (Detection too close to the sensor to quantify)\n\ + # +Inf represents no detection within the fixed distance.\n\ + # (Object out of range)\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::Range_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::Range_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.radiation_type); + stream.next(m.field_of_view); + stream.next(m.min_range); + stream.next(m.max_range); + stream.next(m.range); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Range_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::Range_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::Range_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "radiation_type: "; + Printer::stream(s, indent + " ", v.radiation_type); + s << indent << "field_of_view: "; + Printer::stream(s, indent + " ", v.field_of_view); + s << indent << "min_range: "; + Printer::stream(s, indent + " ", v.min_range); + s << indent << "max_range: "; + Printer::stream(s, indent + " ", v.max_range); + s << indent << "range: "; + Printer::stream(s, indent + " ", v.range); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_RANGE_H diff --git a/thirdparty/ros/include/sensor_msgs/RegionOfInterest.h b/thirdparty/ros/include/sensor_msgs/RegionOfInterest.h new file mode 100644 index 0000000..53facfa --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/RegionOfInterest.h @@ -0,0 +1,237 @@ +// Generated by gencpp from file sensor_msgs/RegionOfInterest.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_REGIONOFINTEREST_H +#define SENSOR_MSGS_MESSAGE_REGIONOFINTEREST_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace sensor_msgs +{ +template +struct RegionOfInterest_ +{ + typedef RegionOfInterest_ Type; + + RegionOfInterest_() + : x_offset(0) + , y_offset(0) + , height(0) + , width(0) + , do_rectify(false) { + } + RegionOfInterest_(const ContainerAllocator& _alloc) + : x_offset(0) + , y_offset(0) + , height(0) + , width(0) + , do_rectify(false) { + (void)_alloc; + } + + + + typedef uint32_t _x_offset_type; + _x_offset_type x_offset; + + typedef uint32_t _y_offset_type; + _y_offset_type y_offset; + + typedef uint32_t _height_type; + _height_type height; + + typedef uint32_t _width_type; + _width_type width; + + typedef uint8_t _do_rectify_type; + _do_rectify_type do_rectify; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::RegionOfInterest_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::RegionOfInterest_ const> ConstPtr; + +}; // struct RegionOfInterest_ + +typedef ::sensor_msgs::RegionOfInterest_ > RegionOfInterest; + +typedef boost::shared_ptr< ::sensor_msgs::RegionOfInterest > RegionOfInterestPtr; +typedef boost::shared_ptr< ::sensor_msgs::RegionOfInterest const> RegionOfInterestConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::RegionOfInterest_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::RegionOfInterest_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::RegionOfInterest_ > + : TrueType + { }; + +template +struct IsFixedSize< ::sensor_msgs::RegionOfInterest_ const> + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::RegionOfInterest_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::RegionOfInterest_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::RegionOfInterest_ > + : FalseType + { }; + +template +struct HasHeader< ::sensor_msgs::RegionOfInterest_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::sensor_msgs::RegionOfInterest_ > +{ + static const char* value() + { + return "bdb633039d588fcccb441a4d43ccfe09"; + } + + static const char* value(const ::sensor_msgs::RegionOfInterest_&) { return value(); } + static const uint64_t static_value1 = 0xbdb633039d588fccULL; + static const uint64_t static_value2 = 0xcb441a4d43ccfe09ULL; +}; + +template +struct DataType< ::sensor_msgs::RegionOfInterest_ > +{ + static const char* value() + { + return "sensor_msgs/RegionOfInterest"; + } + + static const char* value(const ::sensor_msgs::RegionOfInterest_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::RegionOfInterest_ > +{ + static const char* value() + { + return "# This message is used to specify a region of interest within an image.\n\ +#\n\ +# When used to specify the ROI setting of the camera when the image was\n\ +# taken, the height and width fields should either match the height and\n\ +# width fields for the associated image; or height = width = 0\n\ +# indicates that the full resolution image was captured.\n\ +\n\ +uint32 x_offset # Leftmost pixel of the ROI\n\ + # (0 if the ROI includes the left edge of the image)\n\ +uint32 y_offset # Topmost pixel of the ROI\n\ + # (0 if the ROI includes the top edge of the image)\n\ +uint32 height # Height of ROI\n\ +uint32 width # Width of ROI\n\ +\n\ +# True if a distinct rectified ROI should be calculated from the \"raw\"\n\ +# ROI in this message. Typically this should be False if the full image\n\ +# is captured (ROI not used), and True if a subwindow is captured (ROI\n\ +# used).\n\ +bool do_rectify\n\ +"; + } + + static const char* value(const ::sensor_msgs::RegionOfInterest_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::RegionOfInterest_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.x_offset); + stream.next(m.y_offset); + stream.next(m.height); + stream.next(m.width); + stream.next(m.do_rectify); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct RegionOfInterest_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::RegionOfInterest_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::RegionOfInterest_& v) + { + s << indent << "x_offset: "; + Printer::stream(s, indent + " ", v.x_offset); + s << indent << "y_offset: "; + Printer::stream(s, indent + " ", v.y_offset); + s << indent << "height: "; + Printer::stream(s, indent + " ", v.height); + s << indent << "width: "; + Printer::stream(s, indent + " ", v.width); + s << indent << "do_rectify: "; + Printer::stream(s, indent + " ", v.do_rectify); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_REGIONOFINTEREST_H diff --git a/thirdparty/ros/include/sensor_msgs/RelativeHumidity.h b/thirdparty/ros/include/sensor_msgs/RelativeHumidity.h new file mode 100644 index 0000000..ff5ec8e --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/RelativeHumidity.h @@ -0,0 +1,233 @@ +// Generated by gencpp from file sensor_msgs/RelativeHumidity.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_RELATIVEHUMIDITY_H +#define SENSOR_MSGS_MESSAGE_RELATIVEHUMIDITY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct RelativeHumidity_ +{ + typedef RelativeHumidity_ Type; + + RelativeHumidity_() + : header() + , relative_humidity(0.0) + , variance(0.0) { + } + RelativeHumidity_(const ContainerAllocator& _alloc) + : header(_alloc) + , relative_humidity(0.0) + , variance(0.0) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef double _relative_humidity_type; + _relative_humidity_type relative_humidity; + + typedef double _variance_type; + _variance_type variance; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::RelativeHumidity_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::RelativeHumidity_ const> ConstPtr; + +}; // struct RelativeHumidity_ + +typedef ::sensor_msgs::RelativeHumidity_ > RelativeHumidity; + +typedef boost::shared_ptr< ::sensor_msgs::RelativeHumidity > RelativeHumidityPtr; +typedef boost::shared_ptr< ::sensor_msgs::RelativeHumidity const> RelativeHumidityConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::RelativeHumidity_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::RelativeHumidity_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::RelativeHumidity_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::RelativeHumidity_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::RelativeHumidity_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::RelativeHumidity_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::RelativeHumidity_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::RelativeHumidity_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::RelativeHumidity_ > +{ + static const char* value() + { + return "8730015b05955b7e992ce29a2678d90f"; + } + + static const char* value(const ::sensor_msgs::RelativeHumidity_&) { return value(); } + static const uint64_t static_value1 = 0x8730015b05955b7eULL; + static const uint64_t static_value2 = 0x992ce29a2678d90fULL; +}; + +template +struct DataType< ::sensor_msgs::RelativeHumidity_ > +{ + static const char* value() + { + return "sensor_msgs/RelativeHumidity"; + } + + static const char* value(const ::sensor_msgs::RelativeHumidity_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::RelativeHumidity_ > +{ + static const char* value() + { + return " # Single reading from a relative humidity sensor. Defines the ratio of partial\n\ + # pressure of water vapor to the saturated vapor pressure at a temperature.\n\ +\n\ + Header header # timestamp of the measurement\n\ + # frame_id is the location of the humidity sensor\n\ +\n\ + float64 relative_humidity # Expression of the relative humidity\n\ + # from 0.0 to 1.0.\n\ + # 0.0 is no partial pressure of water vapor\n\ + # 1.0 represents partial pressure of saturation\n\ +\n\ + float64 variance # 0 is interpreted as variance unknown\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::RelativeHumidity_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::RelativeHumidity_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.relative_humidity); + stream.next(m.variance); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct RelativeHumidity_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::RelativeHumidity_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::RelativeHumidity_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "relative_humidity: "; + Printer::stream(s, indent + " ", v.relative_humidity); + s << indent << "variance: "; + Printer::stream(s, indent + " ", v.variance); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_RELATIVEHUMIDITY_H diff --git a/thirdparty/ros/include/sensor_msgs/SetCameraInfo.h b/thirdparty/ros/include/sensor_msgs/SetCameraInfo.h new file mode 100644 index 0000000..2e4c167 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/SetCameraInfo.h @@ -0,0 +1,123 @@ +// Generated by gencpp from file sensor_msgs/SetCameraInfo.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_SETCAMERAINFO_H +#define SENSOR_MSGS_MESSAGE_SETCAMERAINFO_H + +#include + + +#include +#include + + +namespace sensor_msgs +{ + +struct SetCameraInfo +{ + +typedef SetCameraInfoRequest Request; +typedef SetCameraInfoResponse Response; +Request request; +Response response; + +typedef Request RequestType; +typedef Response ResponseType; + +}; // struct SetCameraInfo +} // namespace sensor_msgs + + +namespace ros +{ +namespace service_traits +{ + + +template<> +struct MD5Sum< ::sensor_msgs::SetCameraInfo > { + static const char* value() + { + return "bef1df590ed75ed1f393692395e15482"; + } + + static const char* value(const ::sensor_msgs::SetCameraInfo&) { return value(); } +}; + +template<> +struct DataType< ::sensor_msgs::SetCameraInfo > { + static const char* value() + { + return "sensor_msgs/SetCameraInfo"; + } + + static const char* value(const ::sensor_msgs::SetCameraInfo&) { return value(); } +}; + + +// service_traits::MD5Sum< ::sensor_msgs::SetCameraInfoRequest> should match +// service_traits::MD5Sum< ::sensor_msgs::SetCameraInfo > +template<> +struct MD5Sum< ::sensor_msgs::SetCameraInfoRequest> +{ + static const char* value() + { + return MD5Sum< ::sensor_msgs::SetCameraInfo >::value(); + } + static const char* value(const ::sensor_msgs::SetCameraInfoRequest&) + { + return value(); + } +}; + +// service_traits::DataType< ::sensor_msgs::SetCameraInfoRequest> should match +// service_traits::DataType< ::sensor_msgs::SetCameraInfo > +template<> +struct DataType< ::sensor_msgs::SetCameraInfoRequest> +{ + static const char* value() + { + return DataType< ::sensor_msgs::SetCameraInfo >::value(); + } + static const char* value(const ::sensor_msgs::SetCameraInfoRequest&) + { + return value(); + } +}; + +// service_traits::MD5Sum< ::sensor_msgs::SetCameraInfoResponse> should match +// service_traits::MD5Sum< ::sensor_msgs::SetCameraInfo > +template<> +struct MD5Sum< ::sensor_msgs::SetCameraInfoResponse> +{ + static const char* value() + { + return MD5Sum< ::sensor_msgs::SetCameraInfo >::value(); + } + static const char* value(const ::sensor_msgs::SetCameraInfoResponse&) + { + return value(); + } +}; + +// service_traits::DataType< ::sensor_msgs::SetCameraInfoResponse> should match +// service_traits::DataType< ::sensor_msgs::SetCameraInfo > +template<> +struct DataType< ::sensor_msgs::SetCameraInfoResponse> +{ + static const char* value() + { + return DataType< ::sensor_msgs::SetCameraInfo >::value(); + } + static const char* value(const ::sensor_msgs::SetCameraInfoResponse&) + { + return value(); + } +}; + +} // namespace service_traits +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_SETCAMERAINFO_H diff --git a/thirdparty/ros/include/sensor_msgs/SetCameraInfoRequest.h b/thirdparty/ros/include/sensor_msgs/SetCameraInfoRequest.h new file mode 100644 index 0000000..51db184 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/SetCameraInfoRequest.h @@ -0,0 +1,371 @@ +// Generated by gencpp from file sensor_msgs/SetCameraInfoRequest.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_SETCAMERAINFOREQUEST_H +#define SENSOR_MSGS_MESSAGE_SETCAMERAINFOREQUEST_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct SetCameraInfoRequest_ +{ + typedef SetCameraInfoRequest_ Type; + + SetCameraInfoRequest_() + : camera_info() { + } + SetCameraInfoRequest_(const ContainerAllocator& _alloc) + : camera_info(_alloc) { + (void)_alloc; + } + + + + typedef ::sensor_msgs::CameraInfo_ _camera_info_type; + _camera_info_type camera_info; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoRequest_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoRequest_ const> ConstPtr; + +}; // struct SetCameraInfoRequest_ + +typedef ::sensor_msgs::SetCameraInfoRequest_ > SetCameraInfoRequest; + +typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoRequest > SetCameraInfoRequestPtr; +typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoRequest const> SetCameraInfoRequestConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::SetCameraInfoRequest_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::SetCameraInfoRequest_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::SetCameraInfoRequest_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::SetCameraInfoRequest_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::SetCameraInfoRequest_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::SetCameraInfoRequest_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::SetCameraInfoRequest_ > + : FalseType + { }; + +template +struct HasHeader< ::sensor_msgs::SetCameraInfoRequest_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::sensor_msgs::SetCameraInfoRequest_ > +{ + static const char* value() + { + return "ee34be01fdeee563d0d99cd594d5581d"; + } + + static const char* value(const ::sensor_msgs::SetCameraInfoRequest_&) { return value(); } + static const uint64_t static_value1 = 0xee34be01fdeee563ULL; + static const uint64_t static_value2 = 0xd0d99cd594d5581dULL; +}; + +template +struct DataType< ::sensor_msgs::SetCameraInfoRequest_ > +{ + static const char* value() + { + return "sensor_msgs/SetCameraInfoRequest"; + } + + static const char* value(const ::sensor_msgs::SetCameraInfoRequest_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::SetCameraInfoRequest_ > +{ + static const char* value() + { + return "\n\ +\n\ +\n\ +\n\ +\n\ +\n\ +\n\ +\n\ +sensor_msgs/CameraInfo camera_info\n\ +\n\ +================================================================================\n\ +MSG: sensor_msgs/CameraInfo\n\ +# This message defines meta information for a camera. It should be in a\n\ +# camera namespace on topic \"camera_info\" and accompanied by up to five\n\ +# image topics named:\n\ +#\n\ +# image_raw - raw data from the camera driver, possibly Bayer encoded\n\ +# image - monochrome, distorted\n\ +# image_color - color, distorted\n\ +# image_rect - monochrome, rectified\n\ +# image_rect_color - color, rectified\n\ +#\n\ +# The image_pipeline contains packages (image_proc, stereo_image_proc)\n\ +# for producing the four processed image topics from image_raw and\n\ +# camera_info. The meaning of the camera parameters are described in\n\ +# detail at http://www.ros.org/wiki/image_pipeline/CameraInfo.\n\ +#\n\ +# The image_geometry package provides a user-friendly interface to\n\ +# common operations using this meta information. If you want to, e.g.,\n\ +# project a 3d point into image coordinates, we strongly recommend\n\ +# using image_geometry.\n\ +#\n\ +# If the camera is uncalibrated, the matrices D, K, R, P should be left\n\ +# zeroed out. In particular, clients may assume that K[0] == 0.0\n\ +# indicates an uncalibrated camera.\n\ +\n\ +#######################################################################\n\ +# Image acquisition info #\n\ +#######################################################################\n\ +\n\ +# Time of image acquisition, camera coordinate frame ID\n\ +Header header # Header timestamp should be acquisition time of image\n\ + # Header frame_id should be optical frame of camera\n\ + # origin of frame should be optical center of camera\n\ + # +x should point to the right in the image\n\ + # +y should point down in the image\n\ + # +z should point into the plane of the image\n\ +\n\ +\n\ +#######################################################################\n\ +# Calibration Parameters #\n\ +#######################################################################\n\ +# These are fixed during camera calibration. Their values will be the #\n\ +# same in all messages until the camera is recalibrated. Note that #\n\ +# self-calibrating systems may \"recalibrate\" frequently. #\n\ +# #\n\ +# The internal parameters can be used to warp a raw (distorted) image #\n\ +# to: #\n\ +# 1. An undistorted image (requires D and K) #\n\ +# 2. A rectified image (requires D, K, R) #\n\ +# The projection matrix P projects 3D points into the rectified image.#\n\ +#######################################################################\n\ +\n\ +# The image dimensions with which the camera was calibrated. Normally\n\ +# this will be the full camera resolution in pixels.\n\ +uint32 height\n\ +uint32 width\n\ +\n\ +# The distortion model used. Supported models are listed in\n\ +# sensor_msgs/distortion_models.h. For most cameras, \"plumb_bob\" - a\n\ +# simple model of radial and tangential distortion - is sufficient.\n\ +string distortion_model\n\ +\n\ +# The distortion parameters, size depending on the distortion model.\n\ +# For \"plumb_bob\", the 5 parameters are: (k1, k2, t1, t2, k3).\n\ +float64[] D\n\ +\n\ +# Intrinsic camera matrix for the raw (distorted) images.\n\ +# [fx 0 cx]\n\ +# K = [ 0 fy cy]\n\ +# [ 0 0 1]\n\ +# Projects 3D points in the camera coordinate frame to 2D pixel\n\ +# coordinates using the focal lengths (fx, fy) and principal point\n\ +# (cx, cy).\n\ +float64[9] K # 3x3 row-major matrix\n\ +\n\ +# Rectification matrix (stereo cameras only)\n\ +# A rotation matrix aligning the camera coordinate system to the ideal\n\ +# stereo image plane so that epipolar lines in both stereo images are\n\ +# parallel.\n\ +float64[9] R # 3x3 row-major matrix\n\ +\n\ +# Projection/camera matrix\n\ +# [fx' 0 cx' Tx]\n\ +# P = [ 0 fy' cy' Ty]\n\ +# [ 0 0 1 0]\n\ +# By convention, this matrix specifies the intrinsic (camera) matrix\n\ +# of the processed (rectified) image. That is, the left 3x3 portion\n\ +# is the normal camera intrinsic matrix for the rectified image.\n\ +# It projects 3D points in the camera coordinate frame to 2D pixel\n\ +# coordinates using the focal lengths (fx', fy') and principal point\n\ +# (cx', cy') - these may differ from the values in K.\n\ +# For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will\n\ +# also have R = the identity and P[1:3,1:3] = K.\n\ +# For a stereo pair, the fourth column [Tx Ty 0]' is related to the\n\ +# position of the optical center of the second camera in the first\n\ +# camera's frame. We assume Tz = 0 so both cameras are in the same\n\ +# stereo image plane. The first camera always has Tx = Ty = 0. For\n\ +# the right (second) camera of a horizontal stereo pair, Ty = 0 and\n\ +# Tx = -fx' * B, where B is the baseline between the cameras.\n\ +# Given a 3D point [X Y Z]', the projection (x, y) of the point onto\n\ +# the rectified image is given by:\n\ +# [u v w]' = P * [X Y Z 1]'\n\ +# x = u / w\n\ +# y = v / w\n\ +# This holds for both images of a stereo pair.\n\ +float64[12] P # 3x4 row-major matrix\n\ +\n\ +\n\ +#######################################################################\n\ +# Operational Parameters #\n\ +#######################################################################\n\ +# These define the image region actually captured by the camera #\n\ +# driver. Although they affect the geometry of the output image, they #\n\ +# may be changed freely without recalibrating the camera. #\n\ +#######################################################################\n\ +\n\ +# Binning refers here to any camera setting which combines rectangular\n\ +# neighborhoods of pixels into larger \"super-pixels.\" It reduces the\n\ +# resolution of the output image to\n\ +# (width / binning_x) x (height / binning_y).\n\ +# The default values binning_x = binning_y = 0 is considered the same\n\ +# as binning_x = binning_y = 1 (no subsampling).\n\ +uint32 binning_x\n\ +uint32 binning_y\n\ +\n\ +# Region of interest (subwindow of full camera resolution), given in\n\ +# full resolution (unbinned) image coordinates. A particular ROI\n\ +# always denotes the same window of pixels on the camera sensor,\n\ +# regardless of binning settings.\n\ +# The default setting of roi (all values 0) is considered the same as\n\ +# full resolution (roi.width = width, roi.height = height).\n\ +RegionOfInterest roi\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +================================================================================\n\ +MSG: sensor_msgs/RegionOfInterest\n\ +# This message is used to specify a region of interest within an image.\n\ +#\n\ +# When used to specify the ROI setting of the camera when the image was\n\ +# taken, the height and width fields should either match the height and\n\ +# width fields for the associated image; or height = width = 0\n\ +# indicates that the full resolution image was captured.\n\ +\n\ +uint32 x_offset # Leftmost pixel of the ROI\n\ + # (0 if the ROI includes the left edge of the image)\n\ +uint32 y_offset # Topmost pixel of the ROI\n\ + # (0 if the ROI includes the top edge of the image)\n\ +uint32 height # Height of ROI\n\ +uint32 width # Width of ROI\n\ +\n\ +# True if a distinct rectified ROI should be calculated from the \"raw\"\n\ +# ROI in this message. Typically this should be False if the full image\n\ +# is captured (ROI not used), and True if a subwindow is captured (ROI\n\ +# used).\n\ +bool do_rectify\n\ +"; + } + + static const char* value(const ::sensor_msgs::SetCameraInfoRequest_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::SetCameraInfoRequest_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.camera_info); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct SetCameraInfoRequest_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::SetCameraInfoRequest_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::SetCameraInfoRequest_& v) + { + s << indent << "camera_info: "; + s << std::endl; + Printer< ::sensor_msgs::CameraInfo_ >::stream(s, indent + " ", v.camera_info); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_SETCAMERAINFOREQUEST_H diff --git a/thirdparty/ros/include/sensor_msgs/SetCameraInfoResponse.h b/thirdparty/ros/include/sensor_msgs/SetCameraInfoResponse.h new file mode 100644 index 0000000..a1cc27c --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/SetCameraInfoResponse.h @@ -0,0 +1,197 @@ +// Generated by gencpp from file sensor_msgs/SetCameraInfoResponse.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_SETCAMERAINFORESPONSE_H +#define SENSOR_MSGS_MESSAGE_SETCAMERAINFORESPONSE_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace sensor_msgs +{ +template +struct SetCameraInfoResponse_ +{ + typedef SetCameraInfoResponse_ Type; + + SetCameraInfoResponse_() + : success(false) + , status_message() { + } + SetCameraInfoResponse_(const ContainerAllocator& _alloc) + : success(false) + , status_message(_alloc) { + (void)_alloc; + } + + + + typedef uint8_t _success_type; + _success_type success; + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _status_message_type; + _status_message_type status_message; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoResponse_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoResponse_ const> ConstPtr; + +}; // struct SetCameraInfoResponse_ + +typedef ::sensor_msgs::SetCameraInfoResponse_ > SetCameraInfoResponse; + +typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoResponse > SetCameraInfoResponsePtr; +typedef boost::shared_ptr< ::sensor_msgs::SetCameraInfoResponse const> SetCameraInfoResponseConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::SetCameraInfoResponse_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::SetCameraInfoResponse_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::SetCameraInfoResponse_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::SetCameraInfoResponse_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::SetCameraInfoResponse_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::SetCameraInfoResponse_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::SetCameraInfoResponse_ > + : FalseType + { }; + +template +struct HasHeader< ::sensor_msgs::SetCameraInfoResponse_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::sensor_msgs::SetCameraInfoResponse_ > +{ + static const char* value() + { + return "2ec6f3eff0161f4257b808b12bc830c2"; + } + + static const char* value(const ::sensor_msgs::SetCameraInfoResponse_&) { return value(); } + static const uint64_t static_value1 = 0x2ec6f3eff0161f42ULL; + static const uint64_t static_value2 = 0x57b808b12bc830c2ULL; +}; + +template +struct DataType< ::sensor_msgs::SetCameraInfoResponse_ > +{ + static const char* value() + { + return "sensor_msgs/SetCameraInfoResponse"; + } + + static const char* value(const ::sensor_msgs::SetCameraInfoResponse_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::SetCameraInfoResponse_ > +{ + static const char* value() + { + return "bool success\n\ +string status_message\n\ +\n\ +"; + } + + static const char* value(const ::sensor_msgs::SetCameraInfoResponse_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::SetCameraInfoResponse_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.success); + stream.next(m.status_message); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct SetCameraInfoResponse_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::SetCameraInfoResponse_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::SetCameraInfoResponse_& v) + { + s << indent << "success: "; + Printer::stream(s, indent + " ", v.success); + s << indent << "status_message: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.status_message); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_SETCAMERAINFORESPONSE_H diff --git a/thirdparty/ros/include/sensor_msgs/Temperature.h b/thirdparty/ros/include/sensor_msgs/Temperature.h new file mode 100644 index 0000000..21a336a --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/Temperature.h @@ -0,0 +1,229 @@ +// Generated by gencpp from file sensor_msgs/Temperature.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_TEMPERATURE_H +#define SENSOR_MSGS_MESSAGE_TEMPERATURE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct Temperature_ +{ + typedef Temperature_ Type; + + Temperature_() + : header() + , temperature(0.0) + , variance(0.0) { + } + Temperature_(const ContainerAllocator& _alloc) + : header(_alloc) + , temperature(0.0) + , variance(0.0) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef double _temperature_type; + _temperature_type temperature; + + typedef double _variance_type; + _variance_type variance; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::Temperature_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::Temperature_ const> ConstPtr; + +}; // struct Temperature_ + +typedef ::sensor_msgs::Temperature_ > Temperature; + +typedef boost::shared_ptr< ::sensor_msgs::Temperature > TemperaturePtr; +typedef boost::shared_ptr< ::sensor_msgs::Temperature const> TemperatureConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::Temperature_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::Temperature_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::Temperature_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::Temperature_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::Temperature_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::Temperature_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Temperature_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::Temperature_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::Temperature_ > +{ + static const char* value() + { + return "ff71b307acdbe7c871a5a6d7ed359100"; + } + + static const char* value(const ::sensor_msgs::Temperature_&) { return value(); } + static const uint64_t static_value1 = 0xff71b307acdbe7c8ULL; + static const uint64_t static_value2 = 0x71a5a6d7ed359100ULL; +}; + +template +struct DataType< ::sensor_msgs::Temperature_ > +{ + static const char* value() + { + return "sensor_msgs/Temperature"; + } + + static const char* value(const ::sensor_msgs::Temperature_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::Temperature_ > +{ + static const char* value() + { + return " # Single temperature reading.\n\ +\n\ + Header header # timestamp is the time the temperature was measured\n\ + # frame_id is the location of the temperature reading\n\ +\n\ + float64 temperature # Measurement of the Temperature in Degrees Celsius\n\ +\n\ + float64 variance # 0 is interpreted as variance unknown\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::Temperature_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::Temperature_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.temperature); + stream.next(m.variance); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Temperature_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::Temperature_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::Temperature_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "temperature: "; + Printer::stream(s, indent + " ", v.temperature); + s << indent << "variance: "; + Printer::stream(s, indent + " ", v.variance); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_TEMPERATURE_H diff --git a/thirdparty/ros/include/sensor_msgs/TimeReference.h b/thirdparty/ros/include/sensor_msgs/TimeReference.h new file mode 100644 index 0000000..cebc141 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/TimeReference.h @@ -0,0 +1,229 @@ +// Generated by gencpp from file sensor_msgs/TimeReference.msg +// DO NOT EDIT! + + +#ifndef SENSOR_MSGS_MESSAGE_TIMEREFERENCE_H +#define SENSOR_MSGS_MESSAGE_TIMEREFERENCE_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace sensor_msgs +{ +template +struct TimeReference_ +{ + typedef TimeReference_ Type; + + TimeReference_() + : header() + , time_ref() + , source() { + } + TimeReference_(const ContainerAllocator& _alloc) + : header(_alloc) + , time_ref() + , source(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::Header_ _header_type; + _header_type header; + + typedef ros::Time _time_ref_type; + _time_ref_type time_ref; + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _source_type; + _source_type source; + + + + + + typedef boost::shared_ptr< ::sensor_msgs::TimeReference_ > Ptr; + typedef boost::shared_ptr< ::sensor_msgs::TimeReference_ const> ConstPtr; + +}; // struct TimeReference_ + +typedef ::sensor_msgs::TimeReference_ > TimeReference; + +typedef boost::shared_ptr< ::sensor_msgs::TimeReference > TimeReferencePtr; +typedef boost::shared_ptr< ::sensor_msgs::TimeReference const> TimeReferenceConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::sensor_msgs::TimeReference_ & v) +{ +ros::message_operations::Printer< ::sensor_msgs::TimeReference_ >::stream(s, "", v); +return s; +} + +} // namespace sensor_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': True} +// {'std_msgs': ['/opt/ros/kinetic/share/std_msgs/cmake/../msg'], 'geometry_msgs': ['/opt/ros/kinetic/share/geometry_msgs/cmake/../msg'], 'sensor_msgs': ['/tmp/binarydeb/ros-kinetic-sensor-msgs-1.12.5/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::sensor_msgs::TimeReference_ > + : FalseType + { }; + +template +struct IsFixedSize< ::sensor_msgs::TimeReference_ const> + : FalseType + { }; + +template +struct IsMessage< ::sensor_msgs::TimeReference_ > + : TrueType + { }; + +template +struct IsMessage< ::sensor_msgs::TimeReference_ const> + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::TimeReference_ > + : TrueType + { }; + +template +struct HasHeader< ::sensor_msgs::TimeReference_ const> + : TrueType + { }; + + +template +struct MD5Sum< ::sensor_msgs::TimeReference_ > +{ + static const char* value() + { + return "fded64a0265108ba86c3d38fb11c0c16"; + } + + static const char* value(const ::sensor_msgs::TimeReference_&) { return value(); } + static const uint64_t static_value1 = 0xfded64a0265108baULL; + static const uint64_t static_value2 = 0x86c3d38fb11c0c16ULL; +}; + +template +struct DataType< ::sensor_msgs::TimeReference_ > +{ + static const char* value() + { + return "sensor_msgs/TimeReference"; + } + + static const char* value(const ::sensor_msgs::TimeReference_&) { return value(); } +}; + +template +struct Definition< ::sensor_msgs::TimeReference_ > +{ + static const char* value() + { + return "# Measurement from an external time source not actively synchronized with the system clock.\n\ +\n\ +Header header # stamp is system time for which measurement was valid\n\ + # frame_id is not used \n\ +\n\ +time time_ref # corresponding time from this external source\n\ +string source # (optional) name of time source\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/Header\n\ +# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::sensor_msgs::TimeReference_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::sensor_msgs::TimeReference_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.header); + stream.next(m.time_ref); + stream.next(m.source); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct TimeReference_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::sensor_msgs::TimeReference_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::sensor_msgs::TimeReference_& v) + { + s << indent << "header: "; + s << std::endl; + Printer< ::std_msgs::Header_ >::stream(s, indent + " ", v.header); + s << indent << "time_ref: "; + Printer::stream(s, indent + " ", v.time_ref); + s << indent << "source: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.source); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // SENSOR_MSGS_MESSAGE_TIMEREFERENCE_H diff --git a/thirdparty/ros/include/sensor_msgs/distortion_models.h b/thirdparty/ros/include/sensor_msgs/distortion_models.h new file mode 100644 index 0000000..c42492d --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/distortion_models.h @@ -0,0 +1,50 @@ + +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2010, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#ifndef SENSOR_MSGS_DISTORTION_MODELS_H +#define SENSOR_MSGS_DISTORTION_MODELS_H + +#include + +namespace sensor_msgs +{ + namespace distortion_models + { + const std::string PLUMB_BOB = "plumb_bob"; + const std::string RATIONAL_POLYNOMIAL = "rational_polynomial"; + } +} + +#endif diff --git a/thirdparty/ros/include/sensor_msgs/fill_image.h b/thirdparty/ros/include/sensor_msgs/fill_image.h new file mode 100644 index 0000000..8795d2f --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/fill_image.h @@ -0,0 +1,70 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2008, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#ifndef FILLIMAGE_HH +#define FILLIMAGE_HH + +#include "sensor_msgs/Image.h" +#include "sensor_msgs/image_encodings.h" + +namespace sensor_msgs +{ + + static inline bool fillImage(Image& image, + const std::string& encoding_arg, + uint32_t rows_arg, + uint32_t cols_arg, + uint32_t step_arg, + const void* data_arg) + { + image.encoding = encoding_arg; + image.height = rows_arg; + image.width = cols_arg; + image.step = step_arg; + size_t st0 = (step_arg * rows_arg); + image.data.resize(st0); + memcpy(&image.data[0], data_arg, st0); + + image.is_bigendian = 0; + return true; + } + + static inline void clearImage(Image& image) + { + image.data.resize(0); + } +} + + +#endif diff --git a/thirdparty/ros/include/sensor_msgs/image_encodings.h b/thirdparty/ros/include/sensor_msgs/image_encodings.h new file mode 100644 index 0000000..0180491 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/image_encodings.h @@ -0,0 +1,232 @@ + +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2009, Willow Garage, Inc. +* All rights reserved. +* +* Redistribution and use in source and binary forms, with or without +* modification, are permitted provided that the following conditions +* are met: +* +* * Redistributions of source code must retain the above copyright +* notice, this list of conditions and the following disclaimer. +* * Redistributions in binary form must reproduce the above +* copyright notice, this list of conditions and the following +* disclaimer in the documentation and/or other materials provided +* with the distribution. +* * Neither the name of the Willow Garage nor the names of its +* contributors may be used to endorse or promote products derived +* from this software without specific prior written permission. +* +* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER +* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +* POSSIBILITY OF SUCH DAMAGE. +*********************************************************************/ + +#ifndef SENSOR_MSGS_IMAGE_ENCODINGS_H +#define SENSOR_MSGS_IMAGE_ENCODINGS_H + +#include +#include + +namespace sensor_msgs +{ + namespace image_encodings + { + const std::string RGB8 = "rgb8"; + const std::string RGBA8 = "rgba8"; + const std::string RGB16 = "rgb16"; + const std::string RGBA16 = "rgba16"; + const std::string BGR8 = "bgr8"; + const std::string BGRA8 = "bgra8"; + const std::string BGR16 = "bgr16"; + const std::string BGRA16 = "bgra16"; + const std::string MONO8="mono8"; + const std::string MONO16="mono16"; + + // OpenCV CvMat types + const std::string TYPE_8UC1="8UC1"; + const std::string TYPE_8UC2="8UC2"; + const std::string TYPE_8UC3="8UC3"; + const std::string TYPE_8UC4="8UC4"; + const std::string TYPE_8SC1="8SC1"; + const std::string TYPE_8SC2="8SC2"; + const std::string TYPE_8SC3="8SC3"; + const std::string TYPE_8SC4="8SC4"; + const std::string TYPE_16UC1="16UC1"; + const std::string TYPE_16UC2="16UC2"; + const std::string TYPE_16UC3="16UC3"; + const std::string TYPE_16UC4="16UC4"; + const std::string TYPE_16SC1="16SC1"; + const std::string TYPE_16SC2="16SC2"; + const std::string TYPE_16SC3="16SC3"; + const std::string TYPE_16SC4="16SC4"; + const std::string TYPE_32SC1="32SC1"; + const std::string TYPE_32SC2="32SC2"; + const std::string TYPE_32SC3="32SC3"; + const std::string TYPE_32SC4="32SC4"; + const std::string TYPE_32FC1="32FC1"; + const std::string TYPE_32FC2="32FC2"; + const std::string TYPE_32FC3="32FC3"; + const std::string TYPE_32FC4="32FC4"; + const std::string TYPE_64FC1="64FC1"; + const std::string TYPE_64FC2="64FC2"; + const std::string TYPE_64FC3="64FC3"; + const std::string TYPE_64FC4="64FC4"; + + // Bayer encodings + const std::string BAYER_RGGB8="bayer_rggb8"; + const std::string BAYER_BGGR8="bayer_bggr8"; + const std::string BAYER_GBRG8="bayer_gbrg8"; + const std::string BAYER_GRBG8="bayer_grbg8"; + const std::string BAYER_RGGB16="bayer_rggb16"; + const std::string BAYER_BGGR16="bayer_bggr16"; + const std::string BAYER_GBRG16="bayer_gbrg16"; + const std::string BAYER_GRBG16="bayer_grbg16"; + + // Miscellaneous + // This is the UYVY version of YUV422 codec http://www.fourcc.org/yuv.php#UYVY + // with an 8-bit depth + const std::string YUV422="yuv422"; + + // Prefixes for abstract image encodings + const std::string ABSTRACT_ENCODING_PREFIXES[] = { + "8UC", "8SC", "16UC", "16SC", "32SC", "32FC", "64FC"}; + + // Utility functions for inspecting an encoding string + static inline bool isColor(const std::string& encoding) + { + return encoding == RGB8 || encoding == BGR8 || + encoding == RGBA8 || encoding == BGRA8 || + encoding == RGB16 || encoding == BGR16 || + encoding == RGBA16 || encoding == BGRA16; + } + + static inline bool isMono(const std::string& encoding) + { + return encoding == MONO8 || encoding == MONO16; + } + + static inline bool isBayer(const std::string& encoding) + { + return encoding == BAYER_RGGB8 || encoding == BAYER_BGGR8 || + encoding == BAYER_GBRG8 || encoding == BAYER_GRBG8 || + encoding == BAYER_RGGB16 || encoding == BAYER_BGGR16 || + encoding == BAYER_GBRG16 || encoding == BAYER_GRBG16; + } + + static inline bool hasAlpha(const std::string& encoding) + { + return encoding == RGBA8 || encoding == BGRA8 || + encoding == RGBA16 || encoding == BGRA16; + } + + static inline int numChannels(const std::string& encoding) + { + // First do the common-case encodings + if (encoding == MONO8 || + encoding == MONO16) + return 1; + if (encoding == BGR8 || + encoding == RGB8 || + encoding == BGR16 || + encoding == RGB16) + return 3; + if (encoding == BGRA8 || + encoding == RGBA8 || + encoding == BGRA16 || + encoding == RGBA16) + return 4; + if (encoding == BAYER_RGGB8 || + encoding == BAYER_BGGR8 || + encoding == BAYER_GBRG8 || + encoding == BAYER_GRBG8 || + encoding == BAYER_RGGB16 || + encoding == BAYER_BGGR16 || + encoding == BAYER_GBRG16 || + encoding == BAYER_GRBG16) + return 1; + + // Now all the generic content encodings + // TODO: Rewrite with regex when ROS supports C++11 + for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++) + { + std::string prefix = ABSTRACT_ENCODING_PREFIXES[i]; + if (encoding.substr(0, prefix.size()) != prefix) + continue; + if (encoding.size() == prefix.size()) + return 1; // ex. 8UC -> 1 + int n_channel = atoi(encoding.substr(prefix.size(), + encoding.size() - prefix.size()).c_str()); // ex. 8UC5 -> 5 + if (n_channel != 0) + return n_channel; // valid encoding string + } + + if (encoding == YUV422) + return 2; + + throw std::runtime_error("Unknown encoding " + encoding); + return -1; + } + + static inline int bitDepth(const std::string& encoding) + { + if (encoding == MONO16) + return 16; + if (encoding == MONO8 || + encoding == BGR8 || + encoding == RGB8 || + encoding == BGRA8 || + encoding == RGBA8 || + encoding == BAYER_RGGB8 || + encoding == BAYER_BGGR8 || + encoding == BAYER_GBRG8 || + encoding == BAYER_GRBG8) + return 8; + + if (encoding == MONO16 || + encoding == BGR16 || + encoding == RGB16 || + encoding == BGRA16 || + encoding == RGBA16 || + encoding == BAYER_RGGB16 || + encoding == BAYER_BGGR16 || + encoding == BAYER_GBRG16 || + encoding == BAYER_GRBG16) + return 16; + + // Now all the generic content encodings + // TODO: Rewrite with regex when ROS supports C++11 + for (size_t i=0; i < sizeof(ABSTRACT_ENCODING_PREFIXES) / sizeof(*ABSTRACT_ENCODING_PREFIXES); i++) + { + std::string prefix = ABSTRACT_ENCODING_PREFIXES[i]; + if (encoding.substr(0, prefix.size()) != prefix) + continue; + if (encoding.size() == prefix.size()) + return atoi(prefix.c_str()); // ex. 8UC -> 8 + int n_channel = atoi(encoding.substr(prefix.size(), + encoding.size() - prefix.size()).c_str()); // ex. 8UC10 -> 10 + if (n_channel != 0) + return atoi(prefix.c_str()); // valid encoding string + } + + if (encoding == YUV422) + return 8; + + throw std::runtime_error("Unknown encoding " + encoding); + return -1; + } + } +} + +#endif diff --git a/thirdparty/ros/include/sensor_msgs/point_cloud2_iterator.h b/thirdparty/ros/include/sensor_msgs/point_cloud2_iterator.h new file mode 100644 index 0000000..5b9c7a1 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/point_cloud2_iterator.h @@ -0,0 +1,302 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2013, Open Source Robotics Foundation + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Open Source Robotics Foundation nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H +#define SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H + +#include +#include +#include +#include + +/** + * \brief Tools for manipulating sensor_msgs + * + * This file provides two sets of utilities to modify and parse PointCloud2 + * The first set allows you to conveniently set the fields by hand: + *
    + *   #include 
    + *   // Create a PointCloud2
    + *   sensor_msgs::PointCloud2 cloud_msg;
    + *   // Fill some internals of the PoinCloud2 like the header/width/height ...
    + *   cloud_msgs.height = 1;  cloud_msgs.width = 4;
    + *   // Set the point fields to xyzrgb and resize the vector with the following command
    + *   // 4 is for the number of added fields. Each come in triplet: the name of the PointField,
    + *   // the number of occurrences of the type in the PointField, the type of the PointField
    + *   sensor_msgs::PointCloud2Modifier modifier(cloud_msg);
    + *   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);
    + *   // For convenience and the xyz, rgb, rgba fields, you can also use the following overloaded function.
    + *   // You have to be aware that the following function does add extra padding for backward compatibility though
    + *   // so it is definitely the solution of choice for PointXYZ and PointXYZRGB
    + *   // 2 is for the number of fields to add
    + *   modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
    + *   // You can then reserve / resize as usual
    + *   modifier.resize(100);
    + * 
    + * + * The second set allow you to traverse your PointCloud using an iterator: + *
    + *   // Define some raw data we'll put in the PointCloud2
    + *   float point_data[] = {1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0};
    + *   uint8_t color_data[] = {40, 80, 120, 160, 200, 240, 20, 40, 60, 80, 100, 120};
    + *   // Define the iterators. When doing so, you define the Field you would like to iterate upon and
    + *   // the type of you would like returned: it is not necessary the type of the PointField as sometimes
    + *   // you pack data in another type (e.g. 3 uchar + 1 uchar for RGB are packed in a float)
    + *   sensor_msgs::PointCloud2Iterator iter_x(cloud_msg, "x");
    + *   sensor_msgs::PointCloud2Iterator iter_y(cloud_msg, "y");
    + *   sensor_msgs::PointCloud2Iterator iter_z(cloud_msg, "z");
    + *   // Even though the r,g,b,a fields do not exist (it's usually rgb, rgba), you can create iterators for
    + *   // those: they will handle data packing for you (in little endian RGB is packed as *,R,G,B in a float
    + *   // and RGBA as A,R,G,B)
    + *   sensor_msgs::PointCloud2Iterator iter_r(cloud_msg, "r");
    + *   sensor_msgs::PointCloud2Iterator iter_g(cloud_msg, "g");
    + *   sensor_msgs::PointCloud2Iterator iter_b(cloud_msg, "b");
    + *   // Fill the PointCloud2
    + *   for(size_t i=0; i
    + */
    +
    +namespace sensor_msgs
    +{
    +/**
    + * @brief Enables modifying a sensor_msgs::PointCloud2 like a container
    + */
    +class PointCloud2Modifier
    +{
    +public:
    +  /**
    +   * @brief Default constructor
    +   * @param cloud_msg The sensor_msgs::PointCloud2 to modify
    +   */
    +  PointCloud2Modifier(PointCloud2& cloud_msg);
    +
    +  /**
    +   * @return the number of T's in the original sensor_msgs::PointCloud2
    +   */
    +  size_t size() const;
    +
    +  /**
    +   * @param size The number of T's to reserve in the original sensor_msgs::PointCloud2 for
    +   */
    +  void reserve(size_t size);
    +
    +  /**
    +   * @param size The number of T's to change the size of the original sensor_msgs::PointCloud2 by
    +   */
    +  void resize(size_t size);
    +
    +  /**
    +   * @brief remove all T's from the original sensor_msgs::PointCloud2
    +   */
    +  void clear();
    +
    +  /**
    +   * @brief Function setting some fields in a PointCloud and adjusting the
    +   *        internals of the PointCloud2
    +   * @param n_fields the number of fields to add. The fields are given as
    +   *        triplets: name of the field as char*, number of elements in the
    +   *        field, the datatype of the elements in the field
    +   *
    +   * E.g, you create your PointCloud2 message with XYZ/RGB as follows:
    +   * 
    +   *   setPointCloud2Fields(cloud_msg, 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);
    +   * 
    + * WARNING: THIS DOES NOT TAKE INTO ACCOUNT ANY PADDING AS DONE UNTIL HYDRO + * For simple usual cases, the overloaded setPointCloud2FieldsByString is what you want. + */ + void setPointCloud2Fields(int n_fields, ...); + + /** + * @brief Function setting some fields in a PointCloud and adjusting the + * internals of the PointCloud2 + * @param n_fields the number of fields to add. The fields are given as + * strings: "xyz" (3 floats), "rgb" (3 uchar stacked in a float), + * "rgba" (4 uchar stacked in a float) + * @return void + * + * WARNING: THIS FUNCTION DOES ADD ANY NECESSARY PADDING TRANSPARENTLY + */ + void setPointCloud2FieldsByString(int n_fields, ...); +protected: + /** A reference to the original sensor_msgs::PointCloud2 that we read */ + PointCloud2& cloud_msg_; +}; + +namespace impl +{ +/** Private base class for PointCloud2Iterator and PointCloud2ConstIterator + * T is the type of the value on which the child class will be templated + * TT is the type of the value to be retrieved (same as T except for constness) + * U is the type of the raw data in PointCloud2 (only uchar and const uchar are supported) + * C is the type of the pointcloud to intialize from (const or not) + * V is the derived class (yop, curiously recurring template pattern) + */ +template class V> +class PointCloud2IteratorBase +{ +public: + /** + */ + PointCloud2IteratorBase(); + + /** + * @param cloud_msg The PointCloud2 to iterate upon + * @param field_name The field to iterate upon + */ + PointCloud2IteratorBase(C &cloud_msg, const std::string &field_name); + + /** Assignment operator + * @param iter the iterator to copy data from + * @return a reference to *this + */ + V& operator =(const V& iter); + + /** Access the i th element starting at the current pointer (useful when a field has several elements of the same + * type) + * @param i + * @return a reference to the i^th value from the current position + */ + TT& operator [](size_t i) const; + + /** Dereference the iterator. Equivalent to accessing it through [0] + * @return the value to which the iterator is pointing + */ + TT& operator *() const; + + /** Increase the iterator to the next element + * @return a reference to the updated iterator + */ + V& operator ++(); + + /** Basic pointer addition + * @param i the amount to increase the iterator by + * @return an iterator with an increased position + */ + V operator +(int i); + + /** Increase the iterator by a certain amount + * @return a reference to the updated iterator + */ + V& operator +=(int i); + + /** Compare to another iterator + * @return whether the current iterator points to a different address than the other one + */ + bool operator !=(const V& iter) const; + + /** Return the end iterator + * @return the end iterator (useful when performing normal iterator processing with ++) + */ + V end() const; + +private: + /** Common code to set the field of the PointCloud2 + * @param cloud_msg the PointCloud2 to modify + * @param field_name the name of the field to iterate upon + * @return the offset at which the field is found + */ + int set_field(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name); + + /** The "point_step" of the original cloud */ + int point_step_; + /** The raw data in uchar* where the iterator is */ + U* data_char_; + /** The cast data where the iterator is */ + TT* data_; + /** The end() pointer of the iterator */ + TT* data_end_; + /** Whether the fields are stored as bigendian */ + bool is_bigendian_; +}; +} + +/** + * \brief Class that can iterate over a PointCloud2 + * + * T type of the element being iterated upon + * E.g, you create your PointClou2 message as follows: + *
    + *   setPointCloud2FieldsByString(cloud_msg, 2, "xyz", "rgb");
    + * 
    + * + * For iterating over XYZ, you do : + *
    + *   sensor_msgs::PointCloud2Iterator iter_x(cloud_msg, "x");
    + * 
    + * and then access X through iter_x[0] or *iter_x + * You could create an iterator for Y and Z too but as they are consecutive, + * you can just use iter_x[1] and iter_x[2] + * + * For iterating over RGB, you do: + *
    + * sensor_msgs::PointCloud2Iterator iter_rgb(cloud_msg, "rgb");
    + * 
    + * and then access R,G,B through iter_rgb[0], iter_rgb[1], iter_rgb[2] + */ +template +class PointCloud2Iterator : public impl::PointCloud2IteratorBase +{ +public: + PointCloud2Iterator(sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) : + impl::PointCloud2IteratorBase::PointCloud2IteratorBase(cloud_msg, field_name) {} +}; + +/** + * \brief Same as a PointCloud2Iterator but for const data + */ +template +class PointCloud2ConstIterator : public impl::PointCloud2IteratorBase +{ +public: + PointCloud2ConstIterator(const sensor_msgs::PointCloud2 &cloud_msg, const std::string &field_name) : + impl::PointCloud2IteratorBase::PointCloud2IteratorBase(cloud_msg, field_name) {} +}; +} + +#include + +#endif// SENSOR_MSGS_POINT_CLOUD2_ITERATOR_H diff --git a/thirdparty/ros/include/sensor_msgs/point_cloud_conversion.h b/thirdparty/ros/include/sensor_msgs/point_cloud_conversion.h new file mode 100644 index 0000000..439145d --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/point_cloud_conversion.h @@ -0,0 +1,169 @@ +/* + * Software License Agreement (BSD License) + * + * Copyright (c) 2010, Willow Garage, Inc. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above + * copyright notice, this list of conditions and the following + * disclaimer in the documentation and/or other materials provided + * with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived + * from this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + * $Id$ + * + */ + +#ifndef SENSOR_MSGS_POINT_CLOUD_CONVERSION_H +#define SENSOR_MSGS_POINT_CLOUD_CONVERSION_H + +#include +#include +#include + +/** + * \brief Convert between the old (sensor_msgs::PointCloud) and the new (sensor_msgs::PointCloud2) format. + * \author Radu Bogdan Rusu + */ +namespace sensor_msgs +{ + ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Get the index of a specified field (i.e., dimension/channel) + * \param points the the point cloud message + * \param field_name the string defining the field name + */ +static inline int getPointCloud2FieldIndex (const sensor_msgs::PointCloud2 &cloud, const std::string &field_name) +{ + // Get the index we need + for (size_t d = 0; d < cloud.fields.size (); ++d) + if (cloud.fields[d].name == field_name) + return (d); + return (-1); +} + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Convert a sensor_msgs::PointCloud message to a sensor_msgs::PointCloud2 message. + * \param input the message in the sensor_msgs::PointCloud format + * \param output the resultant message in the sensor_msgs::PointCloud2 format + */ +static inline bool convertPointCloudToPointCloud2 (const sensor_msgs::PointCloud &input, sensor_msgs::PointCloud2 &output) +{ + output.header = input.header; + output.width = input.points.size (); + output.height = 1; + output.fields.resize (3 + input.channels.size ()); + // Convert x/y/z to fields + output.fields[0].name = "x"; output.fields[1].name = "y"; output.fields[2].name = "z"; + int offset = 0; + // All offsets are *4, as all field data types are float32 + for (size_t d = 0; d < output.fields.size (); ++d, offset += 4) + { + output.fields[d].offset = offset; + output.fields[d].datatype = sensor_msgs::PointField::FLOAT32; + output.fields[d].count = 1; + } + output.point_step = offset; + output.row_step = output.point_step * output.width; + // Convert the remaining of the channels to fields + for (size_t d = 0; d < input.channels.size (); ++d) + output.fields[3 + d].name = input.channels[d].name; + output.data.resize (input.points.size () * output.point_step); + output.is_bigendian = false; // @todo ? + output.is_dense = false; + + // Copy the data points + for (size_t cp = 0; cp < input.points.size (); ++cp) + { + memcpy (&output.data[cp * output.point_step + output.fields[0].offset], &input.points[cp].x, sizeof (float)); + memcpy (&output.data[cp * output.point_step + output.fields[1].offset], &input.points[cp].y, sizeof (float)); + memcpy (&output.data[cp * output.point_step + output.fields[2].offset], &input.points[cp].z, sizeof (float)); + for (size_t d = 0; d < input.channels.size (); ++d) + { + if (input.channels[d].values.size() == input.points.size()) + { + memcpy (&output.data[cp * output.point_step + output.fields[3 + d].offset], &input.channels[d].values[cp], sizeof (float)); + } + } + } + return (true); +} + + //////////////////////////////////////////////////////////////////////////////////////////////////////////////////// + /** \brief Convert a sensor_msgs::PointCloud2 message to a sensor_msgs::PointCloud message. + * \param input the message in the sensor_msgs::PointCloud2 format + * \param output the resultant message in the sensor_msgs::PointCloud format + */ +static inline bool convertPointCloud2ToPointCloud (const sensor_msgs::PointCloud2 &input, sensor_msgs::PointCloud &output) +{ + + output.header = input.header; + output.points.resize (input.width * input.height); + output.channels.resize (input.fields.size () - 3); + // Get the x/y/z field offsets + int x_idx = getPointCloud2FieldIndex (input, "x"); + int y_idx = getPointCloud2FieldIndex (input, "y"); + int z_idx = getPointCloud2FieldIndex (input, "z"); + if (x_idx == -1 || y_idx == -1 || z_idx == -1) + { + std::cerr << "x/y/z coordinates not found! Cannot convert to sensor_msgs::PointCloud!" << std::endl; + return (false); + } + int x_offset = input.fields[x_idx].offset; + int y_offset = input.fields[y_idx].offset; + int z_offset = input.fields[z_idx].offset; + uint8_t x_datatype = input.fields[x_idx].datatype; + uint8_t y_datatype = input.fields[y_idx].datatype; + uint8_t z_datatype = input.fields[z_idx].datatype; + + // Convert the fields to channels + int cur_c = 0; + for (size_t d = 0; d < input.fields.size (); ++d) + { + if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset) + continue; + output.channels[cur_c].name = input.fields[d].name; + output.channels[cur_c].values.resize (output.points.size ()); + cur_c++; + } + + // Copy the data points + for (size_t cp = 0; cp < output.points.size (); ++cp) + { + // Copy x/y/z + output.points[cp].x = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + x_offset], x_datatype); + output.points[cp].y = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + y_offset], y_datatype); + output.points[cp].z = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + z_offset], z_datatype); + // Copy the rest of the data + int cur_c = 0; + for (size_t d = 0; d < input.fields.size (); ++d) + { + if ((int)input.fields[d].offset == x_offset || (int)input.fields[d].offset == y_offset || (int)input.fields[d].offset == z_offset) + continue; + output.channels[cur_c++].values[cp] = sensor_msgs::readPointCloud2BufferValue(&input.data[cp * input.point_step + input.fields[d].offset], input.fields[d].datatype); + } + } + return (true); +} +} +#endif// SENSOR_MSGS_POINT_CLOUD_CONVERSION_H diff --git a/thirdparty/ros/include/sensor_msgs/point_field_conversion.h b/thirdparty/ros/include/sensor_msgs/point_field_conversion.h new file mode 100644 index 0000000..473b853 --- /dev/null +++ b/thirdparty/ros/include/sensor_msgs/point_field_conversion.h @@ -0,0 +1,178 @@ +/* + * Software License Agreement (BSD License) + * + * Robot Operating System code by the University of Osnabrück + * Copyright (c) 2015, University of Osnabrück + * 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. + * + * + * + * point_field_conversion.h + * + * Created on: 16.07.2015 + * Authors: Sebastian Pütz + */ + +#ifndef SENSOR_MSGS_POINT_FIELD_CONVERSION_H +#define SENSOR_MSGS_POINT_FIELD_CONVERSION_H + +/** + * \brief This file provides a type to enum mapping for the different + * PointField types and methods to read and write in + * a PointCloud2 buffer for the different PointField types. + * \author Sebastian Pütz + */ +namespace sensor_msgs{ + /*! + * \Enum to type mapping. + */ + template struct pointFieldTypeAsType {}; + template<> struct pointFieldTypeAsType { typedef int8_t type; }; + template<> struct pointFieldTypeAsType { typedef uint8_t type; }; + template<> struct pointFieldTypeAsType { typedef int16_t type; }; + template<> struct pointFieldTypeAsType { typedef uint16_t type; }; + template<> struct pointFieldTypeAsType { typedef int32_t type; }; + template<> struct pointFieldTypeAsType { typedef uint32_t type; }; + template<> struct pointFieldTypeAsType { typedef float type; }; + template<> struct pointFieldTypeAsType { typedef double type; }; + + /*! + * \Type to enum mapping. + */ + template struct typeAsPointFieldType {}; + template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::INT8; }; + template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::UINT8; }; + template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::INT16; }; + template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::UINT16; }; + template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::INT32; }; + template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::UINT32; }; + template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::FLOAT32; }; + template<> struct typeAsPointFieldType { static const uint8_t value = sensor_msgs::PointField::FLOAT64; }; + + /*! + * \Converts a value at the given pointer position, interpreted as the datatype + * specified by the given template argument point_field_type, to the given + * template type T and returns it. + * \param data_ptr pointer into the point cloud 2 buffer + * \tparam point_field_type sensor_msgs::PointField datatype value + * \tparam T return type + */ + template + inline T readPointCloud2BufferValue(const unsigned char* data_ptr){ + typedef typename pointFieldTypeAsType::type type; + return static_cast(*(reinterpret_cast(data_ptr))); + } + + /*! + * \Converts a value at the given pointer position interpreted as the datatype + * specified by the given datatype parameter to the given template type and returns it. + * \param data_ptr pointer into the point cloud 2 buffer + * \param datatype sensor_msgs::PointField datatype value + * \tparam T return type + */ + template + inline T readPointCloud2BufferValue(const unsigned char* data_ptr, const unsigned char datatype){ + switch(datatype){ + case sensor_msgs::PointField::INT8: + return readPointCloud2BufferValue(data_ptr); + case sensor_msgs::PointField::UINT8: + return readPointCloud2BufferValue(data_ptr); + case sensor_msgs::PointField::INT16: + return readPointCloud2BufferValue(data_ptr); + case sensor_msgs::PointField::UINT16: + return readPointCloud2BufferValue(data_ptr); + case sensor_msgs::PointField::INT32: + return readPointCloud2BufferValue(data_ptr); + case sensor_msgs::PointField::UINT32: + return readPointCloud2BufferValue(data_ptr); + case sensor_msgs::PointField::FLOAT32: + return readPointCloud2BufferValue(data_ptr); + case sensor_msgs::PointField::FLOAT64: + return readPointCloud2BufferValue(data_ptr); + } + } + + /*! + * \Inserts a given value at the given point position interpreted as the datatype + * specified by the template argument point_field_type. + * \param data_ptr pointer into the point cloud 2 buffer + * \param value the value to insert + * \tparam point_field_type sensor_msgs::PointField datatype value + * \tparam T type of the value to insert + */ + template + inline void writePointCloud2BufferValue(unsigned char* data_ptr, T value){ + typedef typename pointFieldTypeAsType::type type; + *(reinterpret_cast(data_ptr)) = static_cast(value); + } + + /*! + * \Inserts a given value at the given point position interpreted as the datatype + * specified by the given datatype parameter. + * \param data_ptr pointer into the point cloud 2 buffer + * \param datatype sensor_msgs::PointField datatype value + * \param value the value to insert + * \tparam T type of the value to insert + */ + template + inline void writePointCloud2BufferValue(unsigned char* data_ptr, const unsigned char datatype, T value){ + switch(datatype){ + case sensor_msgs::PointField::INT8: + writePointCloud2BufferValue(data_ptr, value); + break; + case sensor_msgs::PointField::UINT8: + writePointCloud2BufferValue(data_ptr, value); + break; + case sensor_msgs::PointField::INT16: + writePointCloud2BufferValue(data_ptr, value); + break; + case sensor_msgs::PointField::UINT16: + writePointCloud2BufferValue(data_ptr, value); + break; + case sensor_msgs::PointField::INT32: + writePointCloud2BufferValue(data_ptr, value); + break; + case sensor_msgs::PointField::UINT32: + writePointCloud2BufferValue(data_ptr, value); + break; + case sensor_msgs::PointField::FLOAT32: + writePointCloud2BufferValue(data_ptr, value); + break; + case sensor_msgs::PointField::FLOAT64: + writePointCloud2BufferValue(data_ptr, value); + break; + } + } +} + +#endif /* point_field_conversion.h */ diff --git a/thirdparty/ros/include/std_msgs/Bool.h b/thirdparty/ros/include/std_msgs/Bool.h new file mode 100644 index 0000000..951197f --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Bool.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Bool.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_BOOL_H +#define STD_MSGS_MESSAGE_BOOL_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Bool_ +{ + typedef Bool_ Type; + + Bool_() + : data(false) { + } + Bool_(const ContainerAllocator& _alloc) + : data(false) { + (void)_alloc; + } + + + + typedef uint8_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Bool_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Bool_ const> ConstPtr; + +}; // struct Bool_ + +typedef ::std_msgs::Bool_ > Bool; + +typedef boost::shared_ptr< ::std_msgs::Bool > BoolPtr; +typedef boost::shared_ptr< ::std_msgs::Bool const> BoolConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Bool_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Bool_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Bool_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Bool_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Bool_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Bool_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Bool_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Bool_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Bool_ > +{ + static const char* value() + { + return "8b94c1b53db61fb6aed406028ad6332a"; + } + + static const char* value(const ::std_msgs::Bool_&) { return value(); } + static const uint64_t static_value1 = 0x8b94c1b53db61fb6ULL; + static const uint64_t static_value2 = 0xaed406028ad6332aULL; +}; + +template +struct DataType< ::std_msgs::Bool_ > +{ + static const char* value() + { + return "std_msgs/Bool"; + } + + static const char* value(const ::std_msgs::Bool_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Bool_ > +{ + static const char* value() + { + return "bool data\n\ +"; + } + + static const char* value(const ::std_msgs::Bool_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Bool_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Bool_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Bool_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Bool_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_BOOL_H diff --git a/thirdparty/ros/include/std_msgs/Byte.h b/thirdparty/ros/include/std_msgs/Byte.h new file mode 100644 index 0000000..2f131e8 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Byte.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Byte.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_BYTE_H +#define STD_MSGS_MESSAGE_BYTE_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Byte_ +{ + typedef Byte_ Type; + + Byte_() + : data(0) { + } + Byte_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef int8_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Byte_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Byte_ const> ConstPtr; + +}; // struct Byte_ + +typedef ::std_msgs::Byte_ > Byte; + +typedef boost::shared_ptr< ::std_msgs::Byte > BytePtr; +typedef boost::shared_ptr< ::std_msgs::Byte const> ByteConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Byte_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Byte_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Byte_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Byte_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Byte_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Byte_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Byte_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Byte_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Byte_ > +{ + static const char* value() + { + return "ad736a2e8818154c487bb80fe42ce43b"; + } + + static const char* value(const ::std_msgs::Byte_&) { return value(); } + static const uint64_t static_value1 = 0xad736a2e8818154cULL; + static const uint64_t static_value2 = 0x487bb80fe42ce43bULL; +}; + +template +struct DataType< ::std_msgs::Byte_ > +{ + static const char* value() + { + return "std_msgs/Byte"; + } + + static const char* value(const ::std_msgs::Byte_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Byte_ > +{ + static const char* value() + { + return "byte data\n\ +"; + } + + static const char* value(const ::std_msgs::Byte_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Byte_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Byte_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Byte_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Byte_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_BYTE_H diff --git a/thirdparty/ros/include/std_msgs/ByteMultiArray.h b/thirdparty/ros/include/std_msgs/ByteMultiArray.h new file mode 100644 index 0000000..0594ad2 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/ByteMultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/ByteMultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_BYTEMULTIARRAY_H +#define STD_MSGS_MESSAGE_BYTEMULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct ByteMultiArray_ +{ + typedef ByteMultiArray_ Type; + + ByteMultiArray_() + : layout() + , data() { + } + ByteMultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::ByteMultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::ByteMultiArray_ const> ConstPtr; + +}; // struct ByteMultiArray_ + +typedef ::std_msgs::ByteMultiArray_ > ByteMultiArray; + +typedef boost::shared_ptr< ::std_msgs::ByteMultiArray > ByteMultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::ByteMultiArray const> ByteMultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::ByteMultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::ByteMultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::ByteMultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::ByteMultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::ByteMultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::ByteMultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::ByteMultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::ByteMultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::ByteMultiArray_ > +{ + static const char* value() + { + return "70ea476cbcfd65ac2f68f3cda1e891fe"; + } + + static const char* value(const ::std_msgs::ByteMultiArray_&) { return value(); } + static const uint64_t static_value1 = 0x70ea476cbcfd65acULL; + static const uint64_t static_value2 = 0x2f68f3cda1e891feULL; +}; + +template +struct DataType< ::std_msgs::ByteMultiArray_ > +{ + static const char* value() + { + return "std_msgs/ByteMultiArray"; + } + + static const char* value(const ::std_msgs::ByteMultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::ByteMultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +byte[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::ByteMultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::ByteMultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct ByteMultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::ByteMultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::ByteMultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_BYTEMULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/Char.h b/thirdparty/ros/include/std_msgs/Char.h new file mode 100644 index 0000000..c743fcc --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Char.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Char.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_CHAR_H +#define STD_MSGS_MESSAGE_CHAR_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Char_ +{ + typedef Char_ Type; + + Char_() + : data(0) { + } + Char_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef uint8_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Char_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Char_ const> ConstPtr; + +}; // struct Char_ + +typedef ::std_msgs::Char_ > Char; + +typedef boost::shared_ptr< ::std_msgs::Char > CharPtr; +typedef boost::shared_ptr< ::std_msgs::Char const> CharConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Char_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Char_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Char_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Char_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Char_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Char_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Char_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Char_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Char_ > +{ + static const char* value() + { + return "1bf77f25acecdedba0e224b162199717"; + } + + static const char* value(const ::std_msgs::Char_&) { return value(); } + static const uint64_t static_value1 = 0x1bf77f25acecdedbULL; + static const uint64_t static_value2 = 0xa0e224b162199717ULL; +}; + +template +struct DataType< ::std_msgs::Char_ > +{ + static const char* value() + { + return "std_msgs/Char"; + } + + static const char* value(const ::std_msgs::Char_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Char_ > +{ + static const char* value() + { + return "char data\n\ +"; + } + + static const char* value(const ::std_msgs::Char_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Char_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Char_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Char_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Char_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_CHAR_H diff --git a/thirdparty/ros/include/std_msgs/ColorRGBA.h b/thirdparty/ros/include/std_msgs/ColorRGBA.h new file mode 100644 index 0000000..8dcef5b --- /dev/null +++ b/thirdparty/ros/include/std_msgs/ColorRGBA.h @@ -0,0 +1,214 @@ +// Generated by gencpp from file std_msgs/ColorRGBA.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_COLORRGBA_H +#define STD_MSGS_MESSAGE_COLORRGBA_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct ColorRGBA_ +{ + typedef ColorRGBA_ Type; + + ColorRGBA_() + : r(0.0) + , g(0.0) + , b(0.0) + , a(0.0) { + } + ColorRGBA_(const ContainerAllocator& _alloc) + : r(0.0) + , g(0.0) + , b(0.0) + , a(0.0) { + (void)_alloc; + } + + + + typedef float _r_type; + _r_type r; + + typedef float _g_type; + _g_type g; + + typedef float _b_type; + _b_type b; + + typedef float _a_type; + _a_type a; + + + + + + typedef boost::shared_ptr< ::std_msgs::ColorRGBA_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::ColorRGBA_ const> ConstPtr; + +}; // struct ColorRGBA_ + +typedef ::std_msgs::ColorRGBA_ > ColorRGBA; + +typedef boost::shared_ptr< ::std_msgs::ColorRGBA > ColorRGBAPtr; +typedef boost::shared_ptr< ::std_msgs::ColorRGBA const> ColorRGBAConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::ColorRGBA_ & v) +{ +ros::message_operations::Printer< ::std_msgs::ColorRGBA_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::ColorRGBA_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::ColorRGBA_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::ColorRGBA_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::ColorRGBA_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::ColorRGBA_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::ColorRGBA_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::ColorRGBA_ > +{ + static const char* value() + { + return "a29a96539573343b1310c73607334b00"; + } + + static const char* value(const ::std_msgs::ColorRGBA_&) { return value(); } + static const uint64_t static_value1 = 0xa29a96539573343bULL; + static const uint64_t static_value2 = 0x1310c73607334b00ULL; +}; + +template +struct DataType< ::std_msgs::ColorRGBA_ > +{ + static const char* value() + { + return "std_msgs/ColorRGBA"; + } + + static const char* value(const ::std_msgs::ColorRGBA_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::ColorRGBA_ > +{ + static const char* value() + { + return "float32 r\n\ +float32 g\n\ +float32 b\n\ +float32 a\n\ +"; + } + + static const char* value(const ::std_msgs::ColorRGBA_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::ColorRGBA_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.r); + stream.next(m.g); + stream.next(m.b); + stream.next(m.a); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct ColorRGBA_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::ColorRGBA_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::ColorRGBA_& v) + { + s << indent << "r: "; + Printer::stream(s, indent + " ", v.r); + s << indent << "g: "; + Printer::stream(s, indent + " ", v.g); + s << indent << "b: "; + Printer::stream(s, indent + " ", v.b); + s << indent << "a: "; + Printer::stream(s, indent + " ", v.a); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_COLORRGBA_H diff --git a/thirdparty/ros/include/std_msgs/Duration.h b/thirdparty/ros/include/std_msgs/Duration.h new file mode 100644 index 0000000..40319b5 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Duration.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Duration.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_DURATION_H +#define STD_MSGS_MESSAGE_DURATION_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Duration_ +{ + typedef Duration_ Type; + + Duration_() + : data() { + } + Duration_(const ContainerAllocator& _alloc) + : data() { + (void)_alloc; + } + + + + typedef ros::Duration _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Duration_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Duration_ const> ConstPtr; + +}; // struct Duration_ + +typedef ::std_msgs::Duration_ > Duration; + +typedef boost::shared_ptr< ::std_msgs::Duration > DurationPtr; +typedef boost::shared_ptr< ::std_msgs::Duration const> DurationConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Duration_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Duration_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Duration_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Duration_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Duration_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Duration_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Duration_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Duration_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Duration_ > +{ + static const char* value() + { + return "3e286caf4241d664e55f3ad380e2ae46"; + } + + static const char* value(const ::std_msgs::Duration_&) { return value(); } + static const uint64_t static_value1 = 0x3e286caf4241d664ULL; + static const uint64_t static_value2 = 0xe55f3ad380e2ae46ULL; +}; + +template +struct DataType< ::std_msgs::Duration_ > +{ + static const char* value() + { + return "std_msgs/Duration"; + } + + static const char* value(const ::std_msgs::Duration_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Duration_ > +{ + static const char* value() + { + return "duration data\n\ +"; + } + + static const char* value(const ::std_msgs::Duration_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Duration_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Duration_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Duration_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Duration_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_DURATION_H diff --git a/thirdparty/ros/include/std_msgs/Empty.h b/thirdparty/ros/include/std_msgs/Empty.h new file mode 100644 index 0000000..cb0bacc --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Empty.h @@ -0,0 +1,179 @@ +// Generated by gencpp from file std_msgs/Empty.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_EMPTY_H +#define STD_MSGS_MESSAGE_EMPTY_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Empty_ +{ + typedef Empty_ Type; + + Empty_() + { + } + Empty_(const ContainerAllocator& _alloc) + { + (void)_alloc; + } + + + + + + + + typedef boost::shared_ptr< ::std_msgs::Empty_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Empty_ const> ConstPtr; + +}; // struct Empty_ + +typedef ::std_msgs::Empty_ > Empty; + +typedef boost::shared_ptr< ::std_msgs::Empty > EmptyPtr; +typedef boost::shared_ptr< ::std_msgs::Empty const> EmptyConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Empty_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Empty_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Empty_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Empty_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Empty_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Empty_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Empty_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Empty_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Empty_ > +{ + static const char* value() + { + return "d41d8cd98f00b204e9800998ecf8427e"; + } + + static const char* value(const ::std_msgs::Empty_&) { return value(); } + static const uint64_t static_value1 = 0xd41d8cd98f00b204ULL; + static const uint64_t static_value2 = 0xe9800998ecf8427eULL; +}; + +template +struct DataType< ::std_msgs::Empty_ > +{ + static const char* value() + { + return "std_msgs/Empty"; + } + + static const char* value(const ::std_msgs::Empty_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Empty_ > +{ + static const char* value() + { + return "\n\ +"; + } + + static const char* value(const ::std_msgs::Empty_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Empty_ > + { + template inline static void allInOne(Stream&, T) + {} + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Empty_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Empty_ > +{ + template static void stream(Stream&, const std::string&, const ::std_msgs::Empty_&) + {} +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_EMPTY_H diff --git a/thirdparty/ros/include/std_msgs/Float32.h b/thirdparty/ros/include/std_msgs/Float32.h new file mode 100644 index 0000000..0ac3fa1 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Float32.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Float32.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_FLOAT32_H +#define STD_MSGS_MESSAGE_FLOAT32_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Float32_ +{ + typedef Float32_ Type; + + Float32_() + : data(0.0) { + } + Float32_(const ContainerAllocator& _alloc) + : data(0.0) { + (void)_alloc; + } + + + + typedef float _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Float32_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Float32_ const> ConstPtr; + +}; // struct Float32_ + +typedef ::std_msgs::Float32_ > Float32; + +typedef boost::shared_ptr< ::std_msgs::Float32 > Float32Ptr; +typedef boost::shared_ptr< ::std_msgs::Float32 const> Float32ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Float32_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Float32_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Float32_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Float32_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Float32_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Float32_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Float32_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Float32_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Float32_ > +{ + static const char* value() + { + return "73fcbf46b49191e672908e50842a83d4"; + } + + static const char* value(const ::std_msgs::Float32_&) { return value(); } + static const uint64_t static_value1 = 0x73fcbf46b49191e6ULL; + static const uint64_t static_value2 = 0x72908e50842a83d4ULL; +}; + +template +struct DataType< ::std_msgs::Float32_ > +{ + static const char* value() + { + return "std_msgs/Float32"; + } + + static const char* value(const ::std_msgs::Float32_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Float32_ > +{ + static const char* value() + { + return "float32 data\n\ +"; + } + + static const char* value(const ::std_msgs::Float32_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Float32_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Float32_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Float32_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Float32_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_FLOAT32_H diff --git a/thirdparty/ros/include/std_msgs/Float32MultiArray.h b/thirdparty/ros/include/std_msgs/Float32MultiArray.h new file mode 100644 index 0000000..dfd1fa6 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Float32MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/Float32MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_FLOAT32MULTIARRAY_H +#define STD_MSGS_MESSAGE_FLOAT32MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct Float32MultiArray_ +{ + typedef Float32MultiArray_ Type; + + Float32MultiArray_() + : layout() + , data() { + } + Float32MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Float32MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Float32MultiArray_ const> ConstPtr; + +}; // struct Float32MultiArray_ + +typedef ::std_msgs::Float32MultiArray_ > Float32MultiArray; + +typedef boost::shared_ptr< ::std_msgs::Float32MultiArray > Float32MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::Float32MultiArray const> Float32MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Float32MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Float32MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Float32MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::Float32MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::Float32MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Float32MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Float32MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Float32MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Float32MultiArray_ > +{ + static const char* value() + { + return "6a40e0ffa6a17a503ac3f8616991b1f6"; + } + + static const char* value(const ::std_msgs::Float32MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0x6a40e0ffa6a17a50ULL; + static const uint64_t static_value2 = 0x3ac3f8616991b1f6ULL; +}; + +template +struct DataType< ::std_msgs::Float32MultiArray_ > +{ + static const char* value() + { + return "std_msgs/Float32MultiArray"; + } + + static const char* value(const ::std_msgs::Float32MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Float32MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +float32[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::Float32MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Float32MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Float32MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Float32MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Float32MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_FLOAT32MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/Float64.h b/thirdparty/ros/include/std_msgs/Float64.h new file mode 100644 index 0000000..d038016 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Float64.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Float64.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_FLOAT64_H +#define STD_MSGS_MESSAGE_FLOAT64_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Float64_ +{ + typedef Float64_ Type; + + Float64_() + : data(0.0) { + } + Float64_(const ContainerAllocator& _alloc) + : data(0.0) { + (void)_alloc; + } + + + + typedef double _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Float64_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Float64_ const> ConstPtr; + +}; // struct Float64_ + +typedef ::std_msgs::Float64_ > Float64; + +typedef boost::shared_ptr< ::std_msgs::Float64 > Float64Ptr; +typedef boost::shared_ptr< ::std_msgs::Float64 const> Float64ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Float64_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Float64_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Float64_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Float64_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Float64_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Float64_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Float64_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Float64_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Float64_ > +{ + static const char* value() + { + return "fdb28210bfa9d7c91146260178d9a584"; + } + + static const char* value(const ::std_msgs::Float64_&) { return value(); } + static const uint64_t static_value1 = 0xfdb28210bfa9d7c9ULL; + static const uint64_t static_value2 = 0x1146260178d9a584ULL; +}; + +template +struct DataType< ::std_msgs::Float64_ > +{ + static const char* value() + { + return "std_msgs/Float64"; + } + + static const char* value(const ::std_msgs::Float64_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Float64_ > +{ + static const char* value() + { + return "float64 data\n\ +"; + } + + static const char* value(const ::std_msgs::Float64_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Float64_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Float64_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Float64_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Float64_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_FLOAT64_H diff --git a/thirdparty/ros/include/std_msgs/Float64MultiArray.h b/thirdparty/ros/include/std_msgs/Float64MultiArray.h new file mode 100644 index 0000000..62683b3 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Float64MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/Float64MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_FLOAT64MULTIARRAY_H +#define STD_MSGS_MESSAGE_FLOAT64MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct Float64MultiArray_ +{ + typedef Float64MultiArray_ Type; + + Float64MultiArray_() + : layout() + , data() { + } + Float64MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Float64MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Float64MultiArray_ const> ConstPtr; + +}; // struct Float64MultiArray_ + +typedef ::std_msgs::Float64MultiArray_ > Float64MultiArray; + +typedef boost::shared_ptr< ::std_msgs::Float64MultiArray > Float64MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::Float64MultiArray const> Float64MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Float64MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Float64MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Float64MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::Float64MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::Float64MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Float64MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Float64MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Float64MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Float64MultiArray_ > +{ + static const char* value() + { + return "4b7d974086d4060e7db4613a7e6c3ba4"; + } + + static const char* value(const ::std_msgs::Float64MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0x4b7d974086d4060eULL; + static const uint64_t static_value2 = 0x7db4613a7e6c3ba4ULL; +}; + +template +struct DataType< ::std_msgs::Float64MultiArray_ > +{ + static const char* value() + { + return "std_msgs/Float64MultiArray"; + } + + static const char* value(const ::std_msgs::Float64MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Float64MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +float64[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::Float64MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Float64MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Float64MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Float64MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Float64MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_FLOAT64MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/Header.h b/thirdparty/ros/include/std_msgs/Header.h new file mode 100644 index 0000000..f8daebe --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Header.h @@ -0,0 +1,217 @@ +// Generated by gencpp from file std_msgs/Header.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_HEADER_H +#define STD_MSGS_MESSAGE_HEADER_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Header_ +{ + typedef Header_ Type; + + Header_() + : seq(0) + , stamp() + , frame_id() { + } + Header_(const ContainerAllocator& _alloc) + : seq(0) + , stamp() + , frame_id(_alloc) { + (void)_alloc; + } + + + + typedef uint32_t _seq_type; + _seq_type seq; + + typedef ros::Time _stamp_type; + _stamp_type stamp; + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _frame_id_type; + _frame_id_type frame_id; + + + + + + typedef boost::shared_ptr< ::std_msgs::Header_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Header_ const> ConstPtr; + +}; // struct Header_ + +typedef ::std_msgs::Header_ > Header; + +typedef boost::shared_ptr< ::std_msgs::Header > HeaderPtr; +typedef boost::shared_ptr< ::std_msgs::Header const> HeaderConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Header_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Header_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Header_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::Header_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::Header_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Header_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Header_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Header_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Header_ > +{ + static const char* value() + { + return "2176decaecbce78abc3b96ef049fabed"; + } + + static const char* value(const ::std_msgs::Header_&) { return value(); } + static const uint64_t static_value1 = 0x2176decaecbce78aULL; + static const uint64_t static_value2 = 0xbc3b96ef049fabedULL; +}; + +template +struct DataType< ::std_msgs::Header_ > +{ + static const char* value() + { + return "std_msgs/Header"; + } + + static const char* value(const ::std_msgs::Header_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Header_ > +{ + static const char* value() + { + return "# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')\n\ +# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +"; + } + + static const char* value(const ::std_msgs::Header_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Header_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.seq); + stream.next(m.stamp); + stream.next(m.frame_id); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Header_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Header_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Header_& v) + { + s << indent << "seq: "; + Printer::stream(s, indent + " ", v.seq); + s << indent << "stamp: "; + Printer::stream(s, indent + " ", v.stamp); + s << indent << "frame_id: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.frame_id); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_HEADER_H diff --git a/thirdparty/ros/include/std_msgs/Int16.h b/thirdparty/ros/include/std_msgs/Int16.h new file mode 100644 index 0000000..2fae55c --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Int16.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Int16.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_INT16_H +#define STD_MSGS_MESSAGE_INT16_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Int16_ +{ + typedef Int16_ Type; + + Int16_() + : data(0) { + } + Int16_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef int16_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Int16_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Int16_ const> ConstPtr; + +}; // struct Int16_ + +typedef ::std_msgs::Int16_ > Int16; + +typedef boost::shared_ptr< ::std_msgs::Int16 > Int16Ptr; +typedef boost::shared_ptr< ::std_msgs::Int16 const> Int16ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Int16_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Int16_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Int16_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Int16_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int16_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int16_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Int16_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Int16_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Int16_ > +{ + static const char* value() + { + return "8524586e34fbd7cb1c08c5f5f1ca0e57"; + } + + static const char* value(const ::std_msgs::Int16_&) { return value(); } + static const uint64_t static_value1 = 0x8524586e34fbd7cbULL; + static const uint64_t static_value2 = 0x1c08c5f5f1ca0e57ULL; +}; + +template +struct DataType< ::std_msgs::Int16_ > +{ + static const char* value() + { + return "std_msgs/Int16"; + } + + static const char* value(const ::std_msgs::Int16_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Int16_ > +{ + static const char* value() + { + return "int16 data\n\ +"; + } + + static const char* value(const ::std_msgs::Int16_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Int16_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Int16_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Int16_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Int16_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_INT16_H diff --git a/thirdparty/ros/include/std_msgs/Int16MultiArray.h b/thirdparty/ros/include/std_msgs/Int16MultiArray.h new file mode 100644 index 0000000..cc57fed --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Int16MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/Int16MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_INT16MULTIARRAY_H +#define STD_MSGS_MESSAGE_INT16MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct Int16MultiArray_ +{ + typedef Int16MultiArray_ Type; + + Int16MultiArray_() + : layout() + , data() { + } + Int16MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Int16MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Int16MultiArray_ const> ConstPtr; + +}; // struct Int16MultiArray_ + +typedef ::std_msgs::Int16MultiArray_ > Int16MultiArray; + +typedef boost::shared_ptr< ::std_msgs::Int16MultiArray > Int16MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::Int16MultiArray const> Int16MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Int16MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Int16MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Int16MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::Int16MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::Int16MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int16MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Int16MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Int16MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Int16MultiArray_ > +{ + static const char* value() + { + return "d9338d7f523fcb692fae9d0a0e9f067c"; + } + + static const char* value(const ::std_msgs::Int16MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0xd9338d7f523fcb69ULL; + static const uint64_t static_value2 = 0x2fae9d0a0e9f067cULL; +}; + +template +struct DataType< ::std_msgs::Int16MultiArray_ > +{ + static const char* value() + { + return "std_msgs/Int16MultiArray"; + } + + static const char* value(const ::std_msgs::Int16MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Int16MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +int16[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::Int16MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Int16MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Int16MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Int16MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Int16MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_INT16MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/Int32.h b/thirdparty/ros/include/std_msgs/Int32.h new file mode 100644 index 0000000..2c03215 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Int32.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Int32.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_INT32_H +#define STD_MSGS_MESSAGE_INT32_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Int32_ +{ + typedef Int32_ Type; + + Int32_() + : data(0) { + } + Int32_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef int32_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Int32_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Int32_ const> ConstPtr; + +}; // struct Int32_ + +typedef ::std_msgs::Int32_ > Int32; + +typedef boost::shared_ptr< ::std_msgs::Int32 > Int32Ptr; +typedef boost::shared_ptr< ::std_msgs::Int32 const> Int32ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Int32_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Int32_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Int32_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Int32_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int32_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int32_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Int32_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Int32_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Int32_ > +{ + static const char* value() + { + return "da5909fbe378aeaf85e547e830cc1bb7"; + } + + static const char* value(const ::std_msgs::Int32_&) { return value(); } + static const uint64_t static_value1 = 0xda5909fbe378aeafULL; + static const uint64_t static_value2 = 0x85e547e830cc1bb7ULL; +}; + +template +struct DataType< ::std_msgs::Int32_ > +{ + static const char* value() + { + return "std_msgs/Int32"; + } + + static const char* value(const ::std_msgs::Int32_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Int32_ > +{ + static const char* value() + { + return "int32 data\n\ +"; + } + + static const char* value(const ::std_msgs::Int32_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Int32_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Int32_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Int32_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Int32_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_INT32_H diff --git a/thirdparty/ros/include/std_msgs/Int32MultiArray.h b/thirdparty/ros/include/std_msgs/Int32MultiArray.h new file mode 100644 index 0000000..47deadb --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Int32MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/Int32MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_INT32MULTIARRAY_H +#define STD_MSGS_MESSAGE_INT32MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct Int32MultiArray_ +{ + typedef Int32MultiArray_ Type; + + Int32MultiArray_() + : layout() + , data() { + } + Int32MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Int32MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Int32MultiArray_ const> ConstPtr; + +}; // struct Int32MultiArray_ + +typedef ::std_msgs::Int32MultiArray_ > Int32MultiArray; + +typedef boost::shared_ptr< ::std_msgs::Int32MultiArray > Int32MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::Int32MultiArray const> Int32MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Int32MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Int32MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Int32MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::Int32MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::Int32MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int32MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Int32MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Int32MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Int32MultiArray_ > +{ + static const char* value() + { + return "1d99f79f8b325b44fee908053e9c945b"; + } + + static const char* value(const ::std_msgs::Int32MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0x1d99f79f8b325b44ULL; + static const uint64_t static_value2 = 0xfee908053e9c945bULL; +}; + +template +struct DataType< ::std_msgs::Int32MultiArray_ > +{ + static const char* value() + { + return "std_msgs/Int32MultiArray"; + } + + static const char* value(const ::std_msgs::Int32MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Int32MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +int32[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::Int32MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Int32MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Int32MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Int32MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Int32MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_INT32MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/Int64.h b/thirdparty/ros/include/std_msgs/Int64.h new file mode 100644 index 0000000..d53ed02 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Int64.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Int64.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_INT64_H +#define STD_MSGS_MESSAGE_INT64_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Int64_ +{ + typedef Int64_ Type; + + Int64_() + : data(0) { + } + Int64_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef int64_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Int64_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Int64_ const> ConstPtr; + +}; // struct Int64_ + +typedef ::std_msgs::Int64_ > Int64; + +typedef boost::shared_ptr< ::std_msgs::Int64 > Int64Ptr; +typedef boost::shared_ptr< ::std_msgs::Int64 const> Int64ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Int64_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Int64_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Int64_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Int64_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int64_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int64_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Int64_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Int64_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Int64_ > +{ + static const char* value() + { + return "34add168574510e6e17f5d23ecc077ef"; + } + + static const char* value(const ::std_msgs::Int64_&) { return value(); } + static const uint64_t static_value1 = 0x34add168574510e6ULL; + static const uint64_t static_value2 = 0xe17f5d23ecc077efULL; +}; + +template +struct DataType< ::std_msgs::Int64_ > +{ + static const char* value() + { + return "std_msgs/Int64"; + } + + static const char* value(const ::std_msgs::Int64_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Int64_ > +{ + static const char* value() + { + return "int64 data\n\ +"; + } + + static const char* value(const ::std_msgs::Int64_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Int64_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Int64_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Int64_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Int64_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_INT64_H diff --git a/thirdparty/ros/include/std_msgs/Int64MultiArray.h b/thirdparty/ros/include/std_msgs/Int64MultiArray.h new file mode 100644 index 0000000..0c209a1 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Int64MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/Int64MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_INT64MULTIARRAY_H +#define STD_MSGS_MESSAGE_INT64MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct Int64MultiArray_ +{ + typedef Int64MultiArray_ Type; + + Int64MultiArray_() + : layout() + , data() { + } + Int64MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Int64MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Int64MultiArray_ const> ConstPtr; + +}; // struct Int64MultiArray_ + +typedef ::std_msgs::Int64MultiArray_ > Int64MultiArray; + +typedef boost::shared_ptr< ::std_msgs::Int64MultiArray > Int64MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::Int64MultiArray const> Int64MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Int64MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Int64MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Int64MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::Int64MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::Int64MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int64MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Int64MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Int64MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Int64MultiArray_ > +{ + static const char* value() + { + return "54865aa6c65be0448113a2afc6a49270"; + } + + static const char* value(const ::std_msgs::Int64MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0x54865aa6c65be044ULL; + static const uint64_t static_value2 = 0x8113a2afc6a49270ULL; +}; + +template +struct DataType< ::std_msgs::Int64MultiArray_ > +{ + static const char* value() + { + return "std_msgs/Int64MultiArray"; + } + + static const char* value(const ::std_msgs::Int64MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Int64MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +int64[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::Int64MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Int64MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Int64MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Int64MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Int64MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_INT64MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/Int8.h b/thirdparty/ros/include/std_msgs/Int8.h new file mode 100644 index 0000000..4c1f164 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Int8.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Int8.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_INT8_H +#define STD_MSGS_MESSAGE_INT8_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Int8_ +{ + typedef Int8_ Type; + + Int8_() + : data(0) { + } + Int8_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef int8_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Int8_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Int8_ const> ConstPtr; + +}; // struct Int8_ + +typedef ::std_msgs::Int8_ > Int8; + +typedef boost::shared_ptr< ::std_msgs::Int8 > Int8Ptr; +typedef boost::shared_ptr< ::std_msgs::Int8 const> Int8ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Int8_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Int8_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Int8_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Int8_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int8_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int8_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Int8_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Int8_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Int8_ > +{ + static const char* value() + { + return "27ffa0c9c4b8fb8492252bcad9e5c57b"; + } + + static const char* value(const ::std_msgs::Int8_&) { return value(); } + static const uint64_t static_value1 = 0x27ffa0c9c4b8fb84ULL; + static const uint64_t static_value2 = 0x92252bcad9e5c57bULL; +}; + +template +struct DataType< ::std_msgs::Int8_ > +{ + static const char* value() + { + return "std_msgs/Int8"; + } + + static const char* value(const ::std_msgs::Int8_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Int8_ > +{ + static const char* value() + { + return "int8 data\n\ +"; + } + + static const char* value(const ::std_msgs::Int8_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Int8_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Int8_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Int8_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Int8_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_INT8_H diff --git a/thirdparty/ros/include/std_msgs/Int8MultiArray.h b/thirdparty/ros/include/std_msgs/Int8MultiArray.h new file mode 100644 index 0000000..3784d3b --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Int8MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/Int8MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_INT8MULTIARRAY_H +#define STD_MSGS_MESSAGE_INT8MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct Int8MultiArray_ +{ + typedef Int8MultiArray_ Type; + + Int8MultiArray_() + : layout() + , data() { + } + Int8MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Int8MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Int8MultiArray_ const> ConstPtr; + +}; // struct Int8MultiArray_ + +typedef ::std_msgs::Int8MultiArray_ > Int8MultiArray; + +typedef boost::shared_ptr< ::std_msgs::Int8MultiArray > Int8MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::Int8MultiArray const> Int8MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Int8MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Int8MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Int8MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::Int8MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::Int8MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Int8MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Int8MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Int8MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Int8MultiArray_ > +{ + static const char* value() + { + return "d7c1af35a1b4781bbe79e03dd94b7c13"; + } + + static const char* value(const ::std_msgs::Int8MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0xd7c1af35a1b4781bULL; + static const uint64_t static_value2 = 0xbe79e03dd94b7c13ULL; +}; + +template +struct DataType< ::std_msgs::Int8MultiArray_ > +{ + static const char* value() + { + return "std_msgs/Int8MultiArray"; + } + + static const char* value(const ::std_msgs::Int8MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Int8MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +int8[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::Int8MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Int8MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Int8MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Int8MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Int8MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_INT8MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/MultiArrayDimension.h b/thirdparty/ros/include/std_msgs/MultiArrayDimension.h new file mode 100644 index 0000000..94bfdc6 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/MultiArrayDimension.h @@ -0,0 +1,205 @@ +// Generated by gencpp from file std_msgs/MultiArrayDimension.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_MULTIARRAYDIMENSION_H +#define STD_MSGS_MESSAGE_MULTIARRAYDIMENSION_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct MultiArrayDimension_ +{ + typedef MultiArrayDimension_ Type; + + MultiArrayDimension_() + : label() + , size(0) + , stride(0) { + } + MultiArrayDimension_(const ContainerAllocator& _alloc) + : label(_alloc) + , size(0) + , stride(0) { + (void)_alloc; + } + + + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _label_type; + _label_type label; + + typedef uint32_t _size_type; + _size_type size; + + typedef uint32_t _stride_type; + _stride_type stride; + + + + + + typedef boost::shared_ptr< ::std_msgs::MultiArrayDimension_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::MultiArrayDimension_ const> ConstPtr; + +}; // struct MultiArrayDimension_ + +typedef ::std_msgs::MultiArrayDimension_ > MultiArrayDimension; + +typedef boost::shared_ptr< ::std_msgs::MultiArrayDimension > MultiArrayDimensionPtr; +typedef boost::shared_ptr< ::std_msgs::MultiArrayDimension const> MultiArrayDimensionConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::MultiArrayDimension_ & v) +{ +ros::message_operations::Printer< ::std_msgs::MultiArrayDimension_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::MultiArrayDimension_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::MultiArrayDimension_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::MultiArrayDimension_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::MultiArrayDimension_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::MultiArrayDimension_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::MultiArrayDimension_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::MultiArrayDimension_ > +{ + static const char* value() + { + return "4cd0c83a8683deae40ecdac60e53bfa8"; + } + + static const char* value(const ::std_msgs::MultiArrayDimension_&) { return value(); } + static const uint64_t static_value1 = 0x4cd0c83a8683deaeULL; + static const uint64_t static_value2 = 0x40ecdac60e53bfa8ULL; +}; + +template +struct DataType< ::std_msgs::MultiArrayDimension_ > +{ + static const char* value() + { + return "std_msgs/MultiArrayDimension"; + } + + static const char* value(const ::std_msgs::MultiArrayDimension_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::MultiArrayDimension_ > +{ + static const char* value() + { + return "string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::MultiArrayDimension_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::MultiArrayDimension_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.label); + stream.next(m.size); + stream.next(m.stride); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct MultiArrayDimension_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::MultiArrayDimension_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::MultiArrayDimension_& v) + { + s << indent << "label: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.label); + s << indent << "size: "; + Printer::stream(s, indent + " ", v.size); + s << indent << "stride: "; + Printer::stream(s, indent + " ", v.stride); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_MULTIARRAYDIMENSION_H diff --git a/thirdparty/ros/include/std_msgs/MultiArrayLayout.h b/thirdparty/ros/include/std_msgs/MultiArrayLayout.h new file mode 100644 index 0000000..3b73764 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/MultiArrayLayout.h @@ -0,0 +1,233 @@ +// Generated by gencpp from file std_msgs/MultiArrayLayout.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_MULTIARRAYLAYOUT_H +#define STD_MSGS_MESSAGE_MULTIARRAYLAYOUT_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct MultiArrayLayout_ +{ + typedef MultiArrayLayout_ Type; + + MultiArrayLayout_() + : dim() + , data_offset(0) { + } + MultiArrayLayout_(const ContainerAllocator& _alloc) + : dim(_alloc) + , data_offset(0) { + (void)_alloc; + } + + + + typedef std::vector< ::std_msgs::MultiArrayDimension_ , typename ContainerAllocator::template rebind< ::std_msgs::MultiArrayDimension_ >::other > _dim_type; + _dim_type dim; + + typedef uint32_t _data_offset_type; + _data_offset_type data_offset; + + + + + + typedef boost::shared_ptr< ::std_msgs::MultiArrayLayout_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::MultiArrayLayout_ const> ConstPtr; + +}; // struct MultiArrayLayout_ + +typedef ::std_msgs::MultiArrayLayout_ > MultiArrayLayout; + +typedef boost::shared_ptr< ::std_msgs::MultiArrayLayout > MultiArrayLayoutPtr; +typedef boost::shared_ptr< ::std_msgs::MultiArrayLayout const> MultiArrayLayoutConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::MultiArrayLayout_ & v) +{ +ros::message_operations::Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::MultiArrayLayout_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::MultiArrayLayout_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::MultiArrayLayout_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::MultiArrayLayout_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::MultiArrayLayout_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::MultiArrayLayout_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::MultiArrayLayout_ > +{ + static const char* value() + { + return "0fed2a11c13e11c5571b4e2a995a91a3"; + } + + static const char* value(const ::std_msgs::MultiArrayLayout_&) { return value(); } + static const uint64_t static_value1 = 0x0fed2a11c13e11c5ULL; + static const uint64_t static_value2 = 0x571b4e2a995a91a3ULL; +}; + +template +struct DataType< ::std_msgs::MultiArrayLayout_ > +{ + static const char* value() + { + return "std_msgs/MultiArrayLayout"; + } + + static const char* value(const ::std_msgs::MultiArrayLayout_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::MultiArrayLayout_ > +{ + static const char* value() + { + return "# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::MultiArrayLayout_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::MultiArrayLayout_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.dim); + stream.next(m.data_offset); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct MultiArrayLayout_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::MultiArrayLayout_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::MultiArrayLayout_& v) + { + s << indent << "dim[]" << std::endl; + for (size_t i = 0; i < v.dim.size(); ++i) + { + s << indent << " dim[" << i << "]: "; + s << std::endl; + s << indent; + Printer< ::std_msgs::MultiArrayDimension_ >::stream(s, indent + " ", v.dim[i]); + } + s << indent << "data_offset: "; + Printer::stream(s, indent + " ", v.data_offset); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_MULTIARRAYLAYOUT_H diff --git a/thirdparty/ros/include/std_msgs/String.h b/thirdparty/ros/include/std_msgs/String.h new file mode 100644 index 0000000..d73c8e1 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/String.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/String.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_STRING_H +#define STD_MSGS_MESSAGE_STRING_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct String_ +{ + typedef String_ Type; + + String_() + : data() { + } + String_(const ContainerAllocator& _alloc) + : data(_alloc) { + (void)_alloc; + } + + + + typedef std::basic_string, typename ContainerAllocator::template rebind::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::String_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::String_ const> ConstPtr; + +}; // struct String_ + +typedef ::std_msgs::String_ > String; + +typedef boost::shared_ptr< ::std_msgs::String > StringPtr; +typedef boost::shared_ptr< ::std_msgs::String const> StringConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::String_ & v) +{ +ros::message_operations::Printer< ::std_msgs::String_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::String_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::String_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::String_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::String_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::String_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::String_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::String_ > +{ + static const char* value() + { + return "992ce8a1687cec8c8bd883ec73ca41d1"; + } + + static const char* value(const ::std_msgs::String_&) { return value(); } + static const uint64_t static_value1 = 0x992ce8a1687cec8cULL; + static const uint64_t static_value2 = 0x8bd883ec73ca41d1ULL; +}; + +template +struct DataType< ::std_msgs::String_ > +{ + static const char* value() + { + return "std_msgs/String"; + } + + static const char* value(const ::std_msgs::String_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::String_ > +{ + static const char* value() + { + return "string data\n\ +"; + } + + static const char* value(const ::std_msgs::String_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::String_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct String_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::String_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::String_& v) + { + s << indent << "data: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_STRING_H diff --git a/thirdparty/ros/include/std_msgs/Time.h b/thirdparty/ros/include/std_msgs/Time.h new file mode 100644 index 0000000..e47fec4 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/Time.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/Time.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_TIME_H +#define STD_MSGS_MESSAGE_TIME_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct Time_ +{ + typedef Time_ Type; + + Time_() + : data() { + } + Time_(const ContainerAllocator& _alloc) + : data() { + (void)_alloc; + } + + + + typedef ros::Time _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::Time_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::Time_ const> ConstPtr; + +}; // struct Time_ + +typedef ::std_msgs::Time_ > Time; + +typedef boost::shared_ptr< ::std_msgs::Time > TimePtr; +typedef boost::shared_ptr< ::std_msgs::Time const> TimeConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::Time_ & v) +{ +ros::message_operations::Printer< ::std_msgs::Time_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::Time_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::Time_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Time_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::Time_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::Time_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::Time_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::Time_ > +{ + static const char* value() + { + return "cd7166c74c552c311fbcc2fe5a7bc289"; + } + + static const char* value(const ::std_msgs::Time_&) { return value(); } + static const uint64_t static_value1 = 0xcd7166c74c552c31ULL; + static const uint64_t static_value2 = 0x1fbcc2fe5a7bc289ULL; +}; + +template +struct DataType< ::std_msgs::Time_ > +{ + static const char* value() + { + return "std_msgs/Time"; + } + + static const char* value(const ::std_msgs::Time_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::Time_ > +{ + static const char* value() + { + return "time data\n\ +"; + } + + static const char* value(const ::std_msgs::Time_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::Time_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct Time_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::Time_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::Time_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_TIME_H diff --git a/thirdparty/ros/include/std_msgs/UInt16.h b/thirdparty/ros/include/std_msgs/UInt16.h new file mode 100644 index 0000000..377ae13 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/UInt16.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/UInt16.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_UINT16_H +#define STD_MSGS_MESSAGE_UINT16_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct UInt16_ +{ + typedef UInt16_ Type; + + UInt16_() + : data(0) { + } + UInt16_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef uint16_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::UInt16_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::UInt16_ const> ConstPtr; + +}; // struct UInt16_ + +typedef ::std_msgs::UInt16_ > UInt16; + +typedef boost::shared_ptr< ::std_msgs::UInt16 > UInt16Ptr; +typedef boost::shared_ptr< ::std_msgs::UInt16 const> UInt16ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::UInt16_ & v) +{ +ros::message_operations::Printer< ::std_msgs::UInt16_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::UInt16_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::UInt16_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt16_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt16_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::UInt16_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::UInt16_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::UInt16_ > +{ + static const char* value() + { + return "1df79edf208b629fe6b81923a544552d"; + } + + static const char* value(const ::std_msgs::UInt16_&) { return value(); } + static const uint64_t static_value1 = 0x1df79edf208b629fULL; + static const uint64_t static_value2 = 0xe6b81923a544552dULL; +}; + +template +struct DataType< ::std_msgs::UInt16_ > +{ + static const char* value() + { + return "std_msgs/UInt16"; + } + + static const char* value(const ::std_msgs::UInt16_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::UInt16_ > +{ + static const char* value() + { + return "uint16 data\n\ +"; + } + + static const char* value(const ::std_msgs::UInt16_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::UInt16_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct UInt16_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::UInt16_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::UInt16_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_UINT16_H diff --git a/thirdparty/ros/include/std_msgs/UInt16MultiArray.h b/thirdparty/ros/include/std_msgs/UInt16MultiArray.h new file mode 100644 index 0000000..a8deaeb --- /dev/null +++ b/thirdparty/ros/include/std_msgs/UInt16MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/UInt16MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_UINT16MULTIARRAY_H +#define STD_MSGS_MESSAGE_UINT16MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct UInt16MultiArray_ +{ + typedef UInt16MultiArray_ Type; + + UInt16MultiArray_() + : layout() + , data() { + } + UInt16MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::UInt16MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::UInt16MultiArray_ const> ConstPtr; + +}; // struct UInt16MultiArray_ + +typedef ::std_msgs::UInt16MultiArray_ > UInt16MultiArray; + +typedef boost::shared_ptr< ::std_msgs::UInt16MultiArray > UInt16MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::UInt16MultiArray const> UInt16MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::UInt16MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::UInt16MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::UInt16MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::UInt16MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::UInt16MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt16MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::UInt16MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::UInt16MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::UInt16MultiArray_ > +{ + static const char* value() + { + return "52f264f1c973c4b73790d384c6cb4484"; + } + + static const char* value(const ::std_msgs::UInt16MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0x52f264f1c973c4b7ULL; + static const uint64_t static_value2 = 0x3790d384c6cb4484ULL; +}; + +template +struct DataType< ::std_msgs::UInt16MultiArray_ > +{ + static const char* value() + { + return "std_msgs/UInt16MultiArray"; + } + + static const char* value(const ::std_msgs::UInt16MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::UInt16MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +uint16[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::UInt16MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::UInt16MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct UInt16MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::UInt16MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::UInt16MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_UINT16MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/UInt32.h b/thirdparty/ros/include/std_msgs/UInt32.h new file mode 100644 index 0000000..2d9f745 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/UInt32.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/UInt32.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_UINT32_H +#define STD_MSGS_MESSAGE_UINT32_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct UInt32_ +{ + typedef UInt32_ Type; + + UInt32_() + : data(0) { + } + UInt32_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef uint32_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::UInt32_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::UInt32_ const> ConstPtr; + +}; // struct UInt32_ + +typedef ::std_msgs::UInt32_ > UInt32; + +typedef boost::shared_ptr< ::std_msgs::UInt32 > UInt32Ptr; +typedef boost::shared_ptr< ::std_msgs::UInt32 const> UInt32ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::UInt32_ & v) +{ +ros::message_operations::Printer< ::std_msgs::UInt32_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::UInt32_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::UInt32_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt32_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt32_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::UInt32_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::UInt32_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::UInt32_ > +{ + static const char* value() + { + return "304a39449588c7f8ce2df6e8001c5fce"; + } + + static const char* value(const ::std_msgs::UInt32_&) { return value(); } + static const uint64_t static_value1 = 0x304a39449588c7f8ULL; + static const uint64_t static_value2 = 0xce2df6e8001c5fceULL; +}; + +template +struct DataType< ::std_msgs::UInt32_ > +{ + static const char* value() + { + return "std_msgs/UInt32"; + } + + static const char* value(const ::std_msgs::UInt32_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::UInt32_ > +{ + static const char* value() + { + return "uint32 data\n\ +"; + } + + static const char* value(const ::std_msgs::UInt32_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::UInt32_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct UInt32_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::UInt32_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::UInt32_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_UINT32_H diff --git a/thirdparty/ros/include/std_msgs/UInt32MultiArray.h b/thirdparty/ros/include/std_msgs/UInt32MultiArray.h new file mode 100644 index 0000000..2fd8f3a --- /dev/null +++ b/thirdparty/ros/include/std_msgs/UInt32MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/UInt32MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_UINT32MULTIARRAY_H +#define STD_MSGS_MESSAGE_UINT32MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct UInt32MultiArray_ +{ + typedef UInt32MultiArray_ Type; + + UInt32MultiArray_() + : layout() + , data() { + } + UInt32MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::UInt32MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::UInt32MultiArray_ const> ConstPtr; + +}; // struct UInt32MultiArray_ + +typedef ::std_msgs::UInt32MultiArray_ > UInt32MultiArray; + +typedef boost::shared_ptr< ::std_msgs::UInt32MultiArray > UInt32MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::UInt32MultiArray const> UInt32MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::UInt32MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::UInt32MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::UInt32MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::UInt32MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::UInt32MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt32MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::UInt32MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::UInt32MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::UInt32MultiArray_ > +{ + static const char* value() + { + return "4d6a180abc9be191b96a7eda6c8a233d"; + } + + static const char* value(const ::std_msgs::UInt32MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0x4d6a180abc9be191ULL; + static const uint64_t static_value2 = 0xb96a7eda6c8a233dULL; +}; + +template +struct DataType< ::std_msgs::UInt32MultiArray_ > +{ + static const char* value() + { + return "std_msgs/UInt32MultiArray"; + } + + static const char* value(const ::std_msgs::UInt32MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::UInt32MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +uint32[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::UInt32MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::UInt32MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct UInt32MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::UInt32MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::UInt32MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_UINT32MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/UInt64.h b/thirdparty/ros/include/std_msgs/UInt64.h new file mode 100644 index 0000000..448393d --- /dev/null +++ b/thirdparty/ros/include/std_msgs/UInt64.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/UInt64.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_UINT64_H +#define STD_MSGS_MESSAGE_UINT64_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct UInt64_ +{ + typedef UInt64_ Type; + + UInt64_() + : data(0) { + } + UInt64_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef uint64_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::UInt64_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::UInt64_ const> ConstPtr; + +}; // struct UInt64_ + +typedef ::std_msgs::UInt64_ > UInt64; + +typedef boost::shared_ptr< ::std_msgs::UInt64 > UInt64Ptr; +typedef boost::shared_ptr< ::std_msgs::UInt64 const> UInt64ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::UInt64_ & v) +{ +ros::message_operations::Printer< ::std_msgs::UInt64_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::UInt64_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::UInt64_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt64_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt64_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::UInt64_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::UInt64_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::UInt64_ > +{ + static const char* value() + { + return "1b2a79973e8bf53d7b53acb71299cb57"; + } + + static const char* value(const ::std_msgs::UInt64_&) { return value(); } + static const uint64_t static_value1 = 0x1b2a79973e8bf53dULL; + static const uint64_t static_value2 = 0x7b53acb71299cb57ULL; +}; + +template +struct DataType< ::std_msgs::UInt64_ > +{ + static const char* value() + { + return "std_msgs/UInt64"; + } + + static const char* value(const ::std_msgs::UInt64_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::UInt64_ > +{ + static const char* value() + { + return "uint64 data\n\ +"; + } + + static const char* value(const ::std_msgs::UInt64_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::UInt64_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct UInt64_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::UInt64_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::UInt64_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_UINT64_H diff --git a/thirdparty/ros/include/std_msgs/UInt64MultiArray.h b/thirdparty/ros/include/std_msgs/UInt64MultiArray.h new file mode 100644 index 0000000..28ac539 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/UInt64MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/UInt64MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_UINT64MULTIARRAY_H +#define STD_MSGS_MESSAGE_UINT64MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct UInt64MultiArray_ +{ + typedef UInt64MultiArray_ Type; + + UInt64MultiArray_() + : layout() + , data() { + } + UInt64MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::UInt64MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::UInt64MultiArray_ const> ConstPtr; + +}; // struct UInt64MultiArray_ + +typedef ::std_msgs::UInt64MultiArray_ > UInt64MultiArray; + +typedef boost::shared_ptr< ::std_msgs::UInt64MultiArray > UInt64MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::UInt64MultiArray const> UInt64MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::UInt64MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::UInt64MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::UInt64MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::UInt64MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::UInt64MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt64MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::UInt64MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::UInt64MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::UInt64MultiArray_ > +{ + static const char* value() + { + return "6088f127afb1d6c72927aa1247e945af"; + } + + static const char* value(const ::std_msgs::UInt64MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0x6088f127afb1d6c7ULL; + static const uint64_t static_value2 = 0x2927aa1247e945afULL; +}; + +template +struct DataType< ::std_msgs::UInt64MultiArray_ > +{ + static const char* value() + { + return "std_msgs/UInt64MultiArray"; + } + + static const char* value(const ::std_msgs::UInt64MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::UInt64MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +uint64[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::UInt64MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::UInt64MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct UInt64MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::UInt64MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::UInt64MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_UINT64MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/UInt8.h b/thirdparty/ros/include/std_msgs/UInt8.h new file mode 100644 index 0000000..e698e5f --- /dev/null +++ b/thirdparty/ros/include/std_msgs/UInt8.h @@ -0,0 +1,187 @@ +// Generated by gencpp from file std_msgs/UInt8.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_UINT8_H +#define STD_MSGS_MESSAGE_UINT8_H + + +#include +#include +#include + +#include +#include +#include +#include + + +namespace std_msgs +{ +template +struct UInt8_ +{ + typedef UInt8_ Type; + + UInt8_() + : data(0) { + } + UInt8_(const ContainerAllocator& _alloc) + : data(0) { + (void)_alloc; + } + + + + typedef uint8_t _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::UInt8_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::UInt8_ const> ConstPtr; + +}; // struct UInt8_ + +typedef ::std_msgs::UInt8_ > UInt8; + +typedef boost::shared_ptr< ::std_msgs::UInt8 > UInt8Ptr; +typedef boost::shared_ptr< ::std_msgs::UInt8 const> UInt8ConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::UInt8_ & v) +{ +ros::message_operations::Printer< ::std_msgs::UInt8_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': True, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::UInt8_ > + : TrueType + { }; + +template +struct IsFixedSize< ::std_msgs::UInt8_ const> + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt8_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt8_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::UInt8_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::UInt8_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::UInt8_ > +{ + static const char* value() + { + return "7c8164229e7d2c17eb95e9231617fdee"; + } + + static const char* value(const ::std_msgs::UInt8_&) { return value(); } + static const uint64_t static_value1 = 0x7c8164229e7d2c17ULL; + static const uint64_t static_value2 = 0xeb95e9231617fdeeULL; +}; + +template +struct DataType< ::std_msgs::UInt8_ > +{ + static const char* value() + { + return "std_msgs/UInt8"; + } + + static const char* value(const ::std_msgs::UInt8_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::UInt8_ > +{ + static const char* value() + { + return "uint8 data\n\ +"; + } + + static const char* value(const ::std_msgs::UInt8_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::UInt8_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct UInt8_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::UInt8_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::UInt8_& v) + { + s << indent << "data: "; + Printer::stream(s, indent + " ", v.data); + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_UINT8_H diff --git a/thirdparty/ros/include/std_msgs/UInt8MultiArray.h b/thirdparty/ros/include/std_msgs/UInt8MultiArray.h new file mode 100644 index 0000000..a185aa0 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/UInt8MultiArray.h @@ -0,0 +1,241 @@ +// Generated by gencpp from file std_msgs/UInt8MultiArray.msg +// DO NOT EDIT! + + +#ifndef STD_MSGS_MESSAGE_UINT8MULTIARRAY_H +#define STD_MSGS_MESSAGE_UINT8MULTIARRAY_H + + +#include +#include +#include + +#include +#include +#include +#include + +#include + +namespace std_msgs +{ +template +struct UInt8MultiArray_ +{ + typedef UInt8MultiArray_ Type; + + UInt8MultiArray_() + : layout() + , data() { + } + UInt8MultiArray_(const ContainerAllocator& _alloc) + : layout(_alloc) + , data(_alloc) { + (void)_alloc; + } + + + + typedef ::std_msgs::MultiArrayLayout_ _layout_type; + _layout_type layout; + + typedef std::vector::other > _data_type; + _data_type data; + + + + + + typedef boost::shared_ptr< ::std_msgs::UInt8MultiArray_ > Ptr; + typedef boost::shared_ptr< ::std_msgs::UInt8MultiArray_ const> ConstPtr; + +}; // struct UInt8MultiArray_ + +typedef ::std_msgs::UInt8MultiArray_ > UInt8MultiArray; + +typedef boost::shared_ptr< ::std_msgs::UInt8MultiArray > UInt8MultiArrayPtr; +typedef boost::shared_ptr< ::std_msgs::UInt8MultiArray const> UInt8MultiArrayConstPtr; + +// constants requiring out of line definition + + + +template +std::ostream& operator<<(std::ostream& s, const ::std_msgs::UInt8MultiArray_ & v) +{ +ros::message_operations::Printer< ::std_msgs::UInt8MultiArray_ >::stream(s, "", v); +return s; +} + +} // namespace std_msgs + +namespace ros +{ +namespace message_traits +{ + + + +// BOOLTRAITS {'IsFixedSize': False, 'IsMessage': True, 'HasHeader': False} +// {'std_msgs': ['/tmp/binarydeb/ros-kinetic-std-msgs-0.5.11/msg']} + +// !!!!!!!!!!! ['__class__', '__delattr__', '__dict__', '__doc__', '__eq__', '__format__', '__getattribute__', '__hash__', '__init__', '__module__', '__ne__', '__new__', '__reduce__', '__reduce_ex__', '__repr__', '__setattr__', '__sizeof__', '__str__', '__subclasshook__', '__weakref__', '_parsed_fields', 'constants', 'fields', 'full_name', 'has_header', 'header_present', 'names', 'package', 'parsed_fields', 'short_name', 'text', 'types'] + + + + +template +struct IsFixedSize< ::std_msgs::UInt8MultiArray_ > + : FalseType + { }; + +template +struct IsFixedSize< ::std_msgs::UInt8MultiArray_ const> + : FalseType + { }; + +template +struct IsMessage< ::std_msgs::UInt8MultiArray_ > + : TrueType + { }; + +template +struct IsMessage< ::std_msgs::UInt8MultiArray_ const> + : TrueType + { }; + +template +struct HasHeader< ::std_msgs::UInt8MultiArray_ > + : FalseType + { }; + +template +struct HasHeader< ::std_msgs::UInt8MultiArray_ const> + : FalseType + { }; + + +template +struct MD5Sum< ::std_msgs::UInt8MultiArray_ > +{ + static const char* value() + { + return "82373f1612381bb6ee473b5cd6f5d89c"; + } + + static const char* value(const ::std_msgs::UInt8MultiArray_&) { return value(); } + static const uint64_t static_value1 = 0x82373f1612381bb6ULL; + static const uint64_t static_value2 = 0xee473b5cd6f5d89cULL; +}; + +template +struct DataType< ::std_msgs::UInt8MultiArray_ > +{ + static const char* value() + { + return "std_msgs/UInt8MultiArray"; + } + + static const char* value(const ::std_msgs::UInt8MultiArray_&) { return value(); } +}; + +template +struct Definition< ::std_msgs::UInt8MultiArray_ > +{ + static const char* value() + { + return "# Please look at the MultiArrayLayout message definition for\n\ +# documentation on all multiarrays.\n\ +\n\ +MultiArrayLayout layout # specification of data layout\n\ +uint8[] data # array of data\n\ +\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayLayout\n\ +# The multiarray declares a generic multi-dimensional array of a\n\ +# particular data type. Dimensions are ordered from outer most\n\ +# to inner most.\n\ +\n\ +MultiArrayDimension[] dim # Array of dimension properties\n\ +uint32 data_offset # padding elements at front of data\n\ +\n\ +# Accessors should ALWAYS be written in terms of dimension stride\n\ +# and specified outer-most dimension first.\n\ +# \n\ +# multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]\n\ +#\n\ +# A standard, 3-channel 640x480 image with interleaved color channels\n\ +# would be specified as:\n\ +#\n\ +# dim[0].label = \"height\"\n\ +# dim[0].size = 480\n\ +# dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)\n\ +# dim[1].label = \"width\"\n\ +# dim[1].size = 640\n\ +# dim[1].stride = 3*640 = 1920\n\ +# dim[2].label = \"channel\"\n\ +# dim[2].size = 3\n\ +# dim[2].stride = 3\n\ +#\n\ +# multiarray(i,j,k) refers to the ith row, jth column, and kth channel.\n\ +\n\ +================================================================================\n\ +MSG: std_msgs/MultiArrayDimension\n\ +string label # label of given dimension\n\ +uint32 size # size of given dimension (in type units)\n\ +uint32 stride # stride of given dimension\n\ +"; + } + + static const char* value(const ::std_msgs::UInt8MultiArray_&) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + + template struct Serializer< ::std_msgs::UInt8MultiArray_ > + { + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.layout); + stream.next(m.data); + } + + ROS_DECLARE_ALLINONE_SERIALIZER + }; // struct UInt8MultiArray_ + +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::std_msgs::UInt8MultiArray_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::std_msgs::UInt8MultiArray_& v) + { + s << indent << "layout: "; + s << std::endl; + Printer< ::std_msgs::MultiArrayLayout_ >::stream(s, indent + " ", v.layout); + s << indent << "data[]" << std::endl; + for (size_t i = 0; i < v.data.size(); ++i) + { + s << indent << " data[" << i << "]: "; + Printer::stream(s, indent + " ", v.data[i]); + } + } +}; + +} // namespace message_operations +} // namespace ros + +#endif // STD_MSGS_MESSAGE_UINT8MULTIARRAY_H diff --git a/thirdparty/ros/include/std_msgs/builtin_bool.h b/thirdparty/ros/include/std_msgs/builtin_bool.h new file mode 100644 index 0000000..e2f0f3d --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_bool.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_BOOL_H +#define STD_MSGS_BUILTIN_BOOL_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(bool, Bool, 0x8b94c1b53db61fb6ULL, 0xaed406028ad6332aULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_double.h b/thirdparty/ros/include/std_msgs/builtin_double.h new file mode 100644 index 0000000..22fd85b --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_double.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_DOUBLE_H +#define STD_MSGS_BUILTIN_DOUBLE_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(double, Float64, 0xfdb28210bfa9d7c9ULL, 0x1146260178d9a584ULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_float.h b/thirdparty/ros/include/std_msgs/builtin_float.h new file mode 100644 index 0000000..1766492 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_float.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_FLOAT_H +#define STD_MSGS_BUILTIN_FLOAT_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(float, Float32, 0x73fcbf46b49191e6ULL, 0x72908e50842a83d4ULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_int16.h b/thirdparty/ros/include/std_msgs/builtin_int16.h new file mode 100644 index 0000000..8f1edf4 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_int16.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_INT16_H +#define STD_MSGS_BUILTIN_INT16_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(int16_t, Int16, 0x8524586e34fbd7cbULL, 0x1c08c5f5f1ca0e57ULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_int32.h b/thirdparty/ros/include/std_msgs/builtin_int32.h new file mode 100644 index 0000000..126c995 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_int32.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_INT32_H +#define STD_MSGS_BUILTIN_INT32_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(int32_t, Int32, 0xda5909fbe378aeafULL, 0x85e547e830cc1bb7ULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_int64.h b/thirdparty/ros/include/std_msgs/builtin_int64.h new file mode 100644 index 0000000..a009542 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_int64.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_INT64_H +#define STD_MSGS_BUILTIN_INT64_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(int64_t, Int64, 0x34add168574510e6ULL, 0xe17f5d23ecc077efULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_int8.h b/thirdparty/ros/include/std_msgs/builtin_int8.h new file mode 100644 index 0000000..b4896ec --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_int8.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_INT8_H +#define STD_MSGS_BUILTIN_INT8_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(int8_t, Int8, 0x27ffa0c9c4b8fb84ULL, 0x92252bcad9e5c57bULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_string.h b/thirdparty/ros/include/std_msgs/builtin_string.h new file mode 100644 index 0000000..1118849 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_string.h @@ -0,0 +1,86 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_STRING_H +#define STD_MSGS_BUILTIN_STRING_H + +#include "trait_macros.h" +#include + +namespace ros +{ +namespace message_traits +{ + +template +struct MD5Sum, ContainerAllocator> > +{ + static const char* value() + { + ROS_STATIC_ASSERT(MD5Sum::static_value1 == 0x992ce8a1687cec8cULL); + ROS_STATIC_ASSERT(MD5Sum::static_value2 == 0x8bd883ec73ca41d1ULL); + return MD5Sum >::value(); + } + + static const char* value(const std::basic_string, ContainerAllocator>&) + { + return value(); + } +}; + +template +struct DataType, ContainerAllocator > > +{ + static const char* value() + { + return DataType >::value(); + } + + static const char* value(const std::basic_string, ContainerAllocator >&) + { + return value(); + } +}; + +template +struct Definition, ContainerAllocator > > +{ + static const char* value() + { + return Definition >::value(); + } + + static const char* value(const std::basic_string, ContainerAllocator >&) + { + return value(); + } +}; + +} +} + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_uint16.h b/thirdparty/ros/include/std_msgs/builtin_uint16.h new file mode 100644 index 0000000..6845f28 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_uint16.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_UINT16_H +#define STD_MSGS_BUILTIN_UINT16_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(uint16_t, UInt16, 0x1df79edf208b629fULL, 0xe6b81923a544552dULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_uint32.h b/thirdparty/ros/include/std_msgs/builtin_uint32.h new file mode 100644 index 0000000..c13436f --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_uint32.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_UINT32_H +#define STD_MSGS_BUILTIN_UINT32_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(uint32_t, UInt32, 0x304a39449588c7f8ULL, 0xce2df6e8001c5fceULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_uint64.h b/thirdparty/ros/include/std_msgs/builtin_uint64.h new file mode 100644 index 0000000..d0fba01 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_uint64.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_UINT64_H +#define STD_MSGS_BUILTIN_UINT64_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(uint64_t, UInt64, 0x1b2a79973e8bf53dULL, 0x7b53acb71299cb57ULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/builtin_uint8.h b/thirdparty/ros/include/std_msgs/builtin_uint8.h new file mode 100644 index 0000000..1de482d --- /dev/null +++ b/thirdparty/ros/include/std_msgs/builtin_uint8.h @@ -0,0 +1,36 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_BUILTIN_UINT8_H +#define STD_MSGS_BUILTIN_UINT8_H + +#include "trait_macros.h" +#include + +STD_MSGS_DEFINE_BUILTIN_TRAITS(uint8_t, UInt8, 0x7c8164229e7d2c17ULL, 0xeb95e9231617fdeeULL) + +#endif diff --git a/thirdparty/ros/include/std_msgs/header_deprecated_def.h b/thirdparty/ros/include/std_msgs/header_deprecated_def.h new file mode 100644 index 0000000..6dbdd09 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/header_deprecated_def.h @@ -0,0 +1,249 @@ +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_INCLUDING_HEADER_DEPRECATED_DEF +#error("Do not include this file directly. Instead, include std_msgs/Header.h") +#endif + +namespace roslib +{ +template +struct Header_ : public std_msgs::Header_ +{ + typedef Header_ Type; + + ROS_DEPRECATED Header_() + { + } + + ROS_DEPRECATED Header_(const ContainerAllocator& _alloc) + : std_msgs::Header_(_alloc) + { + } + + ROS_DEPRECATED Header_(const std_msgs::Header_& rhs) + { + *this = rhs; + } + + ROS_DEPRECATED Type& operator=(const std_msgs::Header_& rhs) + { + if (this == &rhs) + return *this; + this->seq = rhs.seq; + this->stamp = rhs.stamp; + this->frame_id = rhs.frame_id; + return *this; + } + + ROS_DEPRECATED operator std_msgs::Header_() + { + std_msgs::Header_ h; + h.seq = this->seq; + h.stamp = this->stamp; + h.frame_id = this->frame_id; + return h; + } + +private: + static const char* __s_getDataType_() { return "roslib/Header"; } +public: + static const std::string __s_getDataType() { return __s_getDataType_(); } + + const std::string __getDataType() const { return __s_getDataType_(); } + +private: + static const char* __s_getMD5Sum_() { return "2176decaecbce78abc3b96ef049fabed"; } +public: + static const std::string __s_getMD5Sum() { return __s_getMD5Sum_(); } + + const std::string __getMD5Sum() const { return __s_getMD5Sum_(); } + +private: + static const char* __s_getMessageDefinition_() { return "# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.secs: seconds (stamp_secs) since epoch\n\ +# * stamp.nsecs: nanoseconds since stamp_secs\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +"; } +public: + static const std::string __s_getMessageDefinition() { return __s_getMessageDefinition_(); } + + const std::string __getMessageDefinition() const { return __s_getMessageDefinition_(); } + + virtual uint8_t *serialize(uint8_t *write_ptr, uint32_t seq) const + { + ros::serialization::OStream stream(write_ptr, 1000000000); + ros::serialization::serialize(stream, this->seq); + ros::serialization::serialize(stream, this->stamp); + ros::serialization::serialize(stream, this->frame_id); + return stream.getData(); + } + + virtual uint8_t *deserialize(uint8_t *read_ptr) + { + ros::serialization::IStream stream(read_ptr, 1000000000); + ros::serialization::deserialize(stream, this->seq); + ros::serialization::deserialize(stream, this->stamp); + ros::serialization::deserialize(stream, this->frame_id); + return stream.getData(); + } + + virtual uint32_t serializationLength() const + { + uint32_t size = 0; + size += ros::serialization::serializationLength(this->seq); + size += ros::serialization::serializationLength(this->stamp); + size += ros::serialization::serializationLength(this->frame_id); + return size; + } + + typedef boost::shared_ptr< ::roslib::Header_ > Ptr; + typedef boost::shared_ptr< ::roslib::Header_ const> ConstPtr; +}; // struct Header +typedef ::roslib::Header_ > Header; + +typedef boost::shared_ptr< ::roslib::Header> HeaderPtr; +typedef boost::shared_ptr< ::roslib::Header const> HeaderConstPtr; + + +template +std::ostream& operator<<(std::ostream& s, const ::roslib::Header_ & v) +{ + ros::message_operations::Printer< ::roslib::Header_ >::stream(s, "", v); + return s;} + +} // namespace roslib + +namespace ros +{ +namespace message_traits +{ +template +struct MD5Sum< ::roslib::Header_ > { + static const char* value() + { + return "2176decaecbce78abc3b96ef049fabed"; + } + + static const char* value(const ::roslib::Header_ &) { return value(); } + static const uint64_t static_value1 = 0x2176decaecbce78aULL; + static const uint64_t static_value2 = 0xbc3b96ef049fabedULL; +}; + +template +struct DataType< ::roslib::Header_ > { + static const char* value() + { + return "roslib/Header"; + } + + static const char* value(const ::roslib::Header_ &) { return value(); } +}; + +template +struct Definition< ::roslib::Header_ > { + static const char* value() + { + return "# Standard metadata for higher-level stamped data types.\n\ +# This is generally used to communicate timestamped data \n\ +# in a particular coordinate frame.\n\ +# \n\ +# sequence ID: consecutively increasing ID \n\ +uint32 seq\n\ +#Two-integer timestamp that is expressed as:\n\ +# * stamp.secs: seconds (stamp_secs) since epoch\n\ +# * stamp.nsecs: nanoseconds since stamp_secs\n\ +# time-handling sugar is provided by the client library\n\ +time stamp\n\ +#Frame this data is associated with\n\ +# 0: no frame\n\ +# 1: global frame\n\ +string frame_id\n\ +\n\ +"; + } + + static const char* value(const ::roslib::Header_ &) { return value(); } +}; + +} // namespace message_traits +} // namespace ros + +namespace ros +{ +namespace serialization +{ + +template struct Serializer< ::roslib::Header_ > +{ + template inline static void allInOne(Stream& stream, T m) + { + stream.next(m.seq); + stream.next(m.stamp); + stream.next(m.frame_id); + } + + ROS_DECLARE_ALLINONE_SERIALIZER; +}; // struct Header_ +} // namespace serialization +} // namespace ros + +namespace ros +{ +namespace message_operations +{ + +template +struct Printer< ::roslib::Header_ > +{ + template static void stream(Stream& s, const std::string& indent, const ::roslib::Header_ & v) + { + s << indent << "seq: "; + Printer::stream(s, indent + " ", v.seq); + s << indent << "stamp: "; + Printer::stream(s, indent + " ", v.stamp); + s << indent << "frame_id: "; + Printer, typename ContainerAllocator::template rebind::other > >::stream(s, indent + " ", v.frame_id); + } +}; + + +} // namespace message_operations +} // namespace ros + diff --git a/thirdparty/ros/include/std_msgs/trait_macros.h b/thirdparty/ros/include/std_msgs/trait_macros.h new file mode 100644 index 0000000..3efa852 --- /dev/null +++ b/thirdparty/ros/include/std_msgs/trait_macros.h @@ -0,0 +1,80 @@ + +/* + * Copyright (C) 2009, Willow Garage, Inc. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * * Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the names of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef STD_MSGS_TRAIT_MACROS_H +#define STD_MSGS_TRAIT_MACROS_H + +#define STD_MSGS_DEFINE_BUILTIN_TRAITS(builtin, msg, static_md5sum1, static_md5sum2) \ + namespace ros \ + { \ + namespace message_traits \ + { \ + \ + template<> struct MD5Sum \ + { \ + static const char* value() \ + { \ + return MD5Sum::value(); \ + } \ + \ + static const char* value(const builtin&) \ + { \ + return value(); \ + } \ + }; \ + \ + template<> struct DataType \ + { \ + static const char* value() \ + { \ + return DataType::value(); \ + } \ + \ + static const char* value(const builtin&) \ + { \ + return value(); \ + } \ + }; \ + \ + template<> struct Definition \ + { \ + static const char* value() \ + { \ + return Definition::value(); \ + } \ + \ + static const char* value(const builtin&) \ + { \ + return value(); \ + } \ + }; \ + \ + } \ + } + +#endif // STD_MSGS_TRAIT_MACROS_H diff --git a/thirdparty/ros/ros_comm b/thirdparty/ros/ros_comm new file mode 160000 index 0000000..2c8a3f6 --- /dev/null +++ b/thirdparty/ros/ros_comm @@ -0,0 +1 @@ +Subproject commit 2c8a3f65628d0362d97c29d333d5669b2c7803a6 diff --git a/thirdparty/ros/roscpp_core b/thirdparty/ros/roscpp_core new file mode 160000 index 0000000..d2bb8cb --- /dev/null +++ b/thirdparty/ros/roscpp_core @@ -0,0 +1 @@ +Subproject commit d2bb8cbcfd4944e48d16cdb20edfab5d225db265

    I4uhPuijMQRhyErX}8~bjN>{k`yoLD z>zq-OK@)-#Dq&CuH!A|ixGSS;a2uIYQ&^oqREq3!B;MNPY#;?=x!-K#idOI%Ml}8B zMx}+&0YD1!d@pWz)ZV=r{aGBtEsN~%WbT4D`Ms%P;jLwqb2M*6jhw{qXX+MUMe=Rf z`?4r{OX#V(j$3J1EA(lNK1OwGs|b#_ zfqudK&boD>^pi#G*8YDxx3y)z=w~1K85M5S4RV;Hs_{u_s~=MImpj;~7NO^4l1 z#HCUacIuf<7+1s|gc+7qur{yGspxiHio@FcG>n^Utm2_f7bGZz3-^Vu4MtfC=Gdb3 z!~`oDGgS&O8R4OL@Ry?Np0ws36zR>bTF%Br-|ehW*4{i&UMM^+--va+l;@7EaU}-| z#_rv}r&9DrJ;=d!UZZa)OBN~Jx66|EWWP=Awxjq1UxIYL=5& zVJsJ&-!aOj%g@c%sb*c9C0w}J1>t4ST+Y@VT{vdWIjdaHDdN$5>{aSR|LhyR6`bL`*alcD;N;N;Lm6{8x z%1|GJeQnY(HEgm8ICdX)c?(53s~3B}9ILWq%|Utk>D4u2231C%I~I3euu{8BWOQUZ zzww39{t5Gps~Pg#!;^nEzrk9%^RHICl1tUqp;ubLxy);Su`ko-jb5=xHvEuJ+g98u zw3ZjG1oq>d%4%WmsLLXm?On3%~f}^QjB-T`e{_Sm*3#Z zfbK3rEwlEww53H~-s*tC@P_7TC)W!hg+=|lwjn}>{U#cUgje3l5|OE$3~1OkO%iF{ zXl&!@$bOCR_)eWb(yH>o&&_*-A_?-EZB8~BD`uJcK93Ia-mfb_lNV^7TebUO4s0Xz z1{rP;Bb#A<*2*RMzdR4HS9FIyNe9>opfnTs9V==d9Ui#fM4xrEyx)usrS!gg+qWro zBGFwTDQ?j$-(<^OPcG>kS2esuIcSeV_@Uf;Y3m0ZZ5it{GyAdu%p!~lYP5>EA z*;?^*t&FOZ9EJL-1qe*peV5yuKmsEO|9$!X#OP2Tp7did-!?e7P1V+F4^Cv)CgFHX zrPedz7@k>cQ6Beh+>C*1*6IgpPz!i8AyvL-(M>eV-(X%0P@6@U2qth}Lq4lMM*o2R z!BMiHt9d_naO!DyxH6jfSAL!KXFa-RLs*j2?I5~IN4-4K4LMWiG_{$|LwOE!)KKgz zwoUws>YCH#B&b^;wgsg!a38&OI5~Dp{iGih2QXP4{@q0_k>i#e2ns$M0hCj*loG@k zQ6A%G;<~n={loH`Td$$~2+(W3r0oz4@_|3<;Wn_T$&y2g4he-q!~z=*f}4?w3hF0n z(I?h2Spnp!Spvd#N1VL$Bijx9jataoKvdzYOO8{?>vR1%t5<%RoMDHed@{f>2#vqZ zO3qd(wk~A{vhC*%9IAhU?ugfz<4XGPO+9pNeu8&Oc6t8e^$PoCi((eceScoH z%G15D3-ospL+F)S^5#2?52>#99xVY|#4f*d&Y$z3jU;XF^k;VBujKy3w;5qgCu(^j zrYVZxs8B>6vMFD9;B5Qxq;iLP>|oehq-HQ2m%{Pvpe^qrf+;&#rl^H2pM7R!MY(LE zAreqIpyMUzvHaQVp{)cr8R~9wq13Z-%OgRJdfy`e21vnO#X~?&#-;1Ac4momono0KrSkteNm8R_(hvRaaAHa@EM2 zOkBtj`@(-Cc(MPJBmreEu7}osm_K&6SUZ z(GfUC|8W)i^XS007vGr*#X_4}K%fK4aRWymwgW{OtEK0900i`^?FQsKU_G0enW+KB za`y6?BVdaTgreCXyUAO%Pe$q<>~1;&b^;b4MRZ$2cz_cRB55yGAGs}ntSb0vAhWE3 z#9{$oOf&FM`vUtcYm}JfBj7@V{NjLybqXXT&%oHlJ%HIA%4k0X&UWw&TeaP48UsE9 z8sPe%rz!zUaBcyeAGoU_+5~9Dt^tc{-3*Q$V(kLKzYa2ZLmO3~OgD6YDZ0+R+HMr9 z0uFrWE9*iG4FIYGcN`XwBp^iMeL!8cs6MbC0-p~QdW3S6z*~k;$vXz^)|>8#xiokP zjDjnG!Zo)&D5R zb+h+2d}h@o(=fyBZ%uwU-gTw-LV|q;ww73-o%yv;voq(QcUvwucZjttzxhOwE7&-nEKUnl4b?+<{UYPh^iT(pTL67XpMW0+$jX}5FoCOVgM)+E z#lpTs;Et_nZlZ-40H#@`$Nf0$FM#bOtMy!mr=<^O6|umFJ_ZGoq0<1;&XYxh7BV1J z1p%@lYdiE2036^MLOm@r#>083lpfj@0Jt(%dyB@!&rAU89asS&b1a0UIYtFmf)AIZ&O z6R({WGRF$M;G9{fVePk(CX*}gqX%Bj`N4PB)ce+>9b6UZZ`uu)usg((%*NNE%>+)5 zp|H{JT_(f{r|Nj07mm0SBmu1hUr0Z;~9zefF{NhGew#91aP}5r24;n;aFkf8d4TprMhNV zx$1SZ?9_qU@{RnBUxTGhweAe6DtVI}Dex+BXA8RPn8?gB?B5zDm#@~+u#BBoUVp8l zwdlzg7za)e;7<|;?pEk7 zfv9L8HhTfug9TpOAXB)qJsGS!Ugry0K_L!5*e?L#g&+(7ApduQ5GX+9nhg{%0LLU) zl3WM!h+l}5TXu8ZAw~$0FPdoZzXcYT1IzUo_)1NFQXAY*b^u&u+pEFu0RmYiG++zX zBT&)9q_(wP7EQJ4A^Z^l+}O?c>VON$$k_NE*y{{2)} zB5MQN2r#8oHUD>jAE4yMp>HQEwRQ$%__MBY0+IlzsGxjL^gp^}aC`-Zx7+%-oka5557vHezmGeND6|rni8e4u#d4SC zn9+&fY~D~7F;T5h|J4?ExV(AJ8wSfIHNd{6JS!$3kJ%1#@7$6eIpgfg@!Mu`V|G7o zS0(xt5%$C4sznA9Gn|W4vprOZGM+Qgy$`A=CxcCft@P;zw!Yn11;tu%a_pFn#`N$q z`oas4`r1$crOXrOiD+lsm%@{G7Ke5UcP0MU3s9AnPMBLmQ?6HUzSNB1 zGS_S_nMJ>aQ-dc7#~p2adFU&NFmLn_7gHsNxNASUaI&P&YGm#XNX9I>t}W3yq-IqRy#lH_2f6;GBpgZbuwZ!NPQpsOR#vMWh)dOF zn~M^2F+|gy|Lw?P2hRLIM&Fx}fGAg3Sok95|IEIFBl0O$5pWtnw+h9%P&U^=K?C{w zA?ht4^8G2nUInymdDsKm5B7?E0H0D`2qp&*zvh4P@6Y7^U-R#`xBtK9->I~_5+6Ry z3;FvhjRi0iKiMY|!Cr94g0Z~J_39EFthOD$%C&O>1P)dK$ZSIKa7uAyUh9Yr!fW|3 zoC6Vu9FPRq-_$y?dr=AQl$4Z|;vqL0clH`4mF0-H9c4w<)3c+owAY9T`ku0BwEFwO zqM228tI8QYZMMuJ%ppRZyXp7Do6&Wz7n&CZT6Po3$vdN%~#Jdelk52KU7fVY<*q@EPa>d z+71y$|2UiHuq)#GHC#P~yL0kah|G}Vgf)WRG>eQiT1|GC@S8p@(C%SDk~jXonA5$g z7a!+4eJ$JVgk!Xciq%gl$?Uu!-)Z+M%fQXk%UDyU^izS-dap9e;9yFW04Ba+Yz!uI zrGj6xYC}a8b?H z%6(3XgpBjiL_NvC_2%{3?f7O}yvlY}R#M_(luCOAXm~N|rw9mgg&13xa!mS6_5mje#*Y(d#qQOP)jmK#>aDXehy8OcKKB{-hT<}!;|_wm6&|YUZh>s zPn?hT@&H4lZcAMn*4dN3(njUTc>fCXyegr7BDm=pdmz^SBLIB98yae&X0sT~FV3r1 z;i3<>jtl}rqQ(7_bnh_EGyUR44R`<{`>?4Vd`f=0ci%*^*esB$`twSo=%BJ?R*s{f zU4RNvChy#i5qkTfzunKe-wuRBFjLg`foH25xxv}`8-?RyPfpmTckc|<6UZ_p$`+VD zC$vEirOb@$j$rJ;#4GBj<#r}_Nx~rP*1r6dc5wW2hw8d7RqD}a>k73$b%u+1l-03S zVo^`x8)8>)q=y#XB%(zUr@|*yUQ}Me*-3nr_Jx_F74yv{<0eo-9L2^Z?T$}^iBAo< zeyIYEB`b=LA8U&eL;fFO?^yRk919~I$dBo4&h*_&L-4E0`?oA!=b_Fp~m6p#Xmdg!%-q2S6Z1YJ*Omr}#F&+(I}9WW@^2;ZEGqMQDjA z^j9cxNBa~k$ce@S23bw>cO0OmjhBLNM!;NOX`&rT{OS$!SZ=mD{b^pMql)}T&HvSL zfeUA>Pu%awuvNXPrh6DM4MwthA_8^&+aHA+b=qn z5~NIrKL3{dqP&Kp#4~P<-;RQZh)R}Jg~RnPdOPQM-xQlKHtSam;kSlDzKF$&WV?Lt z4+*qDelZ_RIGwD%e|ZZZomiIcs3{je(so$R{fBzNoqw;fKXu<^1Mf#JNl zG%l#XvDf&W@*x&oU!56VtSLECnzd-iFWN>rCpjHKZ>mAdQauxDivNheP5MsGZn~QX zau@$SwE0(6;a>kg$U{%A5s>s$pp+hio;olUfB;q?B?LI=s8;S%RA8YOBn2sDsec5S zHXy91Tet9lJmtM7BC*!3{1DbTuOH!dxE`n5^YhKOTe^>~c|!?ohf!BC&~vx)DZ7J) zb25)0O=Vr3>#^|80lHieGRy<6-k9B{q8fg3};T^nRl zw_0honLw~r79m{N4An2+4`)E#O{ik*G9)i=>cPv167Cz4wb^lMu(XtV8@(MUn%NhnznjglNd*yn|&H>{vrQMf|IIL z+H1y$r`H*sngPm~%k{@g%C(+*Gr;j<#40g=jmV>l$C_Hp2Oq2Gz5ypD56r%_6|fL0 z80c9)5zY{pE*{fo+tfewa^c?NxPrs{ET?tdAt6Ys@Xi_B@FV;YA_Z2)A$<=s;epjtY-&eHb;wJ21Oym^z5l48IT z2p(q8Eh6OnxK}o_-8rE0^^7dLC-5!;<`%pMWG+Fo3bd1z2%?L@Qw)?)1dH&rtfe-Dzc?HB zdz0s8g3SibdV)DmdH;6s)9`73a)R$@}q(~svV!te^}diA>rjDRy8fS5yJb`CS+$LT1N3bf{F04s8x0G{SpH+ zTKancJ-(1f{&=sAxvmJZ?3BL{NZLeLgyJU9PSK`r6`P*tuj!Px<`pjB@wo*8_mmFq z@zrwcqvEVV-Vk7FG#(_~$rAseL*^{BeMy2dA{^H!EaGPJ8wy6XNqbMEfwecu-p*Q* zQ<1w;Pok}&0o)|{2Yr1R=?JEXa76icyN2JXofVhLEc@lDk_OfrV;XC1d{PZ}i+xAs zXbonKAH#;;C!b3=?A3QvSJNGtY>7&}kZREs^{RhFwLr~AV(`rfx7oOk#1E~2+*6w~ zE8AV`>Bl+7^rD9>GkA9k6hJ&;Bb;`J1R`=J5!6CSRmIUQ7E%#L>Jz?YT zB;)V5FY5g^25#sxQC}6V9_$5oR{{S?xS-l!`}mLXDJjPR8MHYnD^4MG)b?i}2xxuV zZruG+0bZe?;w&Ko{mDxl@S6OkT8(07VE&kar#vT|k&hdd<$MCwvin`4A&8 zEV}FJdhpHYGnEsV1ge}s730_W`^rut?Kf{E)MVCw~ zQtI^#*~W_5mojw;y=snpWr|w6)LE3~&(_>7gij9Cm{w7mX-);%L5ti}xw`N@17?nG zKk!7<(+~X4FED-56Yb=w{+io*=cncgOC`Fm{3WeWRDI!8W5+eX#Mm}?Q;>f&m2$ao zt`{%BMM=B%fsIE*`lCz%Tm@V0Ia%JQ_-Jr$(b>1|*Opr#vkzfE-oP`#Wlv>ivdJyj zXL2j!v!9simwl&@hJy(^F7f$}$rgfdfWbQp~4106FEn&DyBmyi#mYZVaT;%Jom0O^v zIy#3<_&0eW{Sn!SyEZ1pL0caf7B|>wwM$HNEOPK6g6=t3aUAuZ{P10Wb_jQ_v*@+9 z3h?1L$}k+*b$*(jEv!jD`pK-9LTrPwm&AS}Ke-Y*E@Ic(6N6Keu<%m}BTI zgjDi&nnWHxj(#F$k!Iu{bRWf~2j%hfY-3ByWld5+-?ZdGiDr!( zU=BT|RYW;Q&4{e$7vD5n5xey{otX1~n{e4kH!Wwk8oo=RWTxdS@p^&xAg z6f^TnTKLm;K?v)A&?DK`bKcg!XfWT;d6fJm z$hGD{V4#uU)cmL)@C5y_VMu4r5CmS;dvZ0nyBIa=wS@G=j6mh0fO^I z*c@R!eom$$xKl;@QLqLU%h;Ol57eKBvya13Gt&h-vX~?f)hm_@av)aMpWk2!zn@gmf_bMHZ-P!jHx%%di_syHC+RLzA zTqhHQ@(LLh6{u;i&<|&YM)+yK8T=&r>>GEC^g@sJ*S%zT_hMoVYs=nMQDVRZhezkO zd%~e*zHC^{7J);+r9xxFxoqG2(cZrN#*InNozsJvP4-_)h2hmrge)_$w;zD*+m#Q!mevEy16&U~I-v-82VBPfyQjZfT2O(#B({(8m9HF8+$! z-#s56a(z$#OL129DI{Phd#qzu?vF!^`m6Al%M-WOyV#eRkiN8eB@*^N zNFNQxW#GAdwh_p>fL}E{50(*G(R^qU!WOb>2~4pw{Z?e7MMhS(>&G6mIYde9hs-vzLp#*yy86f1PPI~s2R_s@mh zQRCRhE~0^|#93CD#*q1(PMrFIu=|S&Z8da0%*>U-M!N8=e-{;wCgy(i>Xj;I zDLcrz)mR`?o?c&5C?HdoWIRb>Fef^%z313Dbex#nxoGFnz{DsC@iW+$oOQ1WRXX;Z zzi<@4m$wI_$C-EJVyE;?jJyTlL=#Uv3#822{tY|rs4rf(F6^=GUFEreL2dDkR=V^4 zeNtrq`$@Sid6Ny0YDIP*A2dVkf@A}7$W7|Hm^o|VFb;)2H;D6+$iQ(938yUHB;3cY z^ROa~DuPCkytmpLQ|W6NC#8Tj_hg3ar;+D)IG8dQY@<-rEspv2@VOiri+Vl-X&a`u z+@422mjnb?C>Zwqe9q#Y@0HDo%tbf{^h!*ZN8#+(uVDQAS%O^MwyC%za@cfVtOF3*| z;T5uLMDcyPE$;3N3n>?c5>byxrKF~Y1HN;%Hh;k!j2eXzQ9O&|QB+j4OmF47?0WQN z(YjSkKt)|_^Q$4VWR$hyVJik<7ug;pP`GeUD#^yP?qcNn6;bf5jMdh1RHB!SF%-QX z;m@PJqdCsMVOG3${%hI6R)2{bZr89PKP_|k-4K-yHOcAzid?nQJpPPY3EEse_7@P4 z9r`XLSGXa>u~{*J;~%K@*EkTzQpA#?*UfqI4XjtZxvr^vdt5%**jd}#665n=EM`OJ z)ki6!3zIbj5Z`_-i-^gKI{~jb*y9=U*N#En_aBWN)|gG<3zUWWxl<-1J$4Z6t{C1^ zMa&lVC-T-xY=}e-fefYwU#5&>1wHRdzVPfypdQ|k|F}9N*9n$)FNgdo3xEEP|M1+{ zGz)7;<}F9l|B6o-3D8=><1n@iy*@8b=C?q8IyE1rrxP+GE<3j&qQ14`PmwU8^>9gv zxL*X1r6~e14a~R7{QBrV!@ljQ_)y0SKk3Lo4`W;X zce29w6`Dm*4b3t8s!;1c@eGg87yw!toSQl<7VON!?|&9)yx|meW9I2-mz{)$xO`68 zvQU9)rkLuV+pfrr?z(#)CWyJe^g9BfJc>H;_*zz=y_-AgMeJ&nXY{{(Y*m8{n4@W# zJGIY~gKy2WGc9a-wRQ~u{8@Dz&PEZ|^Qy!&FL@ke6svV72#t~~CkUNATk}@4);}`~ zb}sL<2|q^%e9b5PwL!A3#=L<-L9hBwriuDF7vHsQuTu7;L{x441PGOW4~2>6f!7WS ztx{FoI(S3inol@BnI@kK9ibG}xbVbhlY6-b`i$Mnc2~&KbP`;#bQ%0w201Xp8C)`( zpbeL=7!>zo<%Vq6eb<*dTNxb1XX;&_i|yXUJ7p)Bq@qxaZNZF&sG+@oV)&jD|L9ig zi}4ees3|9}cDYIO+Cw>1^Y%o4uu!@9*4kG7%isZdykH%qF>rBL0ikdXMI|d<*+dqt zW_VVBMg;y4eFMo+i?ewRK}U4tllNHuTQ8GQ<(uufWJ}u$RWcHkWnzwd5#7{q%Z2Sm5qX`jk^vsVW_rZZ*3Sd_m?iu{&GL@zuI$6*=W2 z#ohDi7L;wS>kPcVe5?iX^Zms{{Hvk<_e?X!EXMrJUw0g}U#4o8 zhngZz)#XsS$iwx^;XSf&$a3dj6)5Sk0%qB<^I2}iuDb3))oLL+>KWYj>)KirXL6%W zGn1)-x{+@n}Tz^je8Plf+S{M4mh{8VJ;;aA>39QArrI#M>vN;*9`3LY?3$Y+{;yxfT3;n z(Q(jSUUpzF`aj{S)c@H-_6Ie7xVJ~XmL}MNBP?)ltjx@BNY=#CMM&N2gq``dSc366 z%r{+{634$bdc%KhJgRD)`T`;GHb(4A;-u9^P;G^5?1$N669xijPACTSTiPG2^yJVf z&R-Gf!xHr69g?_lW^rtj4j^%}Y0zQ&MezZb2P!$a*#`8xCaR!(8^Zs?*Zl|QY?Y$} z>l~Xos!>^#?IfUF`5{#o-UXl%`R2L$(19IkbP(#}jJ@}}OWdaOuoLUl&q0CkciNcn z)d52|_n}Y%oA714rOyCFQ=vH)S$6e=`I2Z|dKnbaGcfGZo$`~=h7BN#Gz~5?f3(sO z*MZ!|w}So?6B>Stn)`a8pPCc%m{HD&!flVi`rJS=E-@r#QNcN8-_|vLx0KW2hU><0 zo9d)ZCgNNQ>y77@DC10urg82G8!Xo7MqX2)M|8>Sm|>{MIT~q$gI(suFzmxlxWg%KxVYcx#pm*2d{+rodg6&Gr3%vutc; z)w4v(c8H78^74`_uAaLtDo?`b7{bde6^~ctt?Hw*((~NDnkMZ1KolQ22*Ra*o^Mw* z5l*tMh$+F=h>d8^!~U|>=C_qJ+mOz5X%|E!G5aJH-u}SP+F$ot)gaI0ov@lTV~#(~ zz#KPW^54~n$IHTU(Apm#)`;TYAKUmkP~w=xB>j?>4PWBs!{;2B-2Cr!9(#RYS76<3 zSSM2F#I#>79yUp{gE%i9$0eLZajHz6gB%10FgWsiXIOi%wUsM9?6hw??r;>J>ABO! zb{(|eKbn;=YF{WEXS)H}EwI)5ltbCR+HmP_uoF%F{pj{Ai+C5qdd)@1Qg!YJE7}++ zs{)`!bzkeiEJq%WSV;=cdPjc*TW9UF5E;t{%XOpI#d5X@jbmRnN5YJ}woGWVK*S$5 z`~y9RW)F3W`)VIw2q#zAGTGyTo1AYY>5!+3yL(PYiNJ}SwAkX6Vm&OLAX|K;GC z3IzODMZTJpEGj!8Gdf>az*L;*}Ax1GP-2C z#X>lpb#-+T!bYy}78LZ*O24_pSp^-~Lgjq5v9S@?Xgg#pk;o;5c*tZ?a;AKtv*~xp zZ)SmNhUi94^+`4xEz@VS=rtiNxewNVU^9PK;OMtDhM6MvK2pTsq)qqTi1*2ylXd1r zVawf)Uv;;nq~?~b&VL1R=8(S7K($!slJ)xg$JD~Hg1WyCH_0on?yWdgueg)ls2ZVQ zt$AXRsjt0ubpw5HSjt6`%EFx}?bf8k5Z^f<* z?=CQ*`MV}i95Ao(tZ7;aW?fkc;q=UZ4y1hFJ9u&_^2Gcc$;s-|gDA7$k*iT8W}<^_ z;^J)0FTzUdHn5f1-%aRK%`z_qfO?U7U*v1?AjivD+j+_^Wih{+=`D(!iAtB zZq;jy96vePky@U3uGxm+ANS}F?<@bxRjqv~ib5Tc=6eqC+9)P;NKC+f6--K+g~I1!VV}JEoJmxa zes9vpy==0BI`Jg1oj;*Jsswrm;Gphgya_q&9Gu}C$Zh&nUQ~2B>-|$<;*Fen4c`q@ zivkmSb4sYEFOqLD^wjx!X?>1O`9_ZJ+4#(V?HjNL?jHU?(4(bU5|9r8h zFTTC*XFV;LuOfn;+1oDyX&)hpGjf-r0G^=n*VcnvikmKQ7MJ>AZHON!A>^U2Plw5C zjdIP8$Eb$9GIkE{gdEijnfZ=th|6*m0e;*EAsfL*Br0@oy0v;Xr5Df`1^e_zCIi8kyHr!}2?AqirjH3!fUNgpm&*SMUzxC6zdJMvxR5PfVy6h&q z5QS9MWlbBlHBhfJM=gnXPK;6xmsDJ3XUBpfI*!NP+g{s( z*g;DdD{h0)?Ik8k=tBGM>F8*xYGv!(O79-rV;Rhf#Q>)8PpF#bFgGl6=|W~hY4P_y zUmZ6cKJSH#dvDgo=Zl!ar#a=k%;uc~M7c2_#0GiA%`@HFY-OH4L%XpE5WWMCoRIt9 zD0EXICsmAx!0p;P<6my8;sO)JqnZrj**vr%na;Q$Ehz53D$&8&;}@O&MzWHrN1;hF zrF45{-SeCMPD?e9pB!Y?pD(M0G6T2P&t*MPSmIs3E&#lQ9Y(oghG~kzEzXa=)fDxC zbo`L$Y!+wq6uP%C0kTJUSTf@gO;KP>BYHVB zGQzp%nfg2Chws7Kd{iCKSflo-J$Iu=mGBiY z)S7inoS6KCB1ex&z`mgIdYEDFkA?X!z_jptQ~ zBaaAFJ|3wozjD4xzUFQrv`KYv&9bM8(6O!d{d;)fZ7M>ubaVLZd9|2Z|FMx3V;?WQ z3oS%YVQre|^2I{0FVVnd5B^<~@Bd3fIPxd(6t%cYuxW~Q!8GG5Pmp=uNtEq@0ZyuV z+V1`llmlptb6;_SMVg>_Ip^FbMO?GNXc+}P8lB%q@7$&IbZ})Mxwby(1Pod>*}fx_ z!-}yf9~O`{%YQ{DkfLwLyoG9AIr!|$+mG}Wp>uHr$#5HxBAzhqYsj3;Y5e=0Bwd(; ztGPekQJF{@a4UwhfkmAe5!e}B6Qcf!p1;^Zr zcjqh%=R1bDGQ0)PE0Yk;SJOHZ9l5b3?Z?&B9i7qTYeNKEZNZ1i!%i=!57o*&Dz9*@ zo`_zreSDJ38Z0;Ig=@zCdiB}AvP>xDfD{$jycVme4|rpc0E)M}-eEh{)b@m?853sR z3CQs&_fJ{(@4c2H~)H+7V)Jc!hj*-ns5HI`!qCyr+?naDu?z`bD?fHh;DUi z`u@#2rrmt4Ac418l}H6i%c!q_O=h|Zg}?;Ayl+%}SQPwK6&6krAT~|CfH*|B=DTyv zrXN|0t@C8{3?ulU6Ml~4WvYw>m-Z(ae~fNYN+cAl15}P)j%XJuv)!5%_f*mJ$ANtL zFF)TLKIZ*<-rrLWvpGsBr(?#m8abX9V~DlGZn5;UhePen%pd?yrD8RZsatnwKiIKz z=!k!qlmCI0M+e%wrNY{2?(wfEo__R^bH&3I2gw%Mk004D!@tgCX-|9ntHU4tET|SE z11vr#wSbNZSm7i*^7^Ix!_>>UjXSnA@ht{)OAI?}BQi|+$4vx8T3ue(Qvfa2NWlKL z{F1*B>$3M$ar0#n#Y!=Zyi-r4$E!#WMmkn!_h5UyeSX(!d1}Q)G}XRdf)(!>J|(k4 zZBab}cMM)y@JAuU0qj;7@tTENUGi)MOhr}%x5@aUjFoj!^0zxIvx0nY08C@Un~bg- zyJSQ3RbQ1HpgX8LzaP|bFSmM03FeS$!9XXW?=#~Q64XBvoy(lu6~k!cZ@dFyQmu$K z+&;)B9`Tj~jcEfTf~y{TzH_+k@MSKg*-k~MlSO_r9JIqkI^rz!uhYoyDlz?Bx4@M} zSyqN2m#*s3PD9FIeDye|6*`=teR0^T4kWAhiX(Z0mPiU=E{9D2<8Va1K;uifsq8!_ z zO_*`;gyc(!92=iot>fOZsxy8x8~Ta;COr5n#jY6}x!m~2=3z%?A^JsQ0DiR2|Nd?Y z6oUim%bC;yLab#Be+zMfV=|4>S)22}&(h*7XolFMwiPhQJOvP6p`0F@AF77|lL7kF zbN`f(5f1cQQq!?#zY}myg!?@&9Kd?-t6{-t`81M?i(?&&GOuv=n+4})hR!|BtKd{0iNvcJ&;pbGeoyWN$M%or%%=;F`-KV&95tzYP89(1 zUEzPf`&PMJB+bvA?_3Y&OrIAej1$2R(vIASIqZ2oUCcVa?y1qovhgZrq3oviyifR% zoxq4K{Kz-s<#$)UR=xsTqhC9jw0y87X9eegN+Y2O8m3|1@*5tI8lulXf=rJpzb+Dq za8(=)b;l%8s|_3V_Z-E4*Rnme6K8YD3^P>}_(ns*s4pE=mNjCv;J9W+*Vbt3CDc>C zZ+}F+2T>(5%Rlx@luu^=?D5w}D0PDR-El(g`58-G;Aj5z0Nm)3Y-CQS^ai)5CEeEaL#T(hSM`RD0>Hl!~o<&UVuSdsMuh7JvUry3T>0Y_9I;H`RbbLw@=OYeTrR=Zu?pbr?CFndldf&lh* zP7UzL>#5(V$L=`Roknrm6oAWXGsi-!_7<(`hM?Ay!DI4filRQZ zi|Vhcsn@JSm)nscbFg{AV?{#~Lu0@B3Xj(VD`A3Vg zYQ%K&ZT^UkO^$E}1ht(euY>On5x^mm?*R}lB!EoUT3me2{b&f|GD7%7?T(#}yuCi{0p@yhfF2Taz3&AB$ic&Bz_FtNkOHD3>C1l(a0 z`Q-T5Vrq{kHSgSrVVv&E|FEeXV`m2)L_NSMC2cv@Y$4aZ-a?=O6|$Q9mU3F~tW|@h zMEMzjD2wLXNVZ!6_8X}??gLuL(7QV@4AHa&$JBUT)*u&LHo5?S&ABr`V%5KUtmYl2 zx~2eV>e+V7&35hidJ>x5+U0{5K-B>R$xelVfIh@CN|Zg3DK<4E`E+7?6F==DZHgn% zVMEnca013LOl7m&E8R9n?$-bYL<|&^Id%V~BqeE{n9<`Q8@-EHmB3hJ^eFe0dlgX$ zTe_o)ed@SjR-y2N?|Uy3$30?E8M>PZD?P{Gb-t^LGE^_OavihmbMLd@z$L+N;~l&6 zbU4=qXvN_MKW2FL3ol)Y9668&UymV)#-Bgy0~+qK&qIk_yd-L%iKmim*R@P1aZ_95 zI%<@USJmo-5weR~*^rrE&-tFFwwSUJZ#e&^U`!pk3Uog)?cbcrf*g-rj2`A-- zalTP(bhL+01!hHvJTj}wjP@}0)g*%7M4h)Aw8ZSN3Kj8B4|!RIK52UbXFxEH1Z=0>fGL{}fT+4R{*mAe2GU^W7tzvpr}xfC-Q}{8LTNr( z7&JXSU3+ynfCi3H5a818-r2DLyr=0RaYxdQMNmfbZ^N zp!1!p6iD^%!1LD59W=2&oo~)JdH_rH4q!=#H!k6F1}LoaqG;iTK%6l((vaYg~0-oHayo;zmYBdgkWlR;aRx z%T`&!cVLu-SHy25tjAuxF10(=!WPAZSr**)$2Wu|T>wU!$VKxRD z$Bqu9d@i|X1`0eX$Fv8$2mIGeU78BucaS8#{q<_2-fqqUt}Y9_ekDEe<*M#A=?R*{KvA1hvQ6Yv+T zF(8E--0h{a27Zw+%FE_S_qBB?9r;I9a0gwmL<+Rhy%r~{g}f#Bs~H>Z$KaM{LGrOh z+f$>V_9}0)-FZ)Xh;UqX&Ob4pWZFMAh4-0E=*(+ARH1p7oF?u%ZEb^{=tNe*RtMV? zEJ3j`#$Kpob9yn;^>U64dKfMiF`?t%C)<^>T^hR_%!>UJ%y2D53M8WQ3yOn*)dCQJ zk9Bo-VgRxi6G#1@4Cigl#roPMF9165bbG2q*TQaGQL^iwi9!e?&c?>p2|(z`0lSZO zqgVSw=1!nxB6M?xM&4bgK!LXcP}al4Xn4ErQje1VUEhw5jtY#ffYcV_L*&i?-2D-q zcZZmm7H_f zicd-k*>~R%#L%>0Xa;6d01Kx)&12y1etwTL81v>`)zdCVcxja7Q!mzO1pA=Nvw8gg z=vwNQ2I)u!VJ(nwtPgw5xd%+bjkyT-0$@LF9zzDc3fv14_>}t0HqFc(5lrclf950* zx1{5-&hX7osk5)L;F86QFkGX&!xbLY1CCaC7qIR{QV@&5AA942=>Xf^T!wnXf!dd*7|CsQBbgCU1e_ovreL;7Prr;fzny4 zWl1GXh83?rqEtPAIqs!X0&5l_R`$yxoq6sSfN^kY@2$oR>4vQKS(RX`FR z+|57jT2$v%s@YJxUCRou!_a6aG;Xu2OsC29xcmp}FsYEI90ePvlRe$9&O^}@WoX#8 zp>8l?jKQ#FuoYN$yl?A!$uI7lhW})1%HjS4V7CdiWow5W`jftgR>g6(HgfF&GYRQ? z|7PR30V<3azYQY73QC#<7*FVs7{EO&)Qv_q9;NJu1_lC#E~OXlz~KT#_bt!?yF#3i zycmNB;XAxzIFMp?-9+yH=k~P+di#iNo0f(2K-tEUY z`xyWwYdH&PIjcOL{@x)^ohx$R?{&@7jdb4;%$j!?P7j-1$nE{^00$NC4y<7Gx9FdP zUY-YR+j>u;y%O$==@uBKn=IL)WRYz`%#JD^4%G!8WS{BaL0A-}$r0UHnqZ=Uv=TZM z*Y7rK@pekw+bUQ5^o;uI83i)o`8VU!OU2gA$~z4*0^GUUidtS$D*V48s5;8@5{bI+gFx*4OMeUXGURU@n+vo zQ2t5;g}ie?0vePbV=fyf8$l#z0E65DNav@E9J_tEz=GHm2$!T zs3_@J)&>4H^lId50h_ly4$f?FSg3qhmPRI5@t4WDr86XS_FOJ!Ki4gvu3D0||G^w> zF2e>E)U7THwrAmz9lcnue0HewCXR_{(>Ur@$jb8b=NIei>x_)CbS071IXnK>DN$)r zK^m{}#LLEz&FeR)miKe&#p~AqimkPB5?5w}Jk6PCWa<6+;b)@4Xs;b2RAE%w9Ifw^ zOi2Z3hjXAzevL`vWbCfxj)zT{m&sq;bTae1+EP<|=c7!T-7r6L#x&;+9hqdAlaqr6 z_KXArB?(jW^{#b~Ax{t>{OP0w?2Kv+j+V*phke|Ff;7OHyMG8QPap-xNB?4q>t+K9tcK_sA6L1nCv*Uqdk?VHg#>nkiJ;sDaxv{Px6{4AKxcq-kLJ8R z)OYe7EAM(-?Y`a0eMA!UqBsEyPM!*I``~ERft-CnrI=qNknL9pciK9uc9Zfb|${m}|23JV>A*?zp_m zP2$5=#MnsZu8CywmNN-CZ9{sXi_O&BgY#87)2%bS!U$2i{l>K$^2dYBTfq%!Q>G1U zAliV&9)WPQpM%DsQeWz%8m3@^*8ZqqKq{o1djnC*!Hg)Cm#7f572WiTT~7FEm3&AP zA)wUoQkhVwTZmq!N3okt-YTS7tB=db#~|A#k9+x?bkpJOfI;{5^8@Y|FO{?01}o5< zrV?p=0&NDthfDl)mr6Ykx#Z!t0UOjYSrB8_x;;alZ?B(mU7I;s84+zg{clYSL%pf& zj_ASW1NomSoW`(e9+~)7Ok0FF4%vRXVWodkGV4+3EJ4#*rDN5sf17J!l!SmPgXO7+ zs+Vg-4s!9vasB;zd^~vj!Pi(PsMDC{?>o+N_O2N-EL0hVC|VS4a`R{H#ESxZ z4VM7ZkI7Ovm+*xzN}Ia>GpMua-3c6)-UqB$5x~-)E&$C+Gh1yLqAbS`1}f>($L*NJ zsm8kpVCC+51ty}utIQF}o)?>#aHmG5YKv(SfY)4xM0fvgbg`rLy21d3DX?rLJ|%_S z>D6=D7tweBzHyD+ItVCzepi|*&w1Tm-}O#8zGHyQE(CDczD_+ZH0~nuI_q%0-qr<` zxK0#M>@V7MJpNZF0QT7V+TH5e6^9ZxZTAB|kk;4~;Je!US8oIVH>PRdgLC2LL~8iO z!T)IiYI*>6`UtP-T&O|FyB+5`yn~eaRYDB!o!LFGHOBw9A4rw`_bVb$4Adyj3p+Wr0?Mt zEj6strGFIoCh-i8f^nw^89$ z$Pf+}ljVwNYZuH%=kEvW5vHJ9wf~yOB zuk#5fjf9o1Hwbx8;9A{|Prkz*00x4!xP*}(K1PjZ6A(9@)2pki^83n0No)pLcJTI} z(=A8JzlnwsQaIS#0?f6^ARthsls&F;6nVu5C5N$7lh-1}7JUwvQ%-)jY$a`~K(ov` z*4XD)nrUy%<~tobj;Jnw#kQ!rv!t?7wuppi*69^?JPO|4Hcdwr)LcVa#X@U-!`wH;ldqXhZ^s zFPfI2oBF7VD2QA;h2}S9&XV*sBlzNz_1^1H(o~SS+w+%#!B=qFqi>tK$!M+V# zdnor~s;?cByEC=?Swkh`ziq@xk$r_kiA=copQ$Bn%}2JVT|1F2d&Q~_2CZ`jqk`lo zdMSBVsTCe_g@?jFQr7$%wE3wz`nc|&G;A%?uJm$uydk?lR7HR66V^XZx); z*DQnQQuAh8dPS0oS>>W*3PL<2REy?&8Z+WR)bLb=(Jaf344r@V{ph<;vCHn?IMZBv zM=ud@Q@Pe?*y~TiH59gXxlt*a1aQyD&E-|rv64ygIp%GF0lWcLjYucYgMK^4G4)OH zH+vI8F|SuKjAw6S%dt|EsM5whT@~%9_38FOOqHxn^lqhEXg*XGe@dKA{fT#o^DdTV z_W4Od3#Oy0kd#f=X@}@2#^Ff74iDIwq}~|dzLYT9_)2@4cHi~AZn)|e*4;CB!k(G)b6LqE8dOy`Xpq}EoN;1LHZ zwQ8rRE6yy3gg{C#4k^sxgvGfqvd96HOKOW@Eg6c_sxQ>}pLsWIsf-2SY~RlrU{BEs z66W`ixN_FQW~LwKv-M4P#b^YTMwJ1x(yEJyC9HIhj{5LsBZH8IM(Ij$ zn&`WFk!DOYw+?T%?4^QMsQhMPl9TF6PF?e_XNXB^US@)g4-*(6p(%(fsu;r>2)E!tz~l#Vhq_B7T=-y5`j|&@Se?o-8C$Ee&TCj8Q1w{Iy%y4s%g(bKJWSnXqVpIRf|4z-#cDCGQ)trJ6#-9 z5fG}-$%P;IR^lI$v73D>B6)tEv4*guAdW&h*4+IPlS*~K zA3A-AdYS-*U zo`0NEqXfBDIWKePufx`A$Uf%2`g6$`3$=%zWcDjm_l6u!3E{nLN=i-TIR4^-yiiP` z46`rz_+Yr1oTD>`Bu?l-pr26}+NX6JIsrQ>KC^wBVc6l3XDHnNvk14e>2UjOS>(qX zr(85fb~xe)=U7%;{)Jn_%!l(l{{Jpp4KfZgyMvNu%iIg9l>g0aSojQw1EE?=fQ8#F zTl!8tbSuiSKF27yt3+m_6xA4R@ zxbT93$LD6M7{YQ-%v_K`*v+>Qp3k1BD|KD6eY2Z)EuFS@lCildqo&sJf6{<1YP-`( z!NQ|uR|~ft<=?k}a-*kMyMba`wTBw4`x2P!##7u+gfuTnWSlHj$Dw?0=o z#Wq}T_rlbNU`AsN!lK{+bWCIK>((lFjBfh+LB1)^qdn(bdv_Lqj&>5&L0~exe%=l-7>}Q z2ddQfY~GWFlNC^#1JBCA*qMUdyrvHwu&@|kOHv(?X z-l$r?y6$LEawVcuz>jk+eq4%kxnk)4uKA5{f^6)rp{l{~$%wo07`3TNqaD?7)?Ne7 zzho)>|LkJ#90=!rcBxkJ84Gcwx8r8wJ8MVfk=r2CfO|_iEwBLJ;)L?+{fA=MhzU8| zcXQ!>xsX!28Dnz3<@hD@D16;x0kaU!Z0_wk21AzGrBpvj)Q$*ssYjM3`|OflElMlz z&yu<4e`8}|kOTCIRRCHB`*WAUaf8fY>DAnMQz!z=R7-309bgCrtHN_+=yT~-AehVp zfmTG^ywzG~ieL)d*JnVzIQ%r0e%U&XOgV^Jg7ikU4}a~$Q^XCzj^t8jq6KFIFW-}v zr7m9pAGGcEAytgTOf9V^*77k%UwBH=Tuymu{o$JCXtTz3)uiYa{UuRVv!W}Xp+%&p zk?|kpTDp;6Vw0>=UIPfiZ_;b9l+bb7Apv2)m)4n+i-BL;YBz3#iy+Ovnx*RVGkBqh z#FxsH?be?x{^)+ZfmIxEs31xH>|oE*|HC!-rZDsEn^IaE<4V^f)>$Ns(E49YGWov~ z?@f?D$KKlZb+#xn-Pcl%(MESp6&J5aBJG1={%Y7(jf3!OWTZpE6b{^j{As>+h|K#( zdjo$t{)h;1{6w~~bMC=KvVCEcPX(!Je8=%4RRg?CNF+8L{X;M>U0&Tlh@&m}gEEI% z2hAPAtx*=s<zZN2-|1-R~SZ5^079I*@xjnh?NRh_^v{@XrdS-H8fkX zaxTxFjrEEu<2IU<%pAydqwbG#C@f!?&1v|cXq*bC@K+dPK}1Ru2A%=;Cpi?qlNdWM zFg)=7{S{f~tqsPMLd9lYFh5YgsXfB89Nhd2rpb=R(UPk-JoxIY4RTJilxljmyb!Oa zmyl~1oq(|JNvOwTf<3!poIxvoLL?8}e_Uv1RgSa}&-p$SFRDG&1a>5i+rS#cJ6z4Q2L6FD{8UlJZ|=qaO3HvmiXPQhP*4b8HZHKG9iY>b#PW zI{mt&*@@bMy3f6{)H?(*`-P6WJiBU>8N|p}9y$!mTQax(F?d=wOPX9=K-Mh`Cg8jD~eDgMyaL2Zrco%s23U@ot8=``99L$>V z@z>-GEDxp5X6-3RUFy}ru*KS<^PV!_H_6mAweWu-r}Te9&Ve#kt%<#85WdVjV*;gT zU=B993Ad*ZY#28j{^Zs3rBANp`^i^p+VUI5!ZnPq5#kzm26(I^^ZWT(mQ&L5t*5NVy0D_Qrj|Rj6Y>`UPbIb)QN5w z&QV8S@s~>J;vRd*eCy)VM=L$G&O2l&!^30|5blibJ`}%8DSN{YwiP9il9{lYQlkK! zjE2hMQ$tokQJ0sV`P_=0@s|EL?sDe6YnfI$dJa2iS|IRfn}r!%O$ z#T_BPmR6^=j0DLHUryi@1!h^h)VY}F(pAvL$d(g%9t2s=iOClB94fD|>7G2y2U%pU zlP(DP@_cfEAEDfmf_HVN=||KDYofd+Zh@+PrPzFdY6!qwFsMo!?W8&J8+%kSCEot8 z81#P~DR^2>5B13?cg?spadjJ?IQS4&7hzNHB+cgCBv=(@V#h&#E)jVlz1TRvZ2f+m zt?NS&Ny^+WbG+|c`@QcG2Lj7-!uZWXXpW3o=}j#|mB0dc_K>5Eq6ruzuyjNDyv14> zWOmn8`-mvVKP9mhL{U$}(D@|dPitSod@2jd3Vj`ptM8#d&E#v#u(3XhWwIxs$GK6} z57;kA@tpf=T3|TznqP3m{KUGS;=sq?u)pDt5{R4o3lY{)YG#VlD3YhG>2N2U>k~iZ zDtX-4CH*7v@Vo1Oy^WvLC&e0p**UjQJ0Bg#R9pdKNLa=*Uv~MEZi#dEQK#l#1FDv> zeGxD#oFsh1&rHq;v~~5M#%`B*9P^|<09mIQp<*yF#SV2YHV^_f+P|%G(;a#>Sa7&8 z7zZg>{r*?A2xtDcBpZk`l_q{NUq1C${zd%$j@jmiRYzc zO}L_S8U5_NkypU%F{Dw?mf9%yLJ@?JXmtrcp1A(x_3z=}`oH_wmjH_KqlXK3Do+$e zvB*Z?$I?Ag*RpGY^Q7bN!S%ZAZIT)h?49r@8NT@0UAV&GUnw57^}Qx?k!rQnPWbSs zR5nIPo${4J8)qTHGWk({HRPb!w->@Cxn%H~mJVWLj_EngUz(~yG!%b*-t|O_p=hS| z3&|8b2(R#$K$M>o=*R>s^p0DTQ`9#S_`#)?VEL@@7vqh)mpovBj>@P$9P-!-= zm@T$0HMA{%cs9wGTJAp{sn${#r8f0=NA~D?N*Pl~aWpo*tiuASezW2n{$bv`al>R7 z#Fp@;r+!hU&jXx6swEVh(*DUiEnb{kyFR4a@1jnbA{L07uVDm zLcryNcc7A;(@&{MU%pn2oS&AlUws_i@BPzJ3C6rqcfXn|s#mD!L~_uBYX#O9(c>8hrLZ=74ZZ$((-QTV!(^7%UH0W=+Hz=L^ zSrUsu2j3iFxD0CTJHGJ9oRmKBvn7Tt6%^?fCqu(?^W78{q$ zx)qK(56dpbK73q8|y(W-ues;ZHKQBbV8>g z9(6)2mF@>BZsjczY1Z_g{5m(tB04pX5&zp}+;Q=r45^YU!R{w6 zr;{$ai%MtZ{;jL*)pBaOAND|u-Dk^nba-Rcy%KO7Nh|TGT1WM0Pr_3{#`~25zfq5j z*yP3JZ8LEsRymD^MZng&0}urQLhD}I>oFHbjMiR?tvqP~n+>S=3=MA_>nxA?nASih z)yI3hPRqlV2M%uQRwkEKW#%Y0-AI%-9su=b0r>9s_P|e>p}?H1{T)?fcl#5~!FvVw zxD*ASiC(qx5pr@3V?Q0BR?~EF;_%!G(xtC1k{0@nI@tyrz~mkjE-x7i9;dtzvz8s# zD_^z@fanGMz6REN)=Bv07ZMEP$1I60I!h8F{=IUyVM$ppy3bR9nK3E9 z@$vjn?!7DMb*>1$N53ov4n{e8A3;|L#cZS9)Vrk~u*2N_@a6o|z*sr`0Wg3jKtFM`KCW_dS8d)RdH%Eqa=tb1#L_P#2ayAZoJ6OyZn# z28*BQ9UPuor-lTam0cV~t66K(falKKtb96xc3UP8yVTP{zL6}b-k~R%wrr_eziVZ{ zWQn&N?hTPx)Kb#!ILVteur*P}>&Y)wSn;geQII#I;8gT5zpKRSTe|8;-NR^XH;amH z6IoV7iZ}?j3UFSj`SwRif)@I}T2wy&h$lxFxfFZm;N3|N>Hu8$Pj$&BX{8XWZxJF# z(C3WP1^2G+xENl{R7!<;ENo9TnDg!wc2JPu7scpb7S4a!!9O3*_>PM3P@$##9d!kF zi*X(vNu67iJ!@jo@clySq8WbSL(d$a9}g+Dis0QQ;b@Y}OT3fY6C+G8A(jq%m3OVBK2D^pt66VGXG2tf1h+4qq&@%g{D z8kcMC!atAX>pGt6ZY0>A<+8sQaquIo&N{z0*4yB;Z+8okHyz-ab^~led(v0O*_Bq9 zPKWk1X8WGha@GHXaK!(ALpTi1F`Y7W$S9+GTz_*Up>=y2%sV$v^|bq4bzPB5kObC( zW94J;vuWFiGsG{7+0yLKmn>8{u9)!MS|vDn+$Km~`5X*Wq*yA=jZ|Zjst3PUKQKNB zb46ZO6dPO*P7HrBWIi=u8j@S;eM|BE1ue#asMIdbjIj$!*QciX~3l`9br!j zV>N}G=I>1iF7lt!Ur$Kbh=U@P=_vEU=kE7VgB-7)liSrn1sEq805|5_a6cf zBweCZO&7E6T!QS(S#OAROMl&Tx`ZWrq5bpH2IteUTa@&EuxQk^IBcEwHr%hW!fm)!1wFeXWRR!%$8jp8wvQw^zqF`eH3?AV}ebYoZ0TmR|b zL4lv%1`5lC_R(||VbRf}=JkNiXfZczh|x{PX;RaG-QElwjcVhjsB>gzS%L!ZvB>ul z0<0&uu&|IDk}N*)+GRD( zi7y=GMYZzZaG}dKKe&ADMFnhlIP$cb4zl+%$}%8GV&KQt=6Kp)$gd|Z^+5zcC9q78 zY-ZK6m+7agZI_~iz3!RFnA^nN6N|?BBH}iKca~Ft_|kvZ7k~_2O?l3_Pp|?Ac#+)e z7qtMy$U{%1$nM%*V<0m&GQpDWPa@)DlNv3x8^}sL|MMe%REkX|Gk~*fUdXFd3dz#c z4$M}w{hPzY*vdL#$#!tzNmBa!gX@WSN;9UcYxCvud*QxCDs@IaMb84(tYqmmaonvL zT0Jc(67);XPHiyoFXJASgM1Q~!qsgt@9jB3Lh&!7gXq)RSXRBDpy0>cj@!{E%ejFg zI$a?gy9?2&h1oLC75>w{a2Ek;Wg9^qrudlyo=#Nj@vnJL`VI-}LO`UCiQ+PcfuE+M zQBPc=U!`WjG2cRGp!A3+z~eJ#QW<=bRgXJq>!_@fTgKvRPr4uN4LtcU$%=NNxN0X3H1tWKri+$=pXmE<(@v>`(aPJ@hFAMk?&1b%Z#ylFQrHeSpQ6apYPOG zUe|^8Pk!w9G-x**7H{VEloK)`yurqEW;8#}EkLbT+qQcJ{B?QXOmrL$FP8B!HMpU);ZJYspp&VSYeUBIKH*P9n3*IJ?d zb1$Q%6IDu;;(aU5%RaPHh7lB%FaMn5Q{2X7F~I+KGcr$`FLQa}5aSq47FZr`PVQ;M z-M;00Dc6kf*({U;2qS@_P26ud)IuYpzPJb&!Xq=&ed>VtFATjr-(WT=_qEk zja_?g=q6NG5E~>ZBw(k)vxuD!#Bd5T-zy9VwkmY9D16q%ZI&MS_uCX97Ffb%u?n%Du*Zbx#P}5wSN^x}?>sae%$;BY5)8ABD{)yrIpEp-rS4$+cWvg2(DO@sv4SDirjC5u8Aly_bK~Agg#Wx@-r}%1*`l(kF6sPSXP~z6exUD* ziHg56r@LR+wpr9B;MT=V&Fh`v({30DKp+99%$ot! zrJ-(bhXvo_jTRO^*G+v)T1I;GyXoD8Gobl?DNX4;%YH_2(RN|T$HkkzL;rwy_rghg z##4HsG1K8+7Wo$+!8d{;!nI0@FW!bH!6Yvf!0Fj+dF<)6s|nhHS#}}&cqpyV#~&Z` z>anKW?p{Mak}`TQqI|C-;G*)Xyr<{NPlaiT!(#c4TtCsj1_g6qvjsQt(yp(q2Sc!U zu-@&~F(}myoXXh?cK%~MIac)=?_`Yg&8+2Zqv3AJ={FCG938T#=xe;+_FSf0?A1)4 zeJtq-9KC5l;v1IV|L%$0qBs52SQf?aSV)@yLSYm+)Ph&RRN>yH+C6If^n&U^+zA>w%E>M8k4}K1Hr)YRO)4MSDwZ=dJ_CJ z$*y=mHz&|)3#Y6qd>DwbsX3MT6OVGP{-C%2$k@!lAQb4Otz3La`lym@VVlg!7N-{5 zZ6_Cop*Qw(UsZ=YPeJm<|2nwKtZ&0s$vIN;rwg>Gt=c(ufc^j!PIN%1iD@H%f<@k7 z5f>P509X>No!N=e=0wH+SodPqn#-AJ zb6Uq48L@dO@dvJRN+TI zU-{K&U&LRq5w6Mqa!`Jhxk2dTFImtboLyc7!uPDxOU)rY9vTS0W|{KkzE_lZ0YUfi z1F7tbHWWgh(wEaCd5z-d6ek<9n?Gx<*^_M8S}QCt?@cV&if|V`tIw4AJRXNN*cW>; z`iuJ83#(-&us@P>1Da1+iNwJcnXH{vjG4mDs>ZXE6)xjs;W4f4za1gV;S3Ty4cg|*^}R^I${m6TzZ8jnLRf4&t7+{lbXQ%Q>ci*Y=-Y36K!@aG z8x7@MnnLCMleu$}t6AZY;m9*jZH4$vr;IYO5K@FoBXKjG%{vmF#! z6%V{sWLAotaz*Bs22?B`es=^o6~d;C0!x}WBpe84lki({_p_-OB(GC|l=^tOy+d+f z1xT%b`on){5+HS51UQrk;2ty>uimn+jt3UBj8HRSaiY>noeXmA@4G51e??&>7e3J~ z0@&0Mc2q|zlH;6!!UNvO59QB^LnxU!;$Y_|cc7!uztZ>(t8(uOBzbh9(}jehu%Vx> zS5a6jUaz@Gslp}neg=LUM|onAZm3G}1f1t&%|>5hE;s90bn%oyOD)rOcu2MZLF4{s z!?GQV?GpJuWs(q}_?iTFlFnq4@8~(dl|?-pFJBwv{>65>{QB}{)ZjBxGDp|etiDsA zf9704tkWik?zw@&eRuO4!{7Os+x8zgFjl|!1;K$!qv|T21c7(6dkRy5cPVFy(hnxT z6FQ<}3o90uo+rBa+aLMRE@v-=%GO3*HV6A?aWmbd-Tm(R%D4ONWOf?QoiaVSQFrzY zhO+7CsaL?@7V<4m|4%sT4wUyeS%1X^h?k0kWmvVlR&v-+ikNcUur7i zR=2q`6V9*2ogw#8;)7AKC1KyBtj{Zt;Y;`sd z5^t20k@$}*95d-ycQo@o9aLMgT$;SpwFWFEU-%vcwGLzrqL3l>wnA+PTho7+2sXfC z6wTp@d$l=@6lDjVbZ97i<#crVLg_& zCFXow(qZF<{|F%fvUu<2CN9)+y6dqNqxybhyp*hMB^RrPon{%_$_iOBPi|s50jf#% z2ss4#Qwum`{A1w!|5EzjM6tSP{6jnBiAx?piL5tRsUFdcpcbmT2V^90kk`2Vbe#wg zP?%l^AXHrMccAP)hI#Yy^DX`l>S2m}5fL{?7D3u%`MQzw6EXpbEr5}XEuxq?fU1|T zGYu$S$A7C`b&|@;@2@lRkc57tHWI>`Um6nCrB*w&sK3+XV=5&40qN7dm~hhWc9qq@ zX}-r-M9!8m{o3>5fc`)hnS{S@Aa@)MP#KpDhr_U-NSQyuXT>7s$0>|IRr^D(UC}cy z`Jj9Dux!GVdy+}3=7-j#P_Xp2^4c6A;RW6dtA_7mlM&&X?5c^(yQ|yxg*AS(eeW6{ zbMew$P|R?k7!GaE@bC96Xo-hBB=Dzo&iM$HE>feeeC%jWcI)IgL_KM@^y-VQQqXOV z!ShPf4=MRhe#;deZ}(P;E#^!46sA6wbsV{+_Z(Tn@?=Ar<;?-|^_YBFMU=Xco(qf8 zG1m%~ekZCdQNzQ*yg`{AxYgUcHT90&E&wvKO+4NC(6#rI-?I++d`z!87Xmk`vBhHx zeZI&a#x-Z(Rk!jMbVB^JZvqT*eI{$2I2yaO56j>cW*tA)%Q^Hm?$^jj+K8mkgWkqwyOI;*d0B{ z1g1wmzlbO(aM+|nUw~bQRq*4r%`oU&kN-atAn)GYX9w1VM=Q0d`35=dFO;0MMGkS{ zC&Ng^`laC~J1q*cf4@jvk8K4M-PoOT(hl|ui$f@25|0A>-)~`R9iy|(CbJ>|-M7t6 zvNmn=Gq@jG4)47!DYAKyGD-LO=`Hn3EYrliXBk^zzId^5Knt*w_kK26vr{L*=`GA4 zk?%k4>IW_1vwXi@ed~_-vh65>nQ|+Isx7;HmmKbnUO=hyKQ5F1+8+4m=)2`s*XOmj z%eL16&t&coMqVS=q8^*Ki-)2qz^o6f|GblB?^C|A*Zt~xt^!`_IK?J`VAIGK^S!HX zJp>YnD%zzSuMqK=X&yEM13*J z@(h`D+h#>p2l+P^$!EwP>$iU^NP5nDJsbXo{rTa&Va1u=o&wftdeuFJRxH~5oS3Nk zlPgNR5k&$Ie?zYe4yiE+&?^hX}RyXUbYGsk@E7SQ)C z#quOj0X$K3kL6C(I^Kiz$FS)*a6qmgx zq5#kloeS7!^8vqwB{LoA03BI5NZ!^xmif(?{ZCQ;jmeMC0Xb^DCFlrn-+3ZJMwI|D zzke4H8+4Z(R51pv;EKsZ`L02K7WJW0@xTYJN?pYsw|jtHeZ_Bz1UKp zf036ocWt+*KFVJRJAW1Wce{yCBp~e1{f4CEME&2Tt1dmk_giI@=5sVO7od`3wyH!?b_`y|1y+O_oJ3P)Y(l;BqEs|4DTuInc@=Kf!H-AIx6!Uu}5 znH-c{fvb3X*qyN}C$3&4mN`x}_TiX&kx_n$>YY46mBnYJD>%J<5y5AywgTU1d6Xo| z8s@HQSUkKmQf%C8xZwJxx|nuxfMrd^F9X)Ln%&tLc-Xg4Ri?MkZhZBW1B@d@?QGu!JRwLF`Bun;Uhb zaD4bQYlX)iivzB<-tP0&|IfIz{XXm|ss?TPPb?qW^lA-we|g9h4iFLRU9|=DF#q;7 zfM)F=bK}Vx4=c!9)gogH6L~|6(~_4WFArb<1BAxjA+HQz5Yqva2=Ye&D^wMIN?71g zAoegtqbkbFZ<2{$AAn;sDiM{CU8TI-u=uZ+=R6b|6?d3sA~$KFq2!80&h3#xILt_czX4}SgUhuqb;^E$BCJYK5sF85 zJv*8~Y9a+a_p<5d>y?%GnZGj-Ci9Ks8&u>*wt_4Y{ww+W=mWRi9Y;Y@@iW_(*=4uI z)|qH>RVl9Oaj+6I(RyJ*z7a$LHNRK7D(;AdmvuA!pxqfLi6k(i}8#S{0l>=EEuDPobKUEgL! zF!G47`KdJqetTg^aQ!6>%<_4VcXu`}^1i&d)sLkV*ZIb--GReUN>~Qb;UL1h7?Z4kjlHKDTnRM-x-tj^=EYf8WlzmRI z9MOQ5o(z~TCixSSl300mgBTm{k=+Ogqxtgm9K>$bMH@ey4THN+mha&t9t1d=K#9vq zC}8YmBe!8#0i@27Pkj2EgTRh;v*4bhV6IC{{>6tK3k)uvb6Z!t4s~=++*lhrg@k%T z{^St!w^+9u^&1!}*h%h+b&DqWz=)6ZU|v>$H3Y;{&l3LAZs3f8^D(&vYW;Maa9l)X ztnw|y`68iKetO%p;vnm`7ML##k<1sj)xW zn<90s==OgJz7HUql)x|}*sz~2%6lXE>!um;R;NUtZlJV2#o9u1M*mD>-l+q(`XT*x zGQ+YBtHaL?r8sSP<`1?L%M&Om%<6N)Mn)!*H0)o<#W2dc;sLz#5iIWU(QlhIiJAAC znNXpDXUfz`K>}HsnWmKu#=i4(%fZ;Z{j4?ftkTmPyMfh6sm4Xsgk}HC4f;|wTrVhl z=dEk)ehk{&KCTq|{dQKI#9nb1oqq!{@x*fatE$P5>w0VwszsHyn$A!DDV~Eb=$!AI zoJ%oBqeL>ZqKN=KfrSFT-ksAPtXL%S{6sDaax_CGRPj$P1NMBcPEQg*+n^P+JR!RS zNoJ{m;6@8T*iOD2rpK}YwFe+n$)s6{S&N^_-~q6HIw~sx9>y499|rW*<`wo14nn|| zMB)*5oD~S(c0%!yz)*Il@$j}7&NC4C~0c0&usmKxH_F_S4BmxZB9ITuZypE1AH7fdXP4v5eL%NCnQ(_Q+?)z-3`)KdJPE`@s| zlU2IV{npB5X}$~D4C~i;(0XR|?pq?EJzkoL4uR1}FMh<_(EZkY`JhN{B=?O{dpqQQMLp%neem=T+NCGcR_+a&V^sW@oiu^QZdr1#-1 zMod%Xj{VBuXPcH#f^L(ogYHp+J+tmP!8nqmPcty>Bz~6HOy}U|Qc;&tLNW4Q%Z10v z4{c5D2Y74+TM10H-avvZ7e#18s_0(*?uADAH*ISc@`MMG}Bf7d?l(XZ>n9B3}eY zO=)Kj`mqB?Dpjioz_;Q#Bw4*iRoNF>%l*!dxf=?AzwmeT0;A=&#RH~qAelE~Q8f(a zK^IPzqcUM0y`1Ni1hkSQIkW+2~YM|$J)AO`%RQ{x1&+(Oj zXA~WLOz+qezNUb#&?`gRJ`thwu{W5~A5A6OAgFPM2Me(XzTeJNW%s4C_kUh{AM)VI z=!AKt+JgFgK>9}xK1#I1%eUPG}JCsx?WYW@W zb;~3z$l;WT0lixH*@`$ERtQA|UGeX(17l_O{lis%#9nts7q`5mW z&SaJJ-vIiD7mxfFAZ??bv7o$cO?64xmBJv(Ihr?qPo6uD zYReW>w2441bQdgBDg+>p|Jrf{B0QE<~Z;$vQ|nt6d=$nVcv#$hSp znTeaX2o|rvXbMx{$}?i+3ZIdQx!8jbP+7iIBd^?JSgYXPuOmIDxy3$;xp1EN4D~3N z08Fe4zY{zFroR9R4MJG2N?<{XN}W54TsUX`i!|UkvdeJf^q$EL+v$Vv!xI_%)=JTl|h300O$9%e~rF zxZxADbs4E(#y(~q3@!E@(Mf6}NiDn(x`0qa8$JxDRgJqC&)8=mH?1$;=Ny)f@MiXrD=1!_3M|QNW3}5ayCP* z!dKVjE6135XF3KyXw2m^%XXe-pm{4;J4J2q3A%S@rkREaQU%JY_ zq3GqL_`-|rwv-pfTWNQ7BYa`aJck>%sje&CHfGJ`F`Z@3y=VijF8U1NC$OiUzM+b{ z-zd_2f0=Jp`>ZJ7vDqb9&sDe?#n!Zb58cLfD$9eAhT(^8>eZyxCjAw^=os?b^F8i88$+eP1?TXc!`+k?(RW zLml5NYb2%8{hi{b{_9wfp-ZArB!0WBakbDwFrGu_sbn)fgwJzx3Q#W1ybJ2;30UDm z6!+THNnMGSEhH2=IX9_|_fwznqiRo{rQJ2lD=jLHb)^YejDbG#ODL5&jwkW?FXHq= zv<^%n=@9N7b#R%B!DvbPp`xaXwd^jkQs+5Q@$H8Wf{Wviqf9sFhPS8q)5_NMwM&KL zqs^y~W_gsJIxf27t&XjA$QJ`VRO5SUt`8It)%i?=_-0qSEi=8#sq`zF|)a=sx`^#e9 zt?69`-%AU_-IQVhmM&Beo2obc@1lSP`v0y|g}%|ZMaNRZJ$&fP49dJZ_0}%*Y4_Ag zYmKgjQU6Jga?UOblA|ao7JBuTqPAPrwAf{2r0nr)`{+Rlr-0r=%wbkHiNiknK+I_fa;APuf8H9zNUWfFZ z_kNRpd|AEXJ3h*Gv$g~6YVy~##87!9e>kK}K-u<@MCUC}O+ERmEk~`5ylf~>ZG2cA z{S5=N1*hym_AYT-c}-~#P38JKbNz8fSp|0amnIbYZpAfGZQppFsCs}m;^EKz4$E}; z^Z9_Elq}zjuH*p?x>(o=j{Yk#x4k&Yq8A1FYz8xrNErrVI}{vp=_bv-lVaIz4O`GB zqfm=qkubfMtEYiaRH*v`hx+teL$7J$Q-ekG)G0&&W4y=H&(rXnEw2E z`kk&Ze6Zr9hhr1$dQPSk1N`4-&frVQFfc$V7PuD0{){#56F1rgJt?wW4f5MA-c2(w z#s9HIiKiWjyaFx(i#n@x61GKeq!2)Wi82GU@N)Fs9othAbD`%2e0h{h z3mAu!$9?ZC8)-_MvsU6YWqB5 z)@=q)dhRZ|Rvt54I9#z@IAzAVxR{6u%Xt6qHiP1SnGRWZnNlBj+mRw=o_pjAp+OP) zjNQec!wS;`*F|~G!;H^gw_>{PQ|ojXQY=P+t|a|_3z@b<8+4WFyUcg`*8i7*M|ivd z^93we-s%fDp!$9-kJVHxvnZ-91$~MyP@@H#x1YyZ`=~#osIhG+MHYGnvx6^YQ0g&4%c6B05{{N^ z`O)CHo>Y{HT!*Wy-qUi~8X*DH=EX}iBNJ-8h0l})x9J6m9PZ`($b!qM*rZEO zuN>erat*op%C8e46kjx=gZLy{4-MeQ&yEw|Iq4ynWn}YGw8#R-#YX8e=V-0|U^Od6R#Zarl-Am{kyW&BdmiC#cy`!r zk4*kl|N0IXHkN0mahbH)zPue-HY1H%Gp)IzI33QDu2Ywe;VJmhdgt}TAW>ODGokU; zwDE^1_Rm$jP_-2k-%kQAh!T&k^G1fZ9M&+GK{Yg&t-Z&r<62H^TziUdk)I(hO894A z0=s0I%i*u=r2yENSYK``3lmswdG23#YX0p1@?)+Qna47IvPDy2p&UTS6r%Di+UI4bN~gVB7}bbz6sxVZ3=|YO>GOg%gKJT zR;wT0S_$2RNv{Q^-|zX!H{W%vwCV;SroxQn4CduS9@_kshP44-c(V{>$#}IGR8YJW z{iEet{Y=e|;)Dt4Q(o`+|1u8-xwQa>#L7(X;>VY_i&Ua>)G2n!$Ks8``fFxCMSK0| z%?2rJTweqpU(H+R0vJRoc%O#>PrMw~QDtRxH2yRysL~9^E{Hk3DW`3vd49)4Et*+t z+2W0#gAbp%+0JQz7vV>jGVyC74d2~_7U%jRT*bBcA)V@q3~6IsS;>~=51=#t^mVRb zPug=)QZCweA_2m>H9OgA`J@76{a30tN?xV-Ziubi#@_-dR1eFE&Pt=GnE>Us!nu>^ zrNvge?RKJPx|Y84mFhnhV&{()#^lhoL5XK>|GJo<|C4sn>Ty0B)1mrwKjJCPU3{Y^ zEdG;i^i%VHn$)sJuGc~-zZwhBRkt2bv^LLB#v5qzm76zzLyr%#YkpafLj}ju*6P5L z{rs+e?^5xNFTOUVcN0s{gN+t%`&{|{$Az03*K+MYe7Zq`_M3pf`@OF+s^DECzPWEH ziVfhg?0kRQ?W}}(LlVE1`=8F_#NcHN%@xK_;xTXr$e^ku3-qWwYB2+qxgnDx;|2Vi zHsfcXKwhdQTy{d_+SB`koOKT9vsPXHJWSAXc8RPs)@&4-;e-8ln?oVd`N*wl4IXERMl65-YQr8WgQYk)K#gC{rJ;mB3c^WKCrw_pcQM;7ay{tQ5m_(wnZKY z=hOXfdkvAR`wUWM<1JdcCcIiF^pJ}4kish^0DG^GJM0^KM>|Y6=L@mFvxxf2ZKDQB z-N(5XUv}&SUCJ}zhS4iT$>*sjfC9y%OMw}c{B&}ia`0kY9NYR23;Hv?o2`Lfok^8c zo%|y|2Bkq}CGG^aXonTggvU^~Yyv#!obN(g%UGR^!7G1oe%o-{(7wJjHpsMbsDAAj z^y&-WUn^qG?3a0Q50i{x!hD*DbgUsr004-JSg2cH&wcHsZG802c2y_aJa zsNSsCkP&imq$KDkUo!01Y2kbkpU#Dk^mX<3rib5bZNF(W&oYpYr_A&I;7RZL$cv=l zeZ+360^9LF&1iBLO8fNb=7k#PP&%OZaEo;h=(2L{2HIx?TsDGv()(H``2vkUS?xs0UDk5;1SepfG}`94&26 zW{TKc4X(b~yD|?i3PSM}#95}z)vy~kOiGs{G#ikb#%UCt=`UAi#}-7fG*jE~1I%p^ zlJvv+76OvAG)M1`9a3Cr$cE-ZAj{GW{g=O#MkzwJQc)%6Popsz-JN9T+e!X7k$`)2pSn6q4rfuC(E~gPM^0SzSRfzG{$B$~t5#3aeOev8uTe$wi6e3RveDKp&k0_|E z&#c+sj}fiY9@%#Vc8{*9$5FFVaJ5Uq^x}}foIu}Zz@&7VqQnMiFrhdYP4IV-erU}$ zFo)gZP~0*v4u)jF4{6uuDaM8oLdGQ|$jyBU4bFp_G5#2FQFL6lG?4X%fy4^upwpRS0k?4jmUhraTBnDs!{WY^cdzroi&K8yJH5aj&Zjn*o0XG#cv z+c_`Wo9W!ke)-B)L>QRb{=g|C|L)L;bxK&emOaW*d*(IbtPr{KEn* zv%AX4srqvN;Q)+|HD0oEU_+~J0=HL&8uN?9U$gni_Aw@NA;HFBd zkTk~6QD29~k!lYv+#LN_19KQiKHZ2qijRaax8U4H``s$Iy%u4t{o+oMt((Gg3HyJC zEE2cMY6WS|pQ4*>Po~E-;T>^yEzp{nbAOkXCm6wk49M0kN0x?lE14@M2MD$_IMdlO z&t3K3PvFb;_=(#ONkfpmlod_Palh|aiJgf_M$N$K$tUDoXT$(_*38COmQ*)@csisy z@QT!dLEBr^ANFJ~4-EC!owcO3b0u4pU*R?g`r=$Z)(YE(2=u{x-4p0to3Bm@;STqc zm|ZguP>im$i{U-6GncX9manB-LF>yLrfsmZ^3IuV@#{L+UBrY5`s2AQX~PgJZ4aFs zjKLwGCUO04kNa+TJ*sGNKtLM?&LJyT(NJ^DioM8j{>c$OJ2}|&Hk)hu1Lw_&_Yv+K zmfOMz;rfC6-)9xcNB0z0+%Xkv;WM)G{chpzG*tD?58l4`EwWi;A*`=_*3=ePdLf;P9yAz&P}YWB34!hnt&iI7~$5Itf$D!$5dFPS!2rj zch3~kw$fM4IFiF?(N7|?P<9~94t~%C=O(^!x0*H$^ZOj>e_q8_YwZhJ0i&hH^jESE zD4zpqHl#UhP0Q9w*W7^jrK;C}NzKahw62p@WjG4wj5zB> ze3hCRlgA~!LO`rFk6Ieq=G<^+xeA(Ssm{4(1b)k8>)rOH$dLg?rYX1#!mZLo2C@>| z<&^>@SX@6|oN+UO0%3w#DX8b1sos7!ZxKsAexSJ}b)SNpCg?J(=x$%dfQ8#Qgo+jP zwryx^(yenLbtu99u?#z+;op{~y&S3-pJ!{N3-gQiLRqJ>F8V|uYOii7C())c# zvz|+&fW>1Ic6MG)-ew_b))dd!Z$uvLsv3v%3A6)dOWckcaNlk*Gwcw_w`Y0>%%)VO z31@UnSw7iVQA12LKdXd28K@gbPUSa!(q@L(GJtYR01weB6095Er_9%W-$ z#9mz1R@g{({lxma?G5V_l%24@afkYGa>az{#SLMFVeeZmbC2nANE@cwQY6WNvuT(Q z5>BbOm$FyiJPo^X$-<7sr3pS{kBVO7 z#q345oO+ztV22P)1CrPb9g~xQ(x}L+l=iqfcqANAYqDX|vzT3fl8+orvu3t#AojT> z(2WWy+M{W!gb;Ho%JTgGHlU$|uT`(zVb%7p{zJdcFWrm#up%=1y4(;^TD8U}F4dzm>AP)-S{UC>U5{&p!8vGtpX2SOTTu0q{ z8W9yKc*`yVsQNE+tM0hkPfej)G&nQN(N8hQ;J(Xj7;6EXkF~1QEVBLUnAsPF=Ipa6 zJybT0r?xL-ul{h%qlcXlB!G}kIe6t-U%Ca}dvM#Bv*#k3_&feX+e6-kJJlRw@>F(R z%Vu2(U_=HTMC+VLr)+Iv0!dv(&e#WgKyK|!e~9RFJFUl2OKaM%(1IEWebob4=`187 zSn%QA8pt1vPrPAkhk4Aecyu4Whcs*S&dc`goW26LGx@zsva|es_NsBCoLFVZh^`MB zd;=G!kyc1X-@~|xMXO-ML)|wgrchsp4?lm}umKSf&L+^wLr1jyE!PaHqT;P%d*j*D znS`RXx2L>q;vsV_{jW_qdzTjdHqtgN`zlZ31Qg}tt> z?o)5#a$nM3FMk>9SS6>k&xCX{F0zTg;$2Z$nd7>v1ZmG7cRr`!kV702;4&3Jq`d__ z?>1A|vpGK{(S&b&ksW3Mp{4EdNNGvj4d0xw`{-TLkjX*SYsbL>Wa$V)H3^r=3>D7f zK;mJWJcwnwnHSd6@ZH;w<`S4bI!q#-fR|IxgXC*PhL8y2z*!qYu7Ar8GY;R=cbUSB z(cpWbHF3!ENjL~$7q`I_M8F=3J99^#?okNt@U?eoJelmRftX>Ck3SeHph>IIC>Z;z zB_oKRHHHRG1cNc?5*^NymJNfNn&>P;GfadI9nx)Ts>iI^v*nKKS0ua%ekL2U5rmXS zH-&CZEllAMd%D`jDKHH+X`k-M?6bK!w*e$OPwJ^_jUm>v=X9|hCLadM^PJgDf*@iH zdCrl8r^TY6hUAlKPffSdVyThEGxig-$6s{)*VNRz@+5+V zeu;r11Oll_GOMz_;n+-kn2?a5$`%~T%7UqLfuBQy5~KYXQn1*Yndx^(uV*Qo2oIvBzYkV5AW^>4Cw*;@}Sv z!{by>`;LSy)Gt%O1i+ZyOj`mVQ+Q-L(^@Wgs;Yt&omE#Kh0H#vi{-H9lqzUc zMt0?i)fN{AZ>@tFsR|*_zqiL;$M=c@jhJZ23>4D-BXY7PYjUs( zzU8Q%TR(*o%iu5+PHF#lnT>BH(JYDH`%|^-t)P+lMYG4*@8eNiYIBM{T@9} zL2oOd>=@5!m=LTJ!eZ3R;NIxbe;_7gXIce5cxoZBQUO`%8iK6&fqVyC>>44~nL75% z51lhVTB={2iZTSr{E9j9Q#GbF{)&TcIO;|TnT6(7wqmLg{k32^; zdZ)n8!%UYK~SJw2NO_~HL&D`?x?pG zJYD|nA0FO1?co4vAZT=eBKzd*pi0ou?Q)Q`Dgq&H@f0({%`4<@e0gk6L2%Z1=S-yG zy+-v2gRtSdZ5t9zY>J1d|Iv9^4McV@n<+So(w~`hIm|E*!bXxN^zEZ(fX9|IG9DJ1s^yD$_wJgud~mokduin3JL6MOAf6E_pQe} z6=vM}>ldBbst|JngY|a)*N-O?m&!}gZt~ECv{k7Nh3MjDxLv&9BM#TWBY#s6h%uQ- zbO^X@wa=QAcN7@%H?d2{NhhVDpQ0P#btWqhSTLUVhtIlMb!HjjO0Q!?CI~J$CmF;P zPkC21Z`{N-V%L7f0t2Jch!2wE^M7)55X2Wa<*rT zj*WG)t#?^AL`|#%M>i8R?YZl@h?TMU>cowDp@~F^BayY?r2@4FrIt(c+bX==)7GJ`S6Xoyz>(7)+159kS_4T`o^om23IWDz zj6x6YMmhub@lW2hUEbZ>ql+Tz+eSV00;L!E&l%caB$CJXGGYG zA7JmTny<{FR|4=@6cDX(*VfjSfSDt`kYvS8*_ByM*Fh~UEuD^L+^Z~mZUd4RFaSWH z{`^$;1U`BsAg~08f9)y|cZfOE>ylz5$Jy%CJ%T@CrZM$ZaQ1_s^SsHiueqrx?d+rdS z>8#Du!{E<}84w?+$vCZ;$|FunXTa+lVjm$iopLZk3SFg!s-hKi`#Fjrp3!vn(aD+w zI>&}9-0c0Hkgc1-Qtyq&?UOuKs9jF#-n&Ck*;}?Us;STkM5IFCg4&gd!K|`&lZ)O%eY5gT>tzYk$s?WBzyfB8K^VR3O4 z;`0`J2SpO@VTOGil~ehSv0W?CSO@PR70bH zE@!~QJrPUQ{8x;L@CkcV@dhh)N*`e{!(j3I6!DRi1=0GQ2Ep1UW$z&j^Fm)5kLBGS zj+Q^>CGWhmjh;(OOXZ$>)_`>6#rq1T_7GYdKq>`jR5BMA-ya`tslR$f1!TK0K6>=% zI*a&M;KM7|nSSjq_c1@Qyb46kerkW$w%}B?NC5blF2Dwv7B`gT-%%}Sj3{^8GI|lk z+LNOa0mxni0iRiSW?7HNQc_Z~fb+5J!Ke;kp`2pufc#7rKGB4PDL3YkdbIr70998% zu!y@`NC(0WbqiO>SugDlb;`NRb<#Rvu9bIJ>?|MZ^jDrrq~TZ^SR4f)8KKJ37ZEJB z{ua=j>q$gCW}Hp9)ncQd;gG{c;hLKG#39Idx63{*TREKQ*%);)?7B%O z6-^5vjsknU1J5RtU#P60teh6aO>k`Sa35KK@>aezTuI;4f6MNo#2koxWC_0`Ykch35r zway=B)?(=*W}fGM?tAZRU;Em7%em=c_Os0_Z24DH?iRTobz>XZc#`9Kcv=3aWQX^- zM4a&T)U%t?JUp*ocSO^1L^YyegacBx($d;Wa7;xd8|ov&LBE^tR09g85U5q5rwKnH zC}=s=5Q%|eEtDD$T|#0a`TcYG`S}mi(k}ARJ8iVe$jPP7%-AlL=I8T`RJe70?a7N& z<5~alB^{KX;rv?3sD}v&y-B+p&E10Zk%uGIhN}H#uABSvL(vUm{Dph{{r&chf;@Hf znqjGHO&`Rh+^`+#+6UCn4tx$A&WeP32+tpkMR(oib%|;XmbjrjJIA^tfYh#dn$V@0L0~kLXG#wrxDUL!e8QH5NEriLWCx zMSeTY8l~ECgDhobTHqFm!<^HHVk6PsH%$j>gG|C@;%}9?dT*vUX_2P6PEL)C@BbW4 zI60?`dr|ux?Y28LR<`HTnw&Gu6w6*ec8#m#roEEu{LxX&zW0cA`R6**>i`c<5>MQheaZhA-xJ zr}1sYt;Dym?D!=go~aI$eeDlHhk{c1tYik{QNlzqQ6pN{4upejxx}amX?ZbeL|A!ARIalP1kyx>f zUXyjmy1a4HxM{4ZNT(>6qkOufR;7~OX@3t}t~2<)u`D~S&-JHtVd{4qXVvR>K1cUu zG(Q>>w{g{J9;(gAeqX#}gI_K#_jK*9&DnN&Te;yd_%70G=&t;}y~6MYOK>%V)8#c& zhnMND!#U-yyY0!Ci}_}I-nRl7mosiOS?W;U(Dkfc)h$svzo1+7YdhtZD}xD#t4Idr zjqIH7t_n9@o5Nl%9V@RI+Mx90SSeyC+TNZ0#bCeE=@e<2V!G(0Sopa4YVKf9j%R^u z>Rhsu&ZY{%a&}e=5z*YwZXubkZ8hk5*1_s5qZ`hHm0fdXUD9#2oaLUm z-!XRMKB;0O-zH(7$o1?xeAtj_qQ8<{3;3*~{Eb+fQ)i73PjA9VdpA4SZFWWU!v_y2 za(f*6=AS-&Ix`1w>eQ)Iyr)jRT-bD%4H#;DUsIC>9iMw(R0CtA#EBD;pjE^A8WN-G-gMzM+GUxe#Z^mk|W_EUV&f)Io7CygZ>TyhhUnsvV=)n#nYGOgz z_BLqGkA_{gdt_452~#iuN`FL_{hGZa@`-M?GWZ@CO4v8@q~%sWXvKf6FVsWjlc0!* z+jsXFS$U|)fBx(l3>8y${H|xLW^T^;L@xq7-?Puw%yJ%lt*xy>hHr8{TZ=+}g;1Du z@z!JZ;)@qAj1}1BVmsv*g*JYC0q>{j9M03MpK{u)rLAoms`s3}>&?ir$+{nd3r|W; zhO2#D)S(#57OBQ8b>j#KKAkU4C8wlFxQ$KxB{i-C5}D0U8Sc3f2~heZ;nrcs-2rLYNc08WMy})E4V-`;_s{U zsOwy$V+a&-rJuN5pm*g8a%cSf{L!3BX)p%kxl4tfDoUcGu%5eB5~LfxVbBr?IsOP*4vlT$wT zWA?R*%H1>eF$salEasPqkIXM$y|l8g-Y)zwwNsxA{XnQwQPbPuNhR^roQlj%j0MDXB-P)p5V)+TcjjP!Zx}ogh;X06 z=JWbK@(2dznY236{eC$e<<3D>vVJAH7rKY#3LRt+nwGXiyppl%WarVy{A-Oca>W0*yG%q@*N}fcm|7`EsErj|{ZHdGO6pk!vv3?w^;O zc|wR#4%L>zVWQPgE|mzm$){i6kdiz5)B`vT?F$s!h= zf*Q?k(?04$6ObSKX z-KY1hT`sG7Hb~rF8XBNEtEMafN4jsx&fxN8g5{@$Zw;eMOC{l3s)2z@a8RB=8Hie* zJ~$CIP)_^$`sP15eU*zpf zn)~No2X(qdxsITb|HI#*Mn;gEc|GB;)%Hs$cEK@Fsp9)^{ijk%^VUzf(kCMO4Wn=S zZydha^y{*Rh^;2Of78erp?IT&VZ@Nxq}z1=DRJ)bpDAi+VTy z^#u9`1|LI-$cz;-c#|GIa^iB~h8@7oPV-Vp*B#3D3*khtI?K>|>_sO;tx@#skGtY30Gjy&jkpzw7i+gsk!R40G$PGy%u5i6i zSAaF97yK>+glCM6S&tq)3f1TeOJ6>u96fc-9j5wdIL_BG7CKN&K1<1z za%PNT6qX-2{O`TPKQ)!-(5jxh^dj+?lF1TN++E@}!wLMd7WM;{1gn8%%^@+5`OIVU zzhnUa{QXSSDWWZ5JW8~7vg9^8a$yclP)YEWnyQhF=~sO+xxT9B-#d#47(b8CGQYX& zD=J!*YPVZ5c|eYiT>6aNXN)Ye%YsGx^NPP_K(NcYMT94RNcDU*%v8U5^QLn+@1F$$vi>t_Eu=7{^NgIv0pA)U=GIdSvhs=x zURZKjNew5b6X3UO<~uWAb3oPHzpoaDLQWCi07=cSG-nv`)EKBcL%mI={C-ahcG#cS z1&KhWtyA3`ZV_?X!X^RftZ9h%hnl?vD4WtZH`f6SQ!(y$3Sa?|C8QCM1N!crIMjrl z=cBjk&DS&ySZM?!=?McoODyXMPo6w!Sn19UKogST56KyhKg`a~)}z{-2v#X8D+_>< z9XR^P)^&$jq3%#GMx=N3YGa0+=VO&%Wnj9!zV$~U6XuY&MJ$HdZ-@w;0_G>X(0FDR33ox~=nLJFbnLK@rl^{QP?#epE#z zB^?Q)W>bf65|L6_Zm-T#v54P;;O*n2=%l;sBr`bsmW~d)rf3#Ee*Trg+WkjR@R$vl z^I>{=TYIX6FD$C>x95d`{D{D`Lz|T!#~7o;yuRuo;0;WCFqFqFK&uvjiM!if!N*x+ z2;TrxIMnx z1g+6Ts<4GA-Ht`qVBJD0R!9S41vs`O@E28mZ9+q_pBN+GbWnBB{a(&H`})46&!zgoLPFS%a5VAcO4}!!kMGp!Mu6%=7gp*Kv?X@`;>7erm+1_n^oa~ zMMj2x@>)}c*CW`MR(T5*0t6q_XVf;InKGSXpsn$fkc_U=`^l0H6Rl^r8?M6%^+00j6bnb!*T%=od-v0)Pd3iBf4l~r9KmNIuIZRH zMU^IP)FiQh|2mRRToyce5`kk03H0i5oE_RS zU-~7x240)IpA2JbX=$;9{e_J0HoZM;r`-p5s1^2Bs)PfLgnj$5Q>UUL83c~At3pOY zq)DDS|X+Yl!pllKTJVS_(|4IE0wiGy)~Bw#av4M2vW(c-h-1pRnF{}>(=^s)l* zN=I?Oa%03<4x-+;>i9o!L~VxnGWjl(C@1rsO||voIPx6HI&mG64MH>4PXx;+7JQIZ zcofkIcL?DN@Rvx&2IdBylVw+S$pYc2xXX|zSc%ro&g1<2vk@NZ(ad$Q?b5@#@m*`U zyBf-|Q2WOMqyr3xrU8}>F&R{>k`VwPk&@(sTd4@K2Ho)i^5$1nrI~%W-2={`-WmfJ z`yRgFFj;~zfCJP6i0vHr^5mMkY`aX&3UyKC6a~U`z)69gFwVx!5IiHF1Um(Ra)v_c zP;&L^=aIipJk;1yY}}o77=XvBeX>~XRoGTie<^b#yf~)@Z|BEX^D?!mwU%=9eE0v=cT13-mHY1u}FQlyWiQf1Q43Zep~(f zMAT;7U2izXqMKql{Kp1+GFI~c^CP|*J!i6Gf1NCkfb`!G6)e?Er2)u6|Gr{R{lEF) z%a*r{qBr`V<(Y3l3}g>?*UWn7uT6<4wQA0YAT``5$>#X%QBv;e9QpabU=drv6S==v z_`hB8ONP_`pf&TrpH~55Ob^if=ib#EpNQp-Cj3tAtLx~{Kq&H>BlhnH2h@2Js-w(8 zJdUxnkPM(o()BwXEf0_PHToD8gtHY)kd9FVc&u|*R5JXC{KI_E(Z!eBqTET}FdCvT z1YX3e=|-I&&X9KxiYbvM5fl@C)?oO0tG^&CqNuodzEvRG7Sc{hDJhAM9yPwM82|Lf zsvh-N$zK}I`;%9%qG5I-U8LG$Nhf+Jt`>u1hm1J{rY;0FJL7573zDp}aJp?j-Xoux zpBFe%58;h3AT?h&r_Wx#%mdQ->|N5HJPld|++4kS)N`)gYJYbdg3aFNmj!BI$gKNH zBNLHm&@LLnp(glrNI;N5j?@-xG1B4&K_m#R1qQMGju*`(WelauV&Xa;1Q zC>R>}CX1*gsx3vt0a(5xjEs=9ArG%7Zx#*S50G{pX@J4X+JISCrW)HbzSE# z{2u{d7J7<2%kSF>bKlvcFdncI$U!Y=#&87UYShpN9}&nkK7I4%;q%LdKu>%GKVVoB zAO|aHGyCZg0-=B<+Mib0zq_}yxwbVOw+53@MS-sa3;kHm^Y}l`>zyt6`Sa%$4|dnU z;)6pRs&M0?Rm7v7k+tdPDZk$eSxvck4~qe6|mpi)ge) z(1qf9w<@?B6vP=_&=aB_h8y=vPLME}o`EbYEc%fnM?`N;sUdp|1?CS(K}eMVJ##@@ zo1Z@NArg(SpSt$S5~2#PrJ?xW+~)h$Pp1G-=Dm3F06GnLz(Cp_;NAea7H0XKL?9Tn zNpT~%ps5M`2*SMH{P11c!_yPeaB6uy1>Ojq39KQUaK<1}}+1Vs~&4w`Lz* zM}qpQ+uuI{NC%!4`2h+5u>r77U@wpsiG&CECev-S8 z_-5`$AAHt>A50E`KhgEBrAf4SYqu)|lJ?fB==$WX!3r9YTVLpr3>8>Z03l+Kc=`4X zg9-HYl>;Pb14v1G?X`Jz8q}E(xC3*Igr6Y*+ivux$rQiWyge!Hc-IE5I1_Hjz zx=N3r1JIoZ6mGK1&~Zu(5IHpQ)B?wo8+FH}A@ zM)u#ZEJhYmh;X}=5W0;mrQn-h1`)eGi@R>(_~n007gaeqQic3qC5tY}hCzoUanHF+ z(5X~h{`S%ZZ*M6iC*!j`4rUozws9fre;R{7rvuHe5&sH}usePZTF_#V|A0UU5-lJ^ zGDp~&_3xuHliXqmbceS=G$~-hk1Hu^nrP1!y8MGt)JYU?PH!ml^U1eTP~1eGzR7@0?q}iAhM0tAbT|5BVk}ng;9u zeuJG+6-+J!=EpvN{=76&76oxTyL2GHnNaTxNvB@A>=+h_f`xgYw-HVOc3c~f_G2iBoG>4H!#tk_u4&i845tPaj(O&vq@IdpuiQ~I_rYD=XuDj-7%Qw7it{O;Y8gx(WoW4yxwt{>=oI?H!3|G zM7N1(WiD-Ytr@5q?LU!A-U>1&YA5Tg_m}@rK3VdUd{EpliZ9mzf^qsrNli#7igZ<< zfcymw8`FqXoUo=Vn~&T-QG)J-eri&Znk1`|%c~nE+h=XAbG-!cQg1DvHVbY3Cf4&y z{~j8q9%YOgo*pBR_)<=hg{{jRH`wH$D=87yG%1{bZ?Y|#Z?O`;O%P0QO?ub7HNM_a zD7qvog>`=zFX10jIKbdj zvcF9KJCx8-TQ0wiYEDI%`#-Pd%L=%c*kc$O#vgTT0=5izQ;AQhsEp7}^^Xh53syNQ z?!0(j%Y&ZqvEFm9IYRy{LPQJs>%+`3DIxnxcmj7ibB`*yYq;vq_^}XQ>oZ^U8_*dG z{|(lspVN+CZa*NrCbjEKmM>Y7A$7(Fr`Wt6fGN!7D%4h@rbbx)e_t(;uZY|UM2TBI zvhiB0;AL?9IpUqG-$R)~t#RMOx)MSbL!&}h06wwEl8Jx6%o!L=g`;a&4#iG-H_@ttlbPEbmjwZ#xv2XVbNIsiyu@~Ib;aCrj#NB zqyK{;=;9f!E1C0biD4RUkcyHrlfJ6=|0LUT7N>1V|Axx#Ym_986j#d-J!x@<(_PN} znyOq|=+7EodBUhr6+(SWc2Np9!Pu+hMf10CTv)=kQg)2(mZ{}&bAx@&94>R7Uk11U z+zDJZwiRneEmnGl$Jpk-Z~P_uQ0yi#{yN@#j;YSy$g+YsIga4q?xvbI6Gq_v4$*tQ z{oJ}6mYnWn=DAynxCyy{=&uHlm+9-;38|IYRS~T74v~@e(#Ecvp<91=ShAU)!@RK? zIghRnzlTql6(C{@kw|~LkMjGkcvHvJEc8@JC|Xw|g{Tl`r(RE<{FZe~1$P6dj~hkn zG6=}ic=}+t&y-Iq-P%<&H>f%!BIe?GSmb#|JWiheEuqMXaYvQ$ZeGbxVp5a?5iP;;R7_m}x#&9^ zMiR-{At@0-6mCoN9vCaRUt4pUb!@9d7-IL+liP0vI4deHYN0Ws28T<^1AC6_dlObGpV%gFK&KLo^nfm zJh8W9#Ruc^jW+ZtI&xI){7Tr+P}JrXk3+H?LsRL6l;g~ukIg(2rO4*RM1c7dZ*q5RFH1#OX&V(kXe^de$g!^}jMI zF}D5*$4ww7cxo@kkb2xK;rB*oe{>XWb2hGyO?CV5_*RPup?{jbj_^1`$7Q^^*AP3` zloGjFh>VW6_;_OHzLnfLbmXc8YtU(utVz7eLypjt?jlqX(VQn5HWh|%M;@m@y|Q0s zHKLC3+sSs{NZG4JljGk~i#6f1qJy5MdV6(6cJnUCXlcgAPw?K?=M1m{j3@Ev0i;l4?es81+FI3T$jbXbICX){W8 zal1GySUS#FIel^GJ*UV5hI!fd*-1=cNe6SR!85xDfI;Jv`}4k{xjJ;u2@qJ2bRsz1WdBU(z9%1p0PtK$TC4We|aM+;EQDL@vav-@N zxP~@*l!ckMS>G2<#*F>Z0w8Qcr~WYf2tYLfB;`TZH!9x+9G79a3k&o*vub}V2FY}z zd1qH3+Q3bk`+t{$s)D+lvv-jIf+jua-=G@_imJR9n>K4Us~L?pK~1v_efW^nzS#$9 zpKdO?_yI|JH^W$XkirAs(ZRt#y_`w;|1qVjjov55+kk)E_sSS}%Rc0t@#!X!PNkaH z?_3nGfWW+Gdc^o!8?t50bj-OQAhI4903i4YWYmaWX2gZZ4`TfGbeT8^(h(2>p(ssy z4dhXvEveYX@`PJvkPz$UeGsC6O^i~LZ1p@NQP3{S zt9g;^I(g$B@|1}E+!l~iZDPuagg4Ls8{w9QnPVL>WHHx>*zlanet9f*mu?C= zP-oL9erNjVKRPLkQ^ts$83_Xd@_*uA#+?O0OVI(4O7PSv8@O>uKOEOiLq=QysFz35 zW0Z_SIk~xaAe^EHo*Dm{3yz!0ayiQioFDGb3EeCPAAjm(vbIt-NzN;lt zodoH7acExsyKF?*$jAt}RXSdE6vDs2BW=DzLirfp3Q2%RF^Ski&JI{U@h8kk&H7q(eSA33q=!OCC>ik|CiY;7Z$E_4#;0}%3b<$JfvlWvVv1@+wq`AKXGbzx5R@Z% zuv^nj90Q#P8*T?pDhJ!Tz}6eVF991B%_{XkGx0b99=g~*20|zXwr~yf=uQBI2K4hk zT5u`#1U`B8EMl?fLo7U!iF&SV~UhAEfU_ks>BAMN^$8dkUa zX}5yWt@9J8yCDkrgzgSawPIo&g44~J5z6Gt1cerPYNhpgamt@Snx87;#t8`;M0w5T zhKV;6YQj&}50^PJLHFIl%F4$zfjhuHe1ug!fAJy(g6!d&1Vp57AVYvKTUJ)wpfqup z&2Xn$o9}Xf084Riy$>Q{MiKLNpooxN0mmBh@(6`p9Q5-P&=SzS87W!d2ijJmQ}!;c z%I-q|#mE>2_fgjheN)qR5SXEXc%au&QvrP+lF)$9M5JwkN91#9E*D&ye41iD^>Z+8 z*K;d|O(r2Zxe4Yq)B*k0j!;cV-GM}xVm+7;^jxX~Hd!1 z9ZRg(Rgf7I1AVZUdVLg1)&2erQ*T+4(ln}lVh)6N-Z&!e^I&@z- zP-RXx_}AqyTCPseB>DbwavSSw^4ni8R6%YFRCA9YoeJq?G;}1^)Yc}!!3A3b&pGC| z_?n7c_8}-B@QK;G_b%{#lo~XxhZz^0Mh=;c@9f%`K@<Uo7a<$?$iRgp`{Xsohtx;p3kC^`3Ff)X9yjX? z?h9qdz+<(EQ)*JBRZ@fS0R_htGSfE}9gibaJfz#>7|LZ$)&_DWzk(-Z1epvNT}VqL(9JWNhj2NH%w<|g}F!=*R35s@M&#^Gat zKI7-Ve_^I?S$TK#6nvtSf9R%H0Hlr}^+$S)HAXyWcdOv-n*(@&Vz-wJ;f{1YJj9Va z7i@z07@2X$lM3{a?ByauBl>EwjeMB43oH*wOMgy!pZ@62e~WtDIbzfU^PZh^;w)x4 zR-pW%_i(MnAC8`;V77rr8xb2z{m}cNs{X;H?at5R&WRkS6cSum9 z4=u+;w1w`hgiSieE>Pd9woJV(;C^&GargkM6*fU*yEVr`*iJSe-GC=DesM5npY@N+ zg7htL-dr2La2VNSZhD=*{yVd4A`}aeUJqoH3np}dd_~e?SgqJ1sO88$*qsM?R3wCb zkY*aL2~<$>TX!@*E-W1LTZE6Kq9L8#VEq;{_*w8hkP?CEf-q8A={$Q>BZQP7b~P|H z4KTa|61j2tu#yFERglU8d#VjeoiydHjt+j{!UK1V=QOK<>Gc4@)4i2HMbE@Ut2Stl zSvf!!b{pSsN)oY>pmQB9y(Glw%v!Fhrc8MdnKHC@LX^xc`sKT8F@i(FXb}Pz%(^RC zSl{gl(#Zo4ye5uwYy$mnWMV>GTq}PR%_OoSPq(F0KhIB|6i*qzgk~#t+jhfN;1kLs zwafN-*V@eHz>2X_j@3@rRGWwVFaQ%c;t}d9dko8vK>LApHu)vKj9wqALVxB$*QRnb>G#Ue-!1%I)-JFila{5eD5 z?H;HtKwgL>C(Z9bTK6?*EqcId=AG>0>VsTKJ52W=0!J4x#PBK7aj=L3G|XT;^-WAh zOLxIqBM-^ew&4V~7?KtQtwzWueuz_s+M!*)Ot%dG zP9pKee!(uH$!D${i)GT?C zf?+yK;W7G1NRbH^Xs4?KLx%!g1d=@m*DTdh;rH_fzyo5mE~GUTQovnEYA+AGW>fI_ zkqo!p%Og}vxr_u>&8Um3MX5iXDXNc$(P>41g z4ZjDSeK{cM3cM_Wrjmt>datNMk^qq$18jZ*>Up5{!vR(lou6We?+dZTT~)5OEdMDs z^kLPhy=$7ZBz^WKdf;Zla*N~bmP|Lu$C9>it& zfgMD2GF$jb;Q>+{zh2aX2V0=oa6?i~0I3k+y~X}&;q<@}CZ@I8gPmF+VkH1y-mKZS zhfAbCdGKqoxDbQM0Dc(kqYom5OsU}I9 ziT#ZVP(|;-Y&a-~5CH=~fG9EG@FP5&z&}cgi=DF5R6iiWQm~4M9Uv`)1z@;UeDF&I z+MHwWku%W0$h$Dw%Y`m3yDNGG7ufcTHM>S}nI0GZno&PMA*7>b!Z}pJSRm<4%!FjE zTL5RlcY&SX=X4}DDnu*P8lxtJ*8J)QB##Ku0g-8>OxWsS%;f2yZ0tK90uy|ehjPT` zy`L|M1$-q|=x2rHsOEw&R?^x)xNH)k>s5ca)Oq`jT;Y+2>s{z81c$9^WW;iiUA-2Y z_(J~R!2i?jA-fZ&wdEs@^6c;VR#zXaSwKz8*-d>7 zjz&lr9wNO94k#ggRQw%MSK0>OJ`XZ*fHrhH2*wiLkU2{ZyV3%|g48l&XW)n6(7YB0 zgn6ie&F2xwa3=(BnGgA4Fc=yci-`N#KLF^B**gI7+>sFAkEILdyuqHN!n~c0E;0_U z!wknSFOZ> zOvUCl&5KijHxYxF2?{2L-&hernl!4#IlHSF2<{FT9oY)zQ1HYFZW)=1^Q;9rnMiep zbuvkm-8{}9zy3;G?!xUO(d~`a^K14z-mm3(c=gXv)Emp&V?UmBVEfYZShXNo)kugj zs?qwbp%7!652c9sK5OP|7WRm(VGwVlCzVE3+dPVkhjz-mMgP=Md4dTtY3}W)!=efCqzQ+7Ni+j8qFv~_Dz=wc#MHQ8##yRt$8E?6La^>O zHUaal5=o!7b#%lyc|||n%ScJlxOHn~ql+^x{LY;_j7<~xiM+cf3oZiv?d0O}ypNu9 ztILuKGyHLW?Vn1bi4;%@^jDlddGf}sfRh9?qevJ6n#G8n4}*)^zl5e9A$N~u=3HAa z%<3TuJzZ)3;i}iAWouQI8)GT=11ngW-`XT3J`B7S(=!>(XCO23&#nJnf#)kHL>bW( zt(*fqW?$oaWt-g|-fNurShGkx_NYmYF&7m%m~(4ikuT8dD}^cPF4gM@GlH?OMPgES zTH|=rXsVHl!%loPB)%@2>NXoH+_dvo(5!NGdz_U7EcjZleK!SHX*FH&T26fhc09tG zNap?N)2G6i{64E+>uOb}h6PO1a`QY|xWoA-TCLxfGE8?<*`9W%;%GkXY9A0Y_`~?v z3h`vDoyf5>wxW%+`qR}Sy|v#2mvmf~H#I`55iw^(g1eVN3Y%O5Nsay)`bbCGr!I%lWLn$&ADqc@^({>swCI%O7Lf32@vv zx*P>#ax*qw>eqRynx1^TSE+4ap@zK$&sJT&8~Xf=i)Q+UgKRvtK7(G>-QI-gNUYYg zR)49b9XCB*g{)Y+h$6C@n3cf95+zo2&R&8IvdMn0^arZ4CA3lN;e`1J4HQd`58v4% z4kt>`5<%+7&ut&t=U@M<)|_B>h@OQ5U0vdOBDi$gmxATVb>7TV^)`;Teb!?yTp_#| z@dZ~q<6?4A?mwFt?i%N8ttIt?)ljt*-pk8SoqKu6yXEkg`1NS#$bOTcy5Vwj`4j%k zyk4d87*46X{^kA;=o2-TzBa7&v~Rb5PX~( zrh&sibqR4W=8^A`tUlNvFuQH)!6SG~yd7J3L7gwSnNQ%fl3qx7+th9i=QEeu89qDO zndf_I8561(L@?E<;ddPWt|2UCuly@+WCP0!H7ktj#_M>A>6K3>lw=0j3hjw5eTaKl zSFuT>sUM(oUcP(wR*=P^nNkan1P_!rzAJ8RCq=Nz!@q>7w_x0c%yjhcEgK4bApG|- zlTV)^63=DT{d!B`wA`p14U3ya+^=!UrP2LX%?q5+2FizPHSLGsCAF;Cqql;BiO=ip z`+j(O0iC%><2t`+{O4&i!b7S1cLAr!?sOh3^ElnJLf(=k##S|VmUrOTLPV?@4c_$5 z#Duz&a%EsbV$x~8WQzCHzFFD*%B_*uD8+VI|G#Ug$>khTZYY#Y)23V*_Qgl<@CO@M z$Z}7~)&AIx5#c8`%%7<9^s{{Fmr4kw?)#T%+%d>uh*YXPo7KuY!Yv#Y+Bra(R6gzf zU+?+ulofRkvZhwU_asB9y|G~&Ny+Yau;t7Xwf7h6zR-y#u!-;u&1=s%jc0{@K{M|y zt1XZi#;&K0-en4L%Q$cj8M$3m^!F0q8s3)LbyceK?BX|G&3KHIM+2Wz@LKZ?T(?=0 zwWUqJPxx|(ms(%k5NRt^U~P77XO|4N{xu{ z&T(|9?CGX-Al22w0c0ZPt3E9GdGiq z8kQ*<*8;`ZRj>1iK9F zm%-w9NvBm0;|a8S8tNZ)ZjxCk<^9)VN;v)R-b@J0`2NFc!n^)6T_Gp9FLtcPP8jERZ7jJd&nZ-YDz<*DOQj2BR?Wa3RJM)hHNNxg>liMg+PTR# z{MquyUB$Zx#Ql(MSqwR5QnBAMJTFPVctZDF*r$?rk2~GRHAv?Tmr|$Xl-DRdq^E+{w-LfdAbQ=M+!?6mwQPXiJ)M0ThMQHZ3p^pCGI z@F*D{%P$36O(=y$hnN{JWwJDJQ-4c&n6hHYM=<&1iB)t-*D1|T{Ye)Mfw5B(84niA z{4YdLc!o%w$SC|YTpm8w@V2EpIAzUOX_ZGe<@{Hc@0m}$&eI=a4^bR-XxjQoX{vkk zKL`4)ZPck+Bd%59T{$V7ynHyE zP^O~ZJ18PLaPp-BDUaK9pfzXD?Ix5j_Cw__Y)PmO`Ta|t`gHR{?$=OeCGl9nBA@aY zEZ4(JWM@=zMz#;`e!Xk$&a_JG7KaLGDjA#U;(e{y#p9q*=Gq#mg&I7=rOnVSp*2{x zR5jD5Od$Pd7ba&uN^M~gy09bbQ>Mc4iGqcSG!-<9z-5X;(1z&4^SJgRpg02M4(dLj z^%xP#xYUsjupxryoO<~n5ni_(Rx~yjFK+pbckT{Ghz{-&&R+$_|K%p>KhP!DVexD!MJWQeR8`7K1)hp6{K8*QMM!@nM7s?hvI1a;xd_nAF1mPuI3#fV|K)ykvw5|s!jV-7=hDnneFjbNXm;{9QM)Vy} z!a<|3BnoQFmcY#~2t|L0m~g3l^d>TX62ct0Sw)zYC4-1Ip|U3rxM~n-dq5oASLW=` zoFbGQtFBCOeDm0<-Uh0I=;b?fM^Ov2A?L;y16y`ZGECZi=OA+S+1&#l+!5SCh+jaB zl-IIyI>@of!dKjIg;>#~ITuUC@`__DiFY6N3`b?@)7`)XXMKF%u1($I#bfhE;U=~@ zOgf|aLV3XFxg(7{hlgl=lbWYo`%n0BuzXxBNg!=2YBIR8UrZ2`ZENvo$IX7YAf-ok zgm6Ch*3Y8z;o@pYK{@7Ne+LQuAX11y>egWK87S^Qh9Uu=a;z76pCX|hw7uX&5(=O; zegMS?2zxb~V$lg9?lzP-AQO6qk@<1k0b2nzrMRp9LSGMK4V8C(}x*xD3 zaW03?SRF9#$eIsuYuC#6keOvX6=NQhsO+F$Ck9PDsiD5X1|sGYPbZ&* zb522J<5bRF8fz%?LE8GD6*-Y{w1r+=jBQ1Y0@w>ULQ~!;ZEUoVxhHWNIrY4&L%MKl z4sSe-R15D;_-HWTRzeaIk`t`COivWk&TLTiY(ClbJ?f;eJa1aUMKN`qI=>|MDS?v( z7o}o$Pm+4?#QOnD%L?hNm#ngpmwa>xLpudU<{O7?q}|EgiQP}R-%>Ajb8;Iesv)qC z|Ds7!a?$GeZzKPY@oktwl@cDEL8Vad)5;BeXO@qa)DS!})v2&N1KTjqM22L66_E6x zMX*xv-l9dtvd@rJcu%1&SAa4XC>p0SJUb^rgGGp4-b_qPygRtaFC&wJ!6@zqsc`E0 z(TWHNglA+7Wmzg`$AP|8)VAd?ka=<-)?Sq0`QMv_z-nI0mgw4p?dKoM|5Z<})!zzMVAfmmq+@hh#dH3t~q z;=>f)>VA`Nx0nUbCyF=Q@l#I;Ns3vvGKQX!S>MkHRTR0|GW9v^$yLr!A#eGGV* z=Pm*w5X=!Oa?+Yrd2!2JC;F+z*+orFJ-VsY1mii+LOc$->VNvUKtwwoLPUduiL%Io z!d`^VQeXQDyEbf)%mS#x4xRDzlmJQgOkD6Tuk*kwL^^lo7}CoMoR*H?o}Qo@q-~J; zviCm+On7T1uKs){oV=xYm&%oUhF^i2<)9qZdY!2>M$ytLdU>(M{B!l4cIMp0%(bQL zP|wCZl_DMS3(ngz&#b6CR?Y zG72RW-XJ)AKC35nihgDxkXZcW?Z-tIAIy}Lv^?q`r1jjFVAu$^TexWVY{~6xBJ=B6 z7RkCYg*2+@fmgL;+lK3|^-_OuQ!>YSx&)M~`b)<`LJ?d1?!4S+eM=G1wE+3{uSJml zxN`maCf z@I=yPN*hDGv(pIskI1iKSqHlG z4WkpOP{5In1$f@5`wR~fas)WYxX*zaJG#XrYW73(72C&(w3QRXK~$JSM;x|ClpGi6 zT!+|(7<@?_-mTyX*u=*~>w5lZ0lbP_TZmSjEqRIxZXK5;X8BgXHm{XK>f}6#TF}wU zy0`lCylsOYxgll7#6UyXE$L6wR|o|QJ{}%9y-cTh%>B@lhjF>N&-?rN)=sJr`X)?7 z%WGKJA0yd$!r~{ArYAb_U5L0_O*Kft)LF9EOIOnB;p1=LRQ3H*c&BfcPo1H1FaLSQ zt&|5Ra7K%~bSvpe>lq0v+byDAJlEamKB+T><@|$4{PVp*#?e5*O+%o;dI3wNcIv1^ z&tSP%fM1^ST5Wvd=L650wj=6up3QQdUd&Fw1a(0_3k2qA9Lupw2j7pRr9mg}xf29j zU_n6vX~>HgCprDTayP|#rvyWfwI5L27Y~fm;X}k*AZ`bpsKdy26D2F$`lK@*-kE=`kI_M@P zzCOOZ>%k=_r!^F~sVlqmrc3tQvpn!vN(SaD59L+kWAVW@yBplApUfjLK^2Wdg=Jn( zpN3mG8!cqG9Zvn3OrlMAg^*Swu$G#|uhwzacb@2Fyv$|~cGEZ=D{C5?_NDgtsMz_M z2B`u2FiUqrl=L#|NZl$i={`zI#DDApJ<8aYA-+qQI+69&++WJT8 zgpUpmCrlG;QTaZ^+@JC7)RBlu9vXWmNy)4YLR=!nrqj_9$gK7)pb42l+`7H}oVpwm=(;L< zl1Lv4M9=&w>BK)dWoUeIYr52QH|esD6?mpgsp9t;bYw%3W+z}lB)}>I3oB)Zp%&5^piO4z662T=SWiReDug4Wm&X0aiX!51fOh9r2`M?-^Z%j zFk3lZ_10@lgt&@eu!7r6fM^G$qMq50@*{0!R<+e@o9ON@Rp{tY3Vr?T(j1I&Qd5i~ zyknkjTkA-3yIlQ-aK!41u>Q4Q#~n<Ac4ymSys zUKS6}t$9keKvL2C;sZyc%NTAz;lZUilfGGc2WLz&Q(leF@rAHYeb4xIywA>dTm{)myV7OmoHV1^aPJQIZus1B;=|f)`haur=_J{{>s~XK`^IR5~{tCv=-7Z z=W<~(rw)?zfv@xJ{_EQTp!T|p>~qLC_Q8!o^T|G%Uyg5=qLEU1rA@_90-}JVlyH;} z&kOK7+-10>G#`_b4>eYNYa z6FI~2dcUQ62laq2(CESZp42zd(`U9<2>p)Fwv^Nm`Yw_>?)6qhVy7$3@u%YHHoS22 znz4bTEXF4@r;90eI$EfdXm^jb`qG@+Ox4M0zx&WUfLGi$J94#v{xQ`UA63Wvd%YoL4qhA07G3!a;snIrf<6OF5zBa#51TdzH)= zgb({$(;V8FSl-Pf8)Nd{eD#*=#bBF>?{3z!We*zhZ=AaJ0)1xnFkSCyTlw+?@9lnBxA z!Tu!Jr~PRYGyN%muh~d_aWvd9Eu&VgQ{Pi>V%f6vll$QxCs)c7=~UOjJ7!1rxd_0k zVE-*-DP*4Cz6JdvF7bNT1_?VbK-4LCx^tU13UvE)qwqzpUTHwcJOfaxFs(=YQc+&T|AG6Tiv2A70vc zU7^`DB07)T_Q)4n;pc19Mbd(2IU8$rB=(r(O}I{K*>tN7KRgmEB`&~ZrTCSSQYHV@ zQk;;*e(jsUw1@gKS)@<6lwQ^}&@eJbEwp@?MVCIXI)#6*W)jkW_wGhSe33-v+C2Tj zTa)l)uP)Wh`3;%|gUIMp{~t|f9TvqKu3?czI;1-V>FzG+5R{hg?k?$C${*bbQqm1d z=Tb|jbl0+UoZ+17{Oz^7vNJpL&G$afeG8uWui8%%q~$0h)HQz5q}KQ|&t?r97aJ1r zu|}%4I!rjffw?cuV?W9B6bK+!Nh$mYa3K_;+_&d$yk{n({DqZ3%N?-~V&YTu!mrq3 zAHudc-O-0!uf^$*pV<0`pVkCHZfXh%#9r)g@GbHb_cN@_lD+p(-{(*isf!O*GK^M! zG#;eEn&q@AZ~-5k_y^4B1|^YOMV*Fh;%CeX<`tzSZ4Ddz>3K6^Wk&k+A(=>IxOITI zEC5zS!2CwdYJaJ4JYpZ%*5q{1JGw%hvG@}VhqKmQ1q@BJI~?l<;gHFa{276r+t0ev#Ia(qp*d=<)5-&Z2&^;peF*Oozrs6>gx3AbDz&^$OpLkiTdf_qC1-P zgjc7gx?2GmH(-sO1#Ek0e)XYR_jeFVwcX+UBT-4VpR@AIKcFUQ2du+(L=nO; z#`5yu5r9R2pm6{U7#jO=`?_yFsC;jAdv~zv2iJZwcWGc$Lzp<2!egvom(c14+`slX zY_%JOm_3eRha5=1>AKyt$;|ZSa@_{q`h%31f3W2!8yZp< z$vepoK;yyh-+wHlCt4A;@v*T#?%(Xcb3f1o2g6N0oSxaYn})Jh8$D5E@#mq0Gcn!r z`W@GDl!$=w-S&1jE)W*&YQprl2NO&ee$NfFvFd3ny17wMOi&+pdU+nL80O4Y1jWxU zE98msTkbrHSwp`oP%8)%6azMbwThe#TRzc)PIhG@PK$%W^d zzWG{L%ntk3#FAH&+0nrTEEc7K8s_=KQ`P=M@!&m-zS0;=P|z&-T5t?)78r%QJ$PmD zQ;se*#sjrbw0H6vTJRJTUBttb(uS)j>1?b$Tjj{tV1nPXYbA#840`aCLtENMaCx>S9*94G_nXG#Y=}@v<`QjW~mzG*fr1kpO!~ zxBf2{kh0$8ll$c+a&Qbm&iO-kNqIRVJhG9TqT(*bKj2w4-|yyD(;K?Sucdd7+J07j zsjg8=%AzBYCzi55WoFpph8))VQSS;(P%w)~Or&YGzO|Jl_WjNlYz_|vACyv`E0NFg z*95b_UzgK*QfPOgJJCcv<*m_~dZ;83S20(qLt&#klTCs-u%t1QXZ&kgdrSwck9hx` zk@98BGHsjnM&J#PKjDQ)V9ix611Cj7VIhFQ_RnlDedK@nFH z27}tz#spx|(>KG(0v}J1XvJADDOPE`p4ZVa$F6~a&~RT+IzY&M1}y(C?o40O<2pLN z^YA5D&(_vj+cLkg<@W6IMtCchnWe<#nxm4HfJjnal@p6M%14V3mSt^EmQ&k-f`E4J z9SS@~%mD7Z-6{PKOy0nm;P!$2OwqBLMF|^i2N08+QYmx?N-s8@L_#2B@=V)Bb(-)g zJw1ZkyK6F|`Yzqp)nCqANU5=QT+_zLjAKjY}gAZdjH)BJ- z+OOWTbgW?@gazaTTwZvOTzG#ft6t+i;MQ-yCJ+6K>kG?_S?>nE`fn0%YMNtIbDn#F z=?5xOHw}KK^5@x*a4E5_=X)+RG^3KPK$>S&%?rPZir?l<5Gge9>A42@dNX*~50B_UThPv2&97&WgP(u&wY48Z zcP+7i^>0a&Cl?~3)8+*aooE*;5C6^LbCA!SIvQHt)_DE5UU(j!I0mARr7gE&pOnmw zJb_H2I)MKJAP2x&o%2RfhDsfUXY;~-)HkQS0${$O0)OV^rK6*Ungx(86f16R6@I!u z>F`~PkN3kxyDP6Cl>uIBRKs7m;v*6dZVFLnO57Qp_^I?my!jwA@MX`t(*hqKD6U>% zRT{q_z+g`cZ5}MZrXIrEkjfuV<5?w&Bxt-0ojO3L71+iG5DT~{2-#bMc<8&ppP;U5 zr88{Kx2oSnroyz{dsIb*y+1sXHmGIrShI~hK#jdG$+1t5e~&8=y1NSo-{f5QW&w8# zTxOQPTjiy{Z2bpLf!%J>vR^{*C;&Cq{A0-BVMz_Zzd&Et?q1c@Wid7$yp2+v^(_@K$txW^eNSJbYO> zu`1IxJ^qN*&Pc`n?9qQjR?!oOvw3*vo(1~N6$g+5P|HKrS125XT9jA-t}vnFsxL-- ze8AWC>rWkP$Tas9FxW%wx87d&16T6?{+m}4sfLEe3YU?-a5nIv7CX$Le}PL!*WeH1 z=bT(oZk)$92jI;4yO(m&#rjkM98!;?K(z4v87s=U>VQafCjJ9IO0*q|O5iuAIQ3_=is*I=s~Ago~bT&u{Ovd@aiJ{8g5UBeb-1mE-SRMa7Nh0AVu6 zm3LgYJlyBcX#nTA>MwMB-uQcFR+bGW0tyfR%*u+gmKL7M_&5(guV7x**H+ul?LK1q zAKxqKdjn{X765IOeEj))dtW)x0eZsQKo!T+JVBr=03?Q1su8g`fIRc-rVJn~k=q0R zgs%A!Vx##GbMJn-zq(5Yh9hqk<+O{aLQBBB{tCtitb4xES95vtuJ6lj>nOw0F`p=` zM@^2^@lDRz6|$IrQ)nB3(c4cclRU2_%Z|_D*TUARY+_|xX}N=gA_JZgSY?gF zE5gvHBl2PoIk1v#GqzXMu)TcTP;7L?6Y02iU!g<5xWw2WNAwLkwPNi4&5<3xg&#Ye zvFTymqBUwB7GgTrXwOS*`fbQnQ*RhONwpjr zo?9_yLA(vD)@~VYV4)QgAEzSU2j)^0ePy8Q0JJ#FJMhe-5Umw&r5YZE#DHPMxATp^ z9}QZPB9P32TggPB*dr-aw#Mxi9P!OXZ7qz+Y!yWgbziwB>${K|V+G5e#$|CeS+bwR zq))88Xx1~(Al;8&Gv})$M_)RbP!`nGbDqQ@r!YAWTk+I9SPQ3E&vJi%+1e_eA~1+q z;>J^0Cc7~<9hCIO9RB@C(wJqI<2NQ5P{8#`$+)EDmIlyk{3CP2i1}9g)(gGFCZ&ua#DnVcFX)*waw)wdh6{b)!8Zp=#_T zoA0~eV7cq=i5E7@&AHbD*bG1e|Htd*qUt>#bp{gN7q$(9Bgf*jybsf9e1h-N>j=rg_ zO?e!DD(a7Djna&zAF+A4f*0^MHPVY}>jJ8vx+QiMcc}495or!Om8=Vr+nk9bJ(URP z^j*o{R8jcEepfuD#NMT#nn2mTo+!>3N!FbQ^cH{toLDzy_eA9SS)w;^S%}>c?ipor z{=$3u$BYTBl)xBT4Fq=quvnY>K@T$JV+@dU$H#|gXhXt)y{95oJ6*`P!x$ke>f*#l zLhZl&)MlSVA__27eszQkwLLH{bD|E!I(_cx)EmrG?@cfFe%t=f^SEv}hiTP}+qoKd z+ON8ti_`-j$$Z10J{a4=0;}O48CIc{8ImDG-Hq)2ldT-mu%)^3mnb1$jNczaQptf}N&-ZHZ#JmEi0Lfn{UallHeBkD_JOf`}gK{Do}= z#27{+Qzng+!(o1(1#IF<*?*&BRFk-Ppv7NwCJgN__fA3&)$D0`tf_Ltt~BsC-`d~@ zB?J4Pe1$@Rg-}7QzhCe;iM?oC=rS_=V`UkOWjo=BRc$ryK7q-A4d0a0MMUBPaao6X zdlM37D`8>XeBb;|o-a2NXFA+mJb^hEEJG|~(zb0Ep5H5CufsXqFGPz#sv@L|NKu=OxC}k%Q(cMZrUGOa1Srh!`twX?b?q{aWhFE zjm-V#=W_K0eRE>{m3Ch!wifd{z)9`~zZxgt1DCp?H2d8KRF$x7B3)|e%9#XDv`kzU= zeC)7a70S534{(7Q1Vt`gN@qiP{;5_EOuv7@J0yJ)9dI(sb{mLA{v0u~cf^F<@6q|0guh8%c&hU*RQAKg&mkAW0j;fI~kc-UYNT0 zr8i{$D4bzPT+Syb!%cj)%*o3Sav?7F6t>eMw`R$cz}*pz9ySoNN!YS8cDAC{0zYtC zrfhsx9KhjAVJtBClUpNI+Wa`b3oHm$z3}c0QWs~-WYOrdr+RM3i#<>K0>o^Z(gVvx zjQ{x??Pf!hTI9>B&x`KQ#2|Ye4Qcc1@T(7Gdv5T|_2o#c69`!O7yfW0l;7(y_;m&~ zuT&=r=zkV+tpu;lx@jyLd_SzKP+#W>zIV^RZ$|25&%dBzI(NYEr3^I}deh7+qYrFr z6B#DCFh^NFN)0`f1e;UH0PEHr05n03jq)0O|Mt%|0z+SUzPiL8_Lp`p=x~{)qz3b^#uPZ**$I&I>XnjDiuU ziLrU{lHCxPFe2woevZ&K=mKtir?Kizh-P%99S0qk$O)Pmu9QXkXEwD_!hdPAeK^R{ z!fr!;a}RzoD1sa6Wt~Yaklb3I3|{lz`N>D!O3D0rSgQ$(%Q7Ht%@A*lbr~;YMk7Nh zCuDz|Q3%W_1 zH;#X#ElLi;*j%euQ5!QPwHf`K;jiSlr&?=H%km&tjl<($FH1zLG&f5A@8o`%r!kGV zR(V2@ToTOQoH%jJ&XfRk^7*)X(}yClD9Wle1Qq6$MDz>_NOLPDELLLcXVIkh0rsAO z7~`2~qrp#sn>sY&LN^e|f$}Q*C5~YyR-JN(aY*Bj$=ejHo*W4jeyQiY6in`nCsbcd zUTbt4kv$dcLmzNJPGa0$Y2_38jxmZ#_%;1q@iwT8&6o4I-D%2C3%?Oq0iWH(yH#st z`x!_VPrZ17_rMK2(~PG45O&h=+$mxkGEx<4kQv;TH}>e!yvgCdyhhG;f54#RQ>~X` zm6gdM7q<-ruMy+q-yahuc?(*F(PzguHyOn2E;EGhf*9q6mI=Vm0h8WM;=krcrurrm zgS{r1XEXK}DT5E`xbLnhwNktT4FOgr4gg^a1krBSZn_3v;h;iSq`>T^ug!y!Wc; z=fpITG?-~5TzXp9k!zV?lPqI1F#dlQz`h}kcgVV(k@+S_{%rnbGA#PV^A0LNsuWqD0Z!OIR~2M#r5?7|s4S0aVom!_ z*w-q4P`w4TK?lij>LWLpFDmhr?-yLhv!;*q@nTU}Hz5V<=y?kKED~AR^k2jC&}*hK zdv>w@LyoTGb%sAPH81Fd;sgF6xQ8BOTsqUnbn)`%q^ySe0SO|6p;} z#(e(;U*$GDyW2Xkb0K^(i2;-c;xtWA-9&sC~y8bV0pY!MG$)vH6I4)qMC;scS>e zmX7(#RpFyJfr`55S@vM0h@9w9((z!|o zyxFlVQA_z-kBOKHnO|K!$?60s@{1U29TR}{Q1~!EMJ`; zRIRB_QCCTMVI$rR1A*)Yd!SL5PJwmLX@}yz_eCE@85o@g@?DmgXc*b$sKT25MS`y# zQ-iFwR7c2;w|lq1yyCJ0f8twM3UvzRK7`*F)jP-E!k1Sk7@fQa2dXX^C)_`Gmp#AB zV|u{*#b_Mw#w5(%ttW<0>J@gwx z9?x^i-KBal>PSVDFkZZ=K**FGB1T6#2$T1aK=iGyNHRlVx_iyy`AR~+X<=AXi5eE9cBs^a3J+=9RwP%JSRnC&j9J>kpXrdwC^W8= zVr3SYpe*I-XZp|RQ3f6tSFU8WVR?%qQpnvenKOf2w^fLW7VC#W@^d2A#cn};*+3`q z0GH19aaP;WLrKnrpB@Zta^09oL`sA~1mmA*;@?edV6qiqoUS^@r(tdSc65hc?k?h2 z-&DEfGV}a-V&!Uxs8PSz#Jr!TUP-xev&stm(*SS$>VA(cDs#c{ndJq%V7^8I$AU?UmSiUub^XtgmuK)R!|mE07g+8Iqk>H4Wnr1?lAvZ`h?K{*9KMy_~G1fGQ6*i!DfNVO2kI1zk2J zQ?Md8u18fK)4$Rg+n9D-vO9}8N&777DHCH2_Wg{VbrME`eTJ$B@RIsmMX0my8Molc z4V&(FL?6C`RufaWi~ZzY%mB+2{-cLDK4|Ef0VTG*IMdX#SdA{_p0rjt;tJh@XhbOH zIITyu6kZR*99U}aF~e*7cZ79pe_d=H#yDO)wC%i= z&P{|xTu;W3srDj_y|M7XEaI^Y$suh6#aMG#*hPBgwtpAv->#{TvKBiikYPTdS>qx} z>jq@)Un|jZT!jC8JstYfh!x{|6?bWQ{w%V|;aTPjiA9e2&7>CXT@^rItcHX?7+?wW zSrs-j23OE^gnFwrVPaew4UE4qEb%QU548P0Dz>a7i4ms9A5CQ9TUCGhR*cPcQb4AH zSN)^;YanSJbc)pb+owGW%;V@mJQ|{peX!&u;;$i>%vh}4{7b`Uf_Z;oMuDWW1XD&O z2kKEG#6@4DbG0lMyy{Jle_%dM$;5)vh2YcvT9mQ-G9I#&?go&f=k7mRF)VcT8}6v1vM@A)$7cQ_uN$PTWR^N6xas#IwLZ-->Y6kM7k7`tG6P-*B=GYNIf+Hh7W%O--?6Lb{iLh04Vul~qMaQ5F zWHxMn#`UV(A&2n!M)PE^MaH>e39e@apYRu6@5?|i<7ERf2%{l`#u0kqD*HK5;l1PN zdlxENsH-++Ph)fux%9QXPuCk5q9%xyo26T%C1Qmvb#N+K@2-Ul`$y4bXWCHH+1o4C z43PxPPkt0!;P2|jCS0ugiIG$7&YXu@1FjIFnB4EJ;Mo=n*0kYq*DLTn3c@GnqXs!1 zK@&OxQ=8qOV}s?6unP4x|IkaerLur3H_Aw%!KwidA@4UT2xK7)ZniEvmZqF&u=d`( zlN2yaD@(#rQP;r9xYr8Ir}OxZyP89ilTv)tIlO5r|XOv`T74He9xTF-wjCe{^; zI;{U-4mO(9%J`om-tj5Nn zP!vnP%N&LkB-jdd1e0uQcN!IP>e)MB+^0my~?UcCW)m_$=7KyiUYgdWM#gs z`TYY&x!wo%Nsi{eMLE;-DBXOx0^~-uD#L_4w7~+eEn1o#iA`>_G3R$$4}_( zG12l)rkboPtH&&R5@QW7;NjmfMM{4w7tWTc+Ow13e|*N+-mat*HoA=-lJ{vPQQ>MT z5hV#(-px%QeProyk03o?I(#xz-rPtSc!N*XgybZ$+qdun9BE3G^Nh>in4M;&FGTF# z2Ef=ix5dFh%>YZuc~pY-(*u@b0_Xi+0fF4VWJ2VE8%~k#`J}+0V~cGULWu+t7EO`U z&jw~%*z*^K6!S`i+N7z%2gk8XMPw^qI2;bb))M1}2GsFc&d(ODx%hef)BPd-ZrUx$viwh_gcQ5EL@+o!~oU z@R;Iio@ysIQ3blqtz<8_UQuSwmb!oHS$|TUpdx<*~hl-W< zly7f;EOuI7cF9S1RX5_HGIQ?``bDg=n_6($Nj6;JZQZJA&M`9Yl|A9n!m^Z$vOM8k z%6QmJ7II%v-`n*d4*5wQc}b;kc*ehu~p{ooZc}oebN^o85-R35r;qU!M`DXLi7l9itF}UN-awG;$(hXDI3;xeVIH# zH{jod>cOzgr2s@EK+n+CGU!s&VM#CWOW+{o*9&M1>p`^c8Hh!47Tb2%l2o#zj196L zfzWO>U9^$sni&5uDubQlj()M@Q2KBE-2)gMpR1~haCB=HePJtBkO)z#h+`>k4ukkx zuk!v9FCX_nioREoPEnO+q#L0LhqkNtT9TA@_B6#?=jXAh z6-7K&@+5MXqT*H3>VK37%XGA!{4d7Sp69bU?H4Ii3is;eCHhu*f#nwqI^J4Nxa}nx zziAAVe^3isu1$iyGqJj&JqM)J7c8Go=s-YsDQw0$3|UlS5QVGh4ZpWJr9pJubw1YR zN;`tb{*$!?h{@Ksts}zjR*?E&?FTh?DltPp);nKJ5`hS;{jrw}K35%VzXL0j`3lbD zZ+|yD31;0uPO%pi5A?rskT>t;qnT+$sk&vtj=|e_$HglNsVosC^Te@~iJNBD2-5;Xqndw%m|PEinS0;6V?<^@ zr+ltDztE?ijEGzvHc*KZ0hgH9z$|}fq{0)pwfNBD_`=>5{3C4X99KKi7xec46*6I< zWb2?L>f0?DF!I(w`U)lW&-Gh<^wmbZN6k*z>A`OC3y=0G($+PGX=m)f?+!9zzlW`AIZlr`hcb%i{QfC6 zf<8~&R$P@J;5*09{m!6BH7#k4!di0J73rH!0bywPzAm&pHB_-8u&X`EdGujw7d8&0 z_f?B;6@V!-1yI&z%`62fXvt^{Wikv`PTb?nkpEQOpAW4Ki(FVPgELT9vIkt63y|(J zbqu%-(KNKTt&+S{+R*7m*~662aX;NC<8N>oDrbzQU-PwuE%<>X^La;qezI=Y^$?I} zT<;H!gTVuZ1JiS1IvWk;VqJSb6A?iQiLn3X&`VP;lI!EyIW;04og=m~7cz4o{d{t| zG&Z5mad76wTu1b}ipOovN^xg>RxsFdq=;MgSzA%TA|Fp2XYAv{w^Dn?X|AQmqal_L z`bK;NL%)}{i}|A5v5~Pm$Gq5AthAyZ;o-qk^h3qX$hM#Lf9YkFof}T&=ob8iTA2rK zc>Z=1<%Y8piO?tU%asmHk1y+Qg-gptGPgeih`#-Q$S$GX`3+Yr%*<@=36IhPr&OHs z1=*A_aeVKhQqlZ~hdUl4``U`~g`bc_Td92cEETWO8|+20ucUd}hwHS{k=#7u4gXHXZvDj@Y$w8-lKevL+J8bhWv<@xqv2bc+oPIGj)8AMt`z&; z<5Ws~{zfEW{%|dp#`16R3(-0Gf~IFzT&2LAxPhiHXWh(*n(XL)*0QySw=l|Q;40Es zrg|Kq^94cS`1t&N=5;QS2jvvSn2PnRlW6rC)Z|L6GnhfF7dqx$*-VdOlHykNQ)A7m z&?BVN3!NBeDVxth?=r{Kc|tVf${8plr31mEbR3Hrq6IxM33%Ks4d)z}X2vL)p0Y^w?>}qx^aMs(-bLd}qS((3YhS$S9A^Gg{T>ObbreZP+)wwu`HxKI znpcxmm~a5OzEhW)2#K0jgCU*(Y398$eLAwL7?%@q_XCnPcMui^OPB0!iNfr_7nV

    RWZ^mxUUFM&4 zl2Ej?y18ROS!r>i2G9<++82)V<+#8l8Ts)6lUjBPXmkM#-4IY?o`80gK+x5?wXTy( zMMGoYe69WKY76H-4A-B==t3%=F=5w3j4XafI@ZrCS^&M_-vs{Y>8Zl7GZW|<6CT!m z;(z3NM*%nQOn%1+k%!g(fA0#Qxc)tWYK}UVHir0hDjyQSHIV+ha0B1M3@D&;KsxxT z{zL1JM+~)Ec1-%Om&*5mID_tI3KiK(UE51fe{m&Krt-UKY!6y3DrdTwelr{^KTO7M z#0=qak_#PMQY(!D!i84kK+YPoumK)8FR-(-DN6bLsimV`U!IU9vs!f?JYvaII~QpK zXBpdPT*?&f(L2;G8flMwi2I2!c5a$J&V!ubF0~S-2#FarshV_l^{6@guM1+-BIOPe z(Z&qYJDoVRrD!q}bNag~IdNcqbmus|w(R~81mkW&ocp{iM*${A93@#zHq)=a8&B)~1#JmgdZRUj$e$2$raRubqhKBKlUh%o9_ORo zWhlMff2dZjnDI*A+*{rRGmes$LenxT ziZhLB;OJd3nZ1dqO?95TCs7z22IV*pzJaBIKly4ivO{6Ed`X_0 zfyqQ|?UF^86{YH~mGPouwfv?P1=U+Tbz2=rSlN&#E;V`vnPIHgdk`Nm$#>-r%0hP- zY9E-gY>01JLq?7&QMV!w?GTR zrL7aAOWm|w$SKoMpi1GZ;nMt)|8pK(C?c0^%{^$FX*a~hredTOv@ zs7ak#g6P?K{X`pUD#LVi6ziu!yUoYx^`)z){z&wi9Uj!qzt^=p?@bJSri0euf4G}7vST7%Vs)IKE1~8 ze4-vl^wq4{>+z){!yt;`C8S^>SxQF!^`R0>~jn6qpJmzG3zi1Gb!ft&zA#?)Y zDmHSm&8XN`O+}rN#DbYE%gd!oOc0*Wvk)tcqbU7lgzcAnZP@-=?!#>2mc2MWR-yPi zy^d5KE0<89CvP+E+!*fal;j^A^s=Qo7n{IR890dhA)d>Y*HiH%q*3>Ka0j6tA%DBT z_>LxL)vKDbrGou|8hVYJo^V$J?IT3r5B!7%=tNC&?ZpQHQ9CFqBOeSyDZ1oR2e^Ix z6W@uCZ_xg+nMjE?BJcv2N1p8DoDn*UeQw6sDosI7#YO0IXRBWPV`=P^rP6+oYLB#( z1vL4#ueh+>Pz3@=;$5Wewus0k-z&-(77DSb+4m{1R?B|JL()k#pLF=$M^E39M2$1% zMLX>1Ju=Y06t!MKQTjSAvW$?gn#ron?iwbX~IFuDjEVoI7NnUhKXc^BU zi(HKSwTU1@eN3poDZ{$<8O4G@M$#OHYR~zby?I)MVu>l#+}k^BByCOAS2`1XZvxQ6 z65mLKqPV$3@%UplLDVsDICpp3;BmtaKg#UOef+3QWmrFcdHpAoetSKELK}b6%M;!U zDKR*pd#v{Bf)~*T!;?S*-SM=tv3^@JuRuB>*I!Q<)o-kvg3o zb;K_N?_EcIkoa4NrtMt#|9tAY?HNL0TJ1K2Z5!7Cg`A_kqSB&iAfre=)S$Wxl*+4w z4uv&;sOG)o$D1l%aQ>ul(%xA+V;uF7)PW>|_3hdawpz-^LD}wFTj)}vp%2FxeIr)- zkV=yXN%fnPWf`>JC2SD1d+Xy5_eOC>E04k-t?2d|^EA|Kaqo-+BX>42LKhv$0Ko{j zc}f7|)^t95UFnNFz`Fro{~M&s{_icI-D788G@SwfmH!64z{~~w`?op3C!(RDnfjre zS2GbX`}{PE8r(Fgsm(rF_|mU z`Ds}L$LIdk1So?492x)?AJ^9znyQZLPi^jJp8#GNzz`${s$`Mba2(Ks3jE_P%_<4S z7Dz>?>FRz0sypBj@edYT>T$8&V7nLx45g~tm1qtJ@r@J#2d>t;1wDbgIrSr;#dPev z!;>R*)9`xA1enw=05&Z-HB|=af4yF>hDUzK(4h;(jrP)mGv1l6aYSX!dp=rAt;?Hk zv$>xMq6?VCQ_ghq{TV?0dda>?`l|Uq053t%zB^8bb-(rdd}Q+cge>+f?B+}0S3V*Q zTYB(YfUjYy2pH>WAz{c8=IgUxxe{Kg%$(A;D4@`SDlt(LkbNJv-P8|nq9FxIgPOzM zb75W=?|WH-9$(CwL8arb6850+aKGcVakvwn?@%!Zzp60}Dbfui@;lPh>;WD}&gUvb z*nWYnBnuY>u=#TM`#o^X8aUxcy;d$i1bLz-5Re?329%_tvG6Slax}%CB*;T@wQ!WR z!x2GmuodqN7Od;J*8i=?jfN=)VdW|M-H0$N1ve8Jxw{VOsXC%k6K>?ee^7(q;HX#c zMUs+s1vp1A{28&uE)8cJVLzVoX|e)a>N*#(6~1KNP$W~1z7$>Lu++&MQ~4it23FD4 zttj%)49JEiCj+&hRjFbeW*u#ars(nKDldGTsRXwH?P}=K7)7T_2E9hJ24A8@Q?Mu0s0VRAOW)%Oj)={ z=CrBB?Yqd0BPdBf82>gFoPnZ|CXiEze?9jgD8QS0u7~wiPDN{4MbwWY(OAjF4xERJ z3>2(QMWs|C$GUa*aq!^H*5{uT)j4bw;BxcP;t*&Jorb^d@<$X+_C;T`*f?u$oAna3 zrnkf%mxX8^Sw?Zz-{FxlR*Yp7UN&E03jFD9X#6Wu-{+(Bob8kcdixPv8}f|(RgyM3 zvc@k!F@XAihi~U2B})Z-zza}G`Pyh&<{+MMRrIHfEjFOdU^S|z7+$u!jn3#sdN;;h z3lx&V(Vl-(w{B=#B9@qgcL?Zk!Q?p3#@7?bNB&$U&Qf=?(C%IfEn5bo@z23Ld?+Sz zntw5YgTX8C55Ss+2&Osu666CM{_sK^|9hwr`j9vd7bZ-Yz=R1CT>mz9tiOSC`|Y=T z{eJ1CmzFEE10gFbi*DVzQB+h!Qc{vv$(Dy6ddTninl)>dH!7`Drw(Jsj^%*|9$?Fs zEwpISf*LjKA=S5UU;6g#%hs)1Nls3tL4yWf4O8dNwVTAf_S$RZ|9{~Hdy8|shPrj@ za@JXA(XCrIjymcnh7B7=*REaJzkfeXnlvFHK^>105)wH2=%bl2V+O^=#cbccowT$x zuTnZU-gqN7-gqPX_U&Wy=FK!})QE-+85w=C`N=K%AhMp3bAMIjz#y`w{d7Cz;L!v3uv1o2jL@VKN^l*?_Cyq z7J76syG4&8#%cjJi|;`a`ECSu-t*8nT8?Vs=EUlPDjCiuWUnA1@pnY-tw0a22eLdcE*mV>9;RYy8f+oLPuRDp0o6vl1gey{j%(q}gCc3}ZA!YAxl$N$} z95@O&G~tlZ>39d1en63+gV=hcJ&48JhTKW3_H2{Y&}I!RPL^Ns43*f6=@z7>{~^?Y z7V4vBuV11?=MDUW4c*Zg4UVFseu#)^9Oh>mOh4qIJ`2!gGauALz6VVs*@K(}>Q@bG>k==vvFDnylotcPzk3C4Q2=4VPd`X2&^i169 zRt!gjz?#z@;NaI#;-Vt=pk;i9Te^QFbUh{XNT z`aMwaA^@CQ#6(oJtYsD=4!ZuL-#m+Zxi=F)a4H=>NB4gy8eiFXYjQpI&qZ@!%|np*p3Aul zq4^S6brTxzvryooK4BY@r|C2df}Qv6ByFNK-V4*9@K5mZAlTXp=@xHB>s=HbMGv7V zeI;5R6HxM;zdL-Gum_tkeE@A5;bpuFJ(1J$3eNTJD8$S$23O1 zxLd|+9C1_);>z_ns9Ccn4H`7?tA*aSZCk&8>FMb-ZQ9iD{jFQK_9E7uXx6M5DJdyl z#Co`JyM{Jx+R&hZz4as}Ceolm1DZB%T26X9k&uu;?b@|z-MV$a8ufMR)S+$Lwxpz_ zxSk_1F_GrYn^UJw9oN4nCnuAZmPU&fE#ky_wZkQd#4<8ur_*T~M?#GnJ5co7sLOvs zo!NIIr)>)=Hrf|Cq3>D8jzgsV0^FnInMfJ44`~YqA%gK<|KrEwnh_1iz}|x`N9YKc z%+%5V?*UYh{SoYzH#-rNJcQ8A{=!8z`c6%-9o$MrM8x`B)bPgOMD!dAp+h2EwAcIa zc|_$C1;#7LiE~Qr(@~(uH0$ypr_Wc8pH47SyLuuYn{+u2Ia0MyFyTuyr#7K%kgHMP z%MF*~-h}Ub{iyi@T=XWK_Z~E?jV6yFw-2CF7(s}POYcCb&Dm)FHU?&}ckee87n|oW zA4zy04t$<+7|E%@TBKoclDG9xshkvSRl5fsy%E;5hvA(x3@WwW`eHOD!&UVxL$2HF zC=2Ljmt!^%4rz4YKqkq_+X!6$$_+Om0`_YHl8?D)2`UdXwm@t6O0?#c;$YsfY6u`= zF4D}2ilR3G$-`J8!}_R(Cn5rD5s(e5{tOR12%eGRxy>*bhGG#Hq6DuJ>;0~ebuc0{ zjaqvkqQ$TX#JnROd(I6d-4__ts z7$Wb1@E^R5pcM2a21R#SJJXO&*B=o?HTj|d03ZNKL_t(Mk(M-YA`d;Qh#SQq`)oYg zL!J(CtUGq@JPqwbdx=d}q1$-hi^LUed|ppM>$UF~IUn~dhne^*+S9Pt{L|2yU>NE)DRK2#=TAzB}Ag1wjRrLb3_PVu+XfPX;oGDzHl zf(Km*uL-&fzDLXD3}pBJjClG=3${m!AFxYyEGP0n@#|=h7~=KnLDKjS%A7APJ<@Dm zVIa|269bV1CjrgYR|6jTBeJFcSpG^gY^AJev$8shYp7l@Ylqt&`6>S5jtmr)vKzj} z5y#;|T)7@cKwNRf;cxE|>KfX$Ye#Bo71S<`;|Rw0$oYCb=utIm{zh@}dTgd)IwGVq z5gB+iS~3@)4ZJnd7>q*7y+OE_j%bf88GOhAPc8&K~28Qb(y>oVPp==TsGQHThn zWMowxAV}HQv8bHFGNi751QD8NAw~bY#HQiPd}J(FVaKJ(M3C|4>(DMjL{A?4?15Wu zBf8qT;o=%JZrtv*sV$j?NZ3JmJEJoY>01R25G#ZfY&DZ}-M$s6NZvvOPCg)@Jx;3-|njrr|q>>Lgu_Yb;`YW2lW&(bUh~t`+mDO|{ z{3&op7}u49yV};NBRYWAk#CVKI0JYa)*c6ScEUZ2bxGr?q>NS%DoQ&df)Ch(RF8i{ z46NJp>JY|x(l~gq6V03dlYRR}hxyr{d2<^gyfO)I&FY05&<_z2JQ#06KMf^RKN!Jv z#0vAV1FV&ZLga6Dod>nj;Me1TwNTO;p1TePzNu}=_^)}0t7?j>>FhvL=y(59+l@~N!)|>y@{yi!5*Y!H~ZxXyw~4MlnIfB`(~JGoxdSkU)owfV}v=@ zI`-&X^(%4R*XOyso`Uw=>4e|UzzIvqo`#Yw7U1BmiqW3s#0WGO+{mpgbnnbwvWUR* z#z#TF1GwjO_`3^np8pVZ9tyn@yx+rQ0xJXDkco)&mwaBolgJmo4tNLkBP6oFMxt;N z1KpK^0&k7c&4_mI%?B>Reg-WG*r3}LhFsc)B+P#z(xBY#-Capa`acdGD#N|bc>pv^ zhkNqjsbYsY(hv8j?=NT$9*cJ!?b=A#;HwD^6y!-q`=PV`$t;53GgDf~dgdFiM#iyG z(mU_h&Bz`w$OWcCNv^(Hs94t^6l1rNKek@HRc8Eeg^;ifwjHoO&-8hTrhzTG-(65_ zU^>-Mgln2%k0ZK^D@KJ&oS4S<4B&1W(=hQjJf2Eb7xQ3-(FTR+B zR)@Z5H~nY8BY#Aq96MckGqQF;RYfnLO7h~ugxM1(6PaRU1zy?RUf70RhR&cE+0}*k z?Kf{PCohM&kR=|@e zZFLSJ6_SvG!rgLBhMR?-=+?zWCk>_CyPeVnljG(s=l7R3G(yG-m(fa!eM!N;Gc_1(tK@ zP#bF1+K5kg%n)dSh>8vYKHEZhRgKFKJNyAE$CZv;)*Db7J7^7DK$T_McwrHh8_csX z8O4E*8)r?iETB0w-wuuTL0&QZ0df3mP;mDLGubGtJ%J}dHliY~LFJroA+nMrA<(n{nlFN{2EwiV1Drb@ z|IDvc+_R5-QG~nV)9MqDfkeDsr|}>{+PRM`Kx?F%BKdQ?*Pe;Sdiv|qOVIWd%oi0IbX+tBhXv|bbeOHl@6G{{E6 z3-chaCGu>+0wjdkjiO$G_DVN+s8M4V2?^WKUbrF5_hrJ?U!i2UPgx{qSvx08mswvT z>@-x{#FuK=jJv(H8UKc<_hJXEi_yGsjx!U?16mqVem45PKIOiCXbB^I_ozIem&^dS za`H|TB3bcT{kp%^ele+ei=eD2D%W8M_3Z?y*BBm3(Gqukr~|7S>DYA?X9G_}@ZLP+ zdu+m6pWT}>no>q0brTDzS#zWN+baRzpxne*sJ+J_8NioBR(0QWMQMSg53_?Fos4t6 zHhS%zNXivWShwq`~^8aPNV->M93r~=WPhy&dp-%raUu|LN65=^{r4Tm;|I)PqU6c z6EWgG#KB_glEXn4BtHK)w(vP1mZCJds}N~%3sS7NKvw&W=sSOox5_F~RB_H~E)j^p zeAP8Yl#@GaAA>!oQn`(94xr~=glhNy8;zG5xHf3?!@kP9w3wkjcGbspf}8lAQ9kv4 zq=I%Y*A<|^E+VmSg2A;RrBM7*d0&IGtL#+S%5(G}^Z?bjVHuU}5=yOV~29b~Cz;mMB4D$rV+1JolSVJC+UrC6Weg3x*~4p!1&FvA^`SQ{II2q9rTX83Y(@<3T7BnUgp!(}E+<*R3Tk7Sh`H0=>jelQ=;b>0! zmkA7wKO$%9eQFzan&x+|EB4yCIzQ5eFw)$NOaBG@S%{ z&V>BGph084e-?_uTts-!!h^fMGMxxIm0Rbjg};*V8nowL9r_f7C|l@{Xh>~LL1}{Z zku4Vqq3uKx8vo{gj6`!F+dppPru*aPf*CKMzIR`FAi_T=cvrxvM?>q|KH{W|V7VQa5VXx`qF$gVYgYX)^ zEpUnH{s)e?u5SQ(Jmqmu7r}$ohM-yZW^9|YP20;*Q)PPxnxmhgKZH|CE(i)xT%uaZ zAk&cG!;q!#5Lp?gW6*s)h}H}b>W$K*{D|bzXx7x|aSVD|=|u1S7!1TF)*{KNH%9|;EbKVqs5mN2uJ`ZXpZ@*($KqPz zh$D_TVu;_7a%Lnl$b+Y(9XODN)D*tv)ozsTx*FvVPe4xPA?w`6C~Sdpf3Fq{LH*Bw2;X!!|@`UZzszX5Atp z5Wh}D4xMQTHVpU~n$J@ip5u>3#%l2FhUjrV@|5-?rvgL-`!@1(Ln_|gR;wGbQ61E) z5wThiImw?9IAu5okz=(`N_n8t93I?Bm`vc$(DF|BwJjR6BT%EwO=zx7N5Qft$N_h% z*ov%U8>6{l&aW|CqsGf5CtpHw@i}OY{{zW*>mqHCug0ks3YhFbq+l@Y!Cn)Fqg3_F zDJP}=g<^tBLCL;JBe z{fatu_8|3gBSMqw%@N!25_*;{F6$7)udJ~CaT9vpYtcP6@7at>7JY2JHYvnsR~FtU zrb_ETn2Cn=ISZiadMG;^ZhcZix#1UZa*A&M{b;@pS5G}9` z?;aBGpn%8-$9q?xaqP?(8DqV^05}h=2_vlY`Qiq&|C;^$Xf#J>6En@;8)rhBMKG`> zeDMP0yOqX?Yk#I}&UESa*J zWtO%k8`&CPqWX3tNHdJ5Tep|A|u zP;Vof@h0?q>jCeO#Q7AIw&MORTevpHR~`sPpOi_($@ON)>r2Ah8w`bFB;7Ev?cmse z7HWxDK0>Qt)fUnThBWLwsSMcxk!I?pU^gCiJ{8mKy4o}#h$9X^RI7Ms9C5@EN9@oL z8Qr;rv$3~qIU1#y`x>xkU=tzzkn>oE%qP=C%c#E0afi_6zX=ghrkUm|$fyK=Cn7?O zvp(ivu!FiH!~Yr-BuGJ|)7!{Ez5@jgE<>r$(F968);V38pH(KZh%m$25Nsxmex`($ z4U3`1$B1~V3}hfO^9OXV1|Z}3Yvk1%hbs?}tjm4gUx;_Jwh_QWN=sj%df;?KQvVtF z3OWCc39j2|j_nDX6bv^E$2~n^BIRnS@mRk8tB9032YJ9F5qUZqtp!dD0e^IB-PsqUz#~pkGJ=YnC z=nGJ%ycLcrU2D-=HV0KN{mnXPGFmiGN9*%bVSIjNpgWRnSubMXn1(Ti8=U(V~eTx-%kd2UT|5}5<$wZ#xAvXhZ|A5vegT*MI z8E!h+7-VnxVjrTr#)o;HQ&51#*KT_XxQkG|b^xs#4RBPW`2jm{l!G0Vj|9h{fTMGt z&L({I_!r1-_{j0vZ)p7urv|)-0|!R2cW(xE`L%)A)tQ4~I3(;3{>^%)iu0ea{mC>CerdW*KI|uCS zyMVPReeeLP%l|T3Y@R?_wPS(5Qc4Z>lg!*o?4_20e=Fr8wBtmJG&H;JC$d`Wpi!NQ zNcHf-FZpQGZdm@?^swJs6_}3px7{c}IDp8-1gYpL`R-S32;M&=jyMiK;^cZ9am4Xo zircYE3WPR0l9F~4Ub^m&NTrtxJdQT`sXoUfA~I={^*3h?(F;&5+JRIU#e@()PemR@ z0a63j!>;@O1|rl;k&1K~k=0=~I2jq%EuwgD1&~Vw;)NV+@_#N0DlF2im_eUhPd!6Xi zwO3*j;^rDM5#jk1feHJ2(KFH5E-g()#8EhF;8H}AgUAZs=6LAQ)N#Hr5Iv($kYi^u z4OXE0d~=_pL<1?*S#ixRG%EtGXqods+@*1T1rr)4Un) zv7TrBn}GBnKlRtD>k4 zmyCpQ|Aa}8z)Ly!2RuO}=|q>;!@+&n{U@9#ZyMl&JnU42P&gNj|8Vv+pVAlR*B)13 zXB;?ieGYtY%KtcB$YOL)!eU|(1$B(e>tCS>?b=1xfpqMQ2e(pPxrF_UOihNH(URPJ zB6jd28|^8PiXqw|d&^mmIs-+s!dbt^S;zaT=1b8W3x!llN=~xuTF~>!CcG5M<&ZE> z!)+L0R?e!Acf-_fC@AVyx6qWua;|?T<33)8puGbWZ1=65I0P}?(c*WgRS=*A&hyxr z0x7U$FchXhQ`mL$E; z^0Dg#J8>T{6aH}tJYFb|=GY17{+y50toI=UKNro_V<>MnRxcMieGBz{8{OJy-TG;g zlSiTeT0R;mP4Tbo3wnmz(DRFA4i#FT-`V<(BjMEdVB!Oo(B~R7PF}FC-*hyNR@Ie4 z#T@ic9M^EX^>ZFlVqXhTlnTO8l%r<&#E-y7(~g2l&2^w#-Im zu9vzTXZDn6Fah^E#Up^;_A@9S>e(oG<+fIh#Xs2hS44O@2@SuKTFBLBngGHI#3w$V zi)&`dEi++V8))?#{`dP66gUnSZi8(-BG|*p(0LH8FM-(K4up}4p%~6<*8kf9f7pzj zjkp*oZLbdFdYo8}o`dfgF-?C%VJM>AoOa@mXzmRlbY1!uBqna6abrV9=M#Qb!7L~l z3Rk4Tnjc_DHh~+i8_e_h+dF9OUK-$7r_wnE1(@9kxWXWx39>bu4a0-%zYB5cYqSA8 zn<3e)`DiEXTJqPxOH<+bKf-87a3lq2k&Cx5XDXUggOHum4u5rhI7ma;9p@pj&K*R) zXIw^X%N<@$c?l^%Yts4HO7vhzL;lbP?BG>R>%BvPV$S9r*3pLJ_q&zi3XKa0ZONPV zyI|)unr;@s+CB$^GlaAb?HJ*b>z|<2r3I1?ghw0iJ)5c-XA@b&a9z+&zqtcu6`6417b09M2J0Jt!YC<~~t0GCbq+K-FfXJj15WzkY z5l5#W)iUTl4nv-wuk&;c3g)CCV)t_Ed~GV}dLzZ-NUQS{YDzW@8Ns1SeiWkg`>{ce znT5z2UsB1cUpjM$ZD$`WLie^QsJw8%aqE(frLu zBw=3^i1JmkW})?<84+~ZwUC2SXY+vm@a+k(d>7=sj@+)X*aT4l%9@F!nx_*730)ID z7}}r!(QBwat_M3!cNE?ww6OmE75aX@MBD~ck2@5mpo{>l&zb3d*lysG+o0`uG?#-B zGDqP~m{t{jKqO+c83Qh+zQ`?$|mTA zg2`@5#UiAdHv3%*w5K=~c0VFYV?Fks(FOgik~|aJP+ZXVKD-C_4!ErQ`voyfjdc-k2}G5F}jy-*D(gWRF6St6y$KOZ7a|{ z@(qS(Bi7MT%exq~rulxJW4sQYg?|=FxJ1gSXb=34%iju7=EA5D=SoNG;~%g(TD#y8 zv=@ZHAF-u$?u(S9IQLy%{(C6`kZ@uvxls*z_e1PVI?{jT{*6{g+-e-zQO#FeS zP2Vj4T>-@i>UMhyAbT;KdXT{5$6!9*Wulzwe_v#w31-R`r64uFTL~Gbp;wH*U6F}| zAr_u^9Q9H8-2J2dl40^;YX)4JB_6umj7>rNy&>@y!NEE(<`3}o-vHR%bvLvIdS>CR z=1xGRqz0pusyf)MDkH%r6nOj!2^ap2QY#`M*#C~!3gBv%2YJk!lRA%qHo%lD#?J02;I6&s}uS; z{-1)BR%a3ZJxfDGm0P2v>^4x16 zNAzy=1^OeES8wZh-|JXu{rn3e3bf~zmG$QEV=QvCIwCcG0wP?(ArB0qaSSd8&VkQT z2hNHSlLr&Gr*6+FKKD#uB+YPKf7uKGRe_dW*oag`kD#ec|K+=zx zHR1Gy2Y5Ff7PWx^A8FZm8BGH~F8wr^y8s?K8`cek-L3UnP^DugB0q0)`P&?{Cz@K| zucNGmM^WwRd_?4KL~B{9^;$04f4ZY*Zj_*naeq$EfN%~XY4#AAYB~^dpm3*7JF5`w zhY#RaQYs)OTGtfpxn4og@n@u!<%bxRZ@8P?T-=|bS!NQ$eoB7ei60G-qnz0<;c(;rb45j6`d+^EoD?XV@Oi zlVEFj24!Wh7FAg+!w`Q1?8DxfP2GV1Jfn-Wb1vY zD6`3}`Ki;;yBGgweLb?dw?XOwSocRX4qx&=)gaubU1=H&ND=2h+q_sCZ7OFW%JvN4 zT}T`R+w!2;!*3&g)8jqwVYGf3X5I(}dY}N%`$V4MnT8hY67<}QP>|;=bWg&~e0=}~ zRjxy%c11DL`g~`z`dl>E9>li0g5i5)gY356R~v~>psw|RlFNeDy9|hJ=#d0#AM4Cz znTI{YnxmC)Uy%0(LLmx!)kNRwX~OsZ7N9$@3t37jgkzl=io^;RxS&Go@3 z7!-}lyb$>lps`^}(Y=anz;M>EIN~@ws4%$>aQ*dRCB z9H$~XjWNh!s0d*_4LQ>t9iQPrPR(tIXgU*-lGCiePqzNuhSYqw64_O~$ zzlF%Dh_-&^1f=Xg6y^J$L+sOdw6^_Zy}k$kBfM}26%0k-}KWf3i^4opNU>mN}@%PbU(x&ynh<0uqVSca|bGlW?$yosYi zw2nCE+CsF(jB>m-1(hi}4Y9x#$)cJG2XbK6d_?x08sNAg)^$enS%FB$f%=zwg-^LR zQ)aF~fcH6-tm$ZdbTn1<0AoCG|0XCKiubyF6<&e5bj07iT!5E;^LC(Vd-#9$&OAP< z`ds7RB#;byf(pbZ67Y5a03ZNKL_t)QP_2SX4M zG8ErVAQyvL;JHC02S*l>Sy9s|X#SU4+}Z@B4hGJ^!Q{GN0O^6}FHzRehp12W3*@e* zurQTOy%v${L6`*W0^ciypZ*>We9Aq^APF&4ljB_L?+U!NyGu~Uqse^efNcSniaGcP zBOU~P4x=xD3#wt@VsxG^W29%d-$BFK798`*TGZ&Lqj}jP_TUwZjA-%vH+El3Wk-t%I>E8cfEXftViiEA*5+l>Svu6rkpHJ}Nss z9XK6bm7tN-e7+IQc7pQmgfS@lBM${MS`)dx90@@7MeF3y{+%h9gvQre)NW3-UiZzx zF-C~ce28peB1DJ~AuE{0mQmlC6i(1YaULR&8nC_CTQj~z6QWEO0fPum!fYngpt)t} zpLVJK+6OBe)sWmxL3>0hIj7R4h%j1bz5h?7u1qCl{*ENrUZiO$@`-LhDyGlL%aa#q zLqieGZZF}9V^L7)9P~UCTkq{nuqUh`*WdHm#uSrF-Pc@TDV$=F6>*UIe~PtzFYNod z5wRzq0q^J-A3OtodtKnFXY1DU(fxB~6U;#NFXoucBJoFvNdB?^PJOWnJ%8PhhRMw& zwt{qz<*=BI7W#h<+Rz7m5fkw~BAsebfMhOG$lZaiO%=K)7of%Xohkc?qa|rjihB*V z-PX(KIr&TSCJDs5_xlX?{Qx~HZl2by2~Xp0gODSX0Z$$etIm>8csdFsCRu4sfLUil zq8k*ohZFt@^@k$j&kKI{D~^Iezrm&|`jK9gaXup9423Ytdhc-TIs~A8GF7czPI`Yg z8POWwqiO!aF%-Np!Q%T-R*74n=5lgx_cn-RFKUC~sBcL1xd+WPQc2bYqy>?$NWjzG zNxwcn1P)5y?cuMGM9{AV79IjG4TTqug8ptrUjK=LD?uDq5HHK^BwONG^)N!)5&Q$4U+SD>1bT`6>cdTPHC{YcDvuDHHOXza$5WPKhEOgn60$tN@(RDO|wJ*smI9!Uz>oGwahQw0R{TLG{*mGd|=4nVcUQa`9c@QSR zdbjmyw&avC0`)U_{24N^DkHf$e2YS2dyqa`2|^K)EtnNx15&Qv5#qbgV3)2BA3Avp z&AAQ1exCJyG0Nr$tW4gF=!0rzTuOR?F%uXYn4yTUzYxvivvI|b5TWG|k?Rp6M2L_T zZbK7I(8PKR_5^k+Qq~Pb-Rw&(esr0m3Xz55Bu-b7w4kqX&6!`o=AE@xXbY-le}=L zb!;!9zRFM49fZZ$#dwYO>qT@=eu3J;JxICk7gT&4kz-yq5`7Vo+6S9li6fFB#rEZL zv?3m|0IJP$IR^!!n-vL~)jPBXcz$2#_N9_Ioog9`X< zOWD~EvB}0s_@`vgLDzmd3b=R_#!P}KbowE7@mkRJd5+``{x00@BNEoJRbdxY%@qHQ z3iBFe+$~6P-=A&UQj`3PakmniO>kz(V z71n1#fnLYv^FZ|^oT~2_%E|~E)ch4vsizXr%Tb_xDZw^$jgu1>RO0PtZZMLL9seuk zJyUxo2$jHk_+l4$zXIx}A;Nt&-n8ZSP|((#^DNwJ1Q<+5&l>1lr{hlCm!q~&ik_S4 zF58?7^XI`TGyhoW{*yQ2VZ~ktZw!HpZ-b6=tl#WSGD&{}yfzK4P+g*JF{?jV(*x>y z;2NMJj-oaHLByaRic!i)F?N6V4H{?nMD}pEqJb`xz;Opu{POq=zT<}y+_N~!Q6_ID zm`Cb3ZF1_Gvm(kRD7O;ygqaq#2D>!w*QnQ+L^$cn{;21B()!z&U3pc5FepYj3HzZX zjnVaoLmYb?*~fZaghB()((DD(T~Ugj{RdERD%&heC;DRFvE6X5_YxsO>p?`WM~Dz1 zLRMITlx?6%&PCRHZ8>G_B0{B61DbmN58i3>&5RX@d;AMpdj-N2VX_vrMl3lRq%8Ux zdulxh71+uILlBwhEb>-^R3(P!{SnF2=e}s6^fFoydU?m1<1a*uwNe@yj$zA|ooLtY zZ8A$>%_Zg_B4Qv~kS{_DLMiV&#rU7eR%4` zWEyJUM-tpWHBL@k(3fCk>R7gIOC@~c$VR8P&-cpF_4+mJz6yGN1bJyyKwXe}@BM-U zAln;b?PThixQ+8A=v;eQuO5M$c{qk&k2$#4PjtHr4t@i^=>i`=hX}l9(VTE1_Bgy2 zhTH`EjHIyhzabHWM3AlBIo3G@JrlQ}AoYzXn067OYHvc;H;WK0d>P>aB%pEfIh0B9 zEE0e;6*F+3r^W~lVwItOFF4(_`?hVqvtci+$98w}!f0&meK+i$cnW$#K`o%jI?~kg zt!}s$U1@WdO-@FTQO;Bpx6H%Vie!e*k&694*54*OCJ#Mh2D3;nK;0auMOSeR>U*zg z!oEf#5k?R645nsrMu^Zl5s~W=B1DLgHL9>xBxBL+{vBFh_4cqBMfjpeBal+bPkG$T z*n;?GH!)KZjCDr|jYRh^kvygbw0PMA``qhDF(?j!6M)CiqWae!+Ze^Lnfmudi>Yss z&4!=Sq#H_T{V8xH1qB0$#cC)l{0HF!BDq8{l7UqqRnv-8m)Ku0=3ou^V!!XlF3vj%8*j=DUuiM zrud};bwKABbXkYU)w9qwY|U7O81Jx!GPA)I@Ww+`@bk&A&5UCY zq6K>;cHne4Qrz|?oZ7wuWh8{5C9wASg!R1*Deo^t1oB)I@GQmK>LZTG_^(JN*v1iV zT)Un0IxTa7f78&A?;zL9kvcx8$YZ83K?WyEQ9rp3canG(x>sh*vFbKBNyt((PVRLD z$+j@&IdU+Lb5XD=K7pj*Pvx)StOYR9ufMKAmj1!Yc4w|H5H3}s7X*idn=z3SY z1Gyz=a*&Bd!XTudb)G{UjnhF^H3p**;qP`_)#&_FGYB$)83X-LMtyxM$y|&29KZR( z-H05Uqk0VUeg=E|24#MofOnwc6(qJWB>S!;*F{K$lj%MSZ|*diFk`TrwGxWw z^l^E=$8dP@IC#(WZTZN@dUtfK62J;*sDu|^hfl9#&DML_^^RTPwx0wX(^V*=)h|;6 z^c;VIo{Ir!F8%;|_N&qJJRS8rZYSY}eX$Fz9*6`1zi@nBO6J*9Lvg=XV+khxhoTO~ zdwsOV@&DO4b#FwYmtW6uId<>!mE-+c$k1#pBD^=DD<5Vxw-u4=Cb#HS^dtn0fTy9E zYEWK-Kl0E$8H9qq)6w(tH`H$(g}sb(%cVCliDLPXcpTiEw3qfh42O1o+G_TVGHA8>-Db$%o~lpK!5wK zsfe#IH5nUI$lpZD&9kxZ-w*LuK9-|J!()ia+6zs|O-i#N2OqP3ICbhj)_O11U)Z1y zwX4n8U{Pa7IBiTZ!Sme?^lQ@-W9d+Taov^-|zLryNK|3>owIQxIbx@8a2SS1pM#u=z(5> ze-XUafKL(Ou^9i16*qj0|8rxo7*Fd`$YOS77UAcr#T+doBukw6p%c5Xs&j zM6`jI4Tphw_WcTur=kRr)lOTOIJR}baHM4W0)N|)=dEpaLfINIWa0Ka?t_H$y?>Bi z7%mR{f%fgcq@lskEaq9yrs%8rzFYrT28@MXF+JK9AXfZEY-OSwdSerrE`)g{;u|OT zC7Dc%Bcg6@@>^BT?_2wuaRIz?4E*&UC^O^>m*X&n3WF%6V*J}iExPZ1)+vjvI+E# z|3!NC%1A^^KL~}-!;&9R@Xp>awh{^lpcj{jeg;gOkN4@2h~tv#Zk-$bKpcH!Ff=qw&b*2!hF@LRXqLl)4cm`GZx)y0jyuYo@btUhCA=PlZ_jr zLKqR63x>R^LLS~{(e@PVb%a;4T!hXqXo1^|xC5<8Ab{I6)9puSJim#EhilB+T!_S1oM|c+SYF5-BqH_T%rnC}GfZss24Y??&6hqhROgtylakTCYW$ zp#}6M=y~}S{+TUP@FtM9q33Z0$;;b&Nh9_q1C`})-cq!1|BPTytUW#iMSRmklUl+@li;9c@?_99SI)SK0^do zs^_y8s?l?PDr(yXHK?Ori*$qqh<>R`-GKwAq4seQ>MJis85H{=U1BOGS)YOG1-KOr zO|ZuvS5Z)4bd?)XJNwXO+oqr#xE(f>>Jpz<3g62^eN4JljW7l&hK(Y%3SCP_e^hO~ z-DwudQAKkfQ^uYc(0exOgUo03D0r6#lYayK-3nvI5Rn+B zQ-gW9tBha4zug(cP`|f3?jHG|htcnukD&m+7g6~X!PY~gT$Jme>+a{H7e~i`4-{^I z-~AcB7-t=`hawzMdwT|Djm3~)z;7-&1KS$tO1y)tadhot==yuygXd76M;ryxTwpz3 zY0crVNl>^Mc~y5HnbtiA5%%}esMy}t69zA2%YmOlyK%62A>oR7`eCy5TZ<9p`x42| z$ZFINEQwwGnJvfJ=?immGyh!f|A)N*9#F9>nCd} zMl+=bYg^Mp7(%QPEh}zAxyV5}3{(Di3dytk^U#y(*Zb^>M${Ta>JJb2EqAS z{q%b%u+o5t_c3Vw@DxQwE3*29@EC&TrC+0~oJnnwRD6ogYdmUqAE5_5tN<)RgzbZf zTyNv3tE=Pr=bvZOCbvrE!Pu~2151`HVdct|)Ym6R``4^l!)vd-#6| zK&x?{|2Zm4^ck9@F2lYSThOBMG?IM`4gQW6vptl*$RDn(^|{&J=M(&aS`?AQYnsyMuU`M+k2FctpBAOtLyQ z8%#wB#ZRMD=rAekxx!yjyDXqFSO6%XHJj34?u^gQ&(F1UM@W4k-> zuU+6}f(s(oH=zZ+b20u5X=?TnC>{Z5sd_xkS}Zgts6*#>H2#JEQnA1F`Z5YSdDOg! z6~nuO;hWVqKedUJTBUCxyA&s3^*JI)m!b6QkFX2X-GelCL0EzMgxf-F3!)!xN5p`$ zBQHkJ*Ttw$z5o?0_Co^MA>59#ULL@14--jlJA;rK_g3p~C*fyM4m{3hpN)6CHwQg~ zZf&&i1eOHu#&fqU|Py6)60nllGVCFFok$iaRR}FHfWBq zKO&dBGCbzsPY{_R*bMS`$Lf+!i%_{g9xpip}rnQ-U~l?3uUqd zJ^SS-$ZF=1egT9U>~>me!L05w7%B$9dBgDzq+tDMP__?f5SxH9%^o88IW~dgw^17nv*sU){cPW6oy%@$ z+}ITbYVRa;!Cw-%6(JQC5u{4j?}R5?_a}3C((h4ND`@oJhC&sOTYsCL+{o{CMV6PH^|&?h>5f?(V@G zg1ZxfJHg%E{dWF)&w0BK{n9=59zDk1Rkdo>oZr;Qi=it2j4*JUf09!g$$N?Kf7sxT z+7+A;>sJPJeM#K)hkH;|rgrLiyD^t&a6k$6M{UQpu`hKgSxK^>|BV1ihfuiGi0Fly37R{pj5^!KhPeU6$CxGy~#X zITjVDX~ztA$$aH)KzxdH3m*1T;U6vJsUMXyIM%xKYUCsj`dbK$hmXcBf}9k!-{aLs zc=8v(w9Jz>BUwOmw*2O?tS)y!4W5pz7nT9Q<3o5rw(Qoz5l!{kD!m z4|y;#%a7Sy`j$`44SE~9KloLA|;%X_nRBo(@g6mu~avjr`&%-RPV=8*L1Z-VZ##I311V0$; zO%SJ*WrvMcYABHADElx1g7L4KCEJJ$Aebp+sPfg(hJzt)Zq@{LY_IZ*J;cG97wVS+ zw<^5r??gC8U>j1rP!g|(j_|HJMlhzEpcS{?z)8u0=UQLXt> zltn6e4Z26<(3R2WVYQIgep$qg5njJlaB~5&YIX#@nWhwP=rAc$X=6&@&kr2cjK%SG zVetiBx*45-V9T6rI71}&p)Qvw-Z@7DA&6Kzs6`+LlDrD4H!(gn@Z(dVg!nS7c28Nm z@xV&)gVPbSn4uD`!eCw0NmfgkLDcn((>l+ezy}&2VZ9zXde0T}hp8h50!1K!Ogy~A z-(%Ij<$5aw#RY^n`R5u#=09Vp?fLNOei>uhydEWwS5Z~%Gl?J?R#z^4t<4R1IR=q( zQ$bYRjDNSt|F|pf{P6Jt*n@ZoAoN}c7zA|vW%nx^=uZFca?vht7!CT#3VQ#o~6Pg3UO)cbjEfyA2#6{>Mg$-OS{&$7i=R zPZ}mN8IeR&REDuvJPMOZ%`0JEdk~+Kn0qJ(+<5aRX~UHmqJ*VVFj~Lvl1cD`AAc2D z+CeJuxCp`Kup-}Iveq!hbW@BuJP$0!T)@sOmH@T%=7$AJySgL4x$XE^jj=(Vt?9?~H6#qzda!>WTR(Mj-nkNSo5jBYZ#;Uy5 zYU>I+zxXy^%qmeYB;q6HM))%`i~h+OsTt=Iz$U+9@V%qm8GqK#U#Z>pC#~BF&y-^ zr&x)?T|iy9(c;e}vWtI;d*@0K^Tyy&yh-%_n(s{w%T?HSf5GUNXotm3;&9liARR0U zjLY@J_skH~Dv@e+12{i^@Rhwa*ec|3PvlU0>2DoXox|_XPpc7#lH-=sx4bxk{qEq~ zGNQu5j@$};Oq%BsP&e(!{iItym`?XM+Z#lJBg7xu^8mH^DrN&a|BFX~H965fJ*G?M z-pK~n0c91{IaR0WKUWW=8G)E=V^1Xcn-D)OK7&D6{Vm7IZH6&E@K5l0tHS3+R=Acd68wgKbUPjd@ zdCSklmef36GG@@sTJ@by?O8BR#KP&oBCpk#Z zi5RRqot%0~LYh-SiZQ8#)vDSMY-0SBcUgEal8&|&NB)E~FoOZIq@n8U5*7TR!~KdN zJUZlz7agVS^yuOMPqnMq`G)Y*c~fFHoFn9PeK9=xLOmYwfHLRd#B=P9*Sz!Xv7dOfp%gn+xC8Z`^OD-} zVV)vm`v_B5M3L*xOeZ$Q%wL7H96FKDJ<`vXmO-5R3Aw*2e%Ctj69BKtrke3TT7d6N zEgKyO2CFD41zW@=x`9YDbm?UG_NaM~A4k_ZL?81?tbhS&pTNK>_e+u|l51nD=fs7A ztvsOKvKT%XE8KNb{D=(Ia2)W%qtNq3bHD*ZmDGx?(-6vPs$t`Hp!O+w2SFu}Sb|oO zf+w3Eak%i6WD)(;dkrG-_KNCH?opWC%$ps*rQYh>;_j`gwZdZ-hMUOX&-5WFJeIg{ z=oT@K{fbzh;~*00_fy%c@o!gMx;%TF^Ovo(FS$n!MCw}e%CGKR$ts)ReM`+P?rT~* znG-6qESsJ9{F!CM&VTlM9iq3VdO}>wL1shQlBAlxW|kLxt8nR86ZRFiF)>_zEG6eZ zs7|KPA7Iqgn^_?T8lu!}@lJ-vA+nPiV516 z6r)&itU58vAHHsB71(mYwk%qbP#a*$j=Gwx_ z>m0qr0e|VpX@UQiUl5SzRkv->l=WW(gvW-r6$lc<94BxivjK{Z7@k6aho@m+C@CoD zy?>RIl>A5i0$qU-Jp}reLRi=@xeYXS+qT0AjuxtLKzL3|vb| zWvjM(Us&A;z*GN-Ckiu?<+5Ruel;QnOu_)fESV+Dm4=xXpHPyzN+(P!i9aP4Z~>m6 zIocJSI+f7gx-}tB@RFR_k$};Nr-cxU&yD9W*PxtyYAcrz3%T@ugS^A z<6sx3@zqWM-KcdjWb-Rz+zuk$MVc>)#fEtxd&jE}K#t#mBVmtZsHn zYz?^IM*kLDIMU604OYVjLaYiy>su82({E| zws+ONnMa#ETtbm95^MVu-TU*kV%@5U(vGg3ylGDv&e6#DWq}Rz3)|h0#A)NLYJoAM zjX)LJN*4@ZCZ}RJA?p5qSo2Ekth!V|HMD}H&Uk6cq^i`o>&PR6ADvDU@~ja*`{`61 zpJ)N+N9koQVyQnNNy@ekO}jGVn-%OO4p(6;quC{{ZZcAYu_xA*enPW+rSyf)Lwa=~0; zT&Yxc2+?+iqZWH;T|qX!!*;vxbZb(u#*8>BUH=Qn!iV zm!t9ExAMXbE(UZO3AD6&rr|t;_`!f15K1A|bx*^*_kkqI_Y3=i%p=M)YiC5B6vmhf zpQ@n()4r?;B(fuVJc?(GS(}71hvR9e|Gi7lf(*}e+PNmV-x5e&z|VrryNAl>d9n87 z`3NFEV4X~aVbN<&x6}zvV`E`C|E5f5aad~|o|*y?`#{MKBmdCx6&1$AF?iJm9bCu! zAVT{;j5G+5nV6rSUjlHX1Ff?Ef+avB4ig858=C$tz-)IomRB$w)*eqCcrN0BnL=8| z=Weo!^Ygl+NcM@yTr;vRGeN|*uUBC~;kEk@n#l|aBPNP?R6a&x5yXY_l^=O!z{d96#nkUqzfi%Ru!NjORM%ZVX8@|c?Yd4XoDi;a45=>b( zCR)+c_8gi;b!UyZM=LwTx7j_UfQYmZIEiXy>UF77!u9fcsBN}BIBT+0#%xeJCo29p_S}%9U7Vae2XRWiW9O<*yL|d< z)^&#~X1`e9x>AV)^{)37SkbcIgrQ2|E!0RGe&YTJmO<@CsS~AZ_fM#MNvF-P6Q3G4 zJ$1+OFqxhYpa+YwiWjUcs-T&u7eY9Tg7sj2IfO4j|4@PV)GufW5dLGP7Xr6D<8=fu0#mc zF~BxxsAFCZa28bw6o!9}doqD<;C*&X-#rPgvAVatWKWD@|C)(-BCHs$MYnV0&9k=O z5{(w74fck_ga={4i8tTMED6??3`-pITJ&r-{-P)>pW?kJ>}sb|1ihel7FovJHKS1k z%sXK`>c-U@%((CSR^qdD=>8Jk`S>`~iZQx3ToW7oHtIO|Q1}=Ee1OX`%Z&9unfOoSkMjGgZC_e z=N_`Q_(lJlEQ!q=VVCp1757`4VpZ4Q>y_w|!(uMxjgo>bg6?;&rPJokqC;~=c$>p9 zbaaZl7rbU7b5N^;1g)(bq8OA&lvjDjGCDOy&CDEczp7DPT38tLwMsKg)BUn})xi%G zM3k3r^gh21S8KVaUrX%uYlH7y&aAUdVcW)x~6 zLiR|p9r-38O`Md(soU(2rh_DBf~2zVXYXs=+I8Ig z8}#C1Z@3pz(%`>Q)PqrknZkn)U`aW+<$xh6EkzPfbeM?8;U~g`CjP|Y6fuoPI-!0o z!UgqCQ1|z_3yO*`hNBCt!-+kgaFJ(@-}viq(Nt4@i|hS3L;jHTk!_=_K*FPs3W}^2 zm^U+m^Z0wr3J(tg=8gQ$6R8jd`}_U!(};QbFEZT+v}+vlvQn-^5 zz1>-#3*s1}lQEZz=xIG#_i;4r8vi!TXXw<<%ZVDro2MjrV3-5vM;Q`yDkMgT2`l>j zoTzA+>D{!z;myia&F%`dG06hQ-zo1Ra`@m*5uZ;#QlIWwTM5cy`m8}W*XL^XD-fmI z;j|97L7~#~*`C^F>o?wpn1$Bhbmt+@yv$o|OChnv~)eI-Mk4H-$+5TdSr09D79%6ct`4to5L+( zpJ?2YYC<_??4cuB-I<2Q+}$tXVhj{12#>mR)qXD9acS}kZA`fR%L3>}m@%A`xE-j*(xYgjmQBsCUu3WE4n5yF`B0 zD^n0=e**c9*ojE(>v=f#fysOm<97jpsAQjlU{v?aZqdPkHftb;c;&B=X}2EiL{@3i z(k$0Ry|9vb6D+_kEENq3wR_=w=^ujmrALW04n|e&M?nc0d+|Ys+OMmIt$4KFmxB)? z?!Ed4B)fsiib=gSdj-gj;48^@wkL6FD#0nA4kthjf#|dVcbbJj+J+k^)1am)eH@Mn z>FE73hWR`(d2K8HlkhlCstuveTN!fQ^jruO=1~7=&`IQ+RLpQ0is8Uy#xpk{byFM? zrNS8nkm<(@!TFZ2s`bbYDg-g%il?%nb`K7&cpRm4;NN9$Jsmwlo6wziv}m5(DH?vl z_Tx%0g!Rd+VGWQjG;bPn;IB}7_1)NUo4$^@ZtuW=$5|n_GsAH(mCAg>DI7W8Vbi{c zb>kAHDV}sMfNv$qAc$C}CO0|=s`rB2Td0I!JPLi?BIup-N`*t(CN==Oj&u@|BrVW8;B@0_jV8C-a=t zkERM{OphSg+{`K@cgMpEkW|G9%>1nkdr`28ogY+FX7+BbU4rc=L?Z#6<85KBrod0wl@OMP-=t7^bwX+f=Deo*#xu}<)$ud{e2AMerJc2= zE@KZe41=>4T3f8Bp?3{z0eF`qrfU(F+$~`*;Yen7n4xkYG6`|LL8X454qOrJr%EHM z9P2{5(ib6#>s-wSpD{45!uo;oiTX>*3Iix82672&!T(DB&9?(?M0}1&5NxIaMDJ$t z_i1&b5BUex|JTg|Ax0xXjWF)NO}J<6r?rR#Trr?XC>2A)NhlnB5ko^_P?RV_)91gK z98d;seh4yOq*)wqIH=Wjbv;5d*V7|lLamfDx}aq=!8$@X&>IBN2AbFL*vw^;QWcq4 zeD17=<4LAAKR-PG0mwg|rvk%2EI#e5YwDp(Kqk=_=H78pM9#>JawXsa%=h=D@7<42~8h>sAlZw++D2RL|$LMbDe z%1E83pPUWSy{&Axbizw>abW6<%;F^4P5gLF^f~4#>9|(&Ily;zdymDZ52Jvi|BIqt z#lnGZotj7QUMfn|K5SBV{&N`${4-pp9Dy)D9Zd--oi-p8GsB^~JF@`dH>4;f-{(i< zk@J8|65P0{whd#Su-(q~FCJ{tn@i@3SY}b8`QI{V54dUq-Lb*CR*5-Z@8ESeHl>$p zZ;uyF=_-WayZ_=LXJ-!V5+c0e$!51e+GX1+P*>-QxNe`;#ao;%3I=l{YUpe2Dt8;n zCh7D}8i|-BTn@s{JHFwZkQm4unr=NWOjj+E734-&3HyLw=T%{oaht$=y(iqs7qpG- z4tC4@JiYeD{fmHUeuECYlTOn%DYoV=Hf=T}-dB18A;06z%_21Pqlb42M$he!_ynX} zzH}o_bP16?X}1*8NZWkr!4;$r2t$A=65`@q25}>q$K72*fTwNfKP%sB#gUo~rpTXG zyYznyXAew!bAwH0NYXOxyvU`b9#Xu{jkG#?3a4bH28xXkaWrSS#V60atsr5j68JM1 z8$p*Bd6%chDsay)g-+DtMd$s5JjO#BimX;H7?5j&=k%Y$>Cc2LA}Eqq8)-xX(W2s$P6Dwbye3euYa_BZ4YYqqjj1{9Yr7H zwd{HI7`IfdrTE997E(?-_>zc(o;eR7aXSqlU2Fs-Q-fOE+bQ94Q0mMtTPyCi z?STk(zbB`~Y8`PC6EcGi4@J5RKF`{k&Q{PeLGbxm7uZDI<1jM)Q=R%BaTgky5Vp5k zXM@;dxVfyeGpCYHktSZ~#X1i3`NHRR)C;PCv|AjA!otD^O&JY%SU{QuaB+tiQG~GQ z-$8HO+)r>jugXJu_4|W_osz)Vj8G1G!9DpA2-^2u&0zNh7iDTvX+i_7Yv)ioLl4{v&| z!k+57=Wg@xP1T#lHpUu6%v&ghd()^bPf@i{8-}`^#EU~JH;abTQn0(TC-Q#icvXe0 z*CUk{|4I^~<%mf?M^ROb&Q?8iL%w2zPs#cISDbp5zcyXvK_PfDml;4z0>_RV{N#MK z@F!H=KBBKXGF31xE$}-iAkbcTetu0x_P4o26G&^DOFeKFBKH}rKE!tO32r5uP;0u#~-AI7X?s@&> zhY2WHucprNBA8&8lO=fsNy@G^!5>VV7@PAJ;!85WD+x^P-i~}XGK+8d*^0=^6Y=9A z%XE@lC2eg+=K7u8SfFoeS+e52)M1GLieafFfD8(5b|ga@?FXpW4b28V#4DC9t}N1Q z$iJIks1o(JpD?(~YFv;%n+k{PjhoKanaak{b*2>ZRE;=pavSP2cFw?auJ(zD@55N= zbdx99$!t<)o-3|bkW>)mF-Da+Mhp+$FeqUp;ewxm_S*rPx-*Imv&gMHGe#;)1!ZzS z&1O-(E0y=ofl?@A8__VwrTZE7-|wRzxZ4*Rj8{}Ps=L*fZqkj}f+{G}Nk2UFS}sEE zca!L2B+mhWUUG@=k^1qd;ODC?<^HdC^Or*Yv#uu~%H;@C2ZeIwDk!G&qQe*G{&a@i zS8Vhg*A$3r&~ea=?@{}R1JVf(AD76B1b#pF^(3i*4;0b)ajLe#EQ$S{e8#5?(PDp7 zCh}edPM4xqRQ+D}SB63Cd;q64+B(kD=>97;suJfN#IN97iL1T&=y6`88qDlu?K9i= zNxr?7K(dXoorB&mjO-xQIKG)TjX zNqowN!9PRN8UsbmHR%rYR`E4UAo!+8>BANykt>RQ@L7f6_O@&o3b+82E?~{6;+)5Q z0@^JXn2UA7`0(7~OYTl85(gHo+67&jGP?U&Isq7<{Wvn zQ!nI;dY{mSHQ%uoj-H*55v>Z#mPlF~khvTnpv50C)#j27vclOa))=HkLav0trzFfL z@)m=}m7ll8%nLEo##wz9S*^!?ND_A)ZheGr9GNkVbq}teDN6osDma;X5gL5@&Bq&t zH|!}Su9H$YdjKvw%UuJ9R)>89PDWgu^PtEAS2DvZld z({q|6yZNGwdE}RLXRN|H7UxA9^3EGicF&`rha?7N!*9q9Xv9}!E=Z`=`wGSk$va*S znA4fbrYX5bq+5Ts!u)c@Ru8@&drvb3gcw87j&|V>fO``fFtdi2lgl$dU5sBw9d4uL zm=xR9`6ns=g4RY{2*>k!rl4WLf59pdS--pONugZv8KbG)*s_ZDyrXfJ<)CyHA6j?_ zI37)=VQ+!G{@NY<6P_bX2uYE+3e5y{gi5pa@%aO`gbto9B>%_guLZDGllSgywQp#A zeRM9DHRppk)|pon7sEW@Nnn1`(xD69zFwexqLCNOI#H z3X`#4*T99cUl8@@kDv62AuyQ|h@gCaflTq*CU^m`T%APgmqYb|4(7P4pK#08cy|h1P{Cu$rt|F!I zi#ykf5Ef0w0*tTNIu2C1Qm-DZk)8h(Wc?bd<|X5N5sM}j+3j;*Hb)WRdZI~ad02Gy z68Q`U2lAx=PRPjgg23>LFXze6TkGc&%ID|o<<@K5wHVKC5)3nvDOtC!PGafe-EV9b@@PA5O50ldIv;{t~SHl z2;E&aj4Y-pNH;p3t1!NP9*tl3qb6GKm@;o!9~NKoB)!C`^v+;U0ps3xiLi(FJ#)tT zF=&jLn;YSoP4WZQL-+|w?N88*iWVX>5%R5+$WX%fcY84g6SCT&XvH?dEbTITUzt7Nq?9XuY1wmzhS-1Y)=7rToy3x%?qPSbg)1DkB}B0wJfh* z9e7|=BSeD)=OWxGweQ=f|9*^95od?F?CJkPN=5n&et$2x((3H!w%)(Pu(oPXyKRfc z!wLg+6G!P?`-}(Z$La8={c@1m3ftiy%G*sUo)(?(Vxn+Fo*7Z=P}Vp;_BqqoHK$|aI@gW1O_&cLG z!CcYOZMF2=i+91{nB$7^NX~hcaNX)@)JdEHH;Z`Pfop_b1dIo1MW=HTpK~!R___HJ zKR@8Ck-G6O2eKduHxVNiD--@A$8bB=USrF-A?vYBpg2neoLjvMrjIj3NI|rSx1c*~ z+*+IAjS(m2;no*HfA9>$6Jn8fFg+&!`LilJT^St^u#b|@9Y~(4U}ls z7QS9#t01YBy65b4!e#*r(1Ll?^h?5GoqU_&ICU z6DX}?TUF>O08zEU)`^5)hMISmEz_>X6_@d@kQ1NlW4ZBfjHxig#wTl-QelAqzW$ody_Sibpo&8+PNlnB||jCf-XT2nw<*(H-Ww{l zGniBKD2$D^jI<{pVPXsX^b(?R*^1F-w?_mJ#p7cLGxrO)0fN1l!C9C=@(uK&%VI~( ztVGcM)(dgz9}{yxN$Pt;5Bqp**vM9J;=!7q!=GDQN;v5%P0a5}y+552X%cq{x}c$K zE8~y-wid)v{)>2ng#nJ^*M+ zrkBPjAf@L+b$;>RBkclTPuCwO@v|OAitG^vo5$t@OE2&)Ltqj$e~a&J5oeavO`r{p zZ}SUUi!Mu`-9!)(?Za=jTY+0YWw{kipec;ngSj!rjM0%i5WPa@2=v2Vf8-qd)87Z{E1*+-KC-yQUi)ZdKhqPr5Og#X=K@}mfc z&&?~}VIBMSeyML2x)`?!1*K0u6n0ZpqM7BNGZU2z%D2$`H*`v8YvMRg<0{yG~^I_6jzyOBU z?Y69lH+3Xj^e)AcdYoLToql2FNi^PptBknA)-Easf^USr)ZV}N@?G6x^Y&jNYF1~6 znQV8^i~`XdUlSIdPD%aWCUY|!o};uLgX!zwoI|n9v1R^9o5{h0SuqqcL)N}f#~#2y zurIq;=#rbT5YEC&r2$r)%eoDFTvyVQHGQ#pX<_=tL*!I8_X(xdKau+t_FnWuM;B^j z=J2t}>lu4|^j=SuTW!_D)~ba?FItj)up7fZS5O-)a1#vis0?bK5m_)=cLq%EUyZ%=TaPCvM zBCCGkRC{&5G;(uXPJ(J@i2+SXgNot9ibdA%2@Wa=|E=(7YF7+5EleVF(`>q3viAZh zXnMi9I)X%SPJCZ*AU;Kdn>I4fo<0-k2;Gn_$Q}n>GHm(DjXPZW6Y0r=a1t4~2s*=J z6& z4XK4!qf|Wf#(p$VP0`V4+gV~)aUuf{y(zL+H#8i^54W3+Mc2a3N51%EL|W9=L2zG}PFII_Nm;s!EvyN6mxmE0ABgwMg3Tc=c2v32vLrr(O!221d z>4YVbk72)i$AIPyG&U*GKIoHE{v!Al(W_JI7YruYzj&?0wK1>hPpw~U89KlPg40pJm4`oS#2HDU)fAj==f<{Vjf42CBT2ST>NzPVI2hn)c_kPUHY!yHs}p=j>NhqP zYfTtWuGdcBOfBUaYC2zyVi;}l4czRy`AHog1TCBGC=+AP z&q%WKDV>k(T={w$;cPx5d+6-M*hJCbX0m-lNtZ;%p6?s6%O0==x3-f$5R8#Qy)}^` z0@z;ofA+0}0F#90ffPGp^6-a5z646Dxlsct0Wwd z$e1Tax2;H57%+=L;cA9IP2!rnrbMkzm#o%#HE_F_7$@1T#pY$P2xk63g5umw6A>3r z{5pNNM|f6)t;q5B`xBj5D7Hj0LYC0=-~*ilHfS=vj`yrLR#*psJXI?14?uOJSOM0ta1Pn zT3kToI&{CzX|s-gtc>;mHX>jpq^pT6j-ugImCpw^C9!j_n^1DWfcf2sDf`KNxpry!w6)@0a@S? zqM{7V=F0RLzSF5}?K9|h*;|LgGDcD*pML3i+h=wKX8+syjKX@ZyDvQmg%T0A(a0?Z z!b7*|^w*&T=2I?S6U#|7+7Vf8*HdOA_zM#-^A99ov>trfzGP&bf+FUQI7yBEMZ!t6eOCb*Avgr zBaZapZH!kxXy}#=Ru_u~i&lEsj@Ev%lL$Wo!4>T9-}Gqt+@2C1&Nr=Y4+InTe*;^S z6H_@R9R0xBM})(=1X7LyCBe^dZ}7dq=8s^?9eugf4uq^XDjGkC;^+-5&JtlvUVmA| zbdNTeBP!ZPE*wE3ORZ=^%skzyVZZu-m%4TSD5}a<0lG}f3Wq4FL2sjB3OwPcEf|GU z5!3&U5qU$pk(o-%s1zMs1dC*tq7eUy-IS>{&D%j62ke@)nsW;}@o}p#A&$qtqlpy{ zBI~hq!v<{2ixHdA%JF3cu@R(4ycsG@BO6TDP5apdve8TAM1?J$@@XVnlG#KnN^;T} zx?$ow5+hvaCej892h+`Zh|y|iw%p2PrSbbx!IQmjyxhBRNb;nW?SC^zN3J5c@RYjnfriAp-s+pwW<8T3|`R&*OnNpbH7RgYj~ki;J}DABD;fF5>xhWSNbv*8hxp#N zDrl*|*dS=*6V3h=|CgBC`3o~hML^o*im3JJD}r?8(Fxb6`h>$#Bj)eQfArkmfR0`2 zx35Hjub>^#fQ-vM_i}}i6dCtky(EQ`4HkJ9K)iHlpLO5N9+1jfi8j|3zuTo6Ndbz| z0_O`S4i-n{^+awCaV~p8?KpbGm8i{bColVit9lC{IX2mBi905nhhZdRA7c`o3r2A^ zMk&b%q=~-VjA{tW6TxO>Vwq_B`Tm=}_ql>7e0%$3I_01olCMuSgvm@hcx^CS5nY8T zi9u|a(hY1<%J5M#l)SdfDd)bO80|Eo;K+{Yiob;56L^mwT4;U67FkT%&!=l6LMM7n zVD^Lw@z-p`HBO?9*;a4QT9=y3o(~erUC3r9kInxIAo1it3Oe@x?@_IeAetv%F`}ES zhtKXKE$N4y#1El<)|c#~0KH8jBT3t~aWR8NHG+sWu^07eq|0g!pB=eU?%efRxt2Il z;f6i5=Zj#r-Aau0Wad(w8G{JW%y82t^gDG$I0{MTI6Pdo{hf>Ms15 zlNP$gXNuQxhSaAZE;5lMDUVh>>(f(Z3UZ{Zl?E3Khs^yIL@!K~^p#u~rHne`&q&9E z9K{T|Zr6~9A*k?ukm>55Fcn*vo(W8&>!bom3q~c6FvL-I9Y%}aX;Vxam;s!6?Yq2S zoZ)uxMff?f0%}=k7%FqZ*-j0cKpLqt)e&Ae1Q{H~*KH3Da}DycrXhsf$6v@>U?uP< zH1ikHw%;veqBda!9f@^d@pdDu?LH!%TzlY?pm0-1Ti)%?XpC-)kSVFMwlAShn+AQ} zaSdw9j+$2a;1M<@k$Mm|VuclaWI^fz(AE%1V$bLQHiTYjL{XIw!5o#BWehsT&Il4o9G?IVVsBi1FN%80z3T!--!B!4}|H}jw@I42^Rc(KlsH7du!sCdtFS%y_lEC#ty+Yv5bmr;CK+l7WyJeo z96}Gzn-X&`2V(yItZMws!>dcJ5T=E>?@ncv6N!-w{AAv5Y#EWnK^gb#2tf^ym~Gl3 z3rU$gKBzt=I~1;4rPf}&`3dHGy7QX8dVxkEv#fdKZ?1VFVfdR8gWG-9gx2sEVo}@p zXBcPEN=$a;*Wgj}M$s>YSc|Lm5H{zYUv~6>!~hw!fR4g?Ednr}Qn$ z%C(6R^1!Wse5FB7iH!|RRte?1@J!fOZ9a;$(?S-r+0);VJ6)&~X~amSFdAJ~VX+lk zl%B>J(gd|PI+EAyYebYwkAvtFf0_GEnzwNCc?O^^%z=hYiAGMyL98f^1;0cYs2O)3 zX}SI12EFin7mXri72_H`TLv3tQqp!>IQex*x2jJElKxdLkz1*3b}`!N{?49tzKFmt z@W6<3?bOq9n4N$XZ>ktd!#3jj3#?w`1ZE58rXuZfyH#zRE&mqpY+IywkT`W8`<$%l zh7sh2{DzzBisik($#Vj1A<$vnS|ShU*{%sql~;)b2jjd-{Jp|x$RY$XcHAe}e0cPC z@q<|CQ%Yg|1^evFy=+CeJGorVuB-gDsKh(X>89AoYZ>v8Y^Yln+mKj?P93YcCwt1c zz;TN)&dCRP+jX*GC^1{{RgKgmCB{wwU6ygR)YygxjnC%n6BfMg8_?Us@g)&GeaeCQ z?aGBR%QJIJ5p_dkAe{uUjyr9<2^^YSRnKu)xAsCiD0mBD`nP4Yj&*f>;_G;SO9DyY z@;g&++*2@LzH3l%qfoHT{H`VX3+uJ@cX^eZVUArrSR*d~k>Q%fQ|GwHD751M=BOg* zZTvkQ(9s(tbvL{G#J`##vL3>WR~IHDW~7PcbkP`vV|T;wo<|R|C7EeeNs@$3YYAz{ z1GtuVguJ%b^IKyUXRPev8s#a@OEoZD=>>O-8uY%aI~I&;Y0pkDJk*JRQNj=iLcu*V zjjzu%(S#={34MhSj9GL@GK^By6UGso)vPudf}o#Al7LcljjPdn6oZ~vvb?Hskyt|( zJNKZ&JEp=R_4u9X*8mmktW@apIpj3BDMK!)5Hu?_E|z#CozTA#gnJ_|BiPAeZjDc; zTF@uKl`k>oIvN8hfVfgqEje;Jd}9eg4TU2v;mzf&e2$Z3Z7y{&1MlrM-lJfeE5q#k!YOco37=Gass8Qt2J;6 zx^~RiSAA=C%WH4{^O1^Z$c>HN-ld56UVzFjkYPp3ei@kXMTnGFMF9OZAOej~foh!} zWNU^6^(TT*gx?b6nY&UPyPv75F6#`tvi`aM(~SZ$8TFFXAGB(8hvt-pC;r(~qQxiR zL3T5y)YR1Z#ej5-KG1642ZWtKvi&Z0)~*U7lGFjkldGiQutI-?-by{QUf~05tP=T| zr^-kRNO~gOOo0gKokohS?fUk_N;}qCJxF?Rc@jEsCLv!I7JHnJ`aIXJelDKMNsI}k zSDD#?;Zl}mEt+T0dCKm+Ryh&O`y8h*g_C*bC&-dkTxj0?_{Q_#7xe z&7eyd6UHeDSrn~#h=M=i*t}2$k*9s%he(v|fcRQ+MWL4v7AlVv+dYcx!|BtBO{#@6 z(C0Y0M>-|3J7f|0#y-TaJZ4T!L%(mb1+KBqsTI_Ze+Il^Y>1aiE$rLZ^XL_0+Q1DB zeSt|@$+1D-&X`>d%GXxSCUlkXEuv#Y6FIp@u8@MQP+kj%{*E79T*-fD z3flfu{{#5^uk*Z2QO7?JBv4||X$VcF*HSYw%D-Cy#U*>4H!W#5+vzYNbJ8>DHOELs zV_)y58#%O?{VT)}wk@{ut<%m2nIi2vs)yn$pwNbOi@~1{Li@rhD!#JLemPHlFKoh; zO6XP*!g)fgZ`wz(dfoPyco1mpLZN_+6O+W~H$^l3rdgPMLOP7zTRuu_!ei5H4<(2O zypXDmr;p&wwl?R>7eC!0m$A7NtUH0D#;Ebl2FvApC+dJLBSGASX}0rolt7y({mrJs z%?6|a%jP2sYk^Q#>76O4#@EU4I>T`rMX0_UmTh=;d=tR*0f$h5o^V(Mo?||Mob;kd z@6t4+IrNF+8YN~>iKh-w)&n~*k#Cz|s*OI87eE{2XLYhlpf;n1koBV%qazbyP%u(}2Z8k+dzeAu>~zpWFp(CV&QuFC+zBr?VF-#W>dK z{rS1laeGxU))>FLnfaSSTucT$)IXiFx&baq7b~HC5UEDHG+N%dZ&7Wi+2N~b6~M;8 z*2$6$k|No>Vd70lzm1Cha6FTGAk+0= zZR&kZIpgm_|DKtJe&t0&&k#B`6X4eea^P_)HCzq+n9HWm$1L+##a=$uRbzi9aj|7f zQXDXLYwbq9T)>2Ein3c9;_1762B5mq%>M0b!$zSWPRG1wc8vRWI{M!joEbCb z{Zf-MQjL*ztnw*A;_=B`es++%aCUAEEQ8yT7zTyd ze6`sgWETv7dh)WI%A24q&j}vcH36xw7z{fzIy(ih8FfQPcDKjbr_4b{io1(-_y!h9 z3IUHVMi6zJp5j@_pLF*`Hd7w>F;FL~;L2t**@0Y!bNv=b3x}ojgK~kEbM-f6HN%z+ zw!fGedp3OhbHbtiN|~r;z;hZbnKb#ow}A(i-|K%8^@A4%1%K5F0L4PVJs#@4-8nP( z-idD6SI3(W4Aw=JUpbkioEa+j8UNl)gy-+A6*ww}je`2&W}H>bfL~%;L3?wEoRV3a+}cjBNYzs%%`H>;oo_77%8OiI%<;Hd zw~)u={lB`AvCKcd`gYqdQj78tJ#k(!@>z0a!0=n!^>x!@gLmL}F1#;O-xF`Wke<2? z4eP{}zFnon?3>`2Z10+GHc%6+70I}e?C%>j1byDV3nl)guF#d)oqxgkwvMSE@6xjF zK>%7Ld8LWmHJU6sJkEF4JvaADl9hH!(+zi~3&r1daC){f%;L76c55`(cn@<1;HYzY zF9Sb)U0f=S`h-5;ZvPnqVsKf5@9x}kl&D!*3(q}3PMGm*?syQW=O4p;y4&Bk`{jh5 zspE{T(~#LJ#~GU6pf$TNYWr_p=Z@VO*Zy%k`fFn17pO1lW zd(^@vAQw%mer>`kDF6*XK+r`rgRSnGJ4k5vFaWmfGeMRtolhR zfzehy_HNGLal_O<{(1P}o$nEVpm=`b=1TCK2ZUMB41z6K3$ONBUH@9zPr_ z3~4ViH{pY2@2pYyomyKKGVoVlxZ&q?B)n}x3=*MF z;?36PX)pV7CtxMz)9BEn!0%V0@`9P+Dk0A_*wN0a7h_*yRDQO*HryTGkoti!STk2| z<8nkJ)7vdQ165~JoY0MZ9b}cxyWl7oOC5+r93kt8A@pduhyk_5>)BUy<<1`&{)bNYLq zH+bMOJ9RAUATzV~+G}+`{q)n_bm7Y67yb%Izu9?&V%r}I>%wrbkdrce+!oPR z$Zxv^at(8o$E-$vQwN)a%_8pj7aIIzA5J=IM(o7@3p>VS{Sdq-OA!4{%q*m4c*ljrBHXWZ|v$qVXhj{IAL#=J|cR52T?R zlWK-;sf}>F3IREDryvXx_}v`ZaVl9ls;s0$QczIfD$Wd_M;3TBRVYXfuZ_LIUnN{^ z>rFiK^5Sl-7O?_<`yQ@y=B6&HV_j^@!fNvxDI^I-EUYO3a0kV z`X#%FF`laM>owfyQAPmQ;v?|nGd@U$taRu2Q} zGVl_fqpwwPmhlMEi#elUNc@e;NzlOh(k+G=&v(Z+wYK)9DaIDI>hWA^3?!dl%Bv+i ztSTxJr~$!i`qShfIb#0UPsD%7S~M<)H?-&<@!qO1`PhBSYtIGSW^%34?^S+j(XX-4 z6H7INz#YkD)u(^|Smer*IcJJ|FS&Tt*Jtxaq9@9GkA9E^FE?ZEP!z==@{YZr<{LGt z@r0!=FaH2qLeWfZK5^GMo{Ic&J9;xg+-Fb_v$30ep>!jBDwGZDwkC7N>XJwK9s766 z?=La$9{omJ3$=6Y46&<;Xurr^yGd9wIUtg6u=}zmEG&I4;-O$0`*EYHw$bb_$){7! zLdN&ZS>F+gC2Gg3^M9-u_?_s#l5&6!C?`L6I{6V6y|6$NbBML1)bs-HMScX6y1>&f zW~1aqgr`^}Bpo!DOas3d;y;$8h!ea*EJj)rLW;&64JhPbsdM1jS(^w|x@6Lt_pNU0 zz0YHvAg>GlUY0ig`Vac|TzM$Vsr6#%ud}fcbSaPr^er?^+o@@2;P?(LnStB09x2Kk zoOk~F)6bufJTf-+(e8(#rCD&j8Bn4kowx_W{70WY3$n4j?(Nk8!-$oZmX>44@^|!8 zklZuqZd~kU|8BOR#!1M?^2zC!KeOmaf@;ueC-^AuZR~ZA z$--ZFJu#sic_#5!>kHrNRCd*=*%JHFJMEi2c8=u{i%hzECQgm_!qjT%Jb&?9ORclF2J)+B8It|CxckJHg6 zh|I@U7U{orerFH!3acZZdfL6`?TDNv?6B>ZyHX2@THrWKk{3;IW2VnUQ8h#K?cVnTGJK_sQ<&n|*4^1+k_4MMhF;=b-D8?}s*=wT1)vZ+KUnHF`QGp5}E*WmsRsypcYy#v&@h^M!9 z6Dzx2YVSUo)tmA`U;gQ*OiACZ(G}KaXdwFTNls+nQO)R9!Tw5=p!kDN@?_DCVnZfp zmi9HH?g}lUTF2sOqg&`VWB%7O9*s+}@!-pXDWA`IUH)Wn< ztv*aGK6@MAJ8;r)Kq3w#RoHom;ac>uTC)aKkCCA6&fB(Nx2ISjl)C92}LO zkRM|B;bdNb{6aYXQ0Z-HhWk2~@P|^ymWRK8H zgW1@Rg3oA%^ce+Y+K*AoMQ^1nT#?Vee z>61V(IGUIO)7BRQ46SF9be?Z6N)r;R95as^Dt@iT3-;;lYjhr}Y=T|yFLkK_nuhxrQdu$QbccvwB})S>R10WJ3IZNTuzQ7 zZ_?vvWx)TAO=(=xy}%c9A1xw3eQF2BMOj)J8(?KJV1a@5{?8t(<;Wj+U&N=qTBKF zPmTt3CT9ehOy^CR6522YniPFBf7o&i)b_u9ckpArLoeiyi@B1S-ynM1Xwv44oZ;!s zx0{?wHH{4|ttmuz2h5CFD&)~^aF!6?_xylEDLe`wUsE)Zs0Gbd;IqxEHs8(P#X zfTJ^1tNZlZ>BSW9-v!x+yiY%08(7Nc$J7^!RGMI?iJ&#MXmf-%m}Gv*ROhM_(cpwM zCx<4rNq=xL{CsQpW?AFw#`hFiJ&WGTNdRu@$}(BmKBVO{x>INEOcC*SyL!!;V7-+nJj3+* zd4tXITGGl8{h7){f3t7ao4G>@>|O>zC-US*7wro3Q-3iO41W{w6n|;`Wdtwyp=m4? zN1lYfVH=u{{k&pm+@0As9d>0z#3qC9wOt5Gc+UtcX;hMoePRXt9&t`SxOdRAX(aYB zugqO?u;+Ztg4p>bJ{{TFrh4jj+;DIGf?yU4&6?T?ne{@Rp+j%RnxnY!NbH?gFB*LMdL=t0pTgXy@$f*kVYjaabJK;iu+q8J9e@0a1`ZFxyul(>IDLdKA%+%pzm|chh3wa!PZmus75cGnAuEU4dRD4@ja8)ELfAe#Fz4%bVIM8 zSN!E`j)siVOxPZxTm4tK^|{2gHK`&qt5kQI=SX%lUahu9E?%$jd~FtUboBbTQUG1J zWX`qb;-}TcC3T+LUVwzwcSl+R7}2YP5&g{2_Qm8VmylM*ZT=^-^=UJ40f~#{6?&-@ z5xTOEo6^A-$rVp)5{0dYhW!X!22kjs#_#C!9~v>Am3**HiCz6{l=}oCv^h}qPReAQ ztgO8ndav%wbIl!!%g*{9+($2B3ea9k`PqY^e)w9v+c}`)%Fn@ju*)T5a4dHXPhKprkuAz5elpYxPl*<2q@} z?x_5G7ljtw70=qdI!V^kuYbuVy5O# zRh3;rqI&n@eHoe5^PfZXEwxGh=$&WGvGXZj+cif0m>{pTS|ztmdq^-?A1Nzl(uh&5 z=YM%3Kw*fNbv-%KKP_+IKL5H9O<5JeQs5$;CUJQ*er z{~X7M-Bve{aJ0K$drD`Fss93-QR^Rh^cS!4wG63s zk=)&-kXLLhOOpggCGIi-W-gis{pGY};hTNlgp&^am-HVU<@5Hk8yR{Q7LcEAV9v|Q z;Mfbf;L6CzT>E?~e-Lf+Xt{l7Ppey?95)oRoLn`STx&I3t^Bh^HZm-l*OiG_=kTnk z25mmpZ*CPU5I*oe7W%GLwv*lW$a%L!fJ!;`GUBCSA>E_h!pn*k%atcsXKe4c-mqyU z+BpjS5Lj^MRMOhfn`oUE$0C2;$gf>3MIkhk5mR-Zn|Q{@lTh3JQE~^@R4bmO^C=ar z>hN);6F)`huM>PR-r7}=W8OVq zr(>_MMAOQ)F{~xI=P&ZFIFYqi@>U!&>kjILQCeskLTXWf(q%4h|9TsOc%YS2p9&`bT4}d#83=h z;trf@QV2VxIpPT5*7f9zu`hqU>7A=q1*V*)eG+%3`E~zVOM}G3;d7p-#iKE*x+g{y zG^r#{Zbk2%9hQ-Bcip5Y^Q#EQiTI&eAaphgE&k0 zSGiDe`VW`yzf`yT=VnO=yu+fee|Vb~UH;WGc!NNj!IgE_jBZLLhjy{{Q&!S+EbgB} zZ^?UUMorgDPvn;hPSZ!Mo4<7`7BuBv^$O20I?@tuztCCF&rA5)(xbP*^PFd(GFx@P zVcMRFnPD9P%Xq*_IQfA$L_7fko`={zC3ej-vwF)8>$h@jcf+z&BftI(+oT;eX$P5< zUv|NhK_5If8zCBsarM~^eRO#)OTL$D{+j)nOs_Zl!D>%aO~SPUn1bS=GIV$>-8-W9 z_9Eu+9PO&dvK7vd=3cDXkNO&HMXv*ki@OfE&p8wMq-C-+9@A1#L7S1^*}<7e zKaBk&zMQrFoU7+2x`5{ncM+X1MYihkRTME9YSxmSsOUkqC#rEn?cCBtc(m04c1O-w z(10$Occ1G@&vio6%EaIBzr5Oh6>!YL7OC z$*|{@NATqoh%j@}oFC5DwB9zorI4V!-W{)GjVCi8a{YKOD*w~!=`Y~}JQm|!&I_Tl zMEgCnN!<^x$vxGa6GM~WqL_aktb=lo?(Tf zrSQlVRt*a}Iyy*3rIyEC>1|kUBWvDr$4+zVRCCw%;7?) zw$H%2a=Mx~Dw~UZN%*t=ti2CsSjf>p8s@X(RzaVPvYDw0Uav1&tllSkpj7p9Ak%tydlN)>XbicvLZke7DRy&$XJ%$ShvFnsSqsnKgHuW{P@p z%_rNq+6!&&5!Yg)*4IX8ZZs>@t6re&7lCR0LaIISJL%IS_NdM7k2prE0cN4+4e4Ii znqa4=s2fTA7JohP-IaONlHQ1iCa3B{-Qz#?i_D*2JCW?99G+fmAItLaU8$>u-yE4W zqMKXs+AGyU@6xQZtyAStZHne>wb)W?_s)uP5sv3=k52?KS->tmV&^06pPVEP{gl99 z^iifr%D55}fMKlI8^~Y1S|>2Ma+g}~Qbc-6As;I%tGcD2Ho;umoQ>T6A5-amM(b~b zj*~N|A_UhDT?;6a$WX+kB_sVE`9^Azc5Kn6Dd87t+T|aaSh~i3nR0J(!;ag(LQ?H< z$prV^Dy}z$k=vt11KSe;lz(+{R`EBge3DslnRaf5ag|vLBU{tfPJ^1Ghx7MX!oog$ zwW2PuedKhdo_*m2&q-F6(?`8gJzr>=Vo_?uDdHWpRQe5@3ioHLMhHB8nGzdc1Rx(z3CeBT2+?wMkjsFe5zmZV3Mcr zFNV5M>=;{iyY=45k7c}dh2OODwrT^~=@xC(4NmVR>q=SIIQZ)N=5eErn3saaUWWzk zSG7C17|#Y~$%8Yyqob#*UyIDiphHulvID_c)*^C4|$+28CJp$gI8Pk2Jx7tc17-M+t z?9|LZrRW#cm@i=|ZT{LPO20s*(a8Tz_qUl{qWsHqc={aWg3Wknr3A(czN~peSlX_#HDF-fX$t96xfeSxKP^JcW){afmlWPz6 zn$0kh7k?;OANqYdu54K2dUr#5-=!A6YlMg*V(Q-uG>rD^=P3KMGE@1mJ*xkYC5q#~ z>D}y*@%OCUq*LtOCn!@_s&$8U_RXks_86DSR7-q19|e{(r4zq@n}jGTaB%XZmz8};PG$`W3FYMB+8pO)d$yzvS-9-y zMhm@Z&}27-?i0@qX>)Tn-4bhKX!^drJbY_PR76CiYHz~h{rmTJgO4pJE?s(*F~o7> zh8a*`D7~_G3^rwcCC^7+rz}unx4dQQh`c_)YZS|)->z$0eR0zniqHcar;W}|Po}LC zu#f`vFJFA`1(FH6XtIX%EnE{3`3QV-R3Zz0{l@E0Buyqxq0gqBE9I4x{y@JGq$ApX z8dAS*nK4YQhbS^2EA(_-NH_b{E4<&oe?t<|wy$c6)`%~Lt{nF%`EqkeDFHtdw@-e} z>*r*6BRGbG`SC`Frr2G)1uq0`FO;0W>csp^+(|5ar{4Us7cr)9{gN$iSpntUa_K=4 zdTxvD7dJ*j@Lyv!=6erFpqsKT2(w@mqR5_vG;N{p-o?3tsoip1n_$Z5Yjc_Oy3~7U zED^4p?n&LKU@eu|FP!uJCMj_di{FaoS(5^d*UJ@)hdZsia#D0lFUm-B5@<( zUCOC#J*MiZ>04-z9RATt%!1yc?2u{LRmvXI8~4ldTIqjp(%rJFG!25#y=A3^iOPR; zg$)SgM@l3&d17xo8`M_Fj*X6PhPK5rR#sL&r`)~0B@KN}1fj3vXXvEtME1?2+F*Bi zxUoH&yBt~-UDS(x2drm6l?~9FWPvFvJrO^tAN?(gUWc5_`@|cW9d<4HrYrZyJRy15Np(4JO%t$QK{~eidF=qqL zy9?s$D|HI3{kt#jqo3pZYzY}h$%8o(Y0ysYtQ9RFM8kspDneGPXhDK#34Bi; z$U-@6oz)FWDk?f*yUQOxeq@yNEZb%8H|hVXj*K6{5?`;wMH$vq)sI@|x^MrLhTO{m zjIoZJ!zaYHFuG3cjsFH;vaXOD_i-40vww7B8TCFs4OT_e6qS;sU-amQ*~&BVn6w(~ z4$oTbj@2sEwp5zXzn50lSWw4mcBhu?;LYh{Z(zP-+sPZno7 zr9ZjJrc@OQD-g~sVJ8}IJ+32IU138Y}t>xb~vx0s<%gxH#+0h4a1tx&;ce9QeLv*%w5L^TPg17njkqX_kwbU%gQ!4XNPM<>IU$_ zUEK3W8U*n#ofP}k*7M);r@P~J!#dwc3@z`USD@6R_{^%T$lzK2*%Ti^pe&_pQNW}V zn$7+GC6oHCJ5_bhF%OM0*9y)*ZLm0x3f%0DzvID-g)!WI0XhxJOP5-ad_1&MXGbV-_C(JHSfK6?H%;vh7D*p&V@$(0_GiMs zJ6P;&^fBDFNd*oT$M2_d0Sm@HugUB_XXFD|a|R#u*?S`pN;=;i(v1o9VKd zw^xBjv`F-dLFVZ|k5_E%N$2{P_)2j?VaQK&a&ih$hcGWhXv{Vf?nR3$fYwXMG-~O9 zy|MBV@hKkBg&q8fMmAbfp|USn9XgYW>uvT&I8qIZ1wAeN{bE@01r_yJJ{eX0fpW?d zkR}=!cxq%7-Fj$}7|e>IqFeqR@n+>HmcmouwajfFm0ox2Ng_wd69QM#j=QS$Z;Kz| z&OW@+x>(%PT-bMIy+E+irt2aFg{2iNsRm?vfN2gyF1){A3+r%it*4P(sx#hY;&I6Y zw6sQA;qt_WLjNFs=psMiHqTVYM)yy~`vo|{z}6YCk27{!Dv7~iVYxJRdx{DQzd;C* zq?#z{xQvOQQWcNr@9$Tj+6CMB#c70!ipml)uaF>jnQ#ky^M>SfGq(0!ObkI?o7?f(0)8OX$rY~*mzaRbADF!Dj=|K0XMy#cy_}5{{Ww>#1tYpML9x>`I*Y6H_c;(#yn(8j6 zgM@;ag#{H0i|WufeQpU!^Ue?SxIMT8Bu3K>0n)KU(NcUYR8;pgG$p_az3km4igiTb@%FJOo9I+L$BzAt@&7qjH06V&MS*i1lIt<<+f{~ z>}nXZ2Prx&(RVlkrcxLS3$UsTALSgk5WiQo8DYvc9w+ahY;j=-AJ8`pHS<0-WI7`Y zRv|7pz`4tL+nr$j0?pT)Hrsr!F+<`}+|O?x7Exp_YFK{@dWbGg$=d02$oE=ky@P_b zzWCf00)A7inrAbC1yka6?OaQpO*l(Nt*X(#X(%FS6zX?4q9H*64`0}GpKoJh!z|pw z%0zKF1fYkK#&C1D>w}~LVGNU_$JEy#ElPX?T)8@kPl=YVvdR_ee zru3c()$a8}@6&s3c3xC=__Kaa`E9BmrcU2|@QUygvS%i*{IVpif1tbXmame8m(#~K zy7xJ2R&b)Oox)3g_C$QLRO#9~YE(X1{azGtLGX(_tkcCx2}16RRGpI60zW;ill#Z- z_*ml%WMLm$YthTf$mj?}2Lx+Ch6d6&_9r_-nvkikgKSM1H1jO~6RFrfs9Wj$d>AkN zXm5@E>Q#SeFBf}btuKQd%)w=D?oddEN*=G@1Ho4R6Q9;}<+w6n-LLNnz-SqeCw1R2Ac`(8?J zmi{A*e#-f=e=BRV8wwZDcA3es*tdnsCsqAa3ydP=ggcu=Z6xd2gjPbM2QhkP)t-~0 zF4#jF2IeW*Yu=A!aCFJ2P0Rwa7KuA?dp-98515Z`s(Dr9yof9KwCq*Trs_j}jQUYA zt~OYK*ju7+4+JZ`|m*TE6L+hji_O&$lU`r9ql^Lrd+thmZ7|LA;Dr_t7Gu4a{#dIJb87 z2TaY-UHEaC-4#&lee2O>L(WeCA-CpK-hl_oPXC=#UUOmhy^Tb!JwmO0uUp!;%aV^g zOXm*^qzLdsu6Z6a$-1Z;TsmUIiIqNNB+j1gUA)IBr!qL@;urIT`P`NM6dGO-_` zU2N=wIHBiRxmzR8^6;NGhFs*vlKY1YX7WY6 zF#M^tjwfVx^(ACJ_xZQe*~y**{2?5#>6rc9K+OB+B{9!bAdB}GlMNg%G{KgS`Wys15gO1S94+M*7&`z{ba6F)r>tku`q&!B21H==^=M zbvkYH^jkEZ^ykIHlqJh!H;pP2YrBsu(U&!cKT_Hl8XXxZ#|xdB+2UL>ju-dxl3HAj zxKnauvqo5x?B4okj%djV??nM>m&G(HiGbmT)~{#`M+mz=supMes;Es!kX&e5As=Nw z#REoZ=x7}rtj_W#D6wxL)wK03f+WD$U*d4897iO06jx>K*7;v$yZlEBFeN>hXQ&D> zMJtobXHgd!nNK=~C|ZZOwbSZ4PPDAqLn=?Hq;_l#Kg#7%M{zrHnlDx5uji|=$J7Id zC^EYqyeH&ayH?aDKZ$iJ>*iZcPV`ODsK@kZ2u^*@(GKqETc%5UMs%x$9Es-ywd%P7 zy#sL|(C}IVxGeGrZ?(FJWs;5ZG%57_!J+aqnVJ?YR!N;cPP-jr zdUO?ikRnu9E}iiG14uQr;@R&stzDf|RX!eG3N47_<3Y9O3pEX){lhARFS-^r%nW0^ zz1+WsA>e}9`24qUCNUw#I0}mMaZOE4?}nVp^$>Mp!Y$`zG&CZ_6j@Sna&kr|L_v-l zw!v_%kCeQ;d}?Yc-~m}18y>Ht-CWH$)_}(8x)tXKvy&4aKC3Xe&TY7EPrQEY=_zh> zJt3?6o(9YL^XH>Wm>@y}w|i&&Z4c>m*v1RjE#u!4L08#szHWTm_?{+~@-{n}OLApz zMYHO~nd9EzTQ|3*wg2f`b%}@6JDyfD3^; zepNMYm)LqYdaW&Ef6ioN*NWI@M}k%%YVXeUOh8#|nf*2G50{p3C&Neg`fvnx+)$tX ziVwQ#bh+h32P5&>FTMGK*H70=&qAowLxPH^aS6$+-_I{k)+UaP>1k+cT7oA@o8Mo` z+57v;AB4jdE^8|G_BX{`R{ucXQKO$Mp16Q>F1NUTh+8|wOX{J=)_Oie+?$jC^D z%A8I;1DC{UvR*zS;?Pl-8TEUh1>MwMOeFQLP90IOCX(&vl*`_09X%h4O3uB znCNpV0<4V1pC1vP;O~KO89K1F>>?ngZvx=+qr2M%iE@GN_#*8O|HsDuAV98>Q&KWv zqT1uT+m`v}7K6bnOyVrTyXfeL8K#=43;mf?OrnlYOZMvG=F>2bJ0D&0xxer@&9%kV zZaE*-);p>o^4aNw#DT}%i3A7#sPSx<@4OByX+!TdHft$Qk5bMkw_N*ts=qC{Dcv3F z?J-R&5PEz#(YN~>vtr~^?>%;F{C!Id!AVZEtAcR<`~|GxjzW8D`~28y^ClptvB zgRjbccrBq-C&XMVT+kO7Mal>=7D>j<3Xt3hGm^RQE+dPOb%Pg$`U4J_t8(o{In2&T z1ykRD`Y+&>&b>UF0A zWPa$z5GLZz3rg#9Bh&|QMJgG$mVHz~5E3srISqR!`x=J=NAh1gb%#>Cr`Yoa=YX1; zvD}z1(B^`ZedGQ!@oSsT+(;l~jZs^hXAyM_f?Got1wuPnOH0nSwl-kK;&14d zyvj>rWz~@K!ah6KcjTMmRa-09Sjbb`h_jPU`i3=m zJ_&8_kLT2Y{DO^=dPX1=XliNcEqAbh?x}Y`Cb*wrA@rSSLC) zN}mvQ-ZKP$dK4#7z#R8J{bhW$Vtg>$)AXOqYaADP?TYTnq;>=2fG&I@A5~)xQ04Dv zDKBj6FJHd~0Yz}SS9=x#7)D*40yrM9c6^@u>xFHKQb)_ToL9$&Q&*@dBCsg^R?)sE z*psH0u*=bE8mWRhxWc~mb*xi#RxHpBMGxN^i`llbCAhy2FQ;)cV9o|Gj9gcP28}sX zIZR{T1j)redGbWy;MpozJ-~l_e>Y*@fSld|X-sQvZJqtm_nyo(E>9voU;HZ;rqVyy zz6su-bf(IupykEI^)oa!3%BaMR7UU0v|p&M%dR2CY%S#^;BpTFN~?4vHxl-xs7TAt z38>W39I)nmlQa&hl|-(aGRb)4Yw)!WZXDcxRehgzT79`vf>p7{UY2Z23HGWk@T(8e)jJlS%9-Foiq+--w+98uB-X=qzbE9lpWN0~ z7tu9-4z^Uppz_Bh^(oLa&$-kdF+sse&d`?2GNyheT&f$mr#tHE>S>4=cLu1Hx$L|e zq6eCwNRau|a!@B@#G9Y=ag??9f)7r2PU}`TP6CO8?mrjz=H-&Q5s0XvpTt@EmoHy- zqj8Zy(a`(g`lQz$6IhMtn3a*@P#BU>U_aAhC-4y7mTHM=Y&SX1EN5Wty|d!WGBD$| zRS>L(d|m2<77ZKG8y2YqP@MK39ROgQ`SpN>)HD?Nx=+KXsqnAY-pJ&2)qR_@d4(+H zQhMjkITz@E4BO8Rf{|BN9n7BV(hz+$A#=GvB`I?FH>G?&!DD|qkfnXl4JaYum7+dj z_^BI&=ULBZfP0*ec)&b;yY_$-5q@8)-N%P1T$VppfDK|qDkY)5hls^%o5E+mk>vx3 zHn|^t!-H+}{*r;KAC-!*9~=iH20|()Ay8~D**HB~b3o?qJ^66~=?}iG_6?3-!v9eV=2(!qLU{z%9 zgXsq-VN#W}d~_~c>Qp$dYLf^F-$3>|1GOz;#Fu#f{JQ`qN3T2**qm;uGf(Y2gD$9I z7zWpB=(&N91-v=p1w7WOWAkbbL-r#!^89U#s8%u;|0E_Hv}CwZ{92$w-IM1 z2T&#)pR}e8Y!>YL1bAqWJrRccT$rqtn)KWv1u6_~!KP|M7Lb8mxgG))#8%7vk@DEj zpBWJr(0eemVov0Rr4R8gbV%#slb0~clj)12hnV1;fx9|kwWGE>3?zE(h z1+c7Jo;_X$P8T3HCLkdB0dvjm3>lIitX+WTOJPYf>K7PSNrBw%FL^;w2Lmnvn(X=T z3CyP=>{PQwkp&_MkCBWJ5VIK*He4zMQjjHD07^1#>J&m}Ov!TwSn4Mh7Pq{QT_Nf8 zs6<>sA|A?(uy$9+I~oFr-A)hY+d4X~Ub*5|?Xk!I^ylStrH_>P%5XwcAk=}rX-O1k z;6eWVvg|@ipMryfrN8&yoBk(;fD9NG4K>t5tZ{aoBi~w1d2-#w6%;;Dc^4Nk^fFday{%�xB(AYVqa`rNS&}RZXZKMu00&K zEf~Fi>)9acTlw54g^o(6r53P92k=8Wn2`HO&mJG1DzHF-X(zYG9jRcYl@i21B8+Lo z)d!L9-#1-+q$mC21%F1oGd*0rsKZ<*!Zjltj5rMZ122v58%)LiVtq;)k{8HnE&Cn9 z%>l3MHnMkdaUC#9^asL`Ahl@7SdJd=-S48xo&Wf)UQ{~v{B4)3$XX{y0fA8lI_8_U z6IH$)Fpf}nr2vSThZR!KM+AVv(w=#y^nuS0nG*{7VME<~12p zJMc1(wI{26&Q3j#R!XrD8xAIe))x>V(!*)4^J62#9`ee{xdPJJa6m?iERm8mFv|a- zFy2SMlUG!n;q^HnE-x?tGe6%~@?2M(Sv74JvanGgpL_|45e+ppgfhsE{`$`@wTuwD z{f~MKO0`}tQPS9yGC;M~%Ele1AyX3*Irz4%U61X*6prP63pw_2Q1p{4VE^pPJYm)_ z4|3Z6c~J%-#S!VMi4$YWUkBhR%E`-Hu9_nT=bx7xck)z)O!a>Rod0=St`hp?(x-iO zWCj2AN|yKcUs_mLNX^IyO!>!n{rh)wUw;1wHT>tTy(1ieCI9=YqBV4C!S0x6VO9{f}j331AEVuj`Yewz9KhLgs7z4`6bk`p-38Q^-WU`S%CI zUvf+civ92F|MJbLQ~yAUf4yCfsaXKln%)YApy!|qUP5IXtXVhsF(9!ZXRw~m8W>Y#GR*18(QUKuh=2d*m3mQguA<0Y!ejRj6q6tWF0Ci3M5aWcM)rxh z`6d7mV9PWthaqu03_C#cAJFixx3a$CA4(fo0w4-zuxh(kQF>?r%rLOa9#ka?|NeX# z8P<>dLsv1YVt3w7JH%wdJAo&dS6xj_R!@(eqiB?~lk9T2)+RhoM zy2&cB?n#gk2T1aUQ6v(Eg{)^Ao`it2%u*Qzam>G75r31X-0|YTA6L8Ym;f?51{Z7! ztG5l8ku%{6!%SM4Jx~Z<0YDDrp=VRYLk2TYsG0^8;r8M{C}1k+U1=Eme5-nIA|*BT z6&%R#Hshjjsj%axVFi%HS~?t(&P1t1$e+FLZ$TgqGTFzhBL*oLf=}xLq=5NuL2d-K zFF^jnC_@#{OTfi)sY;y)05r zS~OY-{ANT@_;TgettcoA14r44;24lhAeq(dM|lKOze9Q1KwSahzCEz65s{G%z_Q-8 znt?k&%C7Y*9P1Yxk$K8+J@O!Jzydcm3nkXqZr+SIIogYYH$Vn#@jVmy1qKF1C8a4Y zIj_TQV~B8(1R*eO$itQmqi+UWZIChak1t0aR>a?=PfHZbNrBA250~;Rnt~|6aq^io zo$Hp^(}V8{?wCb}e*w%2L>h8{iG-xk{%Ymg2biyn1&f>mEy8rlp4*e2eNX?_Bgl<=xkQlzSO)nDEF?t*Q*~YdO4iWQ zYJ$zw0Yyvyfzz;Ku&1DE8R)uHYX;49B_!?42G0VS1qg1q(8v`MvchXsTV-JXk)na> z5e!7Ea2Z_q819P0#cX71tsB%YKLw%!t90yz;$zFW7K9gv4TJC}MgMC>2bIl?Sup_V zA88*|!6Y`NkNg3UXf1GAGr%GuCKiE7JMHaFo`7(w;FJIS`Sbp{Dd>4%`xtm1m?5|u zG87#+8}Nji7aR*+H%!Qw#n06tI|hdT007XId;S?#A9?}Y8^%k6%4|fYfQ)oAdk(wq zGJr=cgifsmtnQTXvxx0zcf}N-pKG-NeEs8UcR^%uFBQ8A$>_8HT3fj%>T~X|xNh8N zp0=|C&L45m_S(p zfT4V)WE7%~yJ;j_zfvA(s;Sk%DO3hG0A%SkcJ^DQEhHeLpwJM@g8{}bUc8{aX@Up% z&K#(0M9QJ(H1H5h4>B)fFas5YE-_97pY0mXn>}8}g8FerVj9#`2XE~ksIs(xjg6F= zM;pu|$prw(Ez@@I;M9X*e+KRa7xOBew`v^+RG@&UDJdyGK#dxhus*=Dm2ne0;SqSYc*n=A)PkkI!LWBBtDd9gc9Oz{X!Vr60f= zz=mTL5{f}6@Da&6D2#LPKHW+j+V@6*isf%1g5$wbyl`;fO+x0&`3@RcbCHt0R711h#o_oSvAOVZVF- zUh6;1CzxsV6J`OL_*VMx?tdw|;zgYrrtMyNRf21QDquDsBcIO~&@q(%UcY|b-L^3Y+;&du zD|noGJdcLgejT4Z+^CLT?{&-BKuC1f6>)GSA&t}LjwWZ;Fz1~rf#VAX_|w%u33^jY zOVI1lY*v7ifsBNx#Dlwi1*Q+cg=Fjrb;4a|W@avrl}7w?1@GFw4Ka}$4^>EP}PAB32LRnMIZ~X#tjL-h85?)f3g6uJ5tTF z%Kv{uFUz}{5jr{0uL+S&z#~9Xh)C}TZQXhBcu3?77i$Nc!_|Jb2cKj;Ru%#Foj@-mKmQ#-gbhePt7~a#Sq?*}-a6M67nhv*-yPR0 z^S+!%BNTj1-#2|R7#djpWeL%DAmi7RFD2&{7I<_}pCHq$033W9^y7-&fdK!TekJIKK=}nO68MO2h<30*z;FSK>z}!~ z7zt$7C+K$+TFEjyXJ6d3o4Ny|ZL{GmteI(2VYH)cpm>WHDRtTS183{|B$D@* zNnL#SBSp8~$K2(3@X5ij!lao9;L{W9qdS+e0vrA8gpZ5E50vWd8R;1qjEi+56w)rsQ)*;V zySuyd0pZ~!Nr2_$<+biAF2Ev2CVk=O*ceI5uOHpHzc++OMn|uNuy(c9yoAu0HuBmP z`Y;@<_X^jy-6i5~f41DZN%W2P-NuGJq)teo{{0G`wC~-dI_RzS7CNFa$fi*E`}-qq z2k?Zy5#PCDoiM=QM`ar=3`rW9h*AuyBk+*Oph)Ki)|cD*)5U@V^K` z224z9G$%7XsB3%Q!NI}6R2--|JD^La3tE{Q5m&oBQcMheh$NZ4_l@;noa}}B6o}hB z-Oi9QwzeiA@W)1C7klUemYkn|0Sg)7ISnF`COGY1hL-HX2-Mk>&b$>{1x-ma?C*7; zU5s2^X<-}~$O7vjaRV?|8w<<(pu>=rIXopJgRrr&5&hkq)O#~3(db}v*3EY5k%1e& z4@42bbg6+Q1^ZC{RN(jSsBP=|I^QYiLuWv^!|o}`qQ!ObTkWa)m}8%E{;;)MZ7VcP z3hM4wL2ySI@UHv`aR~`6&~)w<7>!G?i9o|O z`@q(-#YZ3Z^x3m}mX-^j=LP6V(=#&cA)oh#>J5bBc@9AqsaaWEPm6UNot)sACs$O^ z!=9&QV!AKR{NV9pI@g3&SiC9cO4v`(icxgmQxX&ju1SHlUmt2~-;KPsy|;HS@*1FS zlH%fG)KrQV*Ywr_A3uMC_dcE!^aWs9k(ZIyGIze<-}z8a@6E`Fj*^m+k&zLWcuz`h zE-BmrtS}!f2?r0)>(&`*LqitWjWIm>Aux^7$jU0@xetFVqqwcDZD7ajOWBnAfJ+AF zD#yFKNw3SlY@GffY~B_n{lb&6HL0kGnv|3ja&Da*@lU@GfBE(F=lFOSoG7@t9Nki~ zzP`S{fB&N2N6k0OWNIZRC*uqZ49KxXsc}Uwm%~B>m& zZ0vuY3edwTyG%=x4BNr)4i>!asg>2;%NKqKmqaLu#*-y;fJHagQ&OFbZQm-`HjSxT zk+<0tfy?t9T_Nb%%Gb$#ckO)L*ue+S`tM0e*l;BREFFF`!tbM_lhV@(^!4>Y_okMq z#lgj8k{2;=3TKJ#QrJ^NF{v4eSqXzbilwyAF{iE`0j_=;Y~Zu*XyoeY}=U@f){k1qbtM zbhN{JK0(6cokE(?_u-$ve)(l2xD%Owr(^M4$3BIoT+$hR(~!*an)p~AA0Ka>1Ms{F z=)*w3C%=K!!o~t9Km{sY`UKBSc}GXbDe#lcAkPVpHE=%)oBp&G()WH zcYDGW7lwqD-+;(6B|DoKG_XR5@vS;q zt#mu_9)8OtX4i3}G~YfWv~?y(h86i3J75UMAf7}hVz9C*er+FfSwoxNt!G`>FAN%_V7P z1M6+SzitfP=KBcLQ z>ol1Zyz#Q+ioVPLv9kh>7(Atz93(n@w(h3ZM0xcPlC>F#$s} zZAU8!ytRo-P4IjG9@%*J}!({c`7t*XB?*KlU z+HwCiFo3U4J-v6d0a3pR(CJ_+8es2ZW0ipd)R_MxjM#k(X+(P1?9k$*>)D%^m#09r z)&!m%ag{KN6oyYDOg-2P5Ue!8Zt{oDj^|$bE-qS$LsGyMn(grcSb+X|#E5hdR958R zZ$mIQ{5@ipBeELMM_3+`1?fh9w9O(STuK>2NEs8`Hf>Ud+bC1nD8p7Nb${Pk|8wu@Z?#&j+U;+8p653_&-;E# zA`ydbdiM64!y3i?Go5!>9`swcZXFVJpgts|s~>XbiF*~yIW_iXwB0}hxqBt&3XMko z;G;qmSzflw+M7}j<+F<}y&v;Y>FMpgq$9zS-Wh>M^;s>;bC-)^`jKPDSW&bezox)z zQe{L*BwR&MK6oIWY*6~IjcGL{%^E zK-1ojI-Z_0+C0HMSgWJu>#N|VxB)gdi)n^w@}T6hB2(@xdL$kv?AUFLRFqm&PF%_Cx0S4{tjLiL!C|7u zJgs`u@W=G|`X(UhEtBopAV5AUcyWA6&4phyfcl-gcb}lM>Gkh7mqfDY<5;bwC(Zxl z>sKXW(67v6@yTi$y`h1GpjV=#A1g7+JF3O6tCM>Kfktp<6BB#bh#ZO+wT{7kRF5?NHD;h$wKt&B+E@_g<8l_c;_JNl0?vi5Nk;1F!tz zQ3APu5s1#z)YOXxdD_R0t({;nFoh=I^Caf~W)AM>%w_l^N{0a6n2oWK!tb8{e5 z4``fsmvUs->AAQ+wS#}mP*1Xs;UrP`Js!UX4g-5#&YmSIl!}UqfbCP~)z{m@&170A z&I$?&NEFA4d!v&K&|DK!Q#%(I&Kzli{e_7er}(Z$JCpe^4QF+pEX~c$oZ;Gl*{;CRX}Hz)zC#uk7Az#fa?k*x zWDs;H70Vg!c>AgyKYm|YqL=VV(Ju=F!A{-7kl zZrku_mH;);${$L}2936|_obpnp5g^YgUcGc=8mFHfWu!LR+?W}kPwK@zIDsiP)I0& z_R(iqYu(we^0E$(gA`(g;w@-BW_V{L&bd(J5Nh>P?MZvb&ma!Z%G|Z{5&sy3T zozvQ7MRq5eQj+AbLAQt(uHmS7htH25<<-lLx3XnSPe*8Hlc=8a`&485`b+@~&1ii#;Vk-cAobXo6IU^P8159Rzl_J)=w_mZLkuACQU7oX15vvW)3xwB_=F-obP30U3M(p-$Ls^1xya*|wkavzygIkX zRA7s`zri1wM)muD4Dl2$RKIfYM#Y3LLUJm8|GdAyeD5A&C=>%9%$QrBFadDO^xh0a zbOVE#lb09H{@%jeykSo5jsNhfzFY4x_Cv@4`XkSfb?6%qRaP|Qho|Ykw}`ABMi1zT z<8>>JTI*PN0Cu0=)P5aFG#X&>!mQ3f#hLXa@w7uv>`GyGvo&<=U4px}d}?ZHGWf@Z z{T9L!=Q-X~ofF$tJO8YvWwG{CFi-u`)VV#1iY-4`@sgyqh4O}|UjQWTyQ0{57_Gmt zZD-wtuIdnkA3%X&G)6;POJ!0RUT&7*K{n&rI_og19J&=)vB*k)FOsL!*mAM#V;|B*iQ8 zgljkM?L=9Lh={oL!Zo{}!O~%wVYHuqXiMT1y(e`-)C znMlTw&13`+2ZU%qbq0xrtcv#HD>E}WaUvIzSB>8E(I*FL$MAMya+F+pXQA`O7~#)j zTZON|VQq3#EI+#2tAP6P<7p3($cP9I9f>tQetr^sR~wwlOEXy{s|pIXA=IC^DK^>4 zYUUj+%_KE+XlxF)*+J$b3V%wlC;^;bP`+sne9$U0{u#-;VCsGN^eGb54U8Riw^NFe zTT>&lC2`yEC$EJ%A3vdTe>IAZgw}W^brYFyS!hFseeEl6t!bg7rlyL{8e7PG3eoBm zSQ=UM>pkl=-B<4X^oMsR_0EHnKVdqpSXfv!rP=8pM1IMr@*SVLd%ZUSS_YVpSEX!_xC@?VtOs zgPF$x(0J;veEY2?17?|^#M)qGz*x{CCCa597t0T)f`_5T`^=n!f%+nz*7@F zdpWQ70OE;>3A0=?EnaZDrd|FCufQbH-KKab#bA0|lVA6FUtd|r3r+Eh0J+IGwHp#7 ziJA=y>hFsT5>tSEUawVsAqG*B1WFf&@jEagf{HQy1P9l-U2A&L} zo}!-D<1(P5!q2rS*K>6q=(a~Kq;mRqN5<_s&{N-!0W>(dsoY6B+W zIKV*uG9}_F3Tc?33dQ7(1mjOjv`75W%;sIm0qX(GzhRCVIPfOq*OK=I!))VQd3o$G zJ*6IdJ@4*r*wTnLc=NBHU-pya*2WUa#H03^1gQvrzhk1T-Ja-bdvq%F6XpPfn0Zmk z(qSx?=Z{ri5M<=bIGg3&10@D^jzHLN7KlcuIQ=;6^nIn5_X}(o!4f8Jivd3(Uk3aP z>&qU(b%cLMDH4QB=v^Fh4(kBl2v4H<@6|Q_^ILyCOvuYkry#`#+$v*2md`T1Rc_*= zW~FxQPzGRX*}Wg(p;QpQDNSMPsIWIoaJN~kmVv2$a;+dNnwy4^nVFfr<`+JugRcPR zauILalew_DYa@)49nHgD)wYW1rGZRWpgXi6lwZt?{gRIX_fUfbLx&jwVhppDkQaGJ z1w}+ITbEFQkT}Sx@E&BmkEMFZU8GydD>a_RnPZ0|ySkS~f$I9kCBV zVOwE7s2tkQ2uGA-EnqmfI1C_gkt4AwYJf75-16y1m^co5uTD?9gK4B5+Cn(E z@dw#V@2x|ThrIe%^!mBa-rSX)`Gy3}|PbiPl_7BB?IHcVWc@9O>F8I0aNA`BX6 z7vSE>6-M|Rj)>k!*;pQ`HAZj>-Lzx{9qv6N`@z(7ad&UQ?2_C<-pBPpp!lj?EOL&y zct{(mV{jv*%ez##i;9Xs>Hp6R-4TYkBA!wS2P_?ZeqF+I!nYFgKc`0;79lkHXS_Oq zB{eNJ4bNmTb+9<+irGM=A;WR5@b?b~KdaHjzMP-%c{JSjXe>a(xoXrcORG!#;MRQwZOwM2 zBSF(9==qoz`E`}qmB~V4bwm7vv>~&R;$WOy(?RTD@)+@L&Nx(VEPWYfmTL*#V-FyQ z{4zE*2b0v67w&8|PFxJqKz1J}Few`=g}9Svp*0N*2m*P{oLphV!SjAO6(LCm14CSO zGnlCT&`=E+gEYH!WkeC4LEcfCVO-OYY-27Mn6zo~4r zjZ;WU&f4!a!fBzUIlDPZqVC6Rdkk%EWJD790kHg9suzD1F25DkMoJ~;mM^1EuQ{ni!+^F7Q? z9YBEUuZijDmUr)9CDB#H7#}_~z^>KiS&D%*hl>o2p$ag9CjC8U3mbg}!uJc`ygkA^ zmyh~$DmzkkxANni*X4%f;+pjnBnjg+HZ~Vq(^$RBSzDEuDEf}p^685`lq5(kuWtO7 zj(`No6>t}o<+3HoPf##|G;H(^>+Y>bV|6^pu%sUy5_D#qp5K#PjF$^2gJ=hPfaMDb z&dU~BIkiGiOe_-nPp@iyb}6Z$BRmE`Sotje8|w)DqmP}BPm-0O!COC|DuZc&2 z4@@~ospTbyCHX!~O|jGGZ~{0EIYF}W#`gX?6L+_aGcOZg;o;(!Dy1{?955T^4;wiF zLpmpEwS#jzZ^Q;Gc=1{lOYZqz-7G6M{4jUVY;Nd`m{0L1bve;qgV~4eZkR`|rw>qPeVKT^CV1P_8KbOljbAF(8J1lR z<4W%Coy@`gaZ`(fvuAgaIX7MA)&Bc88K=2s>iBa@=lCxoHq{_$Lh1X?X^e_p{NG3L zr^QF38+MF)vv-X?+G`>Z@y~y2t|2R!v?biM) z;{mV_74BzV$f6(T(A%}{fa9ru9_VtAg+p|#b9B~R+HQ@M>0SEc0hHzXX^h{#rjGq# zuIJ4B%7sBkyNk*S{f)~Q)Mb-$Rlj|xb)QwBrJA~RruDn>d^A`WocSu?CpgtLT)Hl~AV`nq{`S8M zoqcgdqI1e9MLH@@@@nPKY4LL>{#|)Hv&QQ5%gjLZ6p{@PAI;CcRB+dx9WC^QY~7it zUfXk;<)ZSMFY}YWWSqw`5;3!B-OZ!>_x+1Y9QIHW2;_8@rwqGn$m9Ue{VV%U12s_< z@ZEM{;Uwp3q`x$4%_akh$4|s*RpoW0j%umj?z|yCx6kd@U5f^v_O#9L zUQTPMCdvRyMo`vzaZaizIBSi#rqVaHEWh@-pp+X7uQWkQ7;I$5uj(V48ueG2Y${c2Uv90^J1eUZZZ-3&TmLfpPvO2Hsd^PofFhiO3 z)9FUPiw9Wf-n`8nE*C1rRjK56I;-CocKB7VJmjP-`18Zrlo(%QkDI?03tGFdrG8}x zvwFpF`I$TP)rHQhYMdR4=ni#aJGtfN`bcICYU&NU_Q~8_ai3Mf>Dh<8+>-PSmh=vD zBc9A-a>xFgdc?Qd952RpAWMa#r=0d}84d7w7gywYI?z^Ku0dl?lzn!?!Dppq6XmRv z36gp21Iiw+dNft22a=qo+qD)JU5n^-Mt?{DU#A$fuAG%oeok&LUCyA{)=*RZM8xBa ziZ0#{6_CH_q~-; n0y1l>q(feP8ugN${ql>)nQQmJo@Q@$5`M_KhC0RCwqgGP01w9O literal 0 HcmV?d00001 diff --git a/doc/img/teaser.png b/doc/img/teaser.png new file mode 100644 index 0000000000000000000000000000000000000000..a9a1bff46b6eccaa7269acf210d1de4b33d8d832 GIT binary patch literal 275281 zcmXtfbzGC*`#vDTNJk3NJtU>O8>xv%cL|K{PU&vx5|IW0X{6JE#DLM=-T9mE&+q%% zAB?j-vFF_PeXjeut`n)QDvyKt1``Ph2}e;u28@LC@)QXPnH7MB7%@}6#YOxCY%`^kkN=->RG*l|v=Rhh^NTijGB4qYwq(Mai zO7(J#)HV7ANh!$^%E~0l3`c;X?)ufK{nh^WEpS^CO=!e&gQzi_FU`UXe&>K3(c#t5 zNPsq0|DpJQr#d#m-lA%84;vB}fW=0E{QL4sWE3M)FvCzvz_{Z7t_6M=m2xHZMMW9G z2aI&bF>Nn;z#G>$Q^7Kc^ifjXCwI!pcS?#q82;r@_W!B^KjMDsQ6TKS8ZK#J+ZN6DN3UwEpoaRNklE81Oqn{5@Acb- zM)vkFHKrIYQZ*Gy6nzyc!~Q!iaqSUpVx0yx4H!X*ZUW~kDq0^MJ&mc+vB0WTc0vAG9s9cz)Ibm=4NIg z4!(!w`fZ+7O;yzY_so_8-P`s-KB95UJNF7@_FIMygPlS?VVyVWPngou(%NZZ;9yQ{ zjNm|+q3{swX+OOT_M_=e^ZzEYiH3)xAT!jod6eU!d;8aVoN((hR*;$8YM%EaeW_~B zK~?72D`xP5n8NW8A@dSX3JP;8?q`!Ah6=GQvA>-dEq7OIcixEyN`t!*zR1~#gV1rw zEzQm88BdEqv;e8S%Qqt<$_jHi#VMOn6)K-=f@x{gVjBQy+* zudH8PLRWHtPcZ&CR%f~;p`<7WAOwPHSbqn1t_h!g~Y%V>C($8*U>U1O(!XB$U0HV8?fMJ>%kcXw~nrV-~R zXJqt97~A?jZBtRnPA8Mz1;y$Mq4RPl7OCPB5^0?&ElLeOrcdkCl2g%#R2=fz5Y7#C3fiXRaP z{K4Q~r15_DxauH6b*0*xny!P?5zjeR;cp&m0=W5u=3Ju&S!Shlx3-fn-M6Syh{c^* z{T&LVN#sO*sJoo(Qo!wAjcTonN7KX2(@fcj$xXhf3IK3HtZQz}8}8XN?q zLF#`B#9PcEQU?oqjzmI1(N_zpGRUF}*?=C7p8m#*jscut5w}9ZpC5IzfOzrgX%_1O zu+5#|74LWOlwP&OH7hc%D3aWa)sX9BGjsPGKLSeI=?HYHU&+eb9EltovwkPI`g3dH z;y1`-IO2Zn#R^VYQc8*zzXDTe%F9^*G=rOUfDzg}=;ZFt1g?-{4@YixK(z27BV8=o zvY|EirjT#f$O**a!?DHoF3R;d!%i?YbvzpzPzebs1x*rOI=dl# z`p7#mG1dAx2|%>I*ucpNAX*vAx5n;NIW?iC9Hn?S( z>fDT-Hl{kgN{Q!a@@@rO-qVpi;8!(r9l9cAO>l)dC1@{0&#>6S#g$tl&!x1<4KBVR zm8U0)OVH0YpgqhDQb>z6Ui(6G9wad!?SW-!THiykJO{}G~R;u8nC&et=y7E6riLlGF!MlL3bMd5Xyp=Jn7@Pc6u-1vqp4wi+?S0!bw-cYU{FndljEI zQ1>A<1~C;_>Pm^HbpT`*78V8OS_m1;4QbGmGDnpR3F`7)%htSJN0VNVR`>hZ+vO!Y zjXH>!{;1=)vnRtSFw8($N)8XKM9#p#73GZ=+71Z15JaqSt!Si*ZSTKeZL>Qc_r%xK zI=I_1M!KCFPp#ToLuoDLOx;*GVL;+OR7f_jg}C;ak}w0UoIx^o=t?J2)DV)765k zdknFL5`Ia1EaHh1sDpf$ODC*d#jg(nExG9dbh?#%b9Q9QudEw%LroO)8X}9$+vgb7 z+1%$z^=XA--|ipMCOTKST#8cmB!X#5TI`J#GSLuGbILBI6c*$AC(l21(_4XLj(mYX zD0yh&^R$k^au*I!j;ca=OQfTVK^>=3L(_+15m!WCu=C%_CM?QTdH=|T z`&?jXQo1wVz4k_jRx|#4r#%^{ME&dFvBeQ{su&QF#Ntu~*3&bdt6{Hy@pXo7nrD6` zmt5m~r)y$z^rmsUfbgdt8*!DO3>f({ni?YJi9!pYYiszaN-sz7WfIN({Bl5;Wz#kS zangKQhtq$PE2^vUm~SL|EUIlB!}X+T1tx}0d`DhZ!GS`7IRjN0gJ1@pXq~R_JKEI-E}S3B}ssN9u1PKY{>4|SK2=6&_rlMvsY9fZ5jj- zBMrI~DYOa5%F!b!!xnaMMu6{+={HJp6=vsQHbH9MS?_frTSeFbd+D=;?jox0=;}k4 z_iC3>Ft-NBWe)ld2)w`f?XNNgvoP?5f{M%H5j@MU5NCdU1@c`ilaAN1l8mC$u&8zP zQn_sruZ_ZQ<#7H_D;BA&0>g6hz|$4=TFmBsT+T5IPwZ7vxkmihbf83i$DihTU8ujkOH~Ul=uZyv$h-}IyV2G^ z_{%DhUa&Mfn{Vh~40l&E<>4V49=f|&78*ppX{KCzJ3=!OFR42rmw zkBB4SI4Lqp92ip;HaI?U^Lb(vaUlbliOWJ>4U+u&EtF1|@>gsK$ib?6NL=ZT1EQUK+_~v!6cjt=p==8l z-y`}~U!mF5xE%RBNuu&CrDwE+A@el|ypaOt4Ctv*`zE<$ zDbox-nTYqxHo7Z;F6~Jx{%bfrC=T7TUK@GRG~%uKiXxB<>E>Xf*{%p#L^luvFd`*4 zLHyy`l1-B>lLS@rQz3QwzEBtZ(B4?Gt^KL;>(7=aEx<`zl|lZ1Jpo)LXc=@faW2wD z4~c;=ZaFyoWGf+Tw4h-vw{_9y-wU!g4p|rQ%ngUYos7=?s5)P(7hIdbXS$?D?lSCM zS&ucltPmv+P36Ca3^QL(*$h^-D5svmc)E*!)9QY>bslgO5JUF|yzm9M7<8l7are>E z%4#=E$ekmdQaxox1PGd}n|s$46dJJ7V?4Se|Uft8i@uk}<@qxzaRh#EWC zRbWSwx$p6nX49j=TUkG|kkL$T!Z6SCznoHSW&}n2tpOB|khpg!fMRoq4W^YH_QY;Y z(c-uDmKcZ~=Zv)@A9f}NiWH1t*nAcOA4NwFN(q(X{7?yAnl%;$%zmo=fKo-=)!&EQ z7H6IZoI3MzzY`l<0JuTT6aZIEx>JE#piCsbC|P%Rp$e^G!tMmAQfUe81(ULyb_j zJ$T6EeK))j0XY#c2>*)-Rb*b<(vQ;8DlCo{8_t4(o&ktfPZizop^3m=en9FU%dlXh z!0dHU`^sr$MY2~|Wo>zj^fJxjU1v>~$Ma*S)%S^w@cK^~MD2oToH!MF#1v*#1p}%K zsAgb%WEPEHj>j{O)mdDl$K+}*-Kvwa_Iu`KH~wX>J!b!hbt-N`*#ksVz)FUk5@L^<@l%ZcVlfR^(WBDtLIhm4O^r8H_Ois%g4hM<2f+Pm;(V)7+y?EqbJl|g4q?r zMcK8w78tyI6T3`}E$x5b6wvDPBxO9u*PPoUNpNUF0z@^CZ*LU58<;%OH+g<~jKPUN z8Rdpv%-QvsCWce_XQ=s~C6kMKr*HxUJf1`lgu>dz?xcQ)Z>D#${(QI1IF~5b68&ehI`LX;c*1v#@4bz?bQ+_Z zQ^dgxiZwRizUxOZ>B$F!WDX&&!tx-7wdJX_M<#`ZC0;zK@m*B?7Lk#>XRLrkpQGk* zm{CAZU&%-R=j%>FVe`>L20CE_*dfIye!dcA+-Nbbp}kA0$GqhZ`T&=3KZ>;o6RReM* zotw%0_$;*Eo3=07(hWGR`5UvBRyWOgTqr9=Lg420a{^}y99A8)%!&O%mQ+7kqvNQ! z#5*N`H!q-zu75!#rd;o2UpLqs_G5wi5`da^tz>>xng^bwKP$dyMj@7W_AI~k5Kr`e z^_M(w2v$IfUVPbDS7MoU#umr zwIjoi@QY((ak^t;Js7F}x)o^q5|FkWQ(k0fm1zRgWY0GgXXYTe>T9j=dVq@y;Bs??Qehizmq_ z&7EvQ575R%nJJ7AmF&s}rW64FQE!Q|zD+c8`&#@=K}q z-DE)kk>1b>#!a3f2PtMEf}it&)=lttk?HhStujBOn%Ws?^N@=VkczkzhwUTLC~EAI zT7Z!r*v>qe#Mb^Z8UtGnAy*K4CQ{MQa>e^s?-X^))6Ym`@y09(U~cO?@&is)@{Z%j zd7N+!DrrL5wv%qGhZ%=Q;(+VpCxfHbW3k~)F!`Z_z3q6d5mTVIw{HLGp2dZen_FRZ z@-<^*_0S_I3ej=a+SfByzOP$8_|Q_Bbm&v$f7b8!?fHJAfo8%CO;*@pmoC!(ont1M zjLNHrG0vDV!cX;`88E4)OndRg@Heq&Rr^UJn`?&|cpXvz+6W3?Z>jv){oC7HF`f9s z`R;=dW*uvZwo~Y(R`k$8yacuRjurBjd-gRl z`%sP*&|EQxu@WLUC|L|iuSMx;E`bsiMsxHw)+&nvZ`?$1(eG5dG)pn4b!m?&--sqq zg2b6E8JPxod$E0}(5)vK4rFhzQuXBrPb?3j^Xw7ox`_{Y5edMpTZ^vZnP-!~8(Z3=|s z-75W_B{_hjHwDoT<*)1O>K0DhtP0^ywz@lE$_l2he~3j>w*MsOu+-RWqeG4>eS{(X zBdxE-!fCn=2(CqSWsQykFLc&Q3Ma3=Ti&j-aEi>$&H;L+$qvp_OpFA zsn=uvR${JU#e(%)a-@5yKD^-l7Xzht4sdczX}OfO&n3SQXK;AR>FkN`d~&N2y=N@| zVk1+)Ek6Q;q-r<-*4o6M?6Q7XtX>tr4DU&Z_uY}cQ9AvXhc1p3Qx^04miL!}S3W_` zLcz<~Of6L-h(5CO5#G7TG=P5b67X43456(A=5L6M{|x$RP@F!opIKMsZD@@q(w6!r z`Y!uF(L`1}No}%{t_?V-8opRbY(c@xM}2mSV=^dnL6aOL>XWb8G7UM+?KwN+vbD8! zDqf~O8%qJ)ENqL(mw;ErAHtu3@~2;A!Wi+AdkY!wk`t#bfBGe5^I{B1q8^ap42MMY zkg?s%757oo`U``fH$K}5oELz*;VrGBUz$(YX%UtihGEevxZ@UI@P{-5P-oJ2OXpb*!;Ctu3ihHP)zfA$wN_^cbB@QDs%BTyS~Dn=v=E@ zmgEZpgK=e!HmWw8UsNpxaJ5*Cw3GAbMi3g?8RuD&XA5Z z%>ml9_h;H(C2ch4?tD$&uN+Gw4}U3jG3DXYx%;kQa<`XMZ_&Q)vN^-oaL>=2D>G=o zv&brQX+YRXymP|;KiR173K(bw2f!JzQHsIl`uqhB_SC23M%6H8^LoS)PnsW?TQ}Ob zCA%f_U;J8PYd=*j?b+LVyS~2ut4g^+w?rMZ(qf<9>tS$3Au<{_=Y<(?3;QmNW60v4 z^{JzI^v`P|bm=?`8f_HfK(~?%+!s~ae6R5qD8f)1`-0PHYFJfuiG>Rzk_d0wYg=Dr zH?n?9k^ZRAos;lrOZlowGQ+D!%=;eFUC2URw zG)}uie^>~%Yt2_3?yiOKTs;)OtB?PQi=OwKp7gH^S;9@>)C|*>$zXO5gB}N9S>8?C zuUbj= ztWJph854$6y>{y7?97QNAt6L{#6y+T?;V(;;)!=kn3T9q4tRn-3&zS7IT%1jaguyF z8OVMHmDZ!U{-!(k&YFAuwd<48gdHD(Ej&HVs>5?&xbs)PU)u3rwj+FYhkF$Pe9m3! zpluU(@I(3JgCWqvA!o!mcXa^C7oIn<9k$k2!Y<2j!Kb_8U-$~KM@?}P;7DcBv!~fA zgDE(KZ_kaEnR(NB@xJ0(WVQl!s-GUSuKs5m!LaO3X#5ys%t5Fpv~tP}#VI`V5a+59 z?dFG>?0vW-0FlGFf-YaACnrS^;Dv2@06&;IiiA0J)|yAV8g`$nhEPTk6iXt4ps-SH zItnY)ulV4t4sO*o_BKL>M-RpkCPH3M?3bH7WP?LZh+&7uaLCs&{R8c(#~KJ6H8-3H zb#Yr6n)#in>a@L3ZKzH{`=@zsnN+O1a6ZLWlR&-75Z597B!LN=MbR_grU#luj|vX@ z0r_WVx4Esqg_Ha=YU}|;tht8~{yXXLcXUt7Y?&1BhSM{h2k&rB%z!(bZ~v*>KrAvc zREAy?QVF0b`ml^ot*%NjMu zx_>D|*GKzwCzMnEi8(%|7nusdP;&&_j`$v!QJGm_1={{V>iw58C z%In;tTivdNQJt9Y10l~|sum(zxa20y56fPE&jxka-AJ8-eIlk9W`2BpYO*p~g$CT1 zWqW@6(;PdAYMK)*1$>L1hYOw4NvX3QN1jf7)F{yq@}b&()$s&*>U_R>mad^Ed9EQKT;#N(rR8{e1 z@szW&-s9rnT{6~HK|U}On_)yHr*oV?5-{D|`W#z0xey@7q>oh0*qEPreIdiq()xra z#mU9h-QA6{>6{rE8L78O*+h;Y)s)lO5n765nWiZOf>T1+am>xjOT=M?+pV}L^tfnS z-QIuvbaZ@{)p?sGqtVOXc{|qOm$||1TExQ>#1R^C2~P&Ug(pUfvqe6;SCpp1<5Jo* zHe8d6{pg%O5h#4U;fp5N-AuyA_%>0pNwjwhM*kgq@2 zIn$Iq+!nrgam!gev8&EZ=y`Htg6MJP?}V~q(R`SgymkihoO1_WgySY&i}Vj$$cmg9~rBaED-Vt8w zCr|cFr*H5DSI1oiZ+K(oA}e>wxlVO6>nCCJ1#f+E`aI~hXwmzmrIf#<^crao@H#>t zCSj3){`IPM2=NR=H)nsK*-fg=psS>1wO+RK742Q}{_?@2$WCU>WmjNuUv1|ZXIKI4 z1dCgmVassp9E*dk`1^m9Xr9|o-@I)@@5n@OqET)mI>d>dMS+=Wa`OpFll z?vFe3^f>}o76WthV&db^*P=O`H;0LWsTFo|SadZK7j{^o{thAT!cvjKwIG!1iCWD3 zKec#bNVHw}pRCIb0JJy0GVV67CzqMeVvqgPYHL53hpgKTYtS~635$fJAWI2=zE1UG zDjmsIG?hK6AwQ4&wmN+RcZKtRyEz~T$fRh77Ue#7o}Fc{>_7Xxu0Oy3JY>dG27SI_;FwVlj78@`igKgqdVv6{kd=dr0C=gsx#IqJpDBf0 z5k1#PX0u=w@0$gW6Kb{22d+ko)k`$mK&ao53pNhU;vQdf$)IJu$iqp`!_9#B)@-er z?|Ig8@AV_39cFpauJ~&&=wbSk(WcSUNWf5UFY26KTK?-k04(woGsBo=vSmF6FgYXy z^DA!BpWDw7)BN>@NgMA?g-KH+;pD~QZHrv+-#n&C^PxlQoQe+{&8U(RMH3O58t-$q z%+0;I-Wm~HTK?|cI9*h5A9{eFw`os~i%>112UABB9lHf^^HL=95+qG*Ic)5Z(o?x| zKW%dh+AINu6u!p*i??7AHFY6HWrc4K4#$|(|+@^#4jsw%{ zq_wSrl^_UBnew z_*StHy~c(Ow7q4}Y9@zyl3bu9(D1;rtJY2C3L2O(x~V%}xmFUnw4JtL38=~dWk9Ki z(HC4yr7e}oaov&x)12Un2Irr?VP@e5x5yD#NzzR_O^P#Fxa#LiydQd!xkSKH^=txM z1i(<>7ntJRhRf_w2tVry3{_J34NL;&OX}<9AoJ&yb0Drwde$BmTm*elR95Wl_bW34 z4DB1u)K#sZkx%RnS+OaIWF=&7?5<_~CNKA^t?fODEO}0*q|(sAFedk{NF$|#Ew8!5 z!z=HzZ&eU(Fe~^(M5&qFhl%m#_fWEHcS726y^C*l?Sw{g%1>Q3_oIcOsVTzO9EQcZ zl}{=1{w|25T_1=)znD}*tOI?svm}UEG;woF%@OuM5%n`-s5z~Xp)7F^&X$hC4(8T2 zjpGyw1akvw0||wJYvkXFE4&VF#!0UE0^&wq_uoi-jwm`qdKRvq%8*5vuvP?6G|_gc zy6RL5r+^yUBzu|?+fA6h?cBq=Cwd}RJ8#wAhh(r!+I*Rvp;tPRDti~IJ<#|ENm;=w z!`20Q77pu>2T~5y{mI{;DP9Nx+JZi!&?_BEl;KPL6o{t&I;>&+MA`9tKzuJuSx+>$ zm~`eqcth2poBw!*@nod-7&@BD!g?cCz8L025su(%TNfz>N=Z|g1*~&ZV!G9mo-9M# zF+`ar&X>(sB)LY6;GT-|k~SRw+5hwg8tI=d1_9|`RScV5Bb5rePDOn@R~G~c6UNLP zA!Op%bJjd9iC;t=DyGYO4gYL2Z#!>rk>VcA{(hK$Q{M1qj9LN((T|{ZKoN~e?)E!T zQ3|!HWhhW;<=(#{N0^7F_vGZHQTBp$q}y##z?5<)x*sPvkSWiXi(RS+T_ZUI!t>^) zgG%^?>qWuR6C5w-*)n2=|9o)_{~9i9(3$!DaAVnVF=7HDwnLJPcWT+1iKbpUDXFB$ zo*r!xV=uG8RP>b0$$Qo``H8=}=t%jSQwfE@p}TOJy`s(XesCH82dY)eh})(&Vb5|f z@#fL|{Q$bsA$LFHalT}jw9$Y$@{T0Te%vdg0rx#Au)fQYw+DcE7*;O~|O@);w!2+(s?W3e#i`pi+wAoW0yo$b|eM2mQ zn3=@;ZsF7@XbGojF9==*LFRzWTmHswiauDqzmTY=?r^eWiH)%UjdDYo$3s_&jnnyV z4xUgfbr(p--C}hjbURZ}czAeNX_+<^L4Ten{g+W_J&mkaaq--|JiQy^>iofm%($0Z zBZyWSF^T?1H%Sqk8;d(dVkh#WO=mOwD}&x4ZS2 z5jL`g+miq;>n)HD2VL9Dwvize#?>VRD%<{(4HbJtiJ<(+m6{SRju>a410 zHHm`afu9oYxn;6^oMt%i;{Kd?e?YMGH9C^`G`-|XskId@Al{I|Pzzb@w6Xn6?AORV}|;&dJy@fT^7nOx_EiD?Tnz+DG>~; zDzK)e^Q^XW zMc*IKO{T6n86eo>euOLU*7r%PX#f%=RnQgkN^J1vM!;jqiwUuA_JqGeDF15~Jnyz! z*yrr{_)wEJDz57G-5T5*6-W2h8osd$UzBby+695nZyI}I73L*-_r~n^EwO_Si&Yzw z|03br;2$m`8uCvK^B75y{{)gP-`G ze_Hc|<;xD)N z35;$OpS8ukm@@Y+&*PLE8Bk*E)Fa0{$CNthQLSSv7`!md(?jL*oegH4ZOGK7SNImC zIGEt#FL%}QH3IzzpGcHtQJgAKq`mMA8Q9Ir1a)fk`fFb{Up)J~wEHdF_NzbI&f?)u5MmtyrLpP#9WsY=Z*v&PwMJP10)%fP5k|HeZ|y(s0dx})<9SddakXji_+o( z*R7PRpQFzjDW;Z7{j{I`Euc0(YcQilpfu*Q1GU{Fw9~;y?a%J1-)nCf~{M7wGiyd@^Iw3Mx z%Mt)Q+;=Vy{{9}MN zcXB5TbGyI1X_9n4Dta**`pX`^)BGbBD+^q&XeilPDuXc2AuL^P*x8>IX=>!ea#E-Wlm+Q-9DzSd;q<&|o)g5Rbh9PS8gaD`X!wF_qc<0%(X=&M&rECq0G zCa*+D1LX~287fIFTc-;VT~soFB~4eV1;Poq{MWtXogoodHCK4>kl*}@cRR8MD!ly~ zqU_KUVXBIM10Sl`u}J>v0`np)4cHQei-BOH@ld_!u#bxMc_42(ILr+7tl#ufyKFX{h+l&in{1~ zxmAY>--vsXSjZ9b2QC&xyS?@3LXc|xbR2a(hdq-^@%;#s_^qOxy!`E1dgo|=f4_=B zJ)wbiTHo3N`EO;8cOO}4Q>EU@nqAvRc`V?G`>YMJH2C4*?x@Ajz)szh*%gI;H_``h=<#ILsfN_God#$0XKnHllrl zG9$TVo-Xnlb3S-(=dJQ}r7OmRGKxD^c4PFYLd9VJFi2C2hALeh=@twBqn36$Ic~ch zw+Nn7qvh#}MW46zyF-EZNEFMDkTX)ihv_%)H*IF~*+Rd5 z|IBMlo^I<1P`7!dly0eXo)6%X6zCHVFp*uFrZ_I0V z62q(ZP3QO!KA{>W*rfc@b=tXinGeM>Q&ge7cN-sVXcs<8bXENTiuchC+kg+96#uQ? zLuqX`0`tqgr@@Xy2-p^@ijfXFe()tzLI9rL%f=KLw1T{!#H=lRMs2Fcizuum5=vYe zG7YdTMJcz|bG4+pZ*7r`G4GQMl6RHL1SU~t@oxbai9uWb5ct+=IF%*Bbud|~=25f_ z$%+9h&_vjgwK5HuVg&8r#f?u##KkMWe&5JSK7x|7JHdTtHxLApdWr05*l8Z`h&XAf9p}a&|L?D%azs8 zmw8Vx;GGqcO^F~m9_Fhb-}qb|6iis3q*nWuaJ&HZsYo!pr;i*^k_H)y3vIW!`sP`- ztCDdO%JZ19@Epfspz41cmqHMh#r4ze$1k8LQ=L3cfR0!j_AYkR-&avhPAj^hvJ(n>kzv{kBagP3?2YhV*v$Cp~SEEQzDn)>MeZ_P;A8XG+$g&Km27!+ryYx@bPUoftJ% zo5xg=Eb=P%vHrK-EIiFht?dsUj3O-?xvZshMmOOuskKC*2PSoLDPj6vmy@~qL_G;e-C z=GGkGlKf@gxkYm=ar$G`rnCNALf}_W_>DGemsXTS1iKfUE}=kq?=DSNPDzuad+D2P zacKK-i3Q#pGzmH8INmqeZ0UmP)!Y;I^(kY{E#O_g81Sr;3A3yW?4&le&`f6*Tvs~1 zro~Hs`5cY6J#HMq)fIE#LcOi+CjkT*N=&A$T$; znw$J%0>JN)IO$4xe;*~M;>E3>+Zqk5*`RJMOt{++R**A!zi%Gi^0q5`cpa;=Xn2kp z`~X9GShB0xw?o+&kM7$FGl!9baxM@maVnuXc@t$|c|QKlj6BNL6Rb|t^+ zwamn@F;WZH?z6`%(N*V{Km_!pl{ve+rMP>_68gv8$AW7~I(&*r8p1`zDgUI_c>jx{ zhsw^&CIPoSLa503Xr=!``}MfX$+*jdj+EoxC9K)`mJ4BZTszwwsi>;z*HLfKjqU4` zMR+r)9(UwP-@N(viGH(l7&QO^^9pq<5j%`VMn=fR{j;URaTkdvZocOGn;CpeaK2aY zYiE1Z19NCyyRdn@faMglSibiFe+LaG)PjtA#wH5$4$_qpab64uLB9kd1#u1fv_I0< zR>#{8UOV+90JIw*#j6R6N8WZrO2DWYmywFY28wwggM`Y&;otp9)9kGv^+PbJtAw@&k zk?^30M~e2>uj|pR;np`ehVD!^WSjW2c=r8$wXIXp5S*E4^gEkR7{>3Jze*InPAKJm z_&N6Kku=D%(TeL{1CHSC8QtkKGushOPA#BNj;JVDG}cr5hyb|qbI>6+TVHq5w2IPuAqw=aQl4`X z&;dC*6iJp%7g94s$Mw7?p$$?QS<^1uuHoyHXn3rUTInQSZ&7A zSMvT#8OT%~=*XDf<4#@(GW|7aqSiXL3y!47!EM!JW7i?}`KsdXDpYZO7rKLYIq>7- zTgk2;+ljHXBFs8}%n|Vqb|Kf|CUtLw-=y_Pu@Ahjk3`z4*TIGD>oXIcK(Y)fiCw}_ zUMrW_n^4h^K$<>VaVZR#lpcS8nhR)EyI5EQmg|6BAoH&Pzu|#o;S89xO`3oJCt=2mZls@^ zbdF^IFkxZg(0)pWy{a17u|9O3bX3~ou*FeCvcG9ljZ_T=0l^J_((XKEwpAhu`!lzTI zDFI-dhv4$O(e6sxemAo_zH6a(a44wtr5mWG#K%n<3VeSjW*dgG38Jkg{3IurVb4>; z8XZkQFy+!LU~6twKa?7YfopG{#70aCX^05q?&$$Bla|4n&FtfvoilMc4J-fFu^Lj6 znSC=XeSyuJ^&Sx{0;<<8r9Iyu_4P1&H+UTM{KvKiK$;N_*^@f45rf(qfe{_g+A@N{cIbib}*D6XPqQ_S}>t@rNGqjne_D?SgR1we!4Z5e@`ze&~L$ zC4RRgJf2)DL+DYfO^+>&kThnS9H_ubh&@Rpl$3G+NkpBhHmIK~p0??ejUF?F#jSIS zi$i~hAW}W^O4Y-$0Jgu4o5n!G&b+50TUkJmU8S}$DrTp&Vy#1wyrYnG^PdN+N;zT9 z@z>;+Zch1nQdNt$<1Q(0yFMm8?z2R6gL2%nuu4`tAX%Y)&H9!W7GbHWMD*%5JhNEj zXCf5^nCW{ss%ay3d|9secspC>f|-2mCFT%&QcIu1nbw97(Ck_a#ABYPiZ`Mn;_5xw zZAGtc!;bQ&d*+oEc7&AwoGdR}-=BmphpCC76iGYyKW-a_ zY#W7lUfy~2x1OlVhF|nL?7D zu#mB)WuDj5HRR#g`eu|hbe0S^rvcZ5iJm}q_G831)QQB1gJ_*$_e@p3jl|dls0`Ud zP+m#eE5XM>oi;0xx6ig=n?1Z=ucvSOmTNNw9nIJ*{rit ze!qi&M(S?fm&*bk>zV)A!D>@`n^@U%MWbErc+5(` z=@I#QAHKOCx0_p8{#BfZAi*1*d|t+h7*`*=j5&djKXH)?Nl*$L-Lt~^giFkcJp0{9 z*$J&x)y~ID#rmE~b7}8~St_)N(f#s9=2#OE`wFn+0S}xTKOioGS$!z|epH{Bzri8S z;H1PP3ejLHnn78-642Uo0gaq6g_6nOrf=@z7-JAHn}zVCxcD<1VeMSc%JS5Z8FNdN z8h0iClRom^T}VKRbMu~6o48{=5NIBPlsdFx$rU4mmxHj-vBRc6O@V2uMts@jjp5|l z1{Q2t7Bb9QbvniCoa^_ah}zlAey_{MzU_>7Bc*g^GWc!(?Bq`9ma{i82@E{3sU0lH zMNQ#ArNu5_@^Rw+3##Ew)gV)zSAUbDRYrI2Cex8NqqqlUx*S7B>}>FQy4}9z4%mX8 ze0mx-T5aCW8xZ#)ZhhU{F?o%VYP#5X3d!Qm9Y}(lOO*D60`0!gye#ot;do@Ae7?=w zzV_et@Z1|Qk`u(e)-0cbWJOYUd654hjK-ecN9~9|6OkHOyEILFJmm9YX1=Dql&1(c zC8^u-3f29hSY|I5xnGwy5%SL z0g*`rx|>aRck``%-tPx93^Tgpxnr%X*5#pDg7dWK+3$P%CcQYaGB${I z^x;hLa7EwpvNvnlu~i;B^}#}CRL9FSvTe_}IPQ%WrsLrgCZ?Knm&EOQYKYimXo-nF z3Ri+RE<#}UecW)|aeUgmc)lj-m_I`f%}D*bj_RjBAt{-X^xw9;xH5gq|E#7hm9q!L zn6q?V_)|9ec%*bl zeMTem_^Mw_kVA$h{Hk1I3CO@HXN2ciMfdqRFZfC~r>Y~Ba&hsQA9{a;`t#2p)XySw zs;TB44L(#3=U(E)&d+}ZdQ5C_(lY(h7!K^EUqk7ORFf5nyEht%!wY1GjGWxOD`{RH zNHy&7`px<+ist0DTT}(_Jdw5%ReUpKF^4MnUiGt7p5)yxKTr5MNYF&kL757w1StPR z=xsG$aX;FjORL<9no1_RUu~Bej`DDK{fN6nRv{pL*l$3cWM2+-uY3BsIU*J ze`OAhw-e*mbY<9tLrQmk#`z}UW#@~#CwpE|UJ`rDB%O3_ywC=z!^w<0lYzmg^{#{%9d5;7&`4;I zDdB=_uUm7ZuYtjgnMc%y-m7~YIH}q%|GfZK2}!??jXFgKTMB!No`LgBE8IP{bur?;hIQjq!S4`5RD2J;kB0wwb9X2% zW5JP5i=LTxEs`*0R-)>zbJ44iU)60riXVP_;x>CM`9Zqixh31Go8isN)SR(I+V$CD zy1<_#UxHU!$9*MTg%9kN%-c#Bc$0f#y0or%%)(X?UFS02F!C#U9cVHOJB%Vu6>(b+ zj9(aS{D-u>GN!<~#5v3_@ zWk$ALC)MVY!SIdVv|)LC+`+&)KrAn-nU%+N8tM;ltcIWJVUv51F$L0zKPrmu(To-(LD=WeBNk}qsK;14Y96w7U~zJW6hH%1C~RSKiqm6WagX^K)(=MvP1SKTx@5APkbCo;H@!e?6Ld4|F~v1U_) zFWQ(K)swdBy>*_)X%{ikIiWDv|4jt!1w*rDT^sIHx5)Z=7OfyS{+9q;ab44v2ojs#H=t zIM*tYK8Yw%e*mrLpk86DAfewg!p;nA(Zvk^SLi9Eq|5zBj_|z%pMw2Jt7qj={Xy~p zKjsmuh;ga9ae}NyMF={K*rv^G zStIrM0~JL2`gtz{Os0t**-gI84AD>SNN*%UN#;ykGh&VF?avatX6xl|CcB;^+YgZU zpm4&>axtLGj*Cm6NQhg#5JW^4Jdc&~9HouzRLoUTkZNu50R5A(@i%!n)WVZbO4dY` zk!%8lo<*PmruwDuY%zQE-cnMA7Iyx>qDgiI2-)16#VTv5;CRe@kVJx)=!y7BrN&Ed z@^{)2n8_~TsdQgBEJ_5#{i8rJrxx>!vh=O1#(g|>|4A-&hl0U1h`9lT3gz}nroRRD z?ohV01by`)H-n``-?qbi4XTn9?$;;UYuvfG;ZcStDC^y5y=^BA!arW*TCG=yPyP92 zd*5`$(hswT*;OxjWjpCv<-jXRQDqb5BZ{p7i3?n7l-|#}r+u2bjY^vhGymjU{{C=j zaQZ&g{o=&cD18!-J|I;e8;)(n=^rkjCiN^Vf&o}8t*8)7R{+x$m@J^Mg~%98V(wq! z@Cda=jiB&cN&S#Q7Z?{Gujk|xBbM3J)rCPTm-Oyrdm1-L)SJ9&IETOhgaR4`ej7Df zRW|8iEu#j371EIv-#72!M0|B*p%y2q$IzOrFo+nlBX)Yw)b{&p(KzQr0rl5yC8xpI z#BT#xcN?F#9>lcPMP2eCZ336wufP24NfnorBsmSRR1Weu4QOt-6nsF&z+BEP+O}n5 zPa!Przv`^W#3D_D69RUKEI;$uwww-_0uHcP zU9b3~BS(;CNS13*2U5_`((-_$)WE=?tEGKsZ=c+J$%5(pe*DKZG;SIk_mFVSS zJJIRyfBHOgP5G=Usnap&%Y!DdFkc-M#$zR^N8V@pk0x!=Nxr=8G_vSz?lx>c3dU=* z#eV&Ivtz|DO~3!VFC*&72>f7R-)4m(0ZQHKow z5RV2;2~{aMjDH-dE!Mk5-H`8+Meatr7Zgv5HhsZbd%zS$00RRz^&1F6a^b zc@sIpEYDlp<=J>TALOwYq`S!FwZIjZ6!&h>_SA`U@}&m@ihar#YLs-Px~R@)DwQ$6 zw2EdG>8NkcH`V>#zBO~=_2sQmL+`n*=xmbIxw4ntVqOW^3Nkd!P)Wb|d`AuM)57jn zF8!^ZlTa2$jQjcSq`k*k-W2b84ixGI9cxBS7!S`Srw@L<3~DC3;ZD6t{7_0XoZtJw z{Kv(V9Zpz9rnsI}q4dPYD%HV+tZdVY;OJGMTFXRzVz5zowasl_lD}aBsFakOSBE(~ zN(KA9*Jna2v_j{Pgo}D#0=AGHcT{)kRcoxSedW=qFJ$v9b_1{C^GnqIwBM=A<-~7( znQ8wEenbC))3dMs>nySO^^&hxDTElsrd}jn)HYt!LP_?`?^yGrKw5VN<&5>>ru5%Z z42^45eFdrpbq_w+{SCbVrMGKoc`Zif_Ul?sUR!9k+$-x|Wf*id+g@3!OlSY2`pQ$0n(#{9+TwKX|ZSRl%82fRUo?>=omPE$lZo?3R~G?E@ACz1L*%c7L&aCPPAik`%Qj{0s;@EbR0)dl zh5EciIkTwHEd5E_^uu?SvYSRc@84_3^jF&S`8p$hDK9W7mdjhdEpUT6-bLqDi$@5d zuyxNrGWSQbFv4d1w)2dmyjWk)UJ?7oBk6lS9IV%2o4Rkg9_wZP7Wa;O(x{%{!FUkP$i@Tu+R?ui0lXyO zoa>*^Xf(vae(I+-#D}NdMHfi1Df3M;Zlqncuji?7?60t7Y^iiN)QVM-#}luzghJRj z1^GxACbxs2T1S2O952XbvHi%XLg(Z4mg&onR~LFaGaISyC30}bNpuD-*>)X=xq0$$ zmS-BMYjqm_w5Zkm$ffsd#{Z|hnBGRC>`F+_UkMR$>UiEfkX5dgy4l5cE%%|GZf-K% zEHz%@KNTR%#pOaHX)4hB)_lY8JF2pOT%@MYB4;pt+UhaNGujYuGn@Kj@sb$|_j_3EsRJLen|?5Vu3OOu*4e)MBzUYjHoV-0p>lv`I$It89EMR_kBS^3sF zKa8mUjjqb|&VpdmQig-+?g?o_c6Zdg=Y!4?WPRh}5(jorh1GlQo0FAc)zv(qqym3o z@wQQh@&5+(7Sfgq#{^u!UqBW)U|!DcvP)jA6>7l=iELEBWCW5d)H?4pSf+GjW@dUU zv!x=NN|045=MB#zGU$LZbQNqx5@9s*N?vd~WrxIjj&X%|G~rAp(JBN`Ah2AEO?${nWH0QvYMz zwkz&2a$Hb);a*E<9zzgMkO^*gGkx!$gL*4&Z~i2cH{uL@x9)Q_^tERjbitpT+7lR0{JV0nw_@Tui|bus8M$Tj&-$i%vg>5|%RAm_ ze2Aja4O{j`Ocbe+w?ynG>}=HC`Jz|#DVb)Ia=pV{2N|Oy)=oP87R_8<=wx0$FJ%4; zdOYDnjX0H}_oky53O{`{mY5a$;tA9*fDgc}#40FAy74CkxU;o2GbnLBi+ln?P4(^D z1z`$|*Ni%K?QqUiJFMZ{YHn`Us&#rfVq9*S2*zlONn=-69-4JWl`(iWfPdr{6j+AO zx(Yp8yG=HPx6EoB?MhD#On!HF_sd05JEDZBf4pzeFX6p@A!(Qxf$o`g-+~1lH9699 z66sV~Sov_hGG6{3KV_xfa#ZboXC=~zLo;k14ajSuR`u_POm)9ngYeaLbsN)VK5dGc zs@=Eab=C3dar{c-#rm6fUGm>}jkt~skyo2peNWHM$09CD7=o6TjIIYioXf+pbDYhQ z5RUH?s{Xh|BXMFVn^fhaG}8{KK)=MvWXc?CjymS5JcmQFCshb;rcE~VNV%t$#ODp5 z&H=-QN!nD<_KwC3C=s~32l?d(ScNh~Jdy%0P(PnBay^4Y3xwFbC zZ>$q{^4+y)-6&$w7+2J@hqSb4mCoH#A+hgG-iX%lnxj@qL#pEfznzQX$RUUrz(H*Gj;8YLsbd9mqg7x}dNQH7 z@4ti~!N`uiCeLQNqOPgoaqdAX!e>^3h%WbTiyPq*({GfrLiiI~PKe{O=0A11l=Riu z+{9&^W=sVKcCVS`BKZVT-J+Ua;u1cOuGMJxQ=`t*xfy zN+JJHSX%0Vz<$lJIp_lnbjZisXgG*R;T{bSxp4nO?4X1?ATm?is) zfcW*_w;$iD#mM5)d)(NU(UsKP{L3m$D0oJTH&RVw^h>?h#>(!FwW)hxQit=Feg)Xs2~X>{c(d_E0$T z?n=wtqs8}l7op9iNCXP2YB|RnWJ2moc3O( ze?5LXCeovOtBLIy&rK+F`9vq+A={kW7!-Ta`lkBcka&>N*-GV=g*)z%B4A)36C4%^ z1|PJm-CbrWdW{0r&1WNz+aKaHf-!%*+MYH{=$gA>N0|;cE+r+@aW|Bh2PZNdq#`o1 zvaR%XZoiPgWrby_HA2v7b4-{q)?K%gKhAeDZHEIjyo09yM~A-sEqT1^{+d=AGj4wj z&ho%+i8*08zlQHtl!23u+Q@dvVYP2^#(3g;haoHMqi^57aeJIHhw<;DBl+aBiP45X zu?>gRWj!tt+@Cg3bL1Y$q)6{yT2UD=`~MnM#O>HfWDibD4VD$#qRq@p^*mM&Y}HSF zY}|KcAf~_3kde$SSouXPoVv^X z&b{&hU(cMuwOUfQ51;^E&_tZ$0XX`~8Ak<*i_wkZ9)rB$4Di9CWD@fH2zwFP0o)Am z4=JY5SVLS{wi3OUS@*t4imM+qZgf2iHYisGY9WgJW)vK&!;^W4Wj(+gh4b=^CupH&tcY8YfO|ptypk zQXKWkOOSr}CI9<~Ma2`6?)(ZGEQBn-Ip;+S+2?!8ZE=qY*iDuRAcAbPD|?s2 zmHs4oSEM@b$_|#Glc4q5wjZ`{$kqB}GqB2`wsm5QUKGpVEYM}KZ%#Mq2Y)g@XC z>hGj-{-jJSeoJg#p+9Vv$vL8~65(0?^z{~J?6(}VrGxy?*L&RodM8O+cn-ZlUrg-W#W_>^cq8wbQEn>z$He*ai}8V; zmNTA{gcFQ^37wy)0TzGnw9@dpj$pK zF}_AcB(t%7kB@J-V{u1cL^sF8%+#((i_zMZoJ_!t{aVv~GFr)&MT`9S`Rf~Bg-CL@ z)N^fXN>L$H$wzT50V(b8m2^xbrs!~R{X_1{4q!Z&Gtl9JHH#Mn%~NSj&ELyQ51A~C zff2Tjk92`ENA0@LPyphv)ii>{FEc&TRGMgxGrrZ!NXu%H+>|#;Vzkxyq2EVN5(uNy zDfhd-uPA4WP;1lp;Mk54Iv}vjwVlxi9@S zlG&KD?-hVjfHmcSu4t$fPny23FyupFetqL>&McA2hQ8&}swk0+XgE6CoUCTy8| zndm$o6gHZ4N^<%!S*cM_Qe9nLaJPHPm@|<&v6~ePl@Magw7VDfA<4M3qx}6Sx9vO% zl0RPQO*OH!d`Yt!VVLPkY8=%Vn#FQ4?Nq{>;4+vnt6`oyxc0Sksp8EhEr|pD3^A&x zOe(Kq;Q07>)o~~EPVqWh_Yo)R+S=5yoqMMXVaklL;YxN}6G+}6M?Mv)1%%7q1F-^} z4KcUPY)qIBxU-yU1(?0HZ!85LIw06Gdn&T}Xty1&s%wMwtBvNqL}+Q-xr}0e7RlUc z;8L#YexDxh(Lh6abi@*m7~VK?QTOcbGRjEtD!j(Pp5Rn+G+Ls_9`k1iRF8$g6)3I1 z&I?Dx{=QxB?WeZOqN&=>DtqrSho6Yfa@mT|dWD*z9qlFBaW8is@I#+x zZ*N~!NW^#Ao#B7}6!WhQ^GRe~482m+gGwtz%)KSesv8KO^zA#@BMM2R*+bwm`w`twKL+jxu3X~AZnT}fm+DE?{x`~Fa}QI*OBKjB zs?%Pn{t{Yb;}w!BjHXQN)sMB{v`@sC=4;t4)MG6S$-&hdp;REj91=(0xuDUpN-?(Q zI@7xC%AB!weZTo_n<=BFT19u5lMME`V7QUvlH{aij}hw-4b5rG0M7fzk1+}g=l|sz z*ZO2$E<>O#s@7-9|4HdYneLLvcXRiJp8v{)$IDpCuMxC%Jm1zGQyhtnGtlMf%?mrd zSA_3-c=%H8W{Iz9+z-cpqgN(Nqumhr9MMH$*wxlbr?DqNzk&zX2>QM47pqrEugw4d#yy)`8 zpxBRGv{jn;Ww9a5%Dc?-55-O7N;(NEZ-kM;;UW0~-I@*a5k|LBx9O$fVg863zK8+? zo~?GQSmvV>o>9l~VgocJJ%+3XAig_IC~Oy=*4WfTN=$!Lvl+tSG?-)x0OV zXv*6rwGxU42jtZhrS+(yr8Ly86_cqADcSn$p^2*8r`&^cBl`Ao?X7i>s*WW_|s^qL>oQeBcC*cmJSuXYji!%M8 z8^D{u79Oj0X8KR$5toz%Ex+B-`f$~&yqyb3FTzHFm^Enl;22Yj5zQIYv$6`kx;R0s zD^K6K@?a)O>j=i4>?m6z-L}s$aXcEg1WR=##AM#O9Gt!<}x)JBZDjbNABFc5?9& zoi^gc!}^@m&*yQF6ATg(Opb%`cSr08N7c)A)!gX9Io0?)$XnVDZD?N zlmAJ>l`#D7OpF#5+gtu~vE`-n{2nExO|O7v7P&P(QgnBKy83s)bWO#63Sfk>&}Q7- zGxKO6JK~;uID2VnS3>7DV%Q;!EcQ!{tnAkWO~vMrXSL} z+n+UQ_fAXBJa1_dcqQYZsTw=gE8Wrc2i49a2_&F)bSYM(zba@?Tbe0@gP*9IBbxS= z{8vJrQKo)*t7?;Nn3a^%f9P5@Oi^3a4rKkNX{D|A$7qjFH#N=?ov967THI}+wN5`T zi;bMT+-W~|-04m)l*uQ}EVqz#t}A*hs!c!5jL~6SiX!aCY&bhLjPYyWKqMPCbP4

    M%>pT6KjbxxwP7xLwyqKlM3I9@tS9!t6wL^+f1_Lyj#v?+0&d{TA5JNnnYO|UAR2g!_LlL z`lytW`rs}*i461quLY>`#$52k&yM!h1=?4=Yno_$+YOA|{C3#3?c3Kw3xRFuB53F8 z$S1NNEa-O#AFuZJs(W`sIyN%lyx!0G_;+?S{BJrBp4Z!cqFBecF=FZYV&|PYwx~aX zhsKo>w`-eDT^GDQmX}ZsaCAplm3Cbkcn=}@%`$;LFSNoN4B-(e}m3C zH_x0m3=nK@+bdKeNO^`MC~u?g02_q=AT|);qoCW_R1K@godZ0zfub?5pwMCr;l+_j z^k)BQG2z6-gDm22a67PnU~+!6!}W6tUF)aomBaFLQlt|hV9zpz*Xk zvvYHmu`(`YlJL?tLPrNEfOvOd6mqQ5Jz5b3vV>b$c&jPeD}nfKghO5RBR%w{ow+Xb zklw%rhY?f}@7yQjoZH!mQ^QB5T)4pJ<*bmpan5fGoJu6t5ryq!Ai`cs!kgd}?89q_ zL!W;@dLqrf!ZwSXggEn zc*h=C3XECrD|A`Z_CJ>})yZul|EzC3IB+@AQZnjG#clyf(Lvd>M;PA9*ShvPzE~CT zOOUnAFn=)>3&F{M*s?W~J;lv|Kl=hmM^hf~5{uBUV z9O0yiD;kpSdfy@b=%R(g~}5-KH5dY;X0X*uHPVP)S-BY~L^%H~+4<&YNoR zvEro0X0)DQs_q*YSQl%%Tmiq*9&lyE`VB}WAvIMK0hA&dkNhNvSoK2V&-LkgPY8_0)ExU=-8{IL22bW8@Zw_E!Zds;%Bap$dt8ax3M**#&81I~ zOpm_AOUWe+8+sa!S^WX+MmuJOuu87l^~)~Iso@J;YkyDG zM_P(KerS`)-P-zR-TXPdo%G&L3i?6C6uzqiem|D4*ErrJN9?L#AIc_3@LlYqcSzf0 zLMkWl5pbH}Rkl#o+uFkJH_148yn3Q8|B*#sG@^kVKi8;np3Fp-3bOK5y8lrB<>rZ893s^75PUcL{2_C#;s}s#8%E~iXVBw=!k@hgn zuaLf_FYs-_&=HGWRrQ&&nHHS)<^|HHj1}*2GecP%FE$Ec5r*Pt_spS_M}y9)$naUAcJvbxG+T(*%Sz6QxD$1NF1_ z#5LlN!_4r^ywkh@kut75&<-(!6|X>f1^j6YaAsm?K`zin(yvN*46j9N*z~1&-`|kj z1?N*Gx=DR;MCm!kKyFMdm;Mr0uUruVLlN^`T;ML5TS7w#VFGTE&!6xPo>(}1?7C_bbYDT8BROOqx&2|Ym`D63ATN|Y(DTw*k*1+3G`yx zi|e4_!Hf`8fs@=N%<%hq`e1z$G^^hhM-Lnfl0Kq=^0S6TykvSm5)V;S)|PpN6)LMJ z$J0PXl$3n$?7o@sfkAY&m-?Jt|9Xyfr0hz%>)A6gesp7vn663x6o`mg1o8&6_dZck z*5kgAW<+ngC`GnLP#j$A!%tm|jM~4z<}E5{n9y%9^K{ubk)h_es=SE)sRZ@Q^9Pf; zn;i_qe(n{j6Wn0<>b{`LgSF$!8hTHLyxhFgkDbc;{p%J#ju0FTq_XbBB}3?|Av8y# z=3QUAhz(T-EHe!^nD~Sa@r!8NjoStenEQ%qI-eZM>5J{&+^8*{5%!nU!>74B!jkiG z4`YFa+x@xP$bHH4{9mKzI8zl$QuE?|?XJp;{PA3C?@VwB^I4gx&%HTL7%8gW9?ix8 z$CSmK@tr3A#ovTCKh6uTer@H>cS+V17kZOfm*6P&e&{LZ`6Ppv)}qRH_#(d+&= z#o=OU(KmA3`E1zavxvZHpW(NVvd=C;XvG4X)7zCkYJeu^3^QOt@;!k@Lt@>(0H8*QH2R^Nnze+ z-YfIJvebARTR2ik$UCM(dvtUFx4HXr0=yWptvZiBi5T7{yF5{f4Jf0kTpX1>z{x-X zdah2#tE#DOMvx+@8z(6d7@0{A1EES_Y9gj2lH`wbjIb-PiCfigPpso2wy8+FJkHd^XO@ohlWg&Lk*!aDOg?m>{PYTIo#0HxkdL1 zhIldu!RJSdbG_s=f*{d*$B6m?CfmTKog6!M6cL!2DAS%If){q(>@%twtS)1nBqW?~ z*A}u;!67SQ+sP1EaAV}aks~blKbGLj;on^oLK2*AcU|(04-A|-ptuoQOvHTL`w*N# zKe!^aXK$^C3GmE44jxk%U)mVuiRv0enY@bdHJU9Qsh#puzhYdiDIWV`(IGyCjxu9L zJ?Gsi7I%ii=aW~eBO-kS1{Sxg7jIwICGYnc0|P0}@C1#d(*N~~-U1v8Ib_h=dd!!k zv;bY)2QQkvBpKAo%5Lxdis@&eYRZ?iDk##REhtIt?4(5nhTxhd6UJ<21!SsOY ztVZSoA^DAe0=I8xoA0Cazm3)>8*|V;0L70T7~Z5OrR0d69r_-~|NW;lU0>v&o`aZa zMftY5W=B6+Ue*0#949K*3{*+}CfKqetDC!rKTtI)|>?LRIpkT8V3U4HR0|Nw5^_l7tyw- zK={E)!z7Cj_mD6PIRJ6VVfXP$_5z|POX=FFPa`|)o@hqoX&CDgva^A*6C?C$=f{NH1xai*&~;Ei zW!-}n2Y?olPHflAP3L!Q>G96jP`r4Ko3_Kxw#)cQf~0H^CRL zxMmfv9o#@Xce8(5u!gqG{9JeI^4xgk#~t+aOyKW2Vaar9eb2P1($(|kk6hfX__`Zs z?i_rqPD)ac9RaUI5RNvO(lvf$b6}A~2uSB=CpDw4hpE>cyI&^m|NLAtFYn!<8qX6) zHcp9Yc^GD#9Me3^v5@;G=ajXMK%wEX>Z^FecuL9LJkwHdTzB@VzUsJfloh>$c+kl@ zcP`I0EzF!i4LEl4X1|~3(l{W+iNZ6I#DqJ!zvxa3<-C#Z#?#`Dns!xjYb7<`o$o!g z$4jzAuJ~@5aIORw>IrNhc22QA-DiK91bYbjwy}DsOW{a3An(vx{dhWDQ=pw z86n|AuxJ%y5Q?!qwr%3(`yaK-AJw%p>H3X-UpLG+&#O7nGdPueWbog-qwteg5gt0S z%4)*{2iV-SzF*g!N}%;N96uTq?RoZ*c#38*&QDWbF!Ft9g(5h{9Y-}H%Eo?6YK~nG zV3#EE*C6T$R!X&FE`#g;(e&N%T(|rGq#~6~NVY^GBV>~i6%r}QD57aq_9ij!K2GZG zad!nL0|}!CZlBrmuQI-?QiwXG!gyR#;Ur%|Q$yo+p3KKb^z`-8UFG|;Rl~>hG!#Up zyt>FAh%vWOL4>61^-UK!0_V-2D}5;T8$x7}%*pK{5H%{!@nTb}?Jb9M!l(NGRtrm0w$OGDR_K zAd*gz;*IV&Cd>kT?uh*WH%m=6SS>ALa1S_+4!N)*mZI8Avi>n_tqF(YmkW;SA`!I))I$9ZoHTxtUQ_L(f)#eG7W zhu~I29$V-&W(Ee{E0SdkLw89%ucqdD@(&>fAVSSPy;q{iJslnFU=L!Gl5#lGyr7SP zX0$9`gFdp=5ugF%F(1Sn;M{`{G^xq`*I$pn|NbIVU!{^dZAI++kMDc?eJ*{WdBeT7 z8lP6_))!=$aP8F;l^(b{>-)VSFUdyav!XzvWnfGt^{u^*2s)<*Fkb~Oc<1GslgPX! z3Cur#?xDNwAEtelBP3;<;bDUKo&&eSZ@tPmmA@GCV{p)h`w3@!I9;epGjibEU1w1XSq|E8+)vNc>rT3BcL;Wak%9WBy*Xnq# z#t@#)T?TSqB~wZL;f<|Jyq%6ZRF5~SeU!DhwPm3u;vsipx{s~h=~*(>VK_so-0 z88Um8MgiTufz%% zxotQObMJm5UG@4xnORYDpbb}|lip^7#|yc?4nIiMD`4m1s(}y~>#8K5|Ewh~!BIgy zh2A{}I1TAfgeOP&Y){r9sL)9I4P;mNC_iGYjVE?xq78uem$|!th6f`Sgr`LEdidaH zY$&vH6eLzis$tNEl(!)%nEX{F-#gB*QP&~tANKuz07f09E;&WYfp7gV1cHTy_lQKN zVmKi>Zdlz2=m;W`8V4ONVL~%a4f;=c$>Jv@=OHqN?-xL!2fH;(Vf(4^;h3WwBz@(T zf?}-mk}QQ+pJ6jyz1zCKAS-%6BM>}cQR2yKm_!Jhf#_#26GktdK_w|H;cS(ny-!xQ z4;Cr}UQtk#&3sU#@FNl8fMLi;iyR2@8%&EDR$$G+k}ZoXF?Y+>_@|D1KCWvsKSJn8 zF)zX_QvbdUK$04C3&hrk%b+JXatnMUy`-ks3RdO2q!Y!vK{=W7)_C8U3PrFI;(aqGNt75)Mwh~WN zc5eRvbbf9S=0%J{Rv0CigBY+6!tvFIw;E%;hJ!-^&1s~^P+`uAJrNdiomX36d&l6% z9a$wY?HfgCmS0!*-kywP*>dm0Lb#MjWaqnPR#g@5GioVLP2ri1$5IpY-Ib=7AByz` z`3Mgt2bo0F_OV z=Bq$`xhoxLDHkU%6xML>GbzXx!8O$P)3sacAN(r@2C7>r*r5p%{XBw8o+Ri2Tf|XG zPG2}HTa;$DP>^h6*l?;54AV0_9D=`<+|E$t!qa&pG(w;IbWM-wBiRD=X8lOIP=t|QI%bF0KFn2$kqVL@KXy_fikjYsgg-cS& zd$AFa0_r`~L?Qu*8q*TUa@16jpdr|GVaol#bRSICTefc9@2)%J+B8V3f?kWDCJ~Ah zrCuGK`uMw_Cj<>*wkZT_rk66`6iF9O8nmgWyr(bxtFdI*UHV}D{TNv01@?dIKV8$r1Fwl4CcSO?- z(FNV|*@h({_hg>i@0NlKPTf3|{9v+hX7;{EzSeGI=M8TpR=MX-49p%1 zL~p$Xm^=iauD*P?SNhz0k`71=$MEq2SdWbcsi&5(TSB6KyF-~j(iDj<6kj3ELt!k? zRPe|7uC)7V{a&g0F`Y6}nFICRxLDTr$(4l_k{Z&M8QmA?;6+8T*Gl%R6s4;DPcDV4 zGUgCxP5EdB; zpe00}hl>~?BfF-3pWp!xD7<51M4P-RlIH|r{C#KSe5vGIU1PI4VUd3yE8r%$i)J+5 z=WajwDv25gg+F9FH#JR?SL(gk)ywY6dlC5$U;{`1?5-aXctUM#1mWPRdHWNO=u^n0 ztWQwaITVwa5{M;0aUrupj97l)ARP3;PpJXRFpOUbD_!|{TuIx7IqHIkx==I}NKH?M zS};|8hWGLDKsp{8aktFQ1EzNh;onRrp;|zpwvZCGT*L>~(KoFvT_Uhl>eVf-9sRm~dHb7=2r@#0T zCd)GfbBg@$)prjDs0zQwo#f1E#J1p@KmRb_-|2v?gQ@J{rtn93mG4?8p7S?w@YH$; zZ+yb}EPTpQD2XXPZZ0D)Xlg?6{%4o)e*N|@=PxN~?~aOHe}4Sa_~4*Wg59*maDS^& z+`R9q#s2E!n?(E+j&u1^7x8M1U5pC()imbPtLx)CJ-?tdaDdSwDXEo7cK)^rHHD0J z`HKN5QNAc1?MIIM{p!a*n~Stb<&RcCtor2COAMe3YitwO?pe^g_^MjC53-gm(XaV^ zxJidq+2`>KL<=G+Mxbo0;Z(vFRY={iVbmiKBK||GO~e6tM9YFL2;W_S-5y5+9;`YnXNjIR zFvHA$Yw@L{nD32{ID;Ga1j5|cM?a_b$DIpRH#|#D1Me7#m-)i;GlS^T#I|9uhYbU) z$nSG-L9Ykal}ScXWI&Oh6H)L`O+^%8%B%*V4>!avLck+P5Ud{fbXx2^!dvR`t#vM7 zAsn2&1f~=Tgd}beE^+oY;;hKa%hMI!v7MW{4(FuP_*_N3-O5UODj!h_BDDmQpcQZz zjKp=_Yb)KP;u9nL0SFdIjY(IR#h=bnX7W$*cfn<5XlhE0`IT|!6R@$s%JmzIc9R`I zU%!qZ!RiN&cX4O2Q!;NoCuNyE{MeDrtoXE+<#QIjZymxd2eJnmUvkdNo0J`}tvMFu z-@4y)CVuL1#!SlfS040O(vVb#tL0c%*6sZ+J8>=qk%WIt>Q9eh^ddPVpqh|!%{+07 zzUP{PUBBoXgT7&ko$POQkKZ?!m9c1B>gi3fNim!@@u;hAbo8lp=S+GzZ+3s-=qVY4 zI8(P0#glXb91$%?52X&IpEve8MMtG|twG%{#G$8%d&icCk!oDNoirI{F8My~W*4WI z(x;{+XQaF&9{*GB4WW`7&mDSLm2=B0SL=YyqF|G)*+zkHw*?E-+m@j|#zWWTyXKAA zhF?tVlEydHZJ|7DFc3o9+G(*=&9mx<5$9Z*yI?eC3Hl?{3Ql+H>zy!X|vzmLPz=Rl@j8RDgqvC)>;SlWr z5+fK>BfB=$jzB7J$)6kD^RDU6BWFuhO zi-q_n6#dj6pn$7k+Tr%!PK#eeywF$o zu%Mt`;_H(Gm{iK~Ivuziu*!}V;HZg7FbtA}N&?+={q;{>pICZZ-H_b~rbK{KLf3C# zI0w+>K%ln2FL8M*&3-wiKZwsH00aO1k`i{3C^>Y|DojR&nz9#FxDRX>H zSzeu@Kh0|CcT)K>w#>$DvzRxYwYYeG;m}pp4MbSAmy#?!g(nEO{C_eu!M4$#|6dDm z&v2)-G&3$j5`cvs0A#TqyrL(mDZ(u|C%SI0zjcG2e67H~v4jvxYhYy(|y-ZPA0TN!9;>ECh;WjiHM9c*ZxZtgM*6n ztXHZoSLaCO#aCJy8S$4zBJp(Z7X}rQ90ul`)Sbe#-FnG^XfK+ZSuGymForydp~MWy zz^S;fYHDl4=E_hbKqgt7rUbf>zkJ~WNpL)BVIf|J2s&DL0|4;B|3&;k%ym!<9yL7` zfs5TsSZI*BwnUJmgaVp%L`Ma{c%~~;9|Fh2{JN7ifsyi2s+^AJ;lQQ z)j8(+Xo3CvIY3{e6jyd3`+{_P<57enp~?Z)2=ur*c>g{X(^>$fwKdENFthnVMU6iJ zBLjK!g1zDJJJSQCXNqWMpti}l*?f+9$`Lyt1cAYU{^4vc-~5L}gk`e} z8;WA|hq;nYsn`p(IGnuF+x07jr@`%kosw?eW3D911?W_Jiv-q=eArPPb!4E1Z~M3j z9fxsJh0CIftn5xEdS^3TYKr9>JacEfKQ6imQN8mzl}k4f;`un2OU<|_S4n@5Fm+X- z-nk6fg*~)w^D2*=2GzCs%h?83cnfq@hOkdyIwcD?miy0<5i7%FT)QQ9k~sgImeK(v z;Rt2+_yPd)>Gd%)2q6@w-XJ^xd1LBsuB~OG(UBh$l&=0?1@IOMh#;7!PhY!wm25M_ zPAKK%h8!_yFwvO7J8l2TnrT!I!G>5}st84d=mI=n0O>wUAgT;OV?sAJiJ)FXNDI_ie{&}bj@H1{htg;f{@@DFj2IL`zrxDXcp~vj6 zO=Gw*$Z|$B^N1{?p+A8E9|;oJ?TFX}5H5eOr-=zGX(4j55@?z)rvLH%J44Ntfj4Vi zoiqQ{d|J21tYtVeZVf1bwe^4Ur~)tyHrM4z4}Gx4Lw*c7^B-Kx0|660ZWeonV2)$YWcy+Y=1`@`8ban#r!eAHKWB45l&%RnXD|9_Md|mpTw=NDr&gP_;I_Y?pZ@B}kv^vucXywCcUd%{y?~95@zjZb zsqJSz7OgvQKRdxm=tL7up3%mI3FrN*OM#JU&Wg_NRbi3RPjVa0X!DeOuIzF&(P@jm z^;FpNy8cFoe8&e&1M?08iN{bzfN7{-VgueKx1~1IDX*)4bFTD5s_8a-&y^gFV0`xr zb@lnmBmo@3>GUQ03`ywUckyfJ`omXGY)~5z!tU?NB<$(Xo0!k23`|~@`atq8U2V@MHZp*@)4^ESmE!K5V8(% zQ}EmuD97;tVW1;vV<18WP)7uTGbTFnzjL;0IR8=h}*IO+!yu?(Azl%BY zx569l1J@P73NUWp76MMehu>iq$6ycs4vYfmX07N^1R_U512@vHgN_AaL_)9P1jc`- zhHfsTci;eYT>5vpmvtUA{C`Sr_*HK0Idua(5e0+p38(@!%|A78YXrmL2?;3(UwGo~ zygX;WgV}qKI?qfduw95#V8&vE%4-Uj za+LevdLzUSAWG!g?EyP`@9QVD9g()@vZ=c5{Hn(8?)#x=lZpB*xcxLV8SHgo=Qbd; z9pp8>LgMMe*%|D#f_-crU^!uu5Tg{!aHoGKM03PWpy)_(_e8)v{@a|6Sq%P2=@rFQ z-9NxcPk{%J{1Ifp18WPs%PAh=6P5pyJ3@}bb+a*DddJPFvfcPiG>nYmre&?LxC3F- zit8W^%Fx{5Tp^p+u*UpjI0jC z4CGf~2gH(Op~T^zv;Wf(K~`nsQJJDGnLx51{yoAv);nnP{h?^i;~cH_=k_-b7ucBP zT$?$$Pdrihl^FfQk<4Xti;K9(ho*R`pHja~aQdI%>4Ja$ZaG<55~4{0Ki6wjp+t&U zgR%6JNX$7_kxYzVR7ym=$jkjAy)HqtsM&(|lO{aCahQXp2E=bY4g9 zdg(n>F=e*~r-1#3p7DEksICpw@)W zLk7g%l+STC+^v&%57;T`udKsVN&KQ-^G|6Wsn=QVx1ms-=gTBQIZ{M^u9?$z37-Hg zK~I4Js#wWpg1xU;`Z?j~-7a3X z)K;+0a^+Xno3F25y&}mlkxh6o^+PT}Z;i(Z508d=*2PM=%Nu2-rKCtDWN2@Hc`ZSoN;%)mE4e)`mFT!9c}?DYCh?L^~6LGtPtO}(XVT*KUp z8<)gwBcfnrZ0y?ful03_W6;vI|5>PzMY^QxBi?T>IcoG^-+HsuM`bB` zVew5(U3FzUQmKN=TjdAu>X?6O&8QZQzP#{Cw#`+`($?_jx%k909CFLaoht77aY>JH z@&LPlZ;#=L(+T{p4Zch?f)?9J-v4?SID$ABmL++7+*7fdBm>+U+7Jtva?xyUKALno5 zezTSDWLI{P*+$np+txf|rVh5fyw$6d%1k-RLU0xXpJ`^VnY-OzYFg8%5GBtPRteP^ z6dw?2PG(DZ>vldS@;0ox=nf~r_QobAo2n&y1DS*fxCVsJ4SkF$)B9tTNOQ3pB_57cY*F6v%Mz@e%(m z$u;k~r(fx9Af3X3{J^l;G!0K~_>G2@rjUwhufg*D6SwMfGFl%`i2jWJ-e}5Wldo6%ZV`CyOuVoJOP}?@D zemLk}W|C?ZUG;9VdIMSuA=!;Jj0zGn5?uHmlPGhNA)|D09AwP)H;zOcZR_*ej zWP@JGC7Dm0o9iFlG7_HK9epZ0FPBB<=5F^b`9s3dn+!MKneK4&%wN3!+~(yEr}57H zf4bf*F$*UMl2wBwV}dM%HzkKXjf_nV4Nl4Lkd@DakG~Rm;^+_OS86MLnFLudtWA>8 zTtM^_?$({6LgH<)c>_ibj*gBlD!?gA%y0nI^}|*%4TlgG6I(a)FZhXw)TqQ|n2rdL zh{u^AUWPuUlzzj?B|p9dVbc?vnXR>RozTW+g=Hb8)MFpF#|Yo@JZ0)fxPKtotOwa^ zXks#Glhrm_7xfD>DM`7&7UhU~0>(q$2n{4J)`bg?jnY$9ycNi}iDxxEFHWZwJ2@#4 zBkKp|R8*^`d?c}qh{)LarxiDl*TQZ~N(3uXsCl2>LFy)$Ta-h(|8#AopjR@+WQu;7 z8W0L-K?=n!-^*tp=WIVl2gx6-Ikq;fVDz~Uvm_{7{tqjVoB#~i z3~Cf_Y(Es)xT%Q;8|Qg#?*J}g7+6WO)5tXbGtM0bF#5=l+CMvnaST~)fW5;{bc&h@ z>{biXai?#(wvd_>WlpDzru$6SC67-#7x5Vk z4NBQhNqcCIL2>aG83!m@7o0Vj5~Co#uA^8b0RhK;jGq1qhbau$huGuiql9lBJs>o> z$R#1;AbO}ou=E^41%hgOO70i7x;5O_l3RYL{A$zv+4A#cMTg(EGp-eU&y?{M&vdrn zpBua&R^*itcivb=>$$4C`^lY2O9@WtajrbZIvZrfPx|&$eBvxVA@;7RsTzlyB#H@> zR(#FemZ$0gAl-cJIMGJGXd!naGE&EjGFM;>v^KT`;7Lw6EFR74 zzdY6krN6QfgC(H!zT;f(1*XT3!&`8aS&qn?p{bKZ;V4B_$@@_)Utd*m^AcWr zhTa=-kF_;5c@d%u;jE6a@t2@$NY#i%LMoDR@ER4WY~4tuqU6I>;WjFSFJgK#-NlP^Z^$N5j&-NUe#h)MK-k)lsmRX*D1(J4T&kz zZ^#@+0a*bt3~qt|N1m&H!3|Fv(d*>I>=o=b;=Y3o?+oB8$K|C8lvD_?R=!*vP3t*s z=m+jsU7BdGdX_9!Rv^wmupWWo1{+x!HDbTE;FXF&1Ok>?{9@I*cT);oWjH7JOM0{;a0NX*JqUta3l7+j(gy|b6YEO+rpe(vY75yhNO=5$8S1zOLy zy?ye_@m7;b=iY)gm5Ed1XQk%*mrvF%4XVtS*m5+r^%n1*_iZe(05MFwwrY&ikPG^@8uhMAGU8!;~LyAXLc!tZJR8#s($m+_QBzqxWo-t{`S$rINWB+aodFZ zk=d4(D=*1>HENdr$35@NFZ0-8D0YeGHdteiwERsSBf1533cLGP*)^(EdT(#;K~Ft z4nPp*flX8_ZNi*Pus5T3h!f^cK$ev#DLh8tiYG}Ri9ufVzyXVgKF~Q2&?yNVz!wKN zyJHDzV6=)q+GPq{6ZpLqcm*Pc07?Y9JOl(=uj*>QD)iVAzh=DUFMltd>gYtv9~9e= z!B}zB^|#FIeuiV{POls09)z>=5Ol8Up}rm~3C+eb@So`$lMhg02psnM{LSPEyZDtT zBym?5N&W+Lf&YgSU|=U+0PSJJsh)KBNi>mE2YQ77ESO>x-N%lbn)XAnP3m7-DT5I< zJ3SJD@ELqKp2N-6!*Z7qE~5I`=om@0=`NKwM*3=1Z*>UZWU(!4%M7xBBLGT~C^e|F ztYz<#wicWlq)nXpJN%i9+>4mLiB^fY#qdxOQVwIV>grUqr0cjjDe^!s0x^Gqs0<|g zZ{Ajlas<1s>s}G3xL=g9jzqIx=_(5g;qhUI&*IKU*!IQXLW%;>lTCTzB2QCsVA9~< zdp`YFN7cib{gpPFo{g<<_KiP(D=((OcEOj`FiL4$*x<-t zoeh4f0_6sO6Piv1QGa95m)aJkGqlE4kv~1+_)S}Or0K?nD+%f4HktD7w9MR3{!>Z> zZ_#wgE@>>P-Y}cp{<}5`>Uvi^X(7?@A3e0OXRPU}I&!9b z2LBDbY3hzWz5{kd#UW2Kp_X^vk4K_*XU6SrF|O)IpDjGwldyO9x}+_2208m~g2a*= zUam_y_mgOx;oEERo4B)kwj>Sl>D3jDv)yOR&^Bso?HQ|z=y zXw2Im4i#gcOSo}4LsS-iz!5_@cs8OO!#+#g3i6fIb=`71TTBbfq zC|rd+&HCQB2f^(D&m8#7q;Q;_J37zuLdH%mbpvI-)|=2Or$`@82~uJU-7N zrDrO+#Y=mjDmH2eX~Cg4Z?3L&c+Nb1n6Kopd~Cy)M!Izw>oNiYHm?hK&3mV$?#bE1 z8It#Eihm}5xT^3*XhKPO;fU0VeoI!X?knkgviGjXvB$GNE74&Q3g_j`{ZrIbeoSl3 zaCRwENjQgYnCK}jtz86@D z)r^f3n!Hm}Q%lxXmk8yG*BQbq&d+~{txlghq*}c-4&Xwou>j~fac#w(?OGch_vPmr zi#FDr(2Ci0GH+d_s32Xv+y<2}XWjfl4aSL4aicRQ48(6S7V*`OZ+VY19p8pbyXeBb zxsKrnNvF3YEXCi) zZjpC6--6&rpymlaAQ&@CN^Y~wC;{_xex6zc3K|S7;b`kZOWE zl%x?t@%)hg$VeU*a_m6&s5hJD_mnSxkldkEJ+oVJ)8Qk+63ib)IT7+9s(gGmU#Z z3l8eCaeUVd=Q-5=Zr>w@b8OpO>y)nV2^GWf8vxD?d_Ny--+I|b^0)ASkY-;jI?zKI zUojF*L>5<0u=A#$ydknmDq=eXL*}yRzaBi|rt&*R?ZS_PQ;O^U__H2LI?-~)hrY-= zW-iup^FP(sISqDQejld!0)*3~)AmT|ecwq(6Qmv2*#IbiXM7m9_H+?dy6uJMocKI0 zJinu2FwODo=4LMi&g;IRHq^0RH8&6KjQ^DKDP!f3BWuHnWzO(SSIK9hkwC0WLIx6D(o?|Gw`R-xcZhbmFkl_*W0(`BzhRet|}Er1*2 zch%KckH}{io4&?#Kpzh~%OuJ{?jueI2Me5rL>5k>b}>l#F6Q_Kpwk&o)uT?$zcGk5 zd?_*n+&vb0N8ov8{Y1!&G%{C_e;>Fjso@pE9_8go8@$J5AAOKT1Ugm&!Ccq(yWW`SaLkJ;h0OQ#&-oo3#xu=q9s%{M} z9>n?1=Ytg`XF3T{bs$15JVu4Ee2DtSEbx{N+P%N+j|a9FbA8-j7WB?nVjd$6CU|p7 z&Bya3_NaEs`>3`Ckc0*&iCUcSPhl@G0qvF#-f zeY?^%2DZFYt)AZFT74T&pTs098Bp=qEsf~(^R7*Gf$n__P_u_N2ZPlC(F*aMN^S13PO=2}_a4GAnmr_Vg zX0YO*>$!6vk!Ih3$}RUIJsNBAGO0?@=YqKv8`7PxXTiMW@>msptNn!c|Qwn zt$ZNO(a#iiB?3o_P6pqmS*$VK4=ZM=xjw67-`fu_nm%l;2+?%e!@5|v`-qaNb$gsC zlh$0!Klk*IS`)$0(4jlq%CrLLb33LygDZAQ4L#+}KD@3!>aP*4!WvgZ#k;2XVxero zX945Tp)4*gPTuWa-dM4=G7+4*pPAS;PylN_eWuAqpFX=qWsPfX3aNR-nM&#JKM$Od z9^&(l0daZhAz2E#=mEzg21I@ebu_IWjF?*tMH4&9+@+xx!I6I`%GfXd1tww`?>$o5 z*)|jK5k$hCt8!q&0C)1?LeR@*f{K#Fl@kwfUp2jI4IE*IY-mLk;Bxg_m>E6`+be8H zIoc;OC`$4J*`TMShp3N<>* zy|<&;l%Q{zT#s0yDSK;3^=O+rlA2-oKWF~dpfZ{B9ELU&r)BC*kt#G)+>*Nx2QRb@ zWU(L?R)WrEW(IzsntH#PhNcoLe++^-;TNcys#ud_ao%sS@#&a9HSh272TRT8o>_OF zjYgU5Mv9R?BWieXNbx50G^Ihd%mo#2LO@m_AT1sLz!M5|@?zr>RCftJZfs2B5-bjn zG*%j!1XV@F?Kmo7YRc}NNls37`~Bo4QMy2`b0I}wzhQr0pI^W_jNE*Cly{uJ__fkz zZ)L9|_j@83zdfhCZyzhkFT%$;`IGh2*4WPi+4hCn`%?3#Xjv|r_m6TcDS4_!ORQ~a zsm`_+ipWjq6RrvzocrT?-Rn}fku&9w5XFMx!a~VKx@U}T0K~xy0hZ9x(+f9LoksXH zTohR2wgkRao1u-DkrYj&#jT;88SA0_Y=4{k{;-}4&%W()5H5;5$jx6eeb#n3JTmqt z)t^=C;c)L;vqeKuYJb!>FL6~kXl``9rBj&t=MU%1Z>Il_FIdh5vRLE&Zw-;h!|H%x%-+QBSm4PP3K5ynw{?!= z!*CxFLl8uI#Pg5oV^AGia}A+FptdI|Z>W2nZ+7qrL}(jX{|TFX$mTuPFam_aZKeAS z()?f&mJhp>$ew2>#8`xx-Y|1;gyFG4QLmG^V814Be3K+*M4}Xs`0?WH6l$F0q*S;6 z{)ONx)qL?NxU+y!kzE>?tcRZ^kW>`27@myll=v)-+$_T7L8fRuehua;yayYhRsi!> zY(c%0@8;&FmfOaUn}mcZL9%16)Rt{!Vb0Z6F|+V7Z7mWVwv`zCXkwbCcKOx+8>9O5 ztL}}Cb14@{Z_Jyd33CNDT*CTc+NPnWM;zmN&{ZS=6gU?;k4e-~e0UK>%ETbJYcdr8 ztbIMXtJ1`j<&&J0oRLQ)i-g@mSSa1=)&tp-Jx(!kc5X_VGSLnpUfWi7epX)icOq5f z4vz@u?%6blyOZpXN*81&?@8rXAkX)StZzF_^hYw>iM|EWr z9%Yim83R=rhAJR{M3~(1>e_A#-<4}vH;9Xk6jpKj%v(b%1rvTodO9U89Rf{5QVh)e z%Z1q>X1#HrvbU>hq*CDzQFkTS7-mo<`&DP@@?kGpg9C-LJIAU0|tA6_d91dEZZJh0t1eC_Y zfFK0FwhLO2PvSi!*9c6U@V^jcF#0Yt&$ETS|24@rf~<5CDgbH;RtS_1{SluRsQqwJ@#8kZ z=}8K?jvkHuSdxmr7&=STl+%#M4Ll*<^&7Z|&maO2N%Y{HYe52yye+_KBEz{AqRn88 zbJnGmC#^pHgxrvaZm&7ko2zU7nx6C^o?-#dJPIuKbx4 z)5WW-JFYyPkV%s>Z+v#Dn7Uz~>|#XXSjQAYChMs$j!5l1_bmB=ykHUi4`Ip2@w?dh z?U>v{xgN$`*Y%J(8ss0EqxUB1j~A2s$zLiK;@0ia6L)>(G$&Y>@)Gju3OJHgEyVlg zsJkT;zc$Ekne+_gVUErXt$TVo>gG)i#BQ`2sMdPV{d8@=@uR`d>`5IAdQNCvfR^Cn zbHUVKm`8}h0I_R9$W<%VOz7N7YJRx=kdDY+vD{W5crk&z07&v6g(A2b+E7(rMf$?Y zQH?1V;R9LP4#67gqcl@~FA#4IB_#wH#-gl=5fBX72OY#|M52)5;`nQX@Z{no*EoOv z(IIcfDxDmB%h!H?fyp1{ecTV^mBRcN3=GETQ4NwiaNkZ4)*N{hXapu6le)S( zU=PGT2qqsUmrYYMlau!sPC|x4qJTI#!%4-*|MaNjZXt=&2++b^OES2zT~vdPr09X> z8Mwa)Vo=qU6R!X1@CR2+p$1e3DG*Ol-iN`1e0=mulN7|Y4La7dZr0P0e&?n#%DXA& zP*{Vhk{R(78vcWTX0olFfgg$U+0`(&o+&h}_Seo#U!eK6PO&WGNDy6|fw7=fM1G+j zcd0(hw&U!5iR&0$2H)hpdy^MyNz2n$s9$#IZn9WOS8pM4Ar}5RPAX6OGVf-SO-2|v31TZ^Riq#b{cWGS9EmwX1QRx0v{K0l~8U3M7 zqo0NFCcsRF2y8OlI0c03)h! z+8{~iEyi5PnpAt0Vl~XEQ+*IHbA`weklEeye(O?iNa&sY%q{CWik$>5xt6_X=$gW+ z4jJF%=R*>oWXu6{Bb&M!g8~T&!G-;9(7Ej2_ltik6Skg$V-r!!2{s2^(Zq%e>Qh_W zhP%xhVGR_}xk;oP_BLX^s@uOm z-zuM9Bsy!7E47tk_WqenF(8ISP`J(32OO%n%!>yPZuH^iCbD&K2YmAK9UJID$Du$Z zqqH>nMrrq}YnurR1b7=K$q3)(lfx(jwSrideAYOI9y0xT`h$#Y^JPoo%5GCgbFZxQ zbM#qRUPj`T4r1B7Ha(RIH+|>!y}Fg_pIoX$`06vqmm4)cJsVHhqhYE^E9*(WJwU8h z@q~&&ot_(CkH;=CsqrH=>jx4I&&;2rp9y<^?C4Q-0h25%MAkz$U5ir$b`YR-=!(7n z$=+Vl?aWn5wbt^d&U8%%G~PqMpFX|eG+nkU&M(_Kuj;V#bdjfjQW}j)o_g9?;5~yE zmd-pa+uaW+E7BcTVePGX&~tWfQ>-;km1{D*)a+8pk)Oq)w5c!&UoaP*W;`FkUiq%< zsmS%tDThZB1Du{G8lz9ISMs(}jd06Jc>i99>)@WR~apQ1zGCC8ML04!?W}+AIa63*fz9*CCTQfh+{sOC4&zul?Ku zX?!1Y7SvW-4f?T@=Vt>I{3w2VSO)HbZFt~tvEbVW0~L%vq}6No*n`9BKoP(~L32Gq zX@@b2z+6E7^f_Dp7l+XY2PQFPQ6gIjVTe0(3NQM6Qp&escBb*ak zTe_-W{1*Qe(!PITE#n=}s)BD%^*^~!%hU2x%k4W>hOV`}_Mb>_T1f;FzPq3-0G~o+ zR20EuNpcisPW>ohsM?(QoBQ3 zG5iZ1FiN<6AmzgEVd1l23k?MyJ{KUcaE8g){f0YI5&^8+_>1gXxED*Igurbq-Z%4hbKw>J(lLw%d4PPC1lvm#S^PYKEAZ`J3f0NMA0L`*`%uop0K>A#$(~XDtNb)Qz zxFL%q0W>gOAJOW=)Fv-~uvLx0Ho>j*+5V628#nsh*vfRK*~2d0?%*z&-7-ayH+G%L zqh@cpee$f#(K`p1@)#rP6P4&o*jAy|`f^Cq=BlIJ`vj?&$t`KNi_lF%!U31ZUxg)| z&-Jijs;3*4xE(wx#)gIJ7pvY-a#jRiYH>#CHMyO!la-#z;kT92G_|O!WS6mb0`eE8`3NdGSx#R7sp`^@ZpB z$S|?BwS~*5H0!C*2HN0tpvAQS?30iHknIk2&UVVksn|OvSCM|h@p|(?pR=(a#~kJD zks#Y+_0C3$Fv)<^@x9;zgPuWb&-FG814xSOg`l}qupF-nyoH(629Tn?bm+dGy#0(J z-T!hP3!#L?GCq|*Wb1T>-)HVuuKd!owDi8ABT%-zejnCgqcQn5usC(Y=8b{=oHkfL z!{MT{#^i~a7O~Nr67+-+jY;qmioX;IdA~>QE&s!07uWTh1f9WfFv0~GC;o;sb8TEu zSqu7C2#$cHfS^X9&5+8v{i>u?+R)QO@8gH2WgwfI=3CY@&ApU-=&ep`Z~Svu#p6r| ze16EysDVS!{JX$^DgYo36y;NHm+kG~pB$ofiGU2GsT9k4djD zR(mUPyF*5-bxY_|2VF>DW3pfCuG+>F=r9Q3_gmw_FW?8X%920FoK{cUbnC9}z4x=g zXd+`oZgu6XQ{QmnN>rj#cE-p%v&rC1-|RHcTGfksv}fCIURy2tdsxt5dMvIRHw*!F zAh+9wqPq>a!{-MJe1a{z7FLJ0JM@GJr^d+08xX59Il8f_Ibzs>Jo|G%0?<6GhU`Pw zZ{s2(kL_Y{!?%YjMm>S1|Apuf=P(pWT)=Ix@Ds>|Sh#j5UMJ%uDO7==0(v{LGbl|~ zQWc+$%e|X54=o(58ufS{1ji)s#yG4kv{3lfBa93XWFgKP-O}nEF;`^(8>%799rADh z2C*;BZH3rwvh}+eri7cG`a9zZ!hwhOP}DyP6xj^8kdSeZbq_f2KVk_DmiI*d1xg0@mzZb> zK0h|pEbl$Z>xd#pD{G{FgBE}Ah|Sx}>nQ|T7g|X009i%w0V6WR3Ih(w^8gVCdFwSt zqS(g!kMVmF^4zniLyFfg6ijL&vNm)cWmZ&l3+Y8?5ArYW{0y*2Z=A|}l=_FPLAM*X zP{yHU>oX!#kg*8kfWLb9XN~lx>Fv2&!Zjw{gAMhp z3qhbCSwF?Tje|-ve8bXqUscb06cf63g(vPCi;C>Ab17#=oAH~FtUSK`mfs3vhCyy- zTv)Feut8#dAus34cMrwyD2k*9teg)2_L|v;B2rpAG)Q*(-t2moO}<9IhxI%9<{l?h z*0pTl5q&Hez_w`BZfZ)9lFr_*;5n3=D|z9Wb$L>|{NTYS$BEG&0X!MKHB$Ji z_cl;}hY<|q;_~vaYRKW8)mZABP-%D|+o%`uFtvEk%|BmfR5<@qG2+b*&{h)V^BD~F z7!Dx}NypABI#ToOmYeqnbbz9G11=;s(dR~Ic{sT=k=JYCnIz4Ns z;c|1kU7mJn;0Ux?I33QvN=7UWVKAhm;vQV&`(z4G7ALeCT$xDaQWEb}KxQ+Zw9NgB z4duer`S7&>0?+Q6Mr1==Kke4d)#-|9E(NDuF4}J(ODZWNg{EAF{s~KSOy7CG+z=^; zl&h{K4Rd@(s~vW3J?Hloybl{^6nU8;d%`xR{)nC~tGj{jltlR+i?@S6*gjo%c5`@c zhOB<#QX{EM_`v!X`51s{!`qh$QNfyd8cI#DW z{d&X|?1j$uZ*FR}|SLW#pN4|MCYA3|nx%)KDoa1*bd}P(}T<~%{6^+Kr zgW=SPdK*BS(F^0I#S&y5t`#pyAYoKz;q&wh4}2v$)#IfcJwXo3tGkP9V>O+ z2fAEhKLsU)P?~zYwMdFPwcvUy5n&6e*SGF;QH@AC`0vihX_ikq0aUS|Y<9%u?H#RBiq8zs#!_-imnGk{t${M;+yX3J|vn@+M-x((zH-*m&Vt#q*`+;ql7m z6e@@aK#UuoR7T6*C94&blwsT~PcXG%)Xbn>@_RP^9`G&$^4Ktidb~kT4iw|}k2VGA z6DwyqwE-jstK#}ZUB?dPu`B5a#ssoVB%w$jK=bb*|2~L(fWY&k;P;&? zGOlpBha<9;lkYU*kO^8%A}A1#NebC1^ppSF4Z!jdg9{|*Ws_B#Df|GM0?WGpL_x1xmHHs~G2Z{{=m!^Cp_ya*H>;3cB}*V}&PvWEh<_ur#R zd{gFdB9QJ$Fw_`6pob)J!7&XsL^bR`Dtesy-h62AR^rYW5&vhAN*z%r`1we-5$Yjcd~y9WuUVnnOsQxf#?w37_}c$< z4#ip&$sEP6PT|P;y&b&~0Gf@eZz%%rQ9}R)5^@cXAKw^KeZFRKd8Xyj@KFdWg_y9f zka}al{HXh>b6*MdWB9S(Wr)HtwR~u3==0-R3PQy!&ldQSFh1K?Fv@EIP^KUuUm&3l z-~;rgl!oRmIeAlM^6QWGGJW{M!Io3_1q7_aURPE7V}u*rz+TCxTY_fS%OxKs7#-wx z+PNR7D)HRF3#^-1f$0h?3-q%TB>InwD{GA5Y{B87Essod+rDI`NIcbYv`XZQ)3{L^ z->E~R98qzQL!dh>u4Z=%{|3LF+TphY9Pglg-eXwDdG17~+mN8tE`yD34@Mm2-xxq_ zH68J5)&qf|AGw+d%8a-;q`yNd3T3oT>w%{?Y^8<)x_USk$xp9~vG@9;aKz?*PcW-b zv!=F?YdFW|cwI?>Y?`?4`8PFd;~xzB$M3veh%u5s;eUxgGtu54EHy2XGOW`MrhBPm zqT0d9&3DsxcZ~UWfY{mLVdml?$8&2*QaM1oZPl-kdWC@E$@Yp>R)V6y)>!Q(tHtb| z16_wBB-t!ZCOiNSBz~P_o@q)a1UF%|oYK?{xMdnk}>%m{OEB z+_<(5Kp?rXAATZzT6oS$TYC_|YAVOZlW=7g$GkCnasvt?yfn}|Lp9O^?IUnr9IpNk zF5>DW+rEp-v!@P(dIKDQtx3EzG|XwuvwMk~n3I8&+I_~~gefdWOzbXbDj3wvo+ke} z^clHdS=Xu@Q*;6U-!SpRm$YU8xe5;MR>K1RMhW_zrH*=@zjcP z&+1{f4Z0@JeAj%I`%p9tyGAGH*D$B-DgDQHf%)sR_dWS!zZatsG$Pv$+&=hiK$R+9 zn(f&}j@Wbu{_KN#$t){VjoZ5ET9!Iz-@XvYXyf-0yu+OOVun$jUrEd5fDL6=$$nW` z?S*rQz863JDhLNn!@sr*`@R-fMnm~>=R%E*)KRKCP_Z3pu2T@4ETVn=p~mgtmh!y# zpm&ayKn=t9rV-t3Nq@ zAh+!m`&w9jgN|I$vSsF{k1SF(f!_S9BHxoPnXP~1EjF8c`Pg6I3|9@k8%zyq8B3eG zjP!{ful;9l^MpujWW$T*Rym($-8HDrK$byL$_W>D{qwmwKZIPs1!B}W!3I)i3aum? zNGm2WsNyVv^82WAXk?zUi*R|3i$d|&8>ggA3q`q8wc8b2}w~x`wPN_Xi{XE(?Vwwh#@ud!#BvETy;=zr-a28lOcv!c=MAL_^{W#+tdnzgM z>uT(be~YUf8Wb5q_7r)i6|>1LZQSPg((LNH^|`^(gSmJUK5_()ySYr^_tct zsi(lU@Kwo-H34)&-X==R3i^px8E^@q0*Q9nFWwL)X_AfX25u+4?E)Gif*^u_y-T%4 zbxq0H+1W~lvyd!Y=y^Ty#$z^XcnQby+GwR{Xdb_M8OzvpMcnd}NF^a5t0WQ#&=t^% ztsqKpID==_$Z0JdIGxmBBl9vF1R$|^0;$=%SB>>(*TryCx3G*|NlmAx3!at4O&Z50 zu}moms*JHeG*ANw9mn!nI_h@F9W-d{rPr>C1)Ki8Jf5qC&moG7w>Wh`$r61xaFQOFcz!~RV7Ukh z+k&nBeVQr{<}&e+Q0Q$)Nd!ip(~JB!g$Pc?z6A;^V%fmB@o(b)G4&qcT(|B2xFVD? zvLdSwkrE}9t>j}Q6e>j|M5QFzD*COeXDqhW8#EJXZY*Zq8d$MJuT z=eUpKt~>F0U+?oe&)4}H-72F;{8mbo>FNe$SJPI51uKfPIM)211v&Q2mAHZVcTJAg zx$gxF45e3iFfkMhfkCilPK#Bd#!0EHt$~7 z__zyog_mBQJr@#GU_p_w!V7{`5-F1c9#eE&z8s2r=Ff_Wn{xr z@`_?^#2QKw;GT-p9UKR8ocDl`TCI~TYSbBZPOML>*)6v~UDxT^nY+Hlx~W#}aUUw1 z`f8rh-W^9*mmt4Rf~7xPh)!ekChAyo)EmqB%nuhG?3ZZ{St(Go;T_P*A(MG(ld(wZ zIhNlFomoZZDW#`hM0V~C8Q9~rk-aW{;!7@dqHcDgfZ}@l+&*81H`Vp}%Z^S;uHQOV z^#k@frGBGQkA7Iwseo@CPD(_*RpQ8eQy_~luAyq1ez)mo{(Wtd&jl4iIGSBDA^v^e zc7`qdAs9oDJ(dISzWt-#QW_K6HrRcTX55W`*RC$OG+|Pdj9|jGfYzN5fXFRP*0$1j zHxdw6o?U?fC;_3BdCh!tXu9HjGxB-q3U3VyU)h5ch0$MizLmXYs5b%6Oa5#CA}E$lDBWqCYH!yWJa%pWv353mq<(5)}}sNjF?A*VF^s-=-}ZGvhm`jWK^Ym0MRKzX;=AE}rt9j+X|8v4tcd%OEyGJ6Du zje~u}z|2?XL(707+yX2L<23iWVO-vWuZOX0J*2WL{wN7)C28~k(D9)F9Bo*uG*c_= zG7zmX;#|`6FENL+_r#D$95ztn1xXwa)*Hwp;J*CQEqUz_I5)&^mBbi=Jqcr%9@P%; zHpxzosDGeW1{(LdAaJ<^02T3qaw`_VHHo{Y|G)xF>lj|my0ZK%UmY*YIWA>MS=GZkIluJ6q1gMiFh=r|(rdWs#~m#k%)`lSF#n%xv{m?haQjo{bA7XZpiy zb1Mp|KNIw2s1}>oUthkLHy;vrb*0osSFJzca$srT>bc9$jQBoW+=mH>M1TO0UUnvS zsGBTAP31s^3PjBXKY`rh(C1dz$b7mdiO*^-iYRe#N@ZPVL{RO~EJNhTcw5!y+c%T3 zZC_x{kERB-Swp|B>z$pT=9>jjUe1G1(0z29pn$+5YQ_H%oX1X-y8XM;7CdnXdDshe zHs&IKFYBnYfdM;saOWy+Kn%o+7%C!^gtLpw^n30H`q{Y%afW5{n}NfGUIgz}@cZep zAI3b4plL>>0^yAGsXr;rrGH;}SKixy1>c;@>DfIXufigdKGmD{FWulSuWCL2TSa?Tvs>btVr2j5_A8p~;Yp25 z3VP{#*}LBN3rl~)1+gY(HZ5MKgKwyc*7N-NTW$X!b2j?sQMaFOhM}}RD%=f4#BQOH z$w?M$OW|0ugJT04PPip>zrTBHuE8ygo%gAJw#k6l1)7UWX0AtMN_A}oZR@$Dhdnsf zzKQI9HQ^=H?ouhQ!0ffVcGgk?M$+$dC8b~Fk85;^NnezbdT!6QCet(KVx;Gta~6S> zcMHxv`4@beBOqG$J)-c0ybo6K=$W=;d960NuT+d0?O3$2zTtq!Y9@cnQn_+-!}+3p zYZs3(SGn>;CumdqEuPO#ib}O=J?u3fgL@L;JAvKg%zyQL1-d`T!lnij%+g{0 z2tARep7xRB$639Qj&~vbMkL-_R9a$fga9T0$&Y;!!`cy)z#AUmmRxW}GufSJN>G3S zz@F|P3SELqBOcA*x$WIX9xX+v_fY~&5-DQfQld1ffyS3oUcbg<^TEcrZA59ylx+9RC-w3d5(z{ZSABbaSEy z#edR>{Sc;HwC|N*xDCz%REm)+cSeJQtr5~5Q-4}vj|%_?7#pz+UzqL(y^ADbK5akr zJNf+upR-S$qLb>95p$xLdv)uNCxwsbv42*Fzd3#TbB&>&-#>0*sZ25Ug%2)J3N*V> zNXEp7_m6`DUz6%6R0f2f0FYJZ*BLZo;ECHGIQaCGHd6@FX23LPncEL-FbP|S4uE_L zAf`gSB!t_OY{bwGk|Ii6ph2ZAMw99wD`Dn+()*V#!-$>`2)m9m~Hot3#$+*Ge45k9nJ{>za~nZ532nah{m z+i9blCz3;$6(3&b9QCE}j9%-VykMd-AZjx7^_F_Z-KaxvzyfI2dg#jLv!huq+wIsP z(bzYe9;{2QzyEoZ((_H$Hc1hSL#==tDB?6r9W$Kgl}mJ&f@yYP4iDxUc1(c(@c%qb*;VY@2tr^D$uZC zWTjSLrW3brCdJ>3-H+ufGfRkd16HU1o>6wsJ_VxTln?)ba<)u+& zXT)ZgT`~`C5GxUE@yP!XN_TKZVtkE|G*@2Q;@`@C;a`d>DirgN-}!>7H-@QLvc7DX z-}dD+<#t@R*nrR#5KzrLrq_XZvTD3whoK2Y3WmV0V<%v0b_)*|lhHP?$4KJ`J_sKA zj!l3Ei9G|LXQBy3q%(#W5M2c!to6k%5kD>=K|u-+5CT;k8$u?gE73B7Fm5z@YukB_ zd)K<;kW*kZVFEs3XsE`NnLl?KYf(`5p|0M_ovL#lmc)tsteJ7a+B|rQZ0x>=38v}u zQ5Dv=_HipIq$!en6=yR5`6Zxjx65d1*^+r=Uh{xZ%W9?$;p@`?WhAP zuK`8d>DvJlgvx?159>4#FmL}adGp+uH?}H$2)x5wNz@C77h>JIl?f~y^nMumX|Mk@ zOZuSReoL=^pJ(+(zQ0pPJf=r7Z0xQi89vw_vpNTWU-!N1bymyVsYuWT-`{XEm zYM%M2A8g}zX~wK1W91B3fhhIjdk2rhdFyv#Xi2osSheG?!qtvug9u&-(X>DnrAw(% zY+NU-dbx;=Pit&*w9ne>N;c-hLGeo+avb8l6g_!U(aqBysi#9X{#ou4{dK{mU*M8K z=3K$@y(zbh7R}jb1@ml2Zr53+OYe=AJ99)?{Mu1P&GnJ`J2>Y4#>X^g{@&#-$f7^V zUT!Tt|8^|UN!>6Z#`63wo7*-{pDWthb~HRtXY>0!Zzt3C5;`p{2U zhix?T{<~lK@01kEP&7IgZuYsU|-MmD74_~59k1qs3(WZlR%a%p&fFD*@js0 z04bM8J48%@d6m?w5#bPkogay*`{d3~a|+hXkc^+8-Q9Cc&#~Kc{!Qk^@v$-A78^Ab zIO0VBLOdBg+?$JD()ck>%eb1ik+5hodj0>M3+;IW z5hPC@odViLqLe~T_)IcjrVH?|yjhBMfH_7(vgFSHf!9ZQWx;~XafJ4WGE1&B>@s6{ z2ZME&N2mK;mh`+;(a8^~srZy(y@zPEhK$-8v@fFkKZR-IKq1CZO7l!hW8UR{Xi`1rr&N z;ya@CtEgcbnb)T(=pf2fqFk?$eVCY5%SxHq5hq9_P&;J?8MM7M%ZKq& z5&g-dN9s_|V_k$~>*EibFTYF&nGm()v-@9c`U$E4hUC;-tKK_B6$n`&L)c7APr;MK zei*7rayySLrXiLPeBcDdbUHBRb3w;`$Lo##N(7%AaS{G!F2AU{_xhugn4;rl)a(!w zM7r+kK=jYV`U4OUpi$CNkrYkTF2Zrb+WXeNIR&`=;>9vtQwW|p0swS%BeZJ^k4b9S z>9O4Dl8a)!eR39ydtwR(MhJ2D0e5X@3RXNAlt}cnVT&S6MhWhh(Sk?~ZS}!iq4fS` zSQ-_^sqWH$mKk=8Rl(RLnUR-*=d1l^mY#Nvz46mXKnzp@p zGtO;yKDA}d@kyeE!4m5J{rhDPg@jlztrMc0@}Cjmqr#e15vI=rzhBF`6hbi0PrukQ zcG$ZJd8?UHWYk5La_LW`YIOYgZJ%wo@Y2G*XZ9iOb*=L4zj7*jw}{!z%&=Tx{TDpW zH(^wdJ2gjMGzVn_>1W^U?N%!kanP_?4-&hK0!BN`i8$YID@B`?5y)ffw$%$v@7p7P zIUcG-_jOXb8k>DSFX!g(Q1Nn>X1mMq`!8$VA&<|r?o!RPYBwk<*IJyt6esqJ%SA84 zZs$6NaQkdaF(wSh_{x%Ut96Muhk&_}=Pcdy`dRzEbsQIn_ueVMvx4voKq*Dd@I zdZ0Rm<>Ti40WmTnmL4M1Pgv9v!FgRCaU+9_0eq-O^g0-pAVzb;2glOowR9C~ndOGk zWv1|oJR=Dp)Kp}VHFW*@Ur+^37YT|MWAUC;s(N1|%v@HzY3unn22p(1pJDevXdrFR z&W&$=dH^R9h$>P#LR?u151?uUh$=isr1gyb+s9-cjW z)Lm{&rKP4aqhqy4@+>h&B&Pj%4ZvRuNkFFn5eV>DENF@OB)W-K84bKp5Eee@A~KEs z>SG(ba5&K)5s(}T3vIeFfXO7@2t5QbtR*o6z^}w5%MLn5(OCO*fc$cv`H=9g;-Vtr z-3fDv1Vec`#MTiR5bl)vW}4G?edDPMzZgu4+s^P-eL5D+yz6r4y69t+%V{1L$E)A8 zHmkiAT9mvkwyG%A@cK%corcJf{JFF=?rhh-ujdy#U-?WPJDUh@AgQMAYoBoBhWQ>m z5F2F!&<0Liyd}E+g36I1C(grmA6s&8*x}NqbtKJ7+PcZI@BRAMTorvh(J-@i6W23YSrs#49&N%;Ve*DqC} zmHB$==o8IEw)F?}k0vTmgZH1!oo!^=n(jpXF>5hA&GAFnNk?r-RixuJd;WsG)(0jP zmUPE$X|CH7Qnt=0@MPH({fxV0dSAFY7-~-3kvy;vA<>c`gOM2;p+})UqTt8kfMfW^ zdRz@x6iO|KH1q%xh<7lCow<~QxHp_F(Rcm|5W}LKY}sw!SlI4QItJ?I!bnDB)GD%1 z-Nd{fx17J_w%H|?@{#n$0PG*<*F5^7|KwlP<=fb2A7xQqplKKMV674G4rjR8h5%8oi*iBWotM>RaG;UJ0~ z26L6d2HdEEN8J6o*s3ks&Obti1_XX~`*aSajeJkF+hToxmN@WCg=jP`cmgQ&%} zzXhx7KlCUiE?B$Bi>80@uvfp+G{ttIC^}3fd2l$)WOzE^o<*wIOuNhWm zL_)9Y6s@90zs{FIoL+B+ja`u%m^&dqTNKnCSY$8t*m>Xo;{y04@GNrd&#|Tc-lTuW3546Ni~{+lYEs)3+pzWq zstFFki$`hrMnSK^^?t&@;7H0|;^PUSlf=25PT_bJtB5gLXXpBN-|spNqwgS$aQN_{ zbqvI0Mfe*q0syLEA1obJmz;h4C0<)B+pv!A1Fr@gc_BV0g-5l6ucPj+|Hc2@PL&=0 zp{9%N-s}Dg1$*0T{<*EK4|pC_nIupug|;WDa(?OOI~F1-hjtC_nqjDNWWk3V;5Zm- z(i4##ejGvPT&aYHJftNgt9T1wlrr?fRS}3_Dq!_CI!Rzw41kgwZiDhL5BCkfcozdk0-}9wdC!V^cXlzs@}+E8*777t&I@ zrsXBRvNRia{_gZzSm}`Co;HmBCfZj@S)|HHMt>WO7!G1S@%?*q!`UL+>Q8O&)}S%0 zu{O*9`Xg6??|Mh6mR8v+GLPR4lob(+f^UA4JE11u21Oq@tnZ&B@6kWSv$kaK=e%k< z*b{_ak1mR}wQ{GCc`h~WVa*g2vqYs!ovZszow8i7)NJGWAa%b-P#mr4BCEIs#vlCn zlD)12Dwj?ly%aMR`d24YXr{hI^Aao13AKLK-tC(;jc%XZpyo0o`$l`8baehelMv-L zgPn}iD*=h1p<`pF+13j$dxv96&2FCWc~)B2_-dqd#MJq3{!$qChQ$&L3?O8JpDHb` z*ZpoCki*CSUWRESXrd?XwY0YfqM{I|6O>2n(8znv#B>Bm64A_`eH@!phiZkYbOIP; z@!`Q6*2)GDZbmAvY&p1rY47qkheTe12)}dZNCORrWqVo5+O!X8MATyb?AqGQvQ`l8 z2>1E^KmUZNzs_Zd1mOZL0fT_+02^?#*6o4W@ZSJy6dWhL0Tv*O3V|oD6(((>PvR7N#T5>E}-oPg_t85-Myb7I4N0O#-n(06U=`j~6%#*DZ>q zs=&&nNG{jsB=fhhAAj!4#gabm+CSdP3FS6l{P+2u!KbgL_7$h{KCN?? z#D#(7AoMa8aGNCD)Jb^EJec)DoH1D{;NXDJiEF|iT;ItI7|L4qo&{erwoYx>&!tTY z#3(#?GMItf4H69L0PxtxHevy`CS2W**w&-O5_@J4rQCRbtfg5P_Qv$e08K;7_wPEx zCmtN{32r;(vC?V%5#)$;>kkzy@7~&6b8Acbiu)XF+bYD}s0cyijk8E}F&I{kSTUhE zpzfw);RZ7S{2x>4X5K<{2*f`X++T>biEIs}0x-)h{cQMXFc1fOlyn$sw#Lc9vH?9% z2lhGGk4J(nIqWm7vbrz8dxjlByAOsV?9YihjE$mW$NbIzN)Wv_+QCadww+QIUAp_X zd9BoZ)FeA~c;-cfiN&vL(P6?dX=>G0+3v2%-+3y&kJ_iZMvWO)Eq$BjFFChjn%X@3 zH-BbrbUczEnOGtfW}*Wb6n{d8B^_%bSvvg2>%Yc3ZM{EFKK-?sv`svs{)sMZQ5Q`A z=dR>d!uF8yI%oBnM=-t9n!UY~V*|IjucDa#N)UIfes-qshUXhY6vK_^>jk+GBC*B0 z_7F3BN3N_dOG8*^UjEVBaWOqjuch8+y0Y$7XqmJXq^wcPJT^TaQbgzKQ_Jt?%&po; z>(25dIe5s5Vz+}WD9+RCZ>@LBvM#-M3t!Mw+@J6lQu3Ls;eo{(FSzto#e42ie9swk zsR$$xBmvw~Xql<-{x@DO*-bo4z;3|FL63n>gUpR68o#(gan-YUP0^CUv3S1g2&&~t z#`RHtN^MIaJIcVTDLZXO(o@K`U6BSmZNtN~$@HlZjRQ)vO%8m4h3EfhqQ~|1Rh4qI zB940rfNez7@8BO36q-Wu-MIz#6y%Z|*k*4Zwj_>y=)zB`8H1!nY#oSn15VMfw?u<& zkL)Pud(4q?gcAOlMvW4}s7w9}pxV6L&rIKgaY9y=vNXUb4LkY4NI~#&?#LzFJCdeF zK~GLUf9t=m;80N;nye6NC>LSbgXc;#c+?wO_qe$@HmoDI%a9U5<%Ox4bX3qe-2QNp z45VZ`0{9!97TA0Y&<~N=8gfC=(}M-dbSwMc%O-E!I0gBYLV6VF=Xaf6@&4VVC|}=S zzjej&$;-*D63O_7#%E!t7)C(bzk0q}@e{r*OEcFiB`H%Lm7yhxyv*D3H<>X^hv+fwb z8hc}mEo!*>N4z0Du;73z(k)JASSu2yJXq$qsgINhRB(eC2mF%Hhi0!`By$IRqw>EU&Y3psHf z16FKOlP*Gonq#b+kCmmq7QP8M5BDWNY~-ENV`|@Spe!dVd%nBG6RQ9})dz>bB>Zs2 zR)%-4wDj6gs{_1uG8ym(qUwGsJYN5!^RtIYqE9%V^=Pd?jdjLHs*J_29pdLgoaJ*J z_M~mJ{Iy^IR7T5j>sHm|ve~EWPL)I(==cMRi8i@*wB(Aav6Jw+M8}VE^78s#dUM8` ze>7yh>=_lWNLsz-`u)h|b6@{Fqsse?yz6m1RWjl6XUN0BPCJ2ZT0T2Z8)SL@(0y0f zqvi+nX8~SQ#Kr4|zBB5RS_m41&rqwAqaz8qBrQfytX@w~&#fP@h8&LIPb^9JCxYKE zHkO@m3$P47TUUY^RajpB%h5JT?22*lsv#C0rgOr)0^lG610+~TF$<5tX+jT8s(nt4u14&nc@i`vibq9w^j66Oun+g9Av+rnPF-OWsvP4?`t5+mp66`v)uNyaPNMF@E zcI-a*ig^2P?hcELBy{(RAWsDa1wy&NZVE4W;=Oympxxp}Autql8pna zq!iM0MgHY}zE87m+sf+VpMhW7#08`_P%M0&i+#C1ymZlO$>RlQ@89;abO%p1E_1e$ zLUNz{lob=pk_*^x9AQHDeyD`*&?eo!^I}(7sevCFwD@+@JnjdBwJCU^cN1%$iCBUo zn^5*u#u5*iZI@ydha>;loDuZdJks^j64ASXl1@==~K#b+K>f~#TA z#iX|^cGIb`c~fpj^84*xrp~d4-~A!@dNRzsG;ehD5-!LygMU|yeG3Zqk(tiaR5$X^ z<(Fr14;WM;_T90~sN7ap>%d9QQr)_T4Olu5AezK^LVQ~>)0##(Bw3U3pFdvXO=n{s zIj~m=CBLkgQToQ*8(iwoi+}T?pU6I}np~el8{&BMk_@lM%Hr@sIdqIrtze7N`UYyu z*GS$*D+FUciOgVdYr_X98Vy-lS!8r1Tud}DrHDtIhP51Nyiu6(viR=#=51?ZBo>n*6f-to0Tv0EZJQm5&AAj*Y->*bD5`Spsc}}70nXYnX69N z4?vC#WGaTaC{VzS5hX_*l@`7@=dSFVPd`@|AXFZld|y~swMAA_F5P|FhjyYU&y8Km zVBrJpsaO5K_Ib_vZSp-oZL!JwKuqeK4xfsIiZx2m*McjDL=M*3Ie7tq+r+%>Z`65~ zidfJk#eW1bU$(PjfgvEg8{DL;J3H^nch>$@r2GwPU*q~cYBhlRmPJ8QKUL*q*_e?2 zpY*t{+QJXd#JwDR+5=sOneXm9z@p?T^~vDjO&jB7--juWi-M%09d&Npn(WA{d}MHT z1Hj8E7${j>zPte$3GYGu2PH@8YhdTbyCxA$5zH>Db6Kav-go4^e*L;p>!}ztc4BKm zkf0uPMIj&@TfN`mC@z=`57ZF*Kv>;i#!69_LrN-A6)oh=SBN&pEXU{*jCZMV62yScJja*Q33)y6BCmu zqGUlEb=}z+{0|0H*%6NzcDk~ha~+t5;YtmF`pi{<&E)riitEH@w2l(5Vn`n9{p#-J zy?R9kK8(cn3sb%8QaWA~6jVB=xifbc&#w+@Cm;=lwxL1FBHJWFm`0%c9rwtOmofHb z6TB#tWEK$5aRG}I*^24hJ7aaqu}Oubg=n%I#>jg^;8Fp;^j9&h8~uM)5)lQF`jXn14y%OnyOhqf(_dhSxeWzXi|BC3H zLy4kw*-h%HvtcRwZG&jcZ%aQ(WUKVwKNfUeD8e@1Kre2~%7VC55Y2JFRxV{a=eApg zMi==|GLenfWnWPjMCH!gC_`kDO;{17N@3lC^20F4wiA^l!!=^k`BYD> z4;i(roZ_xU<&x4zA8tGo?R#`(NbeTw7JmNs;19YNL8&>bF73%#+t^qIBig4oPOyK& zNQpc|5)6y02{q1mnm%8>_I5px2oj$KYT1ym&vu{AF z=+C?EUOa=Tn1<=GNv}XG-oOL>q(h~V$^VS^NZoQx0liGHP$?K1W8>rCrJGw@Gn_ts zy51Tq3%F@UfFET3IT9rbQOuY8m3xzjS_Jsu$aZ}YoH|OqRX$&Sd9ukc=9(B{!?4*# zM0wW92Vrnca+2% z1Hi$i#!olP4+-_ylH|eVl=SbI8^~^O-UZ}t>K1cCq{N3qY!QGZ;$~k+@LuG8qOd2( zAWY3OHjahhX)u~V?*OI!y-u5ccaJfk>g*=Ui~db)dj&$DpF7g@)^TBFzBCd`8URZ7 zO5HH);t#38)f0=PP@HQ}rx{?*;DQ^51XuvX-VuKkw^{4ATqYlk%Dxq7$Vs0t3#60nQTQ%Ymoy>=!2 z=#A-zwKSr$>Ngql%|%~cqHk1x;x$tzcHPM-02?DwF){Ke;BP)gw=FwJ)5|iwAa5q& z-we%<{sjfId~c_gQ*z+{5bJ90x4pxQk!7deSFWhVM{l?0FGtmt>corNOwiqg&A9^`R^U-9Qot^zuR@YTIduslve>OhXp7PMBFSJ@s7;{!G*35ju zCQyHI4ePqKT6LOhb0P!YM?P;JzfDQqbveyjD!-TdBlm5&s(H(s62{P6MlPnHqb_;B@L37$)ET_*; zn~xrMhp8oY>t`sm({Y!wf%*U5(#4|EluMM88F_i z`wJOWu-;(9T5T?0Pr&5dx#-l?2yhNApN|f$rXi3Lz!g&(lDmbbwqA;Ha(aILKW)d> zt)U<>^up8P`i&bE(7=&Q6(Y?=atVMV5XOix8<19_$G?|R{PZabDTF3yCJ+H|!ILTlI$@XY}=b?Yx)1RxoCh zbtV9X&orXh(j9_ra-bCZkdFh@3;ewt-dtet9XB#!guEZ>WRtfZJZT=wdrd?|X=w2F z%xS(x@qoqef1MK8NI1stKY!*xM-I&sE+1@h{K&2+{0<5~=vABzA~!~6g<|UnjEQgV zZ6VF5ro>EyROPJf36fO~BPU#Z0+7q(C&9q!6 z%$7SDRIZhtxc-{Q(UiM)c~GjcKJ3F!0keYK8#6%ku#!htCIpr&5So#nKdbSHVDC6u zEfoAh^hAKj(dgnAan6*@Lcd%zcDH;r(%9T!ti{VwqSPkWILt;kMBk5>iU3hRHq7CYt(fAt`TqJSA_VYi_T{Zx=K&BHM=ahmq?r_{9Dc)dp$$aR* zfV+kUii#I_@_ahcsI7k4+2Z6Jf^_YW{EH5@WJHgOtNPQXZ5NVoG<(6x`0vc(SwK%I zD=VwGM~UndSTFv{)DUo0%O_t8FiLjQg*+pIIppL>C{97Ilh>ivPC{!zJj^ zzqR|8iDb=#BY|W?_fUU5bfaL@AexHA9vK)I0N}%;fZA`+_9*WfS^Oxl(gY|smn8N! z1MMdqapBfU_{rnRW3#s)`{2KYG3DqZI@*h^!?|1O$~?bn0yO`ie*X7LWO_P<>`cHC zt-ygJjx+cXK&>E3cX~q^*g79Pm|%K98-A7;G&#AYOf$2tS>|_c>Hu^=UMs>+L&WR{ z8%Hj@pCf-vZ0HK5o^d&bfT8mF2|e-zkC@k7X65D<-UXKTq=`J|M6L>adjQ0A2%AF zHunw81==4Be9K ziLRGS=!A$(93K9j#VnO=q4ptp*|Z%t71&M_A9Y<_U9>ROh(Ok+qoeDA0WAu}ZD3YN z(OC~#Y>I+2R#VJmZUh_bgNmH8as-qW+VbsM&s_4?qjiD1YPk2`cJJFqAEqyktY5{W z@&zypxtkyUa8r`hNtnoh`t7~A?4bC2B!euAN#fYzu!_Yd4cgy*mwQT%5SAmnA<v*}r$fhdwaUfjS5_*=pJz;toKS2sS*u>cg50=?jyzgDmA^80 zUm!@qWO$2kka0In&CXVWmk#3_LXQgx1!oDUHF2lcI$HpjGE(g!$6t$fR%R?Qo^8TT z`m{vJ?6iG}MDvp&g&U1qpV`VqPj7$eDlgb=KFyJ`^THpvyEsH5LC<-{lQuLASiOju<j}L9`nNXW+)2FK?leZsc z+3=-@i;8>deYc23XEoga^}_Ao4Z>b2-Z_3-~l<@i{(D)p(^#bl`UoT~?wEqD2k z@PT94V|uMFb@u})O!lknUP}rADhT$cpKQ#*T*b@YJ9LFgUAKXW2~;a$NraV}r|w<& zU}AG0{^cq$Zq0@9PcF|yF2wBMJ#>z(L~Yl;a~?;)(9}DAhZjbBVvG&i^y_z5xJwq= zUfr_u3{}503u;qvaxx#T*pIQnAjQEcl6cyxX*kIu`1Aw_Cke*AdAhWH?A>Z zdq_yjaVoPLS6n8Uxy5-AG)q!-;Q4e)<~mSf{QWpn8U}(u)hnbv4flv$M4k4jl0BQptT}@&6*;O3M zE>-NmDyH<;XN0yfRnr7_6MB!4As>#(3$8TYs%NXr)P87o-ka!_@V=AZtG4x}?W)H+ zvxmvMyBgZf9(&cc9vXPX7H?sd7}qs-^8eRbrX0EPCV6N?q^7q+I%f^~1Di~iy%Ir3 z8X%8B?}f7>6B4<_WMGSm`@o$o4n-LuHQ_y~VG5he;n4i}M%_*^IwQY?{mf^w6!+3; z4RCDDuI$seb&yd_y-Sr}uy7+oN%Dxd0LzJY6zXloS60i@e{(&js<*h?8pWmhzmMns zROBN?WpFx|D=X=LO`rbx?!Y*X?`rh?OUb9tW~OS(`MSslcWEmnNQb$8d&tMkH0rl3 znsfqu!uMcZFUQZ^k)(s#D-7$J!$4u*NW^VP5aDgaH%}xgFxjKkXjPDvPfsu6Gs`*0 zM6+k)*Zg8n@h?*|GnUA-)#OJuLW(eQI`84Z2O138m_tzY;^IXbq2{nGY2yd zzo-gHDDsKvC70DHx#xtb&dfuUx+zOf<)LEooYo9CWR1&Hfhrg%_Ypla9KdL3F#T#z zP9VsQ3%0ZuzrJjI)GH4&EKtX#YqsGD5ZxPEk;>|rqJ-tZFp9XB?=Ry07qkXEMokw+fXy2|RYQW@iyc- z4D0?!$bhT*#fulO4>$1xW&xe2HQe)td{pM{8`rPjLZT`l!X0U38@RstQ+SH^-D4LW z`yy%F>m$?lf#7LcJ1+ zZmFfPNLDMy!-YD9=TcQVKY1<|s=eTt7V}C8p3`&E0mM#xJh0=yiRAn}-+l{V4XVP4 zlP9UImH1iU1jvq)hM`3j3s>k<@X8TaR}`R+kDZ~m|M&8P78@Lci?3A-u}AQzU}3Kt;1;$kK6!`Fht zh_fKyO!_u#l9WbUkyA+suiy=+@_|Wf4D_4NvLbk8~ zaypm4h8n?reHXwb zA;18*QD7OULBNKZXERrd1{Eg~9$1)vhLV-ZW!~(y;y_b2Z|1TFeW~iji$lH#41-cU zh8lU2mE5`D-X@z8>o+lBtGK#6n>b#d5P*%YTl2>CZLFQj6yqSB?YlnN8LiY8RwkHR z2{09fs5 zCw~;#9BP%Ht|^Llf9#{^LI24wFPVVD5${{#Jc^O!vdiWy`EesL-M!JRw{F$$5n>aY zu)3i3;36kQ**9gkMk-q}?ubkGXnRUdlx+|;WenNK&}P)b|9*D;ao>Wt6C%=^sXrP6 zvk(I4dU1SqwmdS$TlBJl|0~AR0vg$Fg>iH(-TD#2;#L8xX(@ti->I@8*JDE>qRvX` zGjl{A2{J24U)(nCpuFz5zd~q3W8+2`joHJI?|Jg8o61D_2lEf&fsICjZ-q(L%0GNRCwm9iJepF}&u=?7g=3aLIP~MamUecLFh1?a!T)R% z(=bRzaV*)PHMx|82aSZuo$z7!K>PK}mk>0n5BkO+s{s)lK+E|)Q(pFpB|bhr5=;sE z2H@C2`}hCyiP+aLaO1_Rm*($_wb`j;UcnLk$ia*j3Hy(Z!mC>WCH>FVG6-J^wt)Qz z79&;=NSh?FYybxcQ!S&VtgbFt-5)(FH(Jt){zWiqK}QWhf2+Rb?mYf1vEalnG6`Jq z^eoPtPL7LHo6SWhO+rSHaQSHRG&*(g1rgZLx&m?##N#x0NziF>pkc%U6Xd}RS8`YPBZ^)r@~CL--d z9*ZBG#A}||e6v+5ysF=Pe$U7AbTi2#)Jy^UBCrsEfTcfv9OQMdO74KNvaW+zY`E(A z0~=yYs&bC+uz3cI(i!g!2E$$Q>{+x52l|9WvvzhY+19@9U=P*5*>A=8PEPo&yIOZ2 zEe{q&-(?e1Qw!@I8k+@G5+tUQ2K2|{+AUmD4%hoM_{J$8`Xb!iQL^ADdgGshvT;%U z$%g~)G@Z1knT+2u-Bl^MYV2}!noYpSROE~7z<6_3M#!9s_&MFrk>DtaRg;Kp+(vbA zJH0nS;6Y*wh^@f~$1aExNjL`B6!5}e+_=&IfA(U<*XM!e5ppS-HAHCpVvz`^UShIB z!n=qoJ+dQ-w)Q6bV=$$ie}031Mhq)AHbbM?;>pUMypu}PbdBCC1tKX|2{)QZvOtxR zIe4(uz(GwpmPys!&CT|adgnW5skiUmW!sh_TpRnzOA$99f5ch_infaLd*Fz+2^b!R zB~JB=!&s#t8%qtsvBAA4Xk>@7XT$gR|8ipaPGHkjl-E1mE5Ch4;KdsRxlG;(pD_%hm!XwLNX6MHYuH0zJ9u?Mr>oTN!o*_ zyCfpMRnUDRPp+I^t!5l0-R|I3-@${WXFkfpkDf4eQQz)#y*hHU2lxWWR;OhJ^@;Hb z#LO+rlln=22kh=N=e|vPtSEIbbHc#bjb_j3i&Jmob{r3V$w_@Z<#M$1c@c9}0_XHa zQ?UXo?a&GB!sN#~B~PD^88L9Bj01oSo!Y;yV&u%WLzKf>UpO~Uf6x%6y>ErOZ$H&@ zm~diXWKFjA$nTB!yQL)GXeL=NKY3<5mo(TTa^k_l- z0RAhF^JRpDr1!X(SNm!9%=`!nQ$OKe$VaQMYDnjC#&|;rquO5>$)`E|<{6h@`>;!> zP9`{);b%X#p$Y`Q^~CDntr@ z#&2I~%Q+0|fp88eCrJ&2F3)E0GYhUql)MqDc7uou9lngb?BOg)CsuPacK<0=Os>IDD92ph91tGVbK$M0Qo+o?^s! zbma_8_6fKSYm?nBImD{uSN$%RuIj-UNXgZ}$p++fDb=9u4O+qfQn6qsf;rR(ZZ;_6 zd*tM_g!5|GhoUvaEVX;b?r0oYNF@;8&hpssAGrX&>#GWbdJLUwqob=|9Te2#u2U@( zSk(>To-T^6F&J2m=?nEZ*OD!kt!$*+xXSgbMt-f&Qnk{0uJf}_#uD=xuY+S#;{F}I znV6jHkKPq}HGJFhU3I~7>E6*Jr+i~U;a7ct4(b-L&WRsCdItv3JuqMazpLhHEt_t7 zJNCW)Zi1^S3f}3PyiZsj;5qnJMT&NPgnUYb`~x-5kfDGyZSi5B+BMrgF?2XDi*lJo z*qLP}L`xT46Ap=Z@z7e!GuFfPlpR~j5c}w+bi0$8{ZkA1S3?ercete&c9eG7ot*oi z{c`*51`n~_R150{K%8TY&;I!*ChYpk6?2%{6S)Jd@gDO{jE<7@g@?6h8y^}g7o%A0xa`>=MrUQSXj@C=CkB(+A z_+XqMBzM>W5VD%CW1r2spLTQN@kg<6=z8R!g!2YRSPdxdmFn~%JAz#vEKe>#pGyS) zc6L$(dPIzrMk?s1C}-?2JEEt-wMD{ky2k&-^^4V7rgr9@(Xp`#>@Ed@m;n$VxrW4# z!rB+k8YAoZ+PGRSzXV%J1K7=4TH4_k?64{TObYIA3sYBfnu=bl-@~jd%!;(Q-AQX} zWR!T4wVY6YAY9N>SzC~lkAnqnKijim7~Cp;tZTxS88(`1kPXOO<=-0g$Z#j5Y`)+f zu4CvxumaTPBx3{U3m zRj(?wBxYJNHy507VdXcZ^M2{@cW$)R?9ESOyW-n0i}?F;hXg?fDUEAR)mepW#0Uha zWfiOq*%Gdn{j#8-;BDEZ3m4X=dHoR=6&3ZT-?qU6uXK3}d!Q(wObs9<` zd|#FyG3ZG}t5%k9i|bN+q|%GyDh~hQ;HlCd^>mRB2~+Nxu4rR>+3>0+^7PKXn@Ua9 z=6aV{UrMF3*j0u8i5fdSw<*egYq&bhi+W&!xZmsVxLNXD8F6w}?K-|skihpt8WKXrGt$hAR2c#OO)>ECjHvgv~l*Zm(J9sn+t`R ze}>YcIUFWL73@tKEaxYEw_VLIr?cd%>Ln0f>nI`_Mx5;qBn`_x))8gLTB`VFRA%O< z%P;YArE^aQkCe*`23Mv&^gAY6@U|l=MI~J!FNr?KSZ46RtPWZE^2tsqae2Fu7-dez-`G0n!p(zC3pNOJ*7ix&acl z$fw}6v9+}|&P?%lhXtMpJd^!!X#mb9zyvsw6vPsP@m2PB=^qsImaeV{)VSAg-r&GB zUJgU;0WlG^?#Rt!8+Dv70(}NTUaC0HX9{b=hwsxyhX z^WMgP{IHFU-)`_@dW1a^OU` z`=DET;K7!-i4Rj6wOWbc?V#y~l=&`qmY2v6`0M_*TXpmV6dpv#2a?1VLBUrchM*D! z;yfv(;CzteapE$RGEUI=$jB`2oG1TYcH<=?>87Tp>%c6IK8$JPhbonT>qp>mX?Gn5 z%=OqkVK6g@&+i1BjI4e7e~gb;=2_Ihdo}=*;?69Z@yYN^`Y-t4d{f5J9$*l28F>(B z^H#+8_ulMEU&DHKFmMDj^@|&=+4FydEHFPm7@QjVWhm|Ir%Ro-w9D!T8q9(P%Ij%O zy)?s95_acUqzvBm=w$FI)f$kmlUuw$)n;t>clTQ}f2xr`HIdf;@GSGe3lf_(WRsqo z+-!6PI6yK*?J-E>ogv`vW5>2bcj_!1Zg|EV2$~ij+_JrF1I=dFrbh{ERJ8)nD8aV8 zrdPYI{DV^S6grD&5~S%|m(?bX%xiepGo9F==1A3LkM^ljj+H*ks41tec0y}npRwxQ z9m>mWhs7--R*fy=X8s;+Ny+m0T$Dd(w7gJ4Rajc)W#{oKim5G02>J6Oe#rbmeUf2! zq0Ny4Ie0Z-FN{1M>wOo-o)EU9*NojNJ+K1=E%X#46sx;vDSDKzwny3WC0e{SFDc#fF#&?@2-g02}hXqtSb!`3>9` zK+nh&iZjiD@CW{F0q887?4Myk4*RBH>Und?$*9ZS?yyBNMo~1cME4gEK<_s9<-*kJ7EHZK@-BK(nnM}Bof*?$ zr@(MPK;{HLSL*BO=`CED`P^ugMddBTzmjjg{A!wr!K6 z>Cc$FC?-2pv25leHwDqMV{!TEGn)wOE!k-;H=f_B&iFl>mtW-a<8A43`z>2La;5LI zCv~`Q%A_Qoc{|;2xwO68ANHBt)$B@P=L~GWPVfa&^3O2PO2u~CcU1g)N^U01Tk=og z!mpaNTLX>^Eu!3!wB65kD^ckR`E(UGb=ZgSiQCGxjH;F>2@EfG&B~Zxs{UQ`g_)`4 zIdwUp{Yr=3S(ws;ibX1xx_Us=Gw)4MlmSQmV7lNsFZr^7P{mLd-!86etbYp43t=g} zdX+%WT4!1C`wY&R*KAUEneBmoxJ#f5e!&}w6M)+Hf_GE$;0=@KIaSmBHTFP3$uh&a zUmdMm|LTr-AYKK*uYiF$IPB9+Qw|5#*upNB$= zs=;h!Gm0HJ{-?4oU|ua*`sQHs&T}g>Gc#js!*r!}>S64JKo^}s2s^RWOU*yb0L%|S z3BXNA_BH?yF|-qjFh{EbWe`CFp!_)mSPyS;bxjRSF~ZPQ_TGK~<3%hr)3fbyabPOI z+`)wRhg>c+HdXLZkiaiu(M1G@*hag>YxL1pH)YRzLlClsJLq;trGdnNnnse?K?pg}&Q20!;P|@^=)B1ocS)=o#BHM30jN8z%kohO>#BBfd_56WPO5RBzAw(|0Vp&>s^d4^fnynYK?6jML(y~cUL zdLH7|Gj*IGJOdcOzc$(rEn(J2BLkit`cdL^1fC)&g7&}}+$_^%+v1OIS6-UfhyVDv z{8@$m;+4kqTX+fkC-m&Ha&qNeU8$xkO>Nfv8$`-{Y=0Ikc4+am@n}_R=uSlM&9|`9 zW9$eq5^e5$o2k5&v$>FDf3(=({kimFS9U|%4%Siq^hIHp{DnNLh2eCk%(lGUVoa+C zS&AlxN{vmWIOB&)ty{LZ@b=9Ue*gY)Q5s4q5m`}2lo{D&lMxy;kgZ5YwrJUut%S0b21Y)9>3$b|N7j$i|cy5&hzt| z?3glt%^ljc84Jhj4>}NuwYTrYtzMRK48vc-7FH_TXO8)_7%C>vPG5!zd6N{LCotiJ zEJ9`|P@_}t)(UQgP=N&HAg}uauqVg`$ll*F2UJkm1UZ7ZehB2CyeHdT9o3E%UrmZy= zeC2MwsH()>U&BZLe-l}!Eb*8oKjd~#EY^)sfeW%sp;JS5= zxs-qdRIG=f<@l+RH%Z+Hanui^;oC1Y?(P`U+oYmP2dOc?)*8RYaH(e=<;}7(M#U=X zx$_I$fzM-{_zyAlZu}tY&?)mr|4>}v679OhRiB#QDsPUpoV5&_q-73$J>n?vuHZ*{ zx8;`up?A=sZsi|R%_rt#%r>`!&t6&}BRngyty?_NW-1Q#?hlb&{j+50><5H7_@ime zH{%^XN)Ob-*mW~VZlN)2;=$2{=`;^fIRm05RDiirAxDeF%MEd@uXpTis7Sv zsCEaFD~YxSI|stUh+T2(rcL>0IPsCcL5Dco@B*r1si|(=4pbCj$525|8YumtDbUY) zr%}!U#X69HD--?Y(tiP-5REGm)B*V5LYy`S*?J41WkjTCY-~&vDA_dUF)BdN26*#2 z>J>~^KtErDauBTf^>KySuRY2z5U?SF+GANqhEAb#y`GNFBVg)yaZY`t2lJS+vRDdL z<`#Wt=?J9Py|_o@IBE91`2Df-a*|5clj6ie*|&mo(4Y zR!yp#ppNmzXAgyqsM%kX6{G!7fyiH-9Ttv`dNabU%q=OMD>l~Fww@(IihVvQa(_Dy zRjR+vo8D*V09}1MEeFf`o~&95*VQw}E^e6`>bGnDVzap2SCRXCaQw~GalKzXJY}E5 zYHd~)2S)d|Gb_@^F$vKZ)APiJ1o-i07zXPyy%?X9oVVdN*|VSLJ~M;q0Q<>5OO!Rc z{}^dZdja@3c<#-Fd)@o7@854hT0lN#SZ)&T-Fpyc*v~`F}FmP zjML-L4l$=f#7M94Zx=W;c@0M!M2%4&uLA5s8r%T=yuhI3pRKsYcdKLJc%&f^iY*UmSnt@UQ?j&0x+0+Dy!n$jb@3ON&95 zn60uE4q=*uISAE+pXgNZ3sMp5B1vURIvvH`4)Y_44I!dVh=lr2mnu1HZKC@9P!cZ! z@~ws5W|bN>S`!IpmTnTMnL+Z&c~cAr1i}JoiOi`xBzZ3*V;%PO8Uzqc%nzr0jtRht zENMtZ!2v`9Vxg!bg-yRwmqxA57RJWtSpR0{V$Us`qRna2?7bY-x>coYQo3-fN%9Mi zpes8mM+N5hwI^%b`Tk>%@Xd@r73;6Bp8Pn2g|q@dFa}V+soK2%&5T}aL^sXzJAXJl zzk#pg1#j~lzi?z;cYt&O*%34G3a1DLoImT1s*CLniFu|b4 zt!%8a`)u{wpk(|E-%n%k$3cezqJ`7Hxu7kxk@M?GrK*7wcRPb7^C9ll7Kzd?L_ zuZt$EECBICB3&bb$*o%tBeDvc64Vsohz}982z5JhWHoLCikqkg)6N=Le+j%~KG_{n_z2-a$_uU5Oil zzt7psD>`LU=#@K;HZ(JoUss8air(WBBiq9%*r0JX^_9}JwDYgKpFWw1pg9jPn31%u z$9(g%9lg?A)Yn!v(&q|U9=-U{^IqL^JArd5`Egl?Jga|Ia?2mpa@;<;=Z|>ro{Brs zHL+RDdYs7zyfb_+OSM&LNfn1TKx762vK%%CtrQ{;KL&~RwG9NG6)$n8OJ1NJ^#%L26HAY#4CJG-gathJ=ge>&HmGNaUJ z1Yb}OQ#IK$ypGms+lv+kd#!cJIiack{%@I+wpZxYm#_C9)QmCg&Cz_ofpPs*#7>jD zcV+${%6av5ZA%j!dy7ksj6s0H;_H~>@!N0s$X^pG3}ek1F214n6E8|QYoz$?;vuK) z0@^|)_N#Kqa_kN>d#ozA%gyWX2*^;>UpTbf6|PV$_@VLQHqEN8mQ&0b8iSV%1I>et z&kiWj;2tE#6y(orb(M=*w;j;PxiHuTv7tk0|J|YM2J!)xic}tNC;J{iX{0PvAZ&|N z0nbN`q(|7wUy@)Y3TDK1CJrs_C3*b!?rHK|-e9VUN;uFo1HXQSyzcd)1O7ueV~~H_ zP!04Oz4K|Hfm8feq{qI#y@@5BbyO=toaTtCr!+uR=i>L28g^M*69bT(2(%{=>>I38 z+cx0scnNoHdiq+77OpPk=5PJV_sKG0j<~<|epnX%O6*V!GG7oG0uk=9Dc`6E4+yma zUjnu$r1Svf2}QDcE8AyeFHP6JKJzrwr>CjOAx>fEP9kC7?O1%>l!};kraHh|;*A0b zdRz`_X%bb2sB6Tve{P~Nb9=flH%IEm$#1o~)Vzu=$l%K_5M7R4%Y1h1n?#Dh8mP}P ziWA%iCNKg*p+?5Q&=7e&A<%>4tQ-I!N0KJ7u>W9(>5I@l>V2yU*S!0w99#@9AJo2h zi0UD1@bLa(PDxVkfm8_@51%zWBGYuI|Mr9&Ve&2gE-$<|@8)?;*Mqa!5rJVV>2upm zO+zpbP3cvZ+P^%_(aLaf0MF$jH4?r6T&))0<89zF5p+Z~p>DxE? zKtBxkL?>ECLNfn$9|AOF?5kL|?8=ABkeph8ND;Nk&1Qk)4{~t3GrK0YY+oK6yiG^k z0{O_b`uDoDsYvr%JrG zdBv}T>1CDs#;rT+IFiRhbt!j;^1Km0SntQwaZ@tambT8-v_)6hf?opFD$&CfpJbj)QKCq^u9OApU;9a8ukgvH1 zrL1nJA<-SU@wZ5uEmG9>60tGmH4)17bHfc3+JIU!v){qD9@zG#yA5=S(TQH}gfY8o zex&?0AM4g9FDL4$Qxanx92F|GEl-60yy;+S$(4V}PJ!pXRK$Fqa2uD+Q572oc2Cxz zmDlZx&tC>J9{A_ivT;qM^SZBhLcl6kAug~a-{qU7*Z??S5^)a`+EvLqOEEl{nwk4a zpeO4rFP8548lNqcM1DFo4h z90!@$4`ToTpb9*4{7JQQD1s+_sQ0JX5)M&emdGOpLWl@KfWs`?KQ^$2>ZOp=E+eL_k{R8mspW;5?= z3L=tf;r*}!s;H^9to;7{>k0yGaVWNCyP7XWWjiB=1&0UTb8L^peM_G9)Z_-XlGG zON)5NTRyR09tu@M<%1umT>r^0Cf2BaKeywRGPlJ1=MzhIe5rvi_(nSab?y-VeiotN z5;tNW?Aqg3u&|wlFW3kvkrI6((r?u}XgHg6UFE4E+K345-*;a)GVl4YzBOnU|8($whEi7OmPf6#jp4tY{ z48Cwu*l}thxJqpI(er1{gkZn?9K%U9a=VUfHfR9gxg&RDr{F0rIk|JK##G2gyTa?vn?;Ee*G_-(aDbL^0En7;i_5~ z1gJ`upE^QFPYRi!5=T}`IB=Cu4VUZI6+n3e*G?5C-@J?M`+;XD!LSI33=;~LJHm6? z*km1l9(e=*MSnrF!cBy@c?pQbD^B!DKNp-3;oNG`&=sX;Ao(^(xGR6l#)-uB23}ia z)mD;ft%t4dG6u~ZaNM1@Jel|^)zjnn+-j_gFDzh+=xHaS;GJnupc6Ivsetl8&TB#7 zv2eV@(l!Ln)gPCPP+V6-24ReWc_8YS*y1YCQx}05+y_$F<4@WH=6AC274H;$52@=GO#ce-jXU3Y})n{NrFnYwUQmP6kiLmF`qwS>BxdC7(&!BD{p}4UCL}hLgSN;UFu&c>_oq5@OLm zsGFv`ksc5PqAqG4RRr2l-byj=?S6s?ul=$0^~P1yMfA1%ZooUm!C+nU1b%BHBYuKk zzzd5*^z+D7Fkl!LxG^;#)(gJfa)1p2Ntk{pcqP-GKfj~Kw`SJm7ECY1SbRrefuGnS z8?Mt_iEn86)_$8Lq~obSxeAnczUTGl)tZz02@8U7Xp&T3bMHW$F<(Je)^Kjc7jsgq z39gjGYh(}NS1;gj#>lLOpwdI;z}@8Qg`A&3_RK9R+VV@o5h_LEbiDuDIO{X`j3(nA zEU*$6N4soN&{ojDy!6Rh9G-xI)gjK$LGDO8zEo8;7dV_;F{DVkg*?Dxs!6H^@t8Q)((qXUswARYoIcq;i1=%Lpdp1@hTNfFzQn6l zH2iRWQ&d!e0|ocX8vx1Y4WB)G1{YQt{H(~n5g(?%3)2SfC`hu)fa+n;GJ16}_R9Hn zw6xp+8*%5fvFQ0{@XU7vSDZ{wY33_1>fK_LwQvZ&09fOX@ci3Ge zzEL}!iuU|Dm0vLKzvvlgoD{0KtiE8W=kbEx6V~B>L+o<72i1Sw*Cz4uB&&>XSE;0j zOsMPHlJgwGy}?`=7Mf4#+;ab%vHG&R$XbIvr+-_a(4DP!3Z9BiWo=NA=+|QkvMlDG zyYa<+Ze@N8QzT7w+~xhPO)4&xh5Nh?sv2?#n@IhzD^GdR@5DHxOue=?qYsh&D@AY) znhjNlgN;#gcYobZyT8lKV!ni6!T45SsK7x;0{9>q%h!}*iZV2qn15gDHwy_cQePe& z=Qo@GDRqG_o`<$faCJ)YZi~|s z;+KkfpSg*)g0J3Vo?|YB-XGuMHN-AGWM%x{#yR)8Dt~_iR6=*}icrH4BMg!C0FFbs z2G+R%)5q->VZSF%IZ_x0F*T#Opz84)NZTAp&ZbF7$l%b+-h1N(*Jfp5N&(I?WpJ%A zkG_-XJj#@imv@U9i9Emtfgyr6szhzv9U$4o0A+{{7h5R~=JEQs90=isfd;GZ6xZR1 z#a%xSzcSuco9{&B-Ft*))<{;%N6-FjN7kDJA#YvYOYHN~mj80M>rPASy9JA#++6!m z>~43uc~6@{OkHH&hrU>sWp%{`23+Z+`xaIc(CK)uJ3o%p)z%(?MV|=J@styIifEcs zRYR`;&nGYgNr4^5FGKG3t$uSfq-uk>ubD!hcGx1uAL08V|CQ|li2^%%wN3LQ+i!AZ zkw2;Z;4lL*ijm|Xfd7*lG69it^YaId*DoQ!o*SPdK7PgdI=#D)(2iEaF@GVo3+7{6#Gl|_}VaA`sbyUmu$k3}~iR}#07PX!&7!hzv6Q<2IrRdS-OZZTX ze%e1&3*Z?twYIPAUH><_P%rIy_U9Y_1a_p0)vT?GG|77N!XsTEaGOeRCv1B(nG=x6jSxJDU3Bo*;TayGQuLJi#I#&yLrx4 z4y-G%l%bg~rZtWb2#E@;a)VsC@b6C-N!P{EtR6PM)v+Yl#eJI1<`paFwTU%E&H#A= z$7t2h`yjdSa!GTV%^{Kxo39xrdSJ}R4V+WQ_fuY1w-K+kTfliQuXm}UBR_wVD0`CL zAX|)$exgyl8N4FNM?>8`vCxni14nRo`+{ZUFDR*1@i}Atkmc4WyO?Lj>W^Gk7`HlA zA9{ZawtfEWu@bEG9gB1Q4ed`nRi2DkLOlMzkTLHuY2b|)a3m3EnvgRyH*P8*IshrZ zXc+mi`;wKl_5OomBqIVmbicrR_z;QtmRIL~<>vt7i$%zV#7RV&niv??XVGl_e_DX+ zZEYu@r%-BfQbg@JOyLtJtj-k$zz5ND@!E&NfrJ*@TUr?((lw*E?buNvC1RL!0<=0!tSR}B{KYfD3%Y4C4C2|#pk(RvEfsZ3;72L*vJzpe0#lNpY5`yD@f zwjtc~l%5}mPIC0UyhU#&IJ2FDBLb<)L^dEeX8&nF4Ww)2p{CkyeCzcb=iTufs!m~_ zx(6*{^Xh4*RapcJ)#q>4npRdR)Vs$dGpFoyil*>9-Wqhc*76xYUsXxAkd;SpqT}Ne z`%668W%ZcfTz8ZdvFf@8mB*~KoLpm%nMWR%KwQ!gNJGtN-V1>3NY55f?G=Q5!YWq# zaZmHaHum2q#thiQ2ZTy2(pomWI@9DS(e7@WE}ulFJ#H~OI^$Jh%b$2Q;%BdIen8=) zz0I9|l*GvM@uP?GUBs4;{9JnYQA3@cyG!Y9c2U`{*{d3VuL6EcPfzd1IR2x{ z)^(*ITnhpS;>`z@enlmq-DtpCbsa=uD*_UX9m6TZ!}rn-jZIoTs|h-KI(IMAkT*N5{QVR4G6)1K=_I{5e>z3+FY(76v}Wjn4fDa5yxZPP zZ^x0SJwG+fbKt-h5Z>;p>toM^NBnd9>OFkEA@wV0bEnDgngE`zaG>sw6nr2+lBh=T zSg^CRL*W~U1PxTt`a?k^xA><3G7QqVRkAdB3>u}$WlQ8||DS~w9nhvS&#~uV{i~F^ zZnN|aN(#VYV0p^XQLQG_D_9Pg|0Nafwe-a4ixR9LG6QXPL6$a%SPVQ?f~7VHTqbWm zc@KUh;tgodM6uA|J6i~xFi?U?sBI3X1z84m1D`N;^QjCU?aV&@F7?eZ9`R8J_zU;_ zzS(Ugwvt|Xtj1Y*cR`fHf#|LIl-3nhlctESrAOsw#H7Vp``E%?H}vCHx%{d-^#ei- zM6Bu=vFi^anzOK|rmAWk$boX0Dn*?JRbU241M>#=6p0!GewznEwB+4fr^TItZ|;4n z7ytm%5ts~GF}P-c?qhTXbaMD>XDE>zki83;5GB73pzH`Wpgi@^CX?Wpq zSj8@6HFiZ@5CScJPr{+k3}%I_=ydO({NX-Bs{XM@u-vJ9h26T*rIc+}k7_lJs>Y2s*HeoO_11CcPBhersJVW(dtQlgi6BPXvSXo);It)O!fE4Pw4^(8I zD;5eJQJIA80uUm3Fp-Y&5SY7vxFTpI0^PuycmSmOr}p-BaE5K%!P}2-qY7qRqJM-F z1Hw!5mQ>YN2@@(j$LeU~!-V#x;t60RL?J=ZMj|T!(bOi5pL!Cj{#Y+rjs=eu3FAYL zo-)tM%HlY%F$LhI$R}jL{DFn=#)gik=joP{T1DI5@|5TmdK#TR{Uzuc z)S3)CcHAs3mIJS90gVBQb&k6}>vL(AC(#@bv67z{mT%nV zLcqW1#dpK;P8me}yUAKOQkK@@$xt0nS-CauenZT}XJB3S)TG&~Gf?~old<=6rjA== z!2b56g;Xk1Mp}}WQ*PED>4AzGC~n}{S_rZg158T(1#D;_0U$km5cgj<4NgyzuPEyM z&pvQm@98N*!@%jna)>o5!}rpwGgad({;8YYDjj#7=RdB%GkMx;YiwE?%WdQHd`Aie~}hNssuS?K}y zO!)2t=t8uXMYbLtnVqy$Mcw0#Ee9_f2}ettcWrda&EI_B@zjeFV~O`hgCR0@HK}R* zb+-Cjqu=xGpR&@WyBBd}(S5onaz&Eq+l`3GgC6|yJS%Q7IeR!h-(GjGz~<%n$za_G zR}*!wjmsuheX{LOV-}p#KOcYZD9X_nE-Azww&f+p$T%OYHv~>L7hQnmphslA9=_Aw(kT3MkQdFo;|p1Sg)%%}_oA z@gOp0=+~&kc6r+PCz9+ugwS| z!105?;Mw%8}A^urHhXg=jHee=`4>=OM$c=5pF~w7Qd;E9~At>~4T{fwGK9 z4j`Mr*suYalorm<&I&Ps<>+#dRNaHm2N!P*;Tb(AEs0bZuO=?0$LtkkXNRyuU4#L{ z1&TF`77Xwe5)i`1W_Uz}EzoJ#da6GDej%~*VM^QAb>qr&PXI+(q8~4G-za0jdc7x; zRn=y}pB||#r~VjeM`zNmDLR}oL&jvZyWg3Y;P~YJrMx&w`)Z(q; zll_Qilc{l0M9iO-&71bo)H6JbVB>7_-?_yrPw&X(hY?kuG9=iW?s1DJSpGG<-Jsty zcrHqSFD$uD`rz&g+khON8vnFmTT|DA{HlBM=Xo#Pxu!gLE`v*^oD9P4s5*devbEMy zoz#B-1_KsB)xZ0q{L)0l$o#Bdja+$4)7+*iL6nve0LSki5bYz7rxU{k;61XI@i&0- zF1c%Z`ZOs5^N;5d*uVe7)3dJ`!=GA;xs{a0bIMP-G;Zw;}(l}TOb5xeY zXBqkLJ?d@n6+Mt`Ak8+&j{_`q%&7>&E|F4Wi%VW<^0|~W@Ag+%LoZyoKyLP*%_+?VBJ2_B8A=`=bJ??N$_NpI{|I5a zg7y9_9y^y0xRm5w5_{+qsTSSfvHxnfzE7p}p5N+A&6dTvw*t4XZnxt5Y+)OaxP6(* zyCSMpBV!@6TKKcLZ5JEsT_l!y%+qGvri-m-dRbO~;i+jU2OeY~x^qZWBAAj=vY3s$ zL*UGTv7CMlrZZ1Zaaif`bQvj58&lX^26u0!EecZpb?bOYJrgBu`c!MA?e4VE1A~i? zxT2q&2s|FOc;cs_wB};^!WsuZiSx=nx^d-dGs5>2cq)Q_v52vUv<9rijULaxX4$ni zCN3s3=JHF$3}G95T` z3*E+t+h${lF$9z=N-~eM(`@aJZc1eD9UmKuICQCl3kiN8GlZ#h?@I)$2cCUes8b~j zk)Jvz5~|LESAYQ-@2l4>9$)4TkVGQv9_w!P>U0uay<>u!!lVuydq<_x7+JsxcV<=qe;fWj{F#e>vqgjHDgX8D!99-SzXyihJ zNELQPV1hs40uY?pbtais1HTu=_!&hh~0q{ zRAMNh9kXvlfQ}QcQD~+n#xoJpi4#3R!FM5HVx2#DL2lS%Ac2wNx_O<)MC~sdg@xt# z{NCvB6aVwPxL+ttU~e+?5muCs&+4JN;;dZsTEM7udWKQ$mVs-Iyo z^U0qRL4xn;E|%3Z(q1g)7hn>*pyL$3?6&rV^g|2tab4b+oIJtbhQXOy{k2zOG9(0N z_{7CxtJP!o>PKF1Xl?h~=Mz({WVbgtUV7H9G+$aMkxuL#f7AMwmW;LB?9h^6;6W9e zHS>VPDdN^Zo&ro{FTlkBv+$WR84H`5YE}&F3FPd~5Gz3L>uef?{763_t2=a1RGr)} zOBTP44`N2(7Ze0VM8za*5(Ygo^^5ju1#Bf>V)59KqXj*EXItJFV~ingDO`g^_air( zo)V8`*+yPDhz-W>^Xi0$gH-Wo?CU#7U3W2$EBnzJ{9`C1cqu3@df@}ao@-H0i)(wg z`W=ocgb0dSRBv9wiXA5tATK8ed194RN9*qy^18wy=SokqvIw8#F3D*Xa2qE(>Snh= zSqhh3WG@buWT7F&eIl8Y02A4s|>nM`fTyf!OZAqyb%L=}ji?1(?GqvxTe>sgpUQ)9My*1D}?fViNNnk$qD3Pnb+C;-`axKQ->rYu-vLP59 zCSNzJNGk7=hTi8JV*G*w_Cy~WRC?KXy)k*mYUp1I6B* zt}xdq&m4Ws6KtWsKU9gb{f?EDiKTNwQhd`%Rxa*A#rxNI&pv#(TrjV0x6j*;QBmu( zmioRV!|JV;eJ|%sHMi~VcE#^v^%;qGXu*>=X@Svgb7}EHoz#}axlnH0H_W z#o4JX=etrZpz}b=(W5z&Z(qL>q9172mG{puuAwT1WQF0uBwju!2#7(O=tKT!t>l&5 zJI9H5!81>PmggeX9j#{F8p+v(?brGUiHIE04&^}05zTU2i9sk7h>3x?@lXiNVQGzq z4dl$^M9_3H9VIv;aynhFUL}o%bWB2UHY-8f2PT@Z0}~ThIQC)>gQ%s9`5wz1qQ)T6 z@rctbQo!>g%%W2B7l5PZ)XxEYZcu*}4!zZq*-}*PKdHu&5=CL5yqim$WZ3^aTb@_u zjUAVNkf68jxee@3^+M93!kFyJt_hysQ8SROv(J;S;!^I!-~F#vx0aK9(nqke_&34$ z=_&vQkLZ$q6~NR&aB7grktr$7EX}Brz$7Pv_ZCFNhl{T=CNZh8Ac8}0GH;hEwm&ie z5n>b_+cD37o<}0(SP8Z>k_H635(hyZIXK3yxZ5xob+_WAF?-d0st#m&Al^XyJ~rA8 zVHE%#q!_e>Sd%ucHGU@%y5FXn+dEEXO_wLr`)39@a|M6oT%LWt)Hq=o;glDV-RLCX zVjof+XymNM)TDHK^P!(zo{=Um6<7|qa3}BRiDjWlrF`e#t|=$H$)-E5(PL+izL-Z0 zcU(>j-;HbyeXrnYYl~=ZXn)T+_qDsg#SrhlfcH&A=jsf{^f z(UzXZ>v>wARs?m1rwWB(_}L$Jj1Ad;-@TJT?CNz{(Q&5#xh4Hp7ZYUNpSfO!>eC!( z#Dmi!y=1S3;xLC{6t_0?(YVA(Odp6}h36*nV%u7W4u&>40)5vp@a|&Fp{m z#iRmfJ(<7JAVw0ukvAG6Q%Tjsn;y-pLrwKDOK|`G3~&^%xc=Q$v}@OL zVekTiCwD~EvH>d=(oV^_&=gG@a46clltI_oz~MSR7-_^uatG7F{yZLc|F!;k+-Ubl=+MgzK|g*~)^U z?ZH*h;P}@Fx0*VR2+$Wd<-Pxr1p*+d+=Ll`AQl!DTkgbELyzx~>L8LUeq00?gkVjq z=xYIAftMfw zj98)boPX38u{r_}?)90{S^8t6Sb;MT8TaMl+jiY?ym(PbS2yBixcAuG^>`v74H%%~ z653Rnno9hj%7~o%CJudACz@>$1n{R`4Ak=3f2n7-v?r}Ay?>vT?A`0Pa>T^(wAo6) z3vu+w5vr{rcPV>l^KD04JfgDid~$weZkj58vM1kropZdcXD!FLZ!)oWHy*Z3d?`|0f67cXODc4F`xfaA=FsA37W3RK z`dq=)Iofld`cki?Q-`u{&{BJ~S*4qQV2|PV*v+~bZkC(Y74fp_x}FoOxtUg26Vf0X)SEOR&5V@tH5E%6?}wFABW!u z@Z@<;Lu%S73clJulvMy`so*^$;lXrN4ea(eHg^6xm5gd;c*q{;K^0vF(MA076QFL8 zSCEndoZk!*$X=`g;&V4PwrY64;FKZOG@v;Q%ZM_So1Uof*iiOUClS-_?Uyel8UZFX zUX?n)L`TLw$hAq`8{Rmhd=F95ddsOXHj5$xG9%#@z@UI{{t@)57!-~G!!B7_xJ2v@ zq!Jo0I+U%X;Q$~W=*3CLFqQ)(BntB_6bt8H1Zq81yL5~W+RBO0eaFm}=bLLJlJk@h zOhr^tBw*{&qw9{F1z8PK&qcC_mRiaAQ#>R43|9^`6keDWeHh_FQG9>;yUQP=pKX@S z4F(yp9s(IRTMs$eYZV(8Y8KLJke8b_e<9U+XGi#UFE{%Q{h`-|8?jrz#)bs`Ar* z+v1LK=H^g|RQhfE-fH$Rt_mJd3m)3mbNZd`cH)Lgs{wUQpq{#ba`- z+>9J|9@c$0!vOYgcyFS}EwbrFyS6Fl10WEUJ(jy`PoFq(WlSLu z4rbPMz(3`Hpe2Z0poZq2P;Dg}b9A$mNrwz5Anec_c?S>P%{%j>#r=lTQzkl`sg(8- zUk}PbYE?%VoAKNYg8v}RlI3Q*A`evAkK*oSWMVQ$Z4l427^Kod=wHN-C$eiZVq1P# zJ!-NRhf~`L(NB#Jq@$;}!Qw6~c$uW7_$ou!<~QF@Q|#AI1snRd+?M`X;bMQN?k?bs z#bWTtb!Zk50*&_%(ZSl_lNTSZoaudh+mAi%w=HENwA~}SzKC6`88d8s8#598jW1f$ zyob^Bp8d(zF56Ozyp2|q`W*q=_1Ni_z8(J3e(?}FG)Xx$R!IN{c#ZQdv=!&dHFj9S zo3PXgmW{+e0;Z0@^i9myMMXUfHkjE_<;1tD(@^vW5i%+yegy_|l1K~a)y*x7Vdm|syv;GRIT1Bd-Qsu2eeYsst;a$6V&`U zjOyZC$ZV@ZC|jQ8k&|OXlAVgJ?MQ<7lnMsL^6NC~34sIN*sQBH zgS28|0Sn96)C~5Y8xS$lhKiGyaMY4%Ha7M)Tw^5N7|}z}c1Cyb11?er;EFMrgdQOF z4B#mV8z5R22z1ruvJ9SxLe&20k@De%ku(tw8B1nqSyr5#gQTh#U9WfEn7bsme~Ukg zw0j^OP3*pq#Z=!|N7w)7&t?b`kq5U4N}XG{ec*xwVSH&2d~T%^MB`i ztC$E3UHxOc@8-$2-70b;F8P#@p$i^|2UWHG9!@gs%Gn|EP**cE^mwl@E&C__OB9ai zItlYB{d?CNdl`yStQP8~g(LYwb)EE0f~FZM8P5K%n*LQV{C;cbd(1UA^vA^npA3sf zQx_#_B->jm->RiB%$%l3XDnKYok`CKqFJtHtCNwTr+8A>mgy^Pa)#8GtgGfTBu+iH z2zhy`^{P7EeG7|irB`K47#vv+#Ek46lFoND?I;W@u~R!5KUop-8Y#Ic$S=SArokS^Y)g17s^WZAjttV>|xhu1x>wZ$1p?5 zEgmw2RxB-iDWx@Q$WQfp0@9vWFF6dmBuUNYp%z2pARJE(6hMXl_B?vj*KeEm5b&1Y z!snFZ#lEui3NwroZH5+^n#heJgAn19a9#lOo#JcZuz2--%|w$d%&8eyL5zMAbsswi zTX(XfmMLoB0V!aK+Jk~t%$G!)0B8*)Kozqja&6{$o6WnF{+ZzMo=D?d-LcY+%E520h@{S$Quv2lm zFdL#vzi%PPBHiM6YB0|_o#6GgOdBg5A5emEHNx(ML9PF6I}7I)fFs+Ww88B+Hj#r= za-s@@f*ih1(iQ}qpQQOfy|1t|p$y`$++H#bGad%BbIcb$in!$(bV*uVhJ6ND3h6O9 zt>ySCdPm46x=7Sy>!o=9e741kid?(To>k+hBV&n)IGO-u5ONH!XZr3)2${%T1=n3! ze?J%Ie0=JZpNWpZV@T*pv-~XEml~?wt4$D>;uuC1!a6)bWGzFlJf_1kXySH*K&`+} zhJXZ|ss>p;I5*LWKrOd0k|5cef98LFNZ>Ps!HA1v8kt#Opo@mHitHJMm%quRhGQNA zpi8iOh`b>a=|mnhX}oW3r3O8W52Xf{GBtp0pmdSx8ic`j@a9&9GLn=b8%V_Ijx>1wX8FINS1F<@yr$KBu8%c%HdJjM{~8VO6p#z+QRy+EbQT?0XOHu z>)3Xm$cp-VRk2twtm6nmyZl;zv_m?Zvh+cf|Zm;yG^={FBjCax3mf z;!i`yY-+^xH>8do#d$@jc*r(W!I=9Qy=Mgm1lOQcYxO5Jd`-v+a2l-K2sxEgmQ47G ztknZdXWg{Up50CEZMoU6E+M`MfxVKIkISgeQVDAUVDl?|zO#F9g<|hj0oF`_bO=h& z>)K_-_itu~tQZ6vz+>AtVdSbn?SIXT3OD?QlTRq`|Mnnel5qYz8{)~Wy{c!LGI-4k z#|`FMLcSn$qpYF7w*Exk>Y&NaTpvvnljK3`znC(S*1W54Q7P<3DF{~7DH7Tn!lxlX zeK7xHZzXCg%$2AXu9XtAqI(4Ox}<4$#xa1tE;cVGVc<~n{|a}2mciFYF^4lk{)6|0J4Ioar> z8@`ruA5Q^5Ylc66WI|KT>lL1?3T%>fvM}f<3}W_ zZ=;lyDVZVHqgsyj#DyoWoKB^w($B1{Mbw<(y1NIr3%rtNJztq;Sam{DIHo(}aF9c2 zpDmChawFjLx4ZSpkC`ko2tpb=j@_SFK}l3K7O=9iBXWob->_v%72HZF_IQEf7V>Su z8)4I&{7O3D!jrA_k}^AM4gp;Onees5cQ?*p139RJ&}bk()p&lu@xK^U;wHf^h=*40 zef<0Nrv@J(I7-T~_q$y;Bd`RKOC3VEd!1|KTq^Beox%0l{jFK6D434V#6~bwC@gE^Ga3v+FPpSw_kiE zxRs|+79T%e#a){N7>w6PSU!#tVp@!?W4QMq-Jy1b|6dMcQ`1=da@JwNQ7Q@V;~O0p zE>}Nx38KGh?8bLh$Z%fpxAG`kMq(IKzGL73?`NqhZ-ZTFP*R#No%Psr9k43XAn&OSZm;o-pr zdk!p(RQ87&2+R(aq4(gE10So${;PF|D!22oQt_%n+;gMrKd4SUJ-4yo#r1iRxMMr& zw{7Y5bi|23aMStJdWeN!ZsOH_P`h{!YAFy@fsiGje)zV{USpxcRuQ7h0vg|sjaiEH z)`IWd4F$PBT6VGOFbNs?qvD7a(ZX{Gv%b~0x-tu zKQ<~768*KnkrTYuTaL$He&Y%``0X_>dMyjAo0I@$L3;f6j~9dG!p-fak4j_hS?+0X zE9G=cnKKPYZ1ruEH284R+H_65%$?2a>$B{rZW$yF9?A$iQZE~8+rMGua{Y&;K5BeC z9zXBdOoZKVdW+Lw^^Pbj(Mhq?YUu{i#%3Qjys4YZxBu8W>rFu;K3P`Q2@luB#G0yW z6z1W zM2(UrDlDiIC(QHYHqgM9v86*{{`(HqVHql-^CKc7yKh97s@>kv(cNxrW7m(|DD|D~ zU%rqdH8z$Mx#ovf`mUs`Y~)R2_;~S9t6oYq9$ZjF*ZUCD3;X1szEV>L;s3;eOEb^? zR6RZ4p5I^epFv;(S*Sb;3d!-qEPzvS1VUh)VWF$3Igl8CzsVZN_8`2gA70vho|tS9 z#sJ!Q+3-0=1=6qtfB|E{@h1-ZS}>tdQ4zYBgiRmre6R-_hO)9UQOV#zExCH67MKJ& z-!GKB?e6b?c;0wR%k}CbyrG?rltq`yvoS~N5*SxMFWROj2Bp|XMif>>(|I&{9{45At;aO`m|;Hcu*tv8bZXn? z6HYy0ACSwcRva=sVVd^lu-GqS*GwG0j(xTgliO+9G_{BMV-Ila09{1SNC-vhNguR;?9i9Gge_FS*YxYP@b8=d!+@NgKD4o{3n7Id0 zD|>%YT+cD~wYVzX(-kaAY1RFwtN!_Qm0RV%5s%JYC~hDMAOa!i;XB>%wVE1>E50t6 z*QDHY#o>on(a~wzF#N8|zM6bEh`7U)-{VkwV3Nj3&OC0@`54i}CR=-Z6`V{rc0Ty+ zuk#G(c2tAyllBl0j%{siX5BCCpsMh|gz=ZDkF403|KY4PSxlOF-eQZ#vb^EP?OV5~ zo|kM|%`v2G_xA=Gl9N{P@m@XK%Z!>od99>__?sT#O_S7UY!}y zdr$c%w`fW2UvHIvujFRY?f(?{hnJLT4&@r9Gg?*p`zF~jHKiMLT^tLJJR5dYoYxWh z?LU8Vjg-UXmA5cmOgOF@#gdzA`qPNH29N*Un2kE>N=nw*K^_fjh1oeBl-cNLnC=O; z-e+ZRi`-M8>?XA1!{B0SbNIf$ajb<}5nTK3?|;RY%=}zXT8IBB%gW%gn1zw%(Z~VK zo=9ox7~9e=*fuD)bDnBZcQ;~TvDHG$tif|@ zrHC92@LTS7d&SD4fOa25(rqBFNU+NBCSDr>n-U8V6!lQRk&s-hzaQXPg@_0i&HS`O zW`d)610S!6QGIIZ{hx^q*=9$F-(7{r4+YU55T!7(woE{vIKK8mCRJtCseNvPE-`r4jq|4NZFALbW8sZXN`2IDtzjXaa^YT! z1|_=1kgc@S6e)Cga`As(Tsp5-yH|+`#H{A!Ze-f|@!#tU_ip$vXHrf*xvDZPQx*KG z*_G?piJg?=gTGV1Zu=2xpJy4Zov9y~-kQ46SNC6X%ruXij@xHhJ^&$Zk8XynzMcFw3# zq`kuH#R7JO*D^1r%j_%CoiShNWg9h(c^zgIA?5>8g3MpI1-`oX`GzEB$lkzBMQpbK zHQZb+Lx1McF;9AL@sh`&b!Ft!9vpF3?h(%y&Hu;KcgJJ>um2OFj8ZAG+GYrui3WwUeh>v=uL zv-1+{*Kt~<QfXggl>So>8ifu@7jY{$K*vOwhn=|inLn!ih zK1n~dO4!Ji#W61r#lj<8KQQ{}subwb4p*bA(FDAF0Id8ncH+b+fH>~K4iqNxAMc2@ zW7kCHZ=74KkcsP}ka6+bA%nS@nUm0#0-6LRj2589dm1!XIDVJkuoxSBp53|qyaecX zq^E{l%^tNLUV$oGfDfr;vX3t@tGw0d?@Ar&_q=t)K zV}kzyVf_#d8lE6 zw6XW=ED^2FdsFXhtkC*Q;oRSW)H-%YhUb>GH`D!-zl!dEuBatK1-s%8c?`CYnSbEf zNZFVnw9}_YEYr@^%XhCy&{5%A+RJC7Qrk}`OfYZJ1}I+f5gm0D_>}9 zgJ{e~>Xn1{-@2y^Rkw%D?!OiMP3?oiE`EU?*&X$Di}vDa8C?ft)2T%j?+WHhYjv4Q zWlDsGC@WhVwQOmH6p%zB_D=~T^=YuHb6plhg>_@K+P13|6&6C@7YNoZWwiTO?H8@D<1go? z2eZ3?VN9;tXTREZwcN~zK`s$YU5M_j^Ev|s>J0==crWBJ12PPcNQ-=BSRCNWMu!7- z3G6PFf#d{>TqCaZ&!78%jSm7osvsHRK@2%x>>?e+CFh4Ni;$%IlCowSfVq|yt z;yMz^TUk>tAB^dSLV|Yn!G^7`y)w37)+f>>(13a#PYL!%vWYO9ELM#BU`GGeLzFwr z>=$p%QMTY1wL_C74re%1Rp_SzerGDKo8(e%H0og;I;>LA=)l?kben0AI=pzWXe`Lc zT>Vj$#Z@pLRcU`y^hK_9z`eIdAI@`mnHj$OM*mj0F>hZ_#n?5QE3Ur#V@(&S;(Xi8 z2j~?bo}%%*T(Puu@0(;3!y|f5l0ki5ad|@4ZVhWTZgqR|LI*sg!%YxwVt%=pR%F8<(v2Dlx_6DC@%)*Ni0f{veq3cJgEw=vD z`xaR-czzA~G<4CJJ_(8&<@6_+`NfgAdx?oWgfb82-ejP#E`PXTMZ{B@A}$QEKDO57 zzn8`bm(oNcl@R*~lT}nULRbsW6N`Wb%?AkyTwu)hs~O|U0`0|RWww=cc^4dDW&mo9 zX2>mMDU_ZwcCA#6#Wx12zQw0Wk|zn%3z);>8w{+@x@@LITo%FFNR!umE^&J&kpSuI z*WNy^_mXMwYZ)$6vRp8tAbR1t_der>(3E|Au;F~6!y%x{5JUunTL;1>mQIanC1@K+ zBs)-L@Imgu=n)2@aP|_3)!FEYDnra!;JQ05KMjPLc$ejr+pxngko2W^4AFuRBQ%Ex z1q>kTx-C_)Q+Omsxoko6cpM9MR6Za7U}X-E(B$NI9lqv-tpPd(8rF8^7ff&eb`s4K zl$>MLO#hVxbzV9Q1^{@hT7@L#1h)%e-~+=1HEP-U`>+j>H(_{2Ht1#+mUt;48W`Dj z+>qbCc}M08vB-O$Td0-Vtr$)&e0F=I^DldjuQTQYZ%x z7$mQD`1*xEKmH{^D#P{awoKg{e;jr&>SaWDXz7GYsac+}aR~~b+aKqfee51zZ;x$; zaeR_>JB@7mw##QfDV_^g-s&J~67)^~$TP(S-r339z?e?PK8ZD@<7M+PS?`p7iv15= z+)7Y9_lx_-17+JBFUV(R$b3{xpsp!?lfl}QdDrIy4?C^@=0z|XSCu11(CXvOgA$SX z(_#}vu*ggFPh9THmayZVzJ;R)SsAa8kP;ef>)f3Q;5PMT%Q3D1D{IdhV zO1{%@Xy+zI##dmb0q~HZ3ZXzCJcazD^A32-;w<{bkSvyMjKiDC0Eu>(s!qWh}iTo~@ zz+nsKT~Z?dzvKl94~!ash8(FOC}cr1q9oO-%YRYF4XibQD{!HD3^p}d?1{kl9(Pq< zq7Z?6b{RyDAMY+xVO6JW{x%--4SqG^9D&;&k~;E72?4Lt3cue}1dNT4;`=z5QTboB zM%rQ;cZL5S7eLO2A=V&N(e?e($-yM8ZD~Ke=8uH3U0D*nwu>{2fji^2UC`8eP5YSM ztAn4el=90dFG0@E?mvIACU<>lq;|6iZ7Jv3&)un7$qowlPq8a$ClmlZQ}ldZBbBNr zd&OGYj$6RJaxuDcZ%$D>(#UR;lfo;+kX7U1*t7mRI zmHdqekoTSQudlwo`{Q+|fGvS-?+N7+X@jT>fUIuEpB>wR`3%J5ueM+S?I1!T&{?U2 zxQT5G7^9o%e}v|ln6%!^KBcN!4uaW#blq4G1F{gi`neRQWT1hN5Zls$lWu5{4%z)Vt?VdAfqSX4pAT({~_vkQ22Nq8FkVF0VM$M zT^5HE3lALaSB-OhFY30xmq+KHUu(r6$0YRyXHm!fQ#|{B3r zMD&;Xfx3{Yx8h$5?)~40T>i14VRP{L9W1VTFCXwN{M~t0m?bU)H${3=a@Nh-kP{g# zf~uk0IR`|`C|pczM3mQy2`WC?pr?HQ!qv?_D}32}Mmy@?|1;%l7A=4L;Z@&}1S!Ac z=bvp!cx~$AARx^aVqs-kC?)zaB;a#n1W(XcS*_7n{8w` zD??lPgi6#PWZ>Ori`U72dR+GisdNgs+6TpID?6`I#I%k~LL%Ay%A0Ga^|rcS#6uM~ zUjuewjxVJo&{V+ZX_7Ys=tCjys=}5$NU(cN4?VHwyWJ+rx!1`rzX}xEPXF6^Tn>xrNt>%xgB8*sDm^q_?%4q^lRl<37;Ohn6c9aXD)Y+wa}1?NGfE;5y305>O&1i z$s$D@rvm_5z8dwH;~M4MV_5BW4Kf$li(Aq!$)Ogn2M)&sC0l z%S4(naZa+w(I>^4sPgSRU1O;b}OjHGB5I;QvO=%El;s zG3yyy!weh0w&`++baJxGC8sUr-ij~%t-KnQKIA2zI`KH#fBbt}+Y8};hvZZl6fR{R zXVBT~x#hR$eRM$8V&dYv* zJ!ny5@u0KPYfr7(Vy&#~GlQF>NNk8tOUpR)%I`loEOWDz>V}0PdwAoeH_IU=GwW z`m_7Bp2=1ZLv^|JZ{Brom^iyV5?f8erh;Z6G0N#bG9GNtNjadRW$LPTUljv}=8ZcQ ziCtx&9)M_!8#+6K;RC8Tn6DI9hP=rMkkY2Vd79U6&(>#zXAPRf zD;N(*a&QO?8MEDT_d5jcjgwsNn1EJfCfkvVCU>Q1q@AOL#~%*Al<`> z6(O*G4;P7#S z7UA2*cEQ)f{jD@w(zKRr0#w)nG6&5lABITi)W?}TnN*#;U}>;n&&#}xBe=A zPYzYAYWJTPyjWUW9ACVotYBd?cfgrL7p2`G8kWon8Ax*VM$Adhdq4@(;iN<+x&)M z*~3GQ`aKHfVLggVHYc5LKCj`ZSJ@bz)U5IFw8T-GD>IpU^&9R61=T;Ma(^qnW$8&{ zw6uFgC$3aP?UX~98wia;fDh~H_9z_axGlcu_yrP3O!4Zm!uV*n=J5n<{S6vbz&g~c$GHk4QF<%m+F*w7x zJZ;9Nqze}%kzc5(1sR?^@}>ykV%3ssR@*GMBMhW=y7HBkclxP_H?IV<|D9RgcBAwUNV@>J4~6Yf%U>i-mLWdZQThcMD_GgyILR;e zGpi0G6cB2cX+fUspf)C=j~HpFkmo|c7$A|>d!M&-CoCKL z&haWfZ!&p7rE@^}I=ASB%2oemPuKEhy0}r_Igw@Dki`N|J>SYR^Dx`robf$!ZXh?V zDr*ZPAERmSR>%13=QGEnT;;ddNro4_7nI8oK9mx1`wo9C<_=%cuuIH*&2RS6;Nrb9dQL&V)Ez|_ z&&LE&?WZl4;xUtnHUCP*x|_T5sOe};6~E9T@35k1r0T!X>OI55hck*AXU?clO}^Bk z2&4-d*vejDuG#qbtMUR(|DnvgipvOW1%%~IRvc&?mi4k*(Y}zxr-^UZ?4*8g;L=|m zPK1A3&ePo+i*C~W@u8NScD&YZOrh?G8ph55s(KjO@pPFLF?NK z<+t*QfEPmvEF-`W0DS;ON%7Pvx&vpPQ-GX<^G}w>d-mKPSvr#@BCUl8R4jRoRFocg zbGfl@qI8&l$MO)LO;J zp1Ye@c809^mQnQB3qQRjnwMM=M(O-p@DE>RB}Inog-)FW&7VPB+84FVjSCO-1_x#C zS2U=!--Td`%N=<~nR-Q-)*kKJc_!AHvy?93Y+a7eoXD%PJs+MweX#S`m2g417lzl) zgtPg_nnY5n2EVRipnCBno!Z25=QoMU>1NG6w>%@+-!!V-<6kf8sr>J&Y44-%L+xVX za)CRqsf-2=WW`9yYDt;y(%xn2Dy?OdL@5}qs*)>fwWUGAY>=Yg=kx_xm0oQvI>kj^ z>0`V>qU&`e#`&tZssA~(dFlOmLC}xLnqE!qtB?M3cX|jNNe(B<&FD9kR6PN#{)vkp zXf$TMUA%o z3iqi$ZrO62j+$=wQgNZV@ZB%YCGy7&M7|R`cdIRC7zBLGCQ!Mv(=` z^j$(TclOP-x0Z!xE3K1EPSF@wg-3mU^7D~<)9e|uXq5v=6A79hi~A@>#Rh!_ITD<_ z-Z6Oco#0HfGO`XHtjiJ*cQRbn8gpTU`otNmWLVX<(-oQ~ z9-T02mbc&XxVP7UpNTSsSD|R3sz&LKppMy0J6nL!$6@4e4B*!(I$1DG5_!V3%NkI2*6wFp`=>(tVisDqTVw4u2mG zjaHOPB9=~9?UR*}f#tOaG){O%nC7p7I7gBqQ5iXyXq5tYK17AVWvA^yg zxZ8*=X*BpNAgA^e*va~jL+>Txw(M{)c8LtIDJkFfw0B~L>2O;b&Fz17ktCgvTqzK} zfnop)LfY^@{d(L2`WCnzSUAXJyziPr}fKmMaA`**xvz5zcsw} zU~J#rW^F^yDfPCiEaQ2Xcoy9Aefj$03OBs!agGptrO;pdrF#DY`%Ru|iPr|tsMI=N z_v_lkiYM4wxy)a^RGoK}`h*De+O1=(W;3iA5nXW`3r{+&Kb7ZYPOb45 z4*#$;so}etC9HG$$)paSkCT^R4viT{gc=XFNkl#dW3iS;^S6kvTdu?89&?HC?UOe| zShK1fGxRDIJ+!)?n!D?$`(*zV^$L^mKHksX4!iJ^QWU z5^&rp6l80USoNL4t$79ed~ynt_m*G`tB{-PpgJ;HL1AKpi<1ytvB~PTkitIm0r*@} zk!mEj792c6<^=8s+rSv<)^vls`@+TZ>rno%)LsXmKcR*LgC3MY@4wEX_a-MFmZ&K5 zggl5ng(YZXCXi#JP;=Ro;B~w)#Bh{G$vKln?r3hl2t%F@{md4LuDZh?zc3oB?KQ4q zJS^Hj%gY{XRn#$QvUstQ_PU{tL~VV)eTaR^JeM*pzlm<{w^i%evm4!sz6SjB4JbZm!X+3ndJ}xi-2Cmcu%9=xd$0?~0gA2i zB#XYLCQq2l5~Ub!OfyRqjbpgH(hTy}p(pw;r|CZ#9oRF{qzcy{mee2Nj@?*M=i&#s ztGTQ2+UdJ#ToEk$X?`5UjO#92YeQ*f;j!Lu6zZxH5RVz zN5-Hn1*-;Iif@z)KM~8bcEElw<;wIwINO(Fqd}w`aOe4wEYuhO$UC->BLBcJUrE`J zu2bTK=^9Opd!x)Jd7Vt(KigBRtcp0silOAAA#ZNgLgxk>hpU zs?F!{(fED4C$_AUTO%G{C9{K5fm5f$ew%VTQ{`hW?!GEbyYm(^kCxI>JmaJ*AG;;) z+xA>@+OXl$bZ-Yqw)fA_y z8VUY6)4@Gq&rT%xcW~F1RM^`v4B7Ww6go)P?>@zMv|U2(z8a%d+vQy|%$nXVlGO39 z@L@TGar_dp;bE@cRnjZuOB)ma{8gdySX`;53(v$e&;5Ols@e$+840#;`slwu%(aR= z`29e9fOiDFakkwM%??T7+{vy1n$TA%L&|yXQ_gCwTEpjcN;HSvQ`{O4C;kaDVq;TR zTT74;Rpt@uFS|6ukP_aws#P4@svc_e<;%JJi~$QNGSook)_YBUsVye%87(~qE8;n2 zxjb(<8uFrPnE0ol{oEM-#S0XT9Uz)2Ucb%@44nqWn&kKafmTc03PLn7e`);T-na-$ zK+SXKBt2Tmt_7>&-cP~j{`dyp`Q@j4clmdo2`%I#Qe9(D%h0JP!z!6*UWvNv{d?_R zF|-22y#Ubu$XjG)J_mQ9DwsRnwY8(;ZDR@6ZdfCoFL9IOa+|-Leze_OBJ0D4o9uLe z@ktB5XYbxgaw@eo}h9fR*#gu80@;TEx(~@fidT9KocZh1P6tf;}P;BG7OQQc^{oH zym*V}ipF;zI6%|6GG-5=UrMBY&d*V@T;Fpy!o{ZZl>CR@U-pw-yM$g9T_C?4!X-qF%U|wyiq#)kvCjF)nDdFMp7Cn^%E;fp%i#tMhe@k*V#1ct zh#x@bjcA<~eF-qbSW=zg7wP>^`G1QZlhGtL4|E231pw>N}yC@xVJK3UtfMMk#%e{n~(fk?_amPcN;(XtV_&J&GKYO=O z+S@CAa^O#2i?@Li$D2rb_tn-r&)2OezXlF)Ia~j*!Px^_5jU0Xe-OgM$%Ye~U@P69 zFkO-ZCw#AmUOnwpn=XCptEr9q3=F#*6nd1A-t5!7LxhupNHVDISfLnr*Je&OdP+eY zzNjOF!vX>g5tAS+hTxA_0^;T=?;S4Dd5hr<)ywoJ!gC0BK|lZ^YXt!6paWSfjppWpX3t~*ezCsJ`I~n&+D~29n5e-~=wsdyE z%N!;%0>9IzOHnnmZzf*bJYM_PPuIvU+^#;x&SEI-&1CQQ zFi7sUs(S0I`Q#SaNbZj3$r22C&C2V}B{umI2XPshm$&EA??HTyFXt9}Gn8sX!v-b_ z48gonGfeub9}^sC%hs)vNbl$#YK$W*h^FC_;M69lMfz#RDG?e9P5{z3o_uH&9>_XB zhtcD2&Eee_H^D7!9_GL^o8${`M5f|t2I~PvlWPIN@~fZkK*t9mC(C&t%;g0Fo=D@7fPQ0RNnE1$2GfEqV7JxxN4E@K`9X4Wdv z3*_;zlRxQoK$pBiB?qE8Xcm6hLQ8Qlk=KV#5kv)oOaZ@FL6jzpF3GVT9aI0rGxc@H z_U*B+UX=+n^j*^1e)LB%XPl86TY34%iHP!h=+w=_kFaHTE+4qM+AnNemyD)g#$|P3 zkeHQN418u2mz2C^PubWdeW8WwrrX<|=`4=yIGyEyr?OKy&FW>@s<#jNQBmlfd%bM9 zzo~yQclBE_1(j#H)P+5@njE>J2H`zi4`6S;+09LI?DzDvXD6faqlSfwk`fs!*YuA= zkki1Y7N6XlvH!=-3}u@cDCucVtW93&KEFfFk}}i8@T96GO@PQ-Mw;=u9NhLl=-5k_ zri6Bzn=0oPz7cl+G<&RhuLbk290B>KC2_}<3ws0POYPId+UT0z_-}o5Ur0wvtM{Rp z*GvR=2$PfA1-4B=|0GRB{;=gbb!wZPnvFWzTO6n2ts?!%av*43t(lIsW<6W{qSpwO ztyj{}>B0M4XLY6@hI`K3oxI4BoUo{5G%{sv$@k-Tk+Ws1q5ZGs{TiMR5vaBsdUl-B zmyL2R^A=d;lBb$T>1=Ff&T?NPesr+fCDx$J+Y}Z9w+ZpH%DWxG9vepP32fQ-)o=q7 zn-mh&L|zSkjc^41+kXWxJPCfn!WoksTJ7}sBEJ7n#u;xtT7(zlV`c8jy%bT7i#G@l z0rywq7oN5qzeN9!3!q*GxB`ZP%2RD zK6qbyX+n*qdNwSaDxxrCFgHCfHO2espv|3Xv)rVsx+@VJeFIy*FAeEy#&6OXPUqLR z6hGIUnq$abYpBtgL9h8y zt2_;Wx>$N(z8X!?N@3hiM6r-4LC1L`S**hB7pPgJGoEd^$P7Ff9J<{Q%K>a$OWB zibOaEoBU}`CcerTt;l>2wp+TJU){laP)R}s7G4WRyZ&Qy9?liEDELK28IWEzbaY5<45GNuiZsq_%&3CU0^R!27#Hw12{8abbgqHW-}Y>J5XA`O zjZPWBPE33o0RSM}+4EYQuNB(~ba)Xi%a+T-#Y+?lY-e_t-pT33#)Gg*3AY7;f^_=P z@{b>h8xP^0V%To@HVZ`-3-X-)%E^$?KSJ7?7}%hzK*c7BtmX2{RHO+5HLD9RrZ0<< z4Hgb@K*i`UWK@{+YwH!!7vO3z#mL7S;r8NMMgVq6?wnu9&gh8q3@MLcUgoCBC{e?u1)M` z@4Lo-;p3#i&cBno-M3EDTmQVB;~GD1-d5#9BiqdRPCZd~9^vx>BONx@?Al_n^SgHbx}*+2iIi8hmFr-r-h zR=zZzTQxRg^xsPg%rJ@`;vm>r1z+1J+N(8Lhp{ll@+Lc=mY74aAL=D zdzt<%fusk?yn;2<&gaU9ZHVP8A0HpNG{Nq+fUJcK2ACU=Vwb@S86!)K9(-U>I#{B}ai=Lc}rzchbQ>XQ~fS7SAWlA56a%)M?H0K&tIP zom{tru3}Q1i=VT)Wxs>mC)yjGc}~*a9hc?>ytf{d-@0H|1XSR$nTyd>mOgd2B?Iby542Zz&a!lrMZIU8LO#x+2(P+ zV)G8?O>7SsyskF8(~&{yg|fP(#Y&gybKy^zuek3NYq!@n#_(VBQ<01r&ztJ77rmX7 zcFI;iXf^9>yRwQi6Yb6;abXDxtIwK_nXV@O5jYqZ%MvdixoI2icm2mdMOD}-!Z;grwDRe83+DQ<>h(}4m zcriQv7m^SHF&glB+MzdCaX8P7Ri=D@v$W)B!hs}W-#GQ7zG0GgX((p&1zF8GtTiEf9G)@@?a;TC;;62#{{&PnkJr8GLI(!8HD0FmnUt#PceIFWa(5mWMil8Azfm2l#*a{CX zxG^$tALRftF6F*jm=Nc9gbO_nk*HI|#51!Wb&*0N{to1;89WW5cc_)ji+h=Vgul$v zF#|FW*qsCGZ1HO5IWH8M!hh|zh++@E2ZG!EC5%MJ6P$us#fmO*g`UwKKHIE^3B58W z@1Im&91piHd%9JT!RA=ObG%Ge#=J~fLZO9EZ>ZlZ)~=~Z-*`g0)%y~iSC{*KpK6}R z+=j0`CmoLHN10zX-_ZL=Nlbe;mCLZkRz5@1{?i^w%DjG4ib)iO5j*(Hqc)0sy--?| zxK7n0s;eu2Dv!h4f7zhlr7PmGfm|_1oQ}eqpd78`yj3fuqS}eL`dR8Uv?dNIt9pEV zDR*_fvSPN{Ue}1fuRWD?c~?&AOYT@9wFS-oir#If+BUpOq^RvoW>C~uS{~T5ES>*{ zZFnY!S6~Qq2(k!(e?%Pdr7Bhf#B@ID@jdyHg#$-dTXGuOzum`#AD)(oEKDLdCAcdD z-(UdWpjp>2?jnb8N8)z-YjK*m*w{xQArJ6r1`e_XDq%xqf-_7We~f3Az-pJfXyu8? z^jTC?Zvj#ma-$GT37PJ>$h{q94 zyWMtt(g8kCn{Y}FE>>TC-;L{r00RYlB3D1NqVGZmz%6DgK*(gDXA&$&1C<>7zzE<) zO#DgzUiim~%et%+SLnoK5a$m-6NE{9J&svEZ_N#>n7y|e_XuA6z_2!8^V{Yn_eKDT zZn`+8dSXS`CLAMMC6^^~(_Sd>95&5_&Zh7R$s*09xC&E)6WD<$xZ@=zS?kD}Ax zEZ)?_Q(^6N^SC)p1LIW|&ZNJCt6?SQzBn&L)+T?gkq8w!K9V>U+Jg<&HuW)CKiSHM z)?OCkuUwm~FKN46H=Z?>brt?SJRA6dZ)9Mbq%qHlzNrxVMWaNS z_#-c>w{9P=Ja7)30Rdv%mvY>-d!}_^gnI?u3ONh-c4*BTz+U~2-FL?wNsv+}vD7Ep z0>E!1aD@=c$fHASEWv;CLGuvEC5qL;GK2`0i_Lud_U+sC@p?tm+Kf6JOkk5yHg)mN zF%agsmm8J2bw9kvPV07) z(a?Sp#e{Xw_zW|nTT;Kg1eOaE1T`vaVxOgydF(ioG__lAC@Fw}y$zb%?G!*#Z z4efXiG1y~wOc);7wq#cU^$Ur(=HXHHZ`kf4&C7eL_dObM{n|tSB?|PQac;dY45}w| z4(DC10BsX!3bt=#cE{T#sgtAa*@VWL@#ec|gP7E)+22svP~_Y;X)vj1fpmSF9C z=W}n3{OTcWNs8|O##KAR!%KN=4g(l5hR`>1mF7KRccrdZ*n&nxA-a3MAWt{t)9DYF`?m=md{IF>S3}N(ZeTjyGQgGvn8KE*73)gZRWtvcgAsjKBV)# zQ#2{y$k(BmdKWf7gNyvieo>U4C|SOF9x^q}x0)Ye(|0Omdz7Va#kTMw-A>2$4Z{Uv z6`IzBn?Xq-LV0ew#xo4J(>O2qJ|2mkR*kQ)Fw?!wNMkG~^QJwqvu@n35_FZap2@X6`!U18!XOmxNa^2P-mp)v|5xe4#@ zi)3s8FND;WAwkt=a`1fR{@w~CB?q{^iQH`FB|Ax^GQsDI3@pHcJh@kfl=V5e-R5^= z;Y9*?5y?r}I5JhK!<9pVqfv9DmYbq`I`0}3_S;C=gzAUYJtS5WUF1rGpynEPYK+MmOWQ{6!3cFr_Z8%bdJq!K@4*vC^MYv?R zOow-#glFh~+}VB?U9{Hn%QMCCfR8GaKvWA0*r<^}tO*keaLC(h5)m}{#c@ryw0ANF zb3M9m1^5gi6)7vpS-MB9fm368>t&CI>(`A%Pf76hi&{zNmmNsI*qC-bTxq4&)>6|z zXUu};z~SN~=H#B5loH)#!?Eae8C~%N8{O>wktFHR%2>w78-r=K`e>W#&{Ui3mwi?- z*TE;xrtajYVSe1VS@eF6-&_y%?)X5uD~~<}eKR~P;gqR&Sk3B!ruP~3b{gy+7WVgk z%$8^U^+3R0OeTUNNY6=Tzhtm(Ztbm*@El3c0wd=smxTJE{2ATElyUxup*1I`gUa#? zMd@AZ(_D)j1*0IpAZg-cK?RB|m;@YV(Z&44kqs0+w(eA+x2M&i|{t*`mJc-%Wre(MAtrPb4E*{wIH-ZmaszL#?86!T(Qk_Wa31380 zh4v>917LQc0r#f@J!#gA@cp$HXAT5#NRuTxSZ<9%dhs{DcZ{vlHwD9N6IPDzhBZBe zZBqaQ-zZ}u42H3>s_MskK?IK<<|W}LBkl-(xP1Vlnl=AIHt^hHISY#?gv-c4DO(FP~G+MZUB zht%a)wt*+7Q&*}H2O z1xdUFu?pv#+;zms&bYWkKvV$xXK-)!Dg{iWlwbc_Vk!%~0|(Wi>mF^x?7yF-=7z{^jZog@76#JUH+Ei>=7+SktMVo)^h8%zKSGG@1q6W_>OT!8S zcdmXcJE(S{y6|jEdf(*M!gFcoq+V1wGk5KpyZFrh%Gqk^Zx7S@2M1}x>iR>4yx3K{ zJrZdSOGc$E#6L;wm{0NuU$Zi_;mFfw+;;Ac0j($f_q(}ymFwNBrxn%1;_7e66;Hgf zwJJOw5}zMtkVtVy`(b(bpSTX+?RkbplRCqQ9ro)ZJA!W7&qlNZ112 z3c6Ef0+^SmGEswwqkCHC>h`V6D~Bjc<&R8K8=OnK&f_B&wHk7egmor0#w|tvdQOY2 z)JI}ei;yxR8oHC?d|Qb z!y8dbKEb4xWF?NyL=Mu7)j$f5OBE-(-78y)CC9#=3)4gQYR%KhzI zEZKv!1@f*;YjC*`cL*Xe2Zf%-IaBj<21z@^GXgq6Zf}q*qID#PoT-V^GD+J-umb`A zhleNgeYobIbXu&g<6lZPh*^%Ty^Vf#`=r!?Errh>Kk@Sa_(%D>*r_5KRgdYJ_h%i-+#{@D zw_5$x_QH7ra?zb>>v}!9QG;)&*`ZnNWRgc*mDd^WSFBczt}~KfoRh7XESU8(yQ?=y z-P?3q)l8#S;YO@zwUnpNKhKT!Z4HktL+;fDCu{Ay?mjG*S5h3bq3Oerm<&&!(~XP# zPFgaJc@>=Z`m3Jt+c_o64srA{D75qFN>9pH>W*!lV?4+6rAbv=&0<vCXJ;K;%V|Iqpdp=>i`jYmJOfu;PBoPitTq38c z#EUcN*Gbz0BhBtf2e8*9y6#`IY(8gj;3dK~JZU#wq4L0b`Bo4b!L=)Ira>ct{MyK& zZPbnfdF;@sE1WptX&2JgZ$;L(fGK|DTJF75vSK&N9{wd^_&Kl(kOQD;APQtqMr32g z$toGZ39dPDlL?SRNIkq-A4OEr1mPyC3Fz%&73chuG9mgi|6Rz2S!7bwEghtk2?RJ} zAw;nvdO%R{4Ey`C*QLxR#FDht$e9t2Ojyi#4~WEj#r(Y<+UoOp>-uUdji7z!Cbw$_ zFBe6{=`N=_9S9q2kM(-tr))9$r(3X&XTg-d|7>%&dSpl@rE0XV9bdY3_ord;h|f)N zp1i^~EFd7;Hb?*2KQ-4Z!cyPAuq(Dz@pazcldo5>Kc}OkYj6mOXg_n*a98xsZR1C{ zg1vH{hdBk&s;SYt=qTk28=m>j6v~|9sQfc@R(#Q@rGKVxPoi?8^a1%en@4Ng`*Xht z0m;{n6x`g#(4px0S_an<%CmUAQ`B_ZJe9(zW*)f+c%+{1QFE4v7jqZGOjPy5YG;Jt7^r?Uzi(juWz308(5xcyeAk@qLR(j>pT;(CQ}lsgv$ z!$zXo17i21uw^An6+|`yXbuW9b|a}t#GyFYec1%e$@Iz1J1*a8&pPe+#{#sY=W@;; z1{x&8zYvFMqTs^9AEPMQISw0AA0@gJh@D_IKN)z}B~JckG$lGSw2e?HtCb6b^$$~e z1v?4i|Bj-|Oo0QOO%VWnR)3eQDIf2U1TZ@wPy_x`PhRcFokgO67; z&XZsee2jZ`?=IsxD}^S$3}J8&P!nL3dMn%sTeSHu&rK8fZ)PV7gh8WpM)&l}fv&$z!$s=#j9RJBCHxTW%MRHVBPf;|^Zd zpwItlE+Lr5ynYkKm$PSy$t&^ALMgqaIZu(*QBQ~hAW+d7q|Fv|t}sEn-w=ybru9WRcb3^QiMwQ{1*x?^ECK{Gj3S)8e2kX_-$! zKbP6fJM?Atbi+xh7Dd;ofqO~nEH1mEIkvby^`ys|2>4Q{i{bJ=2qtPLnG~ApPJT7G z$>1L-re^#qYr4Oy&t|h6t*^>h&9q9kUEku6gT~^wvpe%wb*zkq>a$bz(~JLT4fE+J z$KHN3bZU5*J}K=$YocH7j(Xl;jbZ03^=;>5?4^q$Z+Z8cP1)uBJvi&Y z5$~IXb^R+Sfgrd8)9{rR?ffl;KDNZh5i~~tq38RB-NCZHj^>B_Exk9oy#gSNVz+V( zEj+pGz>^;NZT%FLj%XAi&!9lkM3VINFie2}iq23VJu7io;eK?T^~vQs2*&~u2w*nux_Hlv&r4b!K*ib(}9@e z)4e})e%Z0Z6*y&mh+&BvCx&V=Y?3_9clitr>D)%JiNT@5e?X$x@=Wl;eFzWIt+3j| zu#8LgtzAuFm*aosd&K?;noUoX$3Oqn@uvE0>w~%Qh+t3ppZWyaU$)J|DH{6kH>4KQ zzg@17v^i+SKF4A4&)a}I)P&zi#W7GN`l)5yZL9nTf@}SQ1|?=Is&5YkDc4NtH>+F5 zIK_Of*O5x@+pO$a_OUb6x+pc3acz=&jTr6)YQ8<6u@2Kt*7iJV3giT|GQj1qg)pd5 z!aY9qmSL$qfduDXOt-ijOF`eaBm!7MRfSy+n6+aC<3|ycMnYGxC94F}lw1dR8aon2 z+`Av{AkP%6&53o6NmW1@8U%mL_7p2rOEo;vs4YiHI2~cglBNgd843_iW2ckhx@3nN zgceUG_!|T}q+dh*T)vv3tNaDSDW&`s|+I+|z@wWOzaWyoH1h)>GN z-I^xJg`+v_UffH0evR*+*jjlWR{b9rAV9R(iDq}Iv7*3YWbM3OcO~CG8<*T-OU8tXJi^J4*UB;&@@?Uw5m{I7=}zO@}Jz@iov6O*_BsU2Pg zU7=|E;7mjO%it*X>7N`%4LCNPz$yaNQXB#lA!O!(5**tohY6Uhx?>gniK`vpKU)t= zzVdwA5xB|yNALLhwL@SA7wk(2Q%B08i-OoXaSlI=%%Uh9@G$>D7j@8M>dsA{4KkX& zK}vVEfA4DD@75$?`pEHqhj*E|QEln0vYYbH?_z?ww$<)+%$NAtjt%dbd-$PzQue|D zOBY|6EyLCsU;F6;6)W=pK2Ow)x8i5jEIBe}W3DK2AB5R+6~dthV_mzecdVTh&o@Xf zys$TzF_hb2&1|u8&9&xs=;ywfgN`mbBOWbfHF9!!seVIGf4<6mHZp!`>1|Gn6c5eq zi%2!@v>MM9O_^1j>^7B3Y^td@E0iuepRFXFpJd~x!rd+$G&uByK2OM)N%l_f*~0ff zN3kfY9L?zrLXryq$U+M4j(3o?7cTyJqd${Rfgu)}rNGweaC73PA%0^Eocai_`(vJntODltbqh3bDbx%?D|PW z>0ln5Sb4qg?5A}xhSWRfdb#6@iVWZ1P?RYGZ5;?c8Bf7hz%GH9j*yBtn*m$|lv8;3 zRv^@8Gc)rm>CdVvDjJ4{UzA#c*(I3>2B)a_(5_Pn7zvTf%8unyp)MM^m8EZekmiP^ z8UiX}6BCtX55KZn)pFaDuDZZExZFQOyZZ!R{VOX?AoxSFYR@b)6)Kh&2Nixw950xE84wN9jkR2Zi zB0T^@cxv>Z9VPI&8<6i^7`AbN0#IKI|GREe+2&rgm6YQR^B=KaAd}b>ZGtGwO!o>e=dgo%`BmT{SDZ-O{Z2O-Z{K@@jW& z?N7e^m5+7ZOhkth4eh}b!ShXy$A?oy{c_!s2VN`(^u&p(>GmG*e5+7x{gUfiyu%RR zrEPave%+Ya5$L7c__TcR>L*?Gve!15mFm~10*jrf22m7;^(AM|DPfKF@| zCY9hLQ*@wL7Fj(>AxaN050B%W)bomy(17;&oa}5zX;sR*-qE$mrvvw0@TwiJyz8NU zI3Y*xdh;RL4w+UlwLIH&s{ns{gVza0C*K$(3VW*6dpwQ2V8d{-NPID{cEbxV(Yu3c zR6Y`B92H_^?0vk)YIz=NE6y0cuBR#%|CjuCFoOB`xhEsBS=**h6?ZgW61jfMYktnp!#1%Q8O#JxKseV}!o<0U#I+q<1;}_g-+kyW_L&g|Rqi~PH4tY$1ZVZ& zm5v>(0ZQkcoF@LjdNPiCnWDx1cVl0Mg-BRf*sU9F)X{M!e5L(X-RMGy55L~q^RHZ^ zqodQ;(_;DUoT?2tnV=~tDJsJT+|pM2o(UPI#J{sFSkj)M`^_t~4VfO!B%!8jPkmV_ zrWH%XmcAbcrG|J9;s1$N7LWz%Av+#pLVdTkem@|H7(g-&oIT4(7P%zo6&f0huml?U zH};DVmd{G2AQ=Pm0fN}&73zTsLdm%&h+CcstpD6xsSev#!}D3!8)K$lyR#6&A2IPJ zT1ceyKKON~_5PU({ZLyzN*hjOdgmF>~7Jit_8e;wM0p25;Sa^csZB?<~Exdl0`Wc|`F{UdOTzJICo0;+^faOUPLi0*dHhQqoi#Rcq^J3m4`-mm zN=K-{u{Y+{==IsTUR0Y!B|%VJ(Qn=3KZ;ks>b$FF4r;!zySCw!z+@DEMTE$+$@tmY zm@P8RuabD^bZhSkpEx_lQ^cX37Pe6!bW7<5x4dX46^gk)-trA@GF(oNCk*6guI~+N ztlRo2@F33*>B^{<@@}P0&7GQ5!7Y5j0y)q6vX4dHisLM(^@9j zbZ3pq^P5K-CHk&eId;Fhjmk`B(NXG-FA8v;A}u=j)8%(^;t+ZQx)45G0;<@J{kVq^ zV-s^5akr_b(Ig%OjW9(aM^S7^>|J2}#D4PKonJE8cwV2EgwHMtJM>y7?Cd14)&QP? zzKJx<2tnLl4(aY3u7bKhXBWsK4thdB_j491K-cd$<0P;gaRz{#_O95?3|DFLgHEGs~!#_yh zXthCdBu<3bd0VPF_i-JU-!=vKBvw%&%x+GYOkIe27`t#IQ=uq*V zPx&1m0^}tnbzCB!9_-M6CDn9@W!K#<3tQ`Hqr+)7aUNfpivp?B#zieg8?W(mhSZ+> ze@wk~Se4t>2TCZ25(eE0inIa}iLRzxd z<0nsEfbazP&=QYbM{4jSLc=F=ScpDN$QCv*G&F~|;;p#D1*C%kZ)rWiMndV;)yCC* zDZ|u1-aBxJj_jD0KOIgxz>1v$(-Z0?Ll6_xW!Y4H5d4ckJR9M{J7Is59r5zKAm zJfflo=J${k5MBh(+P;F95NHR)MFNp>*R7i|Oc`NYXw?Bw8zRE4f@DIl!3}~dV07~V zw-=0T5vUywO_+dyUje5UDt$#ieW>r+r{NYu#~t;t4Z3cFJ`iNyBm|AVW=T>=EJiW! zUi$UEu`zF-H5HD5TO=Xm`r@sL1WA*{LPV9%Dn7V3OIh9M+7mZV{d3bIEoh9V!Dm38 zhM_}yd}w?wi-*HM|A>cCN1MTXk|9ts>!k_Zwd;9jntV^nF38Qa+CP4|ST2~Q)j7{z zXIMyMTeJ0RQG&{2LOINm#%z6PcIaGZqbWJeF@Riry_w@HOi%tQA_4~~^`+mkKwrTD za)RSW>w*xV3_u;an!3G{&L+`GWi{Y=nHqA7WQ4M#|T zERnFG!cUM8?qhiNpA453j$O8>e<*}R3cwwJdWM+VRAND0ydOxoV3@d}ddy3^l%AC~ zphqJPDM4lp3;kwg4;7xzI#fG=n4xk1aN8*JEdUa5yIf;_Q6d915&)5W0o)e^c0iWE z5_00yDfDy$R7VMrBCIIwl{-)nG7jSEhZOf;mo+^RZMZjA$1Vz^DVQkXLOugPl4$PX zC?C8+sKE;X+Az$h&jSDiybq!ik+=hO(+v$7flSrLWf7fa1omzGVYPSJafDrVWffWdtfM&=XMH?)bl_;uKSR+)bRYm^CK`t#R z%>>gR%k$w9Nkk4>u>r*cJ+?Jd31~RJf(#qMzW1Oy6OAosy|(lIJB;o+K)S})Tv6Z7 zQqLYN$L`mA%W*njQv_Dti&#cbb$GSy>_QA-WP;D2u3_qfk$-U$nR~`r zryRs{chUrZbtYf0zOz&9SQNo3ZB!i(g?tQf5$`P7d7py!2qLkGYI0gxtUWikr;Hi3H$jGf-GQu1wSv6Tv$Zz4Ib@gpX0C?sNZ z8``BmzarMrwBxg3n_jU=-JGFT5i7DCvWk~+-|4Lq&*}l#85RssS-+KVx&&wQ&u6!; zxNlmcM+%N3B-N!s>@kl&@iRYS|6agG!ohPNMd*RJV#Kzb zcESs^wn&Qt5C$|#gJA9y5Z!?Qz@pd=fjEs2vpR6}1Ca1_k^z1Jgw!G;BIM$l{NY0I znK8nV0*c>yxOQw4XyHeR&X>Qo>r*XYPm%-B8gMeugsj1sjVe3=MgSe>b=W^ac3G+_ z?l1z%tuX?yPbxr35Z-ckjP18+dYU`DbTEx33m^BBx5?8Q?x-4>^E>#>lV4_C^$}Me} z^y#vyu8Ar0jM`q|BIlL{cbusBVaxoRB!T93iEx9`n?(`W?-o*1E0tHD!FD&24B9j_ z%h*;giIyGIk-z}s18E=tBt6QThsp&9@Uz^90wa1*T^l+s+yyWiS(72G1w=$^EeY3< zY$N5<&uASyC~`mmt@y8uF>#RjY{wQrGemO{52(n=`$X3*PEb+d;K?A^oP8bv#zDyF z0M*-bThuy}F$7aFe79m zD6M6~V869h0+w=5&ik}d|I1T5kA6vb!b=Xh!e0UCK($>U713uh(TAIk{6w zlhvjPRt*_@j zIc=yihwbMr1C+Ax`+3B07%3qjtT5cD2qzsgQ#L| zb8`oHN%?$FAeOhh=Yg9xC=1R z!5#tnsq6n56eLj#=E8eO!Gd^i*-B`FiJLy{z-;jxeZ`#{S}F|WB!Utr>NRLvH81NF|Hjg6wIsIp z`SPb0MUFX0={5~3F@0FOyb$dWH9WhZ$I$B+;I4drx_wfzKcGgPM0@{O=UIr7d83@- z@Ig77iEF!2*u6(f{Db1dDibl6s~^5md~Y!!bga6ZHuj}B_&W_Ip@Q>H=%<<>&WKZC z1F<%|y>b^jUmW6ESo=rb;Z^1vlgXoTZA*V@Zx~QQPWZ<9J=f*P<&?CC)Dm8TcADGfx&tAh0-^!X z(|1riaI{QM@>`7g@0auE#b}zA?8WWDX8UBUmIW@Ep_hw75e}GSG#bGbh@{2_If=0C zAu*h(Xv@OIKp}z_&qucD#8t>fNe9nRhJKr-HzTsDEFoLet@9MJuVv<2iA0~|la`_K)(YfzNkNR?rU zkp4rDSY~*FVJieRiNWxlB#7#V!^;Cx{7?!wjrWiGdBB8@T9~y!S_rCTN`ikW1k@LY zLP22G@`a!TYw z`cd$L_ZFt2)~TM%yWfT9rJ}`YhcWx5dF~q@qMG_=+gx*=>RG%HZmy8A_ne&*rQfgk z(*3q$@W-(N34{s4t{{YIM1Y#;iCZ;>H$@YDQ`ugkw z0=9D1pRQd)$cn3CXrgjr`FLEz3OeOgI#wW=H5@T>x`z9p)L9&284c_XU+A5AJ9(n74 zA$|Jzy_`iwa8Z8Qlv_rQRqH`Io;M|En>oxn87rMTLuMGKUN@PvSxQN0a+*X;tU}Ml zgem&2gOdiOHNbqJ`A4A`01vJ>9gLC#01v}5GJTcv-3^CLU^{yeW(gEz3ssViPEIH_ zv!EX{{$LxBCpg(5Uqs2Ryai(Vt~$-!0F!{SoW)5~~N7|f{1?sfaDpkG;X0qrQO$ErNqvmw<` z4(NX%FlUr10K*+yGNlpc@vKnoDxP zdLblx9KQ4!sHHB=z!4#S20Ro%jX-=c1+uh)if*j2p4IRCP91sD^&2ixqsxN5_1X%$ z;*BpHxGoI6WRHz;{Ct9*lB@sqrDaI~9R6NRakw5@CU)E6M_jjD+qcb_;j^v&`(drx znV#7zo6*Ol&3BGIZqIbW!Bsg8b<2>rP=4F3mHE>nSZ3*gEQBCjt#}d_7yH0xOg8$ zF7E#6FC0Ak%xiOX?jng3QvFdQrm zC>6oLjI6luG9$GJTs)vTH#c5~htmG&0JDuj_Z3J`npSe70Vsggl^sR~+w$QG*H5tV z78n$w^l7v(13Uvp;u;Xx0~)X$@=$j+Kb-Me>)ayv%o_<&lY!TdCZEVWW_Tz) zB5mi0(c1mkD7;%lYwM$doyPV~e09s@RN+i1TF-YWrDQazccHS!Xe-1^?&NwkupEyn zDcJi4W8<{r?)+UIyXViVCvMN`%=Neq%*!UlMiFW`;H#P2H@SsROi@RYyQ-~p&l6a> ztFvQNpH57xEk&ld#Y?5?3y#-0Y2u8(V`Y+yEDXeA`k6UDs~Q@nm8oHl-L%SnxN~j=|BMVcH(umEHJqI`JNIM zJ7f9Q)DD(Fl#>BQp(N?&1G$~EixuZG?$&vswm{G{!eZ%%Ldif)bVWe14!T;DL+Q^i zU}5E@7kxqxHzjD+wIN3tz5quB^_+N>TYrA|W7R-%20vk|4zNYI73=Ry+471z~!dd%Nz z!3o{FBHcwSz1lB#HZ(fOF-L+X%HuixErH!Dx?^NFy4#4N$HrT>*;}|l5#Qch9@m7IoB}QZgWh7n$^CuMRk0i6$YPl znEljXB}+J@Urb$CjeAm=&CuG_wCB07LR5!ri%m0yS&F7u$K~X#58^2v%yUU3QW2S) z8>Kv-CnW*pbcLOI4Y8`7c~>?D=<4snf{AX2zM=m64YfSv{Q zrS41wo?&7N0iUipC;?a9Kcg@Up4y7b1`N4yDTmMsiY~OMYT-~C$%jWYG6%EX&955* z5&ejL`jhtx^t9q(rI7~~6#i6m=1v6)%*AqjZ{45G6r{&JLJA*o9CXem6UnGtBn{nT zVP<~9XFHc(l<8L3vucj%6Kj&pbhp8f-K`&!Z<}ZDSMZ&gei~&z5y19Tuuvt+BHt^R zw^L(G!!!R4MUAY@Fm-J!Ll*vTQXI)~XOo$Nj?38xs<`tYq@>lr9h`Y6rH8}VopU+1 z(461c>z26dYPh4eo|rTJbbOECrWLIkAHQ=EdMs(yR&+ z*&tJepqdwOp7?AopG12S%5-G$Q3|2U_-U!2Pq*=_!hyKjWks|@-_T_>?->-~umkXp zkabwUp-(5wd>IM}D{Ff*v2PQaJl$zin-7aQH03j1yKEX z362$&`gn9o2i^`jt`fm4zXOS5ptvGn*>42e6Of5#)uxRt4B9XQcF4%$V7mu3q%j}%P@+3q|=C4jTnSM}+-p8j+{X;Y)!%{rG+rBAZ%M>-x zkkNcGIj~%z=cb!v)}I19lUbdLRj)~l#fMBe@`h8dj@|uPS?f66TG#rL_DBzL`@Jh5 z9an0ST zuq&|jS}*Gw+fP<}Tx8;SF(QKO5qb5fE$nWYIXV9e**9WdApwXQ4FDjGVY134W}$0> z!b&8#sr|dWF?{&A9JcE_L2#I-<>#M7n=F_V5hV(6U#Gb83_KzM-3E{g3q2F}Kx`~vXB;Eb|URPC<(%3*}URRCZJIRjm*G@#iA1Y9`0p{2e3 z`0BI{JuvEUzFl4Z`)+dws9mVZHSc>`f;Aa(6%syI=do+?kI|=-z1dp0$HkumK-mu) zd?xf1_nG4WcHyVsmJ zf1xydY+XWtA$3zaW-zIf(~Hx?vXY+Mo3dUpV72Gle+(TJ?&YP^L|M)mo#x zRismb+J}_5yx!xNld!CcZ;AQ`mMvuLK*}D_ci>M%FZ%_vj)4FP2nJ;CzZgOX0sV{-EK;uk!wHt6oa{oKG2r^6|9<{S;WF!=(P*~6(bf+sJ5CF-npsj=%Me=~M0fD`+MAltprS6+pT^XxG zoH_Z!hxhvPZ|%%wL=a$^1649cc)?bOqE`NnI4QsP8*<+M&tP#1V9DmId@^@cuGGIe z!+|n$pZs|LrT8XFTLHO$n4}PRNg*uh1&pn0*7O7@?F9DCCrR&8VEkV3TzL*h;#)C0 zRwRRh99;CALb?IceZlesvJ3a^%|kAVI9f$DJw?3h z+I}e?RjbJ0r?`J4auOXlT}s;IZ-fkKB%nrevizD!R>tt*+?|%bE+|w5 zu4%c`^MP}w<7H@Tfv|0bcI+|nn<|Fud8-pAKgU1NT3*N#WnO@P+=YtHGtuSR+XEpqnCpsaq zHUnbRbf(6>9h7I)N-__=&ZaXumHq;27zD;ng4DlW%X_c4TJ(l9LI)7a26$id+7;+S z_=41UvmGo1^|?A3u){m-u3LEg`DumTd4wl{WdLqVq|8IK0=V`AkzK6Hxh+Bk4l(2@ ztlPV=_iJ`59UeYNvlZXn-*CkTartnioS^@-ys?YK&yYU%(82<)!=CYCw2lP@5fVT| z&R>Z*U>@LwK)L8J&=%@dE~Nj3Pc|LYTmo@zuZ+??e-s!BN^OrgHGfrrdRa);lth`q;pLrT73%@qhAce>rP*4W$c+jP8bH?{fR_*)NX!Qw+XwHuVk@b}v|w=@%D9`g+v1Z}ah^ zW|kdHZIN7l$U1#O;CfQgI_;>Got<4EBv%8Pw}#9faQ@QFGn_!LB*-q_rKf-GEYgh& z>`ay{@744!9t;7Y0RyfXw1@9LeYz#Jps>bLrA-fG0HBEtI=`UCzI@D!2_TP%Qdh8) zo(1*oRRMKK4F-88N!LV89bEluKg=V}!(NN1bJ(u!_BV56UpDnPlvQI?Mjp&pjC}S! zIz+kfkhBd*_Qc92ylk!??kr4f`1B^_ zsZ+w~_-GEZt3&X8H`tSB{w^3BNh5pcy5>>JI=aT1AGT2ba9`DRebe-o6zBaLb={6O zo|eX1x7G&9ai9YL8 z`@LRkJC>!e0sYhd0&@ORh;3Q(A>!1ZoLAE zNYqG%#yl7qTpkS?qKtTCg+Q}!naW^){{%7|6VS)m0(p*Vui*Og?VN20rr||S#&ozG z0R2T$-L)LqgBI7a;U%x;g<`LR$JDgcX?A0^^p8r$x9a{%jzHTItTI$1-m)kd*Sn}- z5nGz#2S^NZN(1`}?4pPO%PBCjrOJ3BMN&#U{%rZ+yzC#zzh%7@lEjH{}it-YBio+Nw3Ea2T}=B%50HA=7GEzYt= z37g^Ch+AAw^1PL6f83$v96}bAG#h@Gu|6$BtiJ&UZ4-gGiOnc$^|dLi?vAcekGtEb z?Y5GVaHD*sKo$8*~Nc2zosi%GXBM$CrORup);fY0_HRQp(#pRII0T>s; zpCDR#|CzTl4b)rsL);#^2v+FnB5?jlzML|mf!}aPJUL2vhE=WV?kwg%}Y&P){XeNbNSok4Ao2bB~#Jzd~^oGMVBa9`BYqR*B&Ih$C!%N@>v8~kms}S%3 z0$aETj~#bb{7MCiTqF<#=kzLg4bn0*8!HrPd>r0+z=O2E^J#EV2~-7;W~>8#D(6Rn zCKX*3|Cr5R0yiaCOL7YegqxLNdIEGe0N^BZSfB}U0X=u1ZVu78@Wep!PvXowR91q* z{85exs0WfXb9~t#D%6c*N&Q_#o(S{KNbGMXBiU4i;IX;iOk|f+$DIru*L$DoVYJOI ztTAYEji#TEA;u&(gcgYuD&A!oo5t}vFm~@pX=Xm3@u;ru!keu4vd;P1ab8x=Pom)A zk-nU3Uj3ot$48^W0H4gGJVLm*$qV`)JrTy&$J}jskN+ws#947VbH3uMhT&9YwD~@?NxtXfgW0$@DN2=O}jjkmLG4d z)AVw!S(3bbqq$`cv+(5B4=>!Jc4J%Jvl%tf>DxMGIO%Hii?Vo-mz9H~`}%a8{e*HJ z_KE*qyN#ekJ!G-j{;CN=skEswpN#_)4ey~0Dj>E0OGFB@c1q*GxWfhQ)hz`gB6wHf zCmyf?7dL{hyzti`LkYllmgb&XPo$_v1MMs!0#&b+!R`dfZwT3KnhJGP8bf<1oZIO0 zq9yPNU!!4Ti$HnK!1n_va|~7|B-ujEE$}QNDG$Gbmit!)(;@Wp9aB&LS zU2!T?I-`M;a*N{!b|ts>(|5q?eANqaOjGBE$mcpMvMTcJ zs!BBLG#qa(JQilT(XKM;SEgyEo1nTgzbPd%n3eomDpiq6X3$l#a=%}~mosw6hW34Z zTQsw54ZjH&-nr|8gzWU@G)^sd_k8=!@I)i#OcA^%?nuw8#U*HUx7mfjp~^n~LKw>< zC)f&6_bWJy>Iy~=kSre^u5idc!;ol7ykL0-Sv(y7X3n64xTr|63;AmeoA@u=`JV788o3e&RNJ(1J0>A?&YyXa} zd`d58F$W|CV{x6Jkuc}8mZu@h?Cmc8W)>b`F)pSAtg`Kv>(+s+TZ)fQILlIe`BRfs`zO zCi#zD_fua4HPw$F){2#P3Ju8VuMoh=BS;IjMj#^|%`-s&+W)Gq;dyC z!ABK6Uav##3i=ngB zYIt3M?Sdi990Uxbm}UieSPg)*xIae>;QHKPFSw)<*_GC84G|IsX{SNw> zDxSB^ZZP2bP3ycyBWz(IMSm8WHBprVKYyXd=BrnsjoE@JV`HUca0cOg2#G_#{Q)TL z{R=c4cp5jdFb+Nnlr95#Et*+^qVBpR*Z=V#Qv+rCJR33=G zu}eU;n(nMt9o{cyd&&_iFgjc?8gh%Xo=V;u9O;=tMDrhfv7}_~NsIrYsA0#N9?pwm zKLx89K8mrQ=1ubPD9h(DmPpLhxar*diAdO7%`w`E_}lj`k#k+TW@aQ$1;sKiS{MiB z#OrWpy^fxe!$yW)JJ}=IvKnLEeai#O&iw#`*BrcLim@?KS3k>kN=jWp=w5pgG3NM7 z6=k)129#k2G0kPI4K#vkWEmtSB2?VcnKA=gdGW&6<6?R3dc*-sL+E9vt}WgFX#s%W zIO6Hp0(mb%g63e+s{lf7fSfISrSOhb??-YOPcmgu3?KYyu z)xxfJiQw?{1KrH4$>q8d`Q$QnZo8$FHup6rKlT0SUn8{fHNp*6PUITzi@u3LMZBDN z{ruE&SPb7CT61z_6_&o0<UBda^J5ESpQsQqmzNz7t2s@4uZ< zs^RA+a_GF--*RU!tVeZ$c!+ZEyR)!OhwAHXOjr9k%*u}VgbnxGdG9FAyhIgC^KxGH zdCEs-3!BQno(TvOcn|f|m@N0&>9UT}3oi_Ok|37q4WL3k0|-)ZvxkbMhh zy)OWR4JBr#rcX_*i=OoW+4KUf&}_%4`0O?O;sji>0SYNS8pluO z%Dn)q!3Eg;QK%8z-_=TQngd8sR&&clgXE~OFm_HGV5oL+VU{_2(E^P$n4!>~xVb#a zgv>QS27-PT6rk`Aa%U0}liUN}GwO4NlM7u*3WC)RcoI-)D$ZgEkm?^M9yvX|a}a15 zS_YC}T1e{|WF_8lMhp$ag&`^la(_VP{;Ml_=l1L#;X&s#8T;@HlY#Zhmf7fdS)bYN zmW#HD_6+jFa>K23g%ZWfJSzihB0&PWo>leN%}58&W8I@OnbZ%O7q1%U_I)x8J74=a zPxAk_Byeb5b$6HGb}4dF&>gZ>f0?+Koz6T@YkeF;EGKkDzf%8nF2*%8mB;w(1!}{T z2wt4Y`9bauT~^`y?HhXU@*aoWN#0M6KU4UaE{jV`g~EpA>72KwmCU7ziKcnp?x+X_ zvob})y~JLT$TMv=tr@sHqI}w9qODV=Nm16VYp<#4xYzX-&atR&USTq{?DjQfvGefC zD;;@jm=-FyR}D}fGS7h%BJY~zGA&$6$c|q3aqwb8Qn-RMUobe*q5CKRsBn}+2}>8K zIcSIb;d4P2G04&aq2x>WO)zkk*$oGzO6^}6GV?eS^ybq2{?-_4n@2*-iwA$Vao`7C z1?m+{wyjrw1L&v?94wzWY^CT1g2+(Bc668k2WA0_AIkjbu7vRe44jY#aS-mQ<4FrF zKAI7ra1;@F zDS=*ZE=<{^c0XIY>|i95Q(4;kiinMvdgs9lMJ^t1aV;x#D2woLD@a`3E8`%zV8gOb(PEKAy z=CioC2GF6{mUBQD3Y@!xm_gXUQ5;sydMj`9gNk$=NR9%zD2i7{GXXdyAJiXrXZbx` zP8H$3Xgv9H^${U5ogtkY%;jjjj5Bj5Ln?WY*`|2y*`VHs^mHQN#bD`dPWSH|JfjN# zixBSLeZvFWk3Z2V0|(XBd-rx$CtNoQ%LxcN50}OsKwRcqNf+C4y3Ov4qgqjd`%JA@0?=x1a>^KcWEv& zg||tyy5u#a%w&{y&r8;5s>vj*x#d6CO;*eyRdepKBGVd*NNUE!t1l4?R~GoQ&bm`= z%29c6$dg^Fl1@D-Qsl95;#u-q%@&b(HXY@~zDn<0RJOQmvH#LUD13m6Z@T&;BV6pC@Uc`Y7X}Nr9uAjLnFu z=lLxLHm*`~?$n1r96ff$b;l~tnSD*fn2EF8V%@tN{9+0lIdjJ4M(%oh8O^h%ikM~& z&sf?bS2vTA?3zHP?Ej)XcDB8bT=th;>UtTST>#G`dn@CKdGzQ}DF4Sk`m`lo%`M;> zkW#m$rNtE@$L}9JFfL>G$F!XCah~IKa<&>C#u&wLq|ebjLvDL(ck)iUNqd;9WuS^Y}|R2(YTU( zzR+oE0eh@PEo*)C+tsF1yUWZ*5qs^)f6tocor~SL%l-9juM(Yvh8y=&uBMlV+)~lM zGVG~vQQ`Sq+bTrbyT*~1WREfipbADFuId!>cGm+A2>t;GHTMjk0COMn})HD$y z#suR_*<-1Od5uh0tAZ{4m-a+sf1azRu2o7NoxQBt_3B_DN zKUy<<0gxyVf+ZAyeqa+3-!!({;ZjN z1~4oL`ftt})EDR}xpCAdnf6iox?3^z{P(sfe^ z;uBb*n_PNWY_uyAE@nVsxG8m4GMU-XLJgBn`F)dQFZpOC|9ATTd%5%Fwy9M<$fZ_! zG;-PZ8-+Kw?6{yDT%q?q869*`XR&j4U=-wo2{O03$1of`kr#@2Q<*%X>Z76`3oFQ} zbC3xn6W~`QI+$gR%JpSQO^vZOm1|s|-ju7+-Qt=y9OE3ROvlZ4EG`8*@O^sS8`DX6 zJZeLUfw6}^$HKuPtgg2^L}iF*z4CWWt=v|xXx^BJ`iq_bObKU|sL$b1Y*yyQbL3VeYa5lB!K5ux@cp|}nw z1Hf+g6*E$$pVNYg2Jt-(CXk;B?FeC~>H{cQfS_3ns9b5nAbD(d`2 zrC=xjGRZT;eXB9)Y!V07lHZxFsl|fIYHT~`^u2q8Tq~>WFrF`a{g$ss`OHpxyxtJb zQqaL+R_IbYk8jF1}k*; zYhb5~@aGsmO|J1BZHZi_2n+*TE`{Y@prQgx>eYh8?AH&AH^a&k%k_GK`s^0wM0?*^ zS5jxzYVX)Hsy~fP^1}={GH1Fw;|IvCoU^xKGJOxinrh5*>C-5!0Frv-p}J)3LJ~BF z!VL)pcem#jyf+{NVhau!+-P z8hH=bIs_op&tn-6kXU!b`{;nc2WctckU=>xu-m_aEfD4l6k?A|n_!u+?b4WkD2H<` zDlS%mm_INjvJZ?xa|ZJAx-R6|ekzv)v8XS=xDS9vL>LUnB>|@&t6VsF_hMq+AtiR^ zX_QAs_lQYsZt2;v$lr2B1#0W6Uz=_WsBOd#pT|hPAvM9?x{F__Xy<6*C37_jGF0<0 zn{>mB>N6UUZ>77%?O)~zA z3s6mVts?k6_ zriV)>XTeZw#Pa=H$_1^Y&eh?t!qw&4Q^Mcsb`_QzYTl6XA6^%vegvurj0?Bl-y?(= zpkTPd!H3gx?uvkxe-Mh`kx}8$y&> zO?^e{SG;s+a5s%E$GRrlnsrNAHglyeT6X`9BG;Ynef2mcwMU8WbBoQzPo}uVi)NMv z+3qt^0cCpSs~rwG_?tt!94!RJgNrUU+*x&w*xZa%>qAiH)wQY5v$3TDSN8<(x={8Z zaf^bT?OZl~Rtl56Xi(Z-%2Lyr`RsU<=YDdu%2y38<17cxcEcdno)HTD*hVe!UzVp_ zYT9*8edpw6pR=>v+zuPWxzWvbRvq?95Vr5UOFvT_(n)$;;lE*C@v30KXV(*Uyo`C_x@_Glm|JD^tK0ptcN z|AnF2jerGLjVh;sT!ln5l&l2rEDY^n-awK-q_VicI`ICAi6DOyn9}{E1#4do)6me1 zSZkMeBy78X{?^f<46;H*0t2%FuX&x)00`!#*1vHW&F(>5$yG?<;JEh==t8Jj27!_a zkbBTcf^K9$+kt#Z1Ca=d^B@1>4}nb)VC07XIF3B6@c2=rP!d2o3hEY2IjXK(te*{W za7T&5`+I{sYkhfMD|MR46bHW*d6eL+{?%n{DiC*GklNnsrp5WOb_IPw4fnQT!VHaIa4XrAD&cn_p_zxg&cz zHr8Kpgulu3NaX$zHNi>7!6GyIuCUaxP*`!-rA0MM{nYUwk`ek?Yn2WAh6H@`eEZ_` zjw<#Yk(p4M>uB_!Qi0@*#In}|3Jy^V*_6yJ^)a<-Pfv=J_3!$aK)h&r+VFr~SyK}4 zhs|XD*gegd+g11%yq|SP&uYQzfR-3b%S))b0~QjGWYoKX5EY2P3Fy^e2{{XfdB8O% z><(w_mepUwx!jPQdO$9lDmx~U497btJYlf{H`c=^Uo^F}aB!9GU#QK!x{G?Q;F^{P zqdXwzBvh=Sa9I)%pj1`Vn+Fj9VEvlyOod}RvEfdwy?yELi7>YFXE?FsJiDCjPBMSmlM4ENYRzV7Udnyu zFniW{QrErfxh~d2>65>t^X`a&g>Hh=zBNWzCcpI^`0Hg(^txNm zGb?j?uX0Mcj;XnmJxxsaFMSiB987xrxO0!}oTg}k)}xG{&(#fOR4R)ahP80Sf-326 z6xn3Nh*~^j2KaX5q$Qatk;4lDFxa3V?y=GGXg#8$e*d@%8wCA_!#ebbbKsA~(zm5X(6R>6!F?E5pA&?3OYGdN@ zCc3awzp76{o^LZGjL;$PR!K>>eZF4eEtbF!&`;&DT|L$xy9LUfce%OW-YfL>_Bt$& zNT7yZFgt-hIMr*98`%gB5B_pMiw5M_qwq-O2v!OLbiPA52nD3NbA1&3d?a)D_h5Ss zbw$h5p7PpVZ$mda)G!Dw*RdfJ=G1gxbsz-QPJrncNl741JoMSx-+L9z(KFIL4%<(|A z=bB9-ry1A0N=>0i#Ih^9rYz78oV?pElrb--pM>j|ePi(< z0Zw7tm@9{->p1HWU9iBTe*yyn7*#gz@ZB}z(VAwI9`YUJ-g;f+&B?&WKcG=XB9?6< z;lWq%N3TXa%=z^9n+`4^cbA7;!D z#xyLjv@2}Ud1lU9u%|z{&)EEo39r&=FIQBA#$KLCG<{KIml*jQUA!|&m1Qg@-Zp}XOYq;Kqk)C z-Qrg7ouX&PHNnpR$k9|k>SYa|ZF!Hojl^bR&*NOytlr~TA?@k7p%xrPTybe}X4x~+ z+SqSfP>T5LR&DuFFdaKUUYqqtb-pQIvP0#aMXPilL=%jERd`VEQzx{z<$l1tC?)8f z<6lHS6m>@7Wkft-L%`W@8lo-1gXWC&tP=*p`+auq->F#W z&Qf9y0%D7w56la0$~u!crhMJdt!Op{J8VotW@-;+V)UaO~x(41pT97z{cN>a0L{Z!>ycwu3 z1#%<7iiLm(P@t0^(o$0&gZD0w&8;!_T5N;3vO&>q04Iy0$ ztoO(m4dNjrei5L$RZR*cHwX=1fR$rM;*B&b6(E%kVDywa+`&KC_1xP;EIBB7kLC1o zFGmsi03$K+>-mZjD4XCMKc7O?c0<0_HLBh;(#_R$v)tioH>^6LHXF#;=HYvD zBCR#;XxBsE=`G3n{7&E=iz=)3zMBN*@Y3`<$q7!0=6S_24f(rg!>g>l_DrYW?A_?G z*cJO_7G4cry`Q5rEQP#XPJB21gQ|UP|H34gp3}_g{GRxOZs*I)p+CRZT*+}&@f$w1 zIdTlOd+ogmS6%X?T7J9}w~u@ga)&kfOTKV`D@Hi0mY3)j*M9pkc0ogofV|KRXFp>e zV@IL4VTAKcOOgvW45pn(eZD619^aHUq!ur%xT+MUcT(!BZ)~10XC<^0d>V03Sj%qy zpigT@Y#5d0#>tTK|M2u4;9T$T|F{U9h*HQ_NOsvX@0?GAk>4 zWF#SblaZOdx3~GfpXc}a{;%tt>pE8_();y#-p~7f+>cSED5>O1S0xdC@6kx-LZ>Y> z*qD*%YF!?v>?m~!#f6vE9&^=Lnc53K*3%2^m-cr!%xQxW7BIig^2n!&e@OO2>)^Sj zg4-)Z^jvI>1v^Bb9HQTi{5fbzj^;d1SkcT4<7CzTR3Jzx@55yezXuY&ap435h%$}a z3(untG8N(5z%+#!F*sdlpj2@>7L^I1_JdkG1*i#9ASP4tAaOHhBT!F&Tb;>}wGyGE z@J5x}&xIIxu^W2Rd)GDj7$tlVQJgQLHmQ8bNk5sx*HvyGkLl&Yeb}K#&(_K$$D;ca zi|fISPrr$F4EMHYp0fw zsIxr+fN0dpIV(`Xwe|~NKeqe97x9)QP=N+Dh$wN$@ucvF)!3%+4`lE~Op+a^Z#-C_ zJI7q{x%a&(4U4<0=4fnPlQko?-O#V41(JEAEX~A4A!}a}p)n~@4|(U?wR!eT6hBdQ04_ZE0Ak^{lAN1K7qv z((fA-6?@tCgdJj;{K1@H0u=Z%XZK-sfyN} zIpI%hm7na#)FXEz*Ax~OIxa3unZ3(eFj7BFxy`ChaP(X$BW|QCvJRAXR{cr#f}@voerKqnd(PE2sogiRG9=p9T;ZWWgV;$ zK+eMTGw$2nvfwJG60;?es08EDf2s2D`9r4^^eG#d@Zes`bmImA^lk6~!(9L_rFX!# z17ua4x63qVc1;-)bBkT~@A!-kCOpt30_&S_JWa{7C%K-LhX~Bzh z9{5qdl%NCD?@GCgBN{aPNa|DsQ|cz5`@Hy zz?cU{8Sh3ukguPpjbo1)7bOI2J~4fWeuNcvrpP{ZAhx4_NZ095!=WilSK9Y`$})9k zQzZRl%gNsGU)-1n#TOQZoX>wYd0u=)hy+VJqw?x`>>Sy6v;K$7(rDdF;cj_4b<(~SlIM?)N(Pv@McvoH8E zgGpSL`~N(hk(UFSX;z$oAwo0$j2R24l^E?T^mLFnjTm1zS3}%Wd<8*zAO^iv70+t? zhO5|W8mbE5{Sfy4y*KD0nXW2yvqDl1A|pZOlCciGl+DB)$U~^T3)32sb$adxc;0bz zEcv*G&^ef~DVn-|7Z~0K>JU83gZ{Mn$t}lac6dEFpeP)z7ii_86&m8opy(E9f8qsI z4D33{E?<71n0NuY3MdAsZUD2SNt#q5oo0@|l9=Hcd=H&+YVtk7Nv4 zr6E6=(r-di*Sc7bLsifc{gG6ZUqabK`?o$n8J@YlBVF3(IL(~C9RB>LZ-wbGt#XH+ zt7fF^

    *==ToprJHMHudfuu8KCPk69{1iBa4V_4<(3@AEDa%HY7EUKE`c@dJb#sT))#%U2DKTh7&*7l#y$Km#}eN%+q z-BT=8JFGZd+T9D9XxPoVJIGAsMcLWVnjf%9`G0!k>z8wK-rCdl?Qf5C(rfhM&|7sD{KY}i|{=7^9 z>R~nUoB~{BkcU12A?8nZ7&XPyu97151Ja`2^*I-Bf`qmLLetVNhPP~NDJR&@=k`@% zfutbJ>b}dcX6^#@;W#NeZ?x+@*?r)}0_KvO8=l zUF=>ZN*mVms}ze@UwW`f;d&q{1*L$;iYx8pA%?)`Xw)SBLnK{=UyoZ29{GuM9SKT; zLVImEz);-HWFT|zqwu-?jE@hFH)HFX#`i=#d_zBUoc`gXDc5MxeI$}qXgIGJy04R~ zi*Bb%Ko1d)dVg4@m!& z>GI!+L1!;I`Es}>cHh5RV;}xbtOWY5aal7m`KW>+_8j(lX<9v25h zuL0rLi)rE$cu#wOd9q0Ph`>ixrKjaU2Whd&J?VN6`hLSU1D5EdpkL` z$|%ys!<}2A!Efz)oLvX>`*k3i?Eat?@MsjeQ{Y@id*FYZ`yyP3z5rWai0|PejD2ID zJTKvrN8A1a>v^?joxhvewc_=S%8r1_r-2^~f=gV66-xE&7~f8($A^>1!KXE8Z^83| zuLczPG57R;n6^-|muau^P}if49Gjebd4~dn&tMOPFi{ZF7jU9}PaAm~MrwEO=yH6R z?%0@3h%C>|0@OlDbmf;SVmm|mA3Emlek;A6Y{pmc-!n2YBDyOmIFW!h#QY14>+cEdmL;8$gzBU@l+Cff-baJRLw`3Yh#q|dpNUydJZQctPq=dw{fl)xbB36Lw?)B^Ag+wA3?q6b5S0don@OE#W}+IPbPP_6{tB)1b;} zhMCSl+RC=|TICWKsIh8Ws+lOgW!iT2_9=+!UYbBs>5K0? zFt2%Y-`Sh3NapEuo)&8d!p`W*tR+ahKH*YKmFE;%3<8WsoiO}71ESMsqK-D(^MYn zHLhjCMG3o{bQmA<#nk-$yhQn*-CO}T1Haqd=GMu{{bpfxK;F$sCH{wCml5_lzRy$a zegFvzA}0p5YqsSWxc6 z8ar=4w$q+eQD>h%Uta{nR}+k7{sRp#u*RuGGQB#aO2W>{%)3(~@-jC0boX_3Dw z$|JvI?Kjw0#IGM+psg_Cx8!rHRmG{9cx4c8@VkPM;=$6ED|V4vpibzVT_8?~y7_F$ z@kW*3t^qzze3G3so-mQ~hYuelakXPaY2wzGl(FB9p)>e<)jogeb71$ma-2)sM@GVJ zg%G+wqJ#qAsfvCW&!<7Cgz|8^q;V5eNj-mbd`N7Ma($aZR3+I$#0z1_*X5859X0?c zfG+|19Md(}=77;6{*|?gag{~UGSO{&VGqsa)i1Rsme+nv0z?u~aXNHlH+5YG% zqx6zv*~O*q7b=#;dIAChamzSZ%A0_M8y^14yp$mFGV5K6o3F(0Enxn&p<9u$qRR0J z?2Gk?t{0jG6A%)MY<2QG11t{qCzJ@p_J3KLa6KSSyq|w~hQ8}fTaTVv9CFs}WlSO; zZnzrGgDXEy%2y1DsMS)Fyo~I0;cF567cl-Q#obq%AVxGaT>5l)T5+4GJV!FuP0F(z zytVL+u#lYhk`0BeemxZT&17CC!aJ^Nhx zZ-&`iu8I?)sSesLvuhr=8mZTPJpAR*)8M~;rW;V(5sR>h&Z|mnG@Xo89{7Dke!a{j zFH)EmHNldd>h@<5G*l`iiWpuZkHiUC>?oVFW4B~tDDZeNZN2g7PIFiI#4fb5(dqv` zEr3@6zCYPQyEXDFlk-%RM@AG{~Zn3~bj-b-uOX*nv z?Eq@Nv6h2guQpP)JJba!TrKEO$Cd@Iz=qm>o~x|c1TANyk*>RuE{#3Q%a@JRrqPK4 zVk-$`g6RTVZ&Z`T;yXvKhKq$wpMU&gg^9+YN{3~(e97A`&49upp9r6Ti6(F9ep1SG z9%V+)+-SijIb0OixXP#S5oPyp0{4?+E)?YuNO9v{E@n%j>l^PM+gnrCi2gavgEo zGfr3V1EXPBvl{P0#gn<_$>9jxtL2FrMns?7%3hmB9g!6l_4;`*yNe>8K|52v-e9I( zpo7-jkgI*>qFUFrlAR(+F3hsU=(%(p7T2Q@@!`c&Jnr#;#mp?Htr-$88Z(H-QPuU- zf=;qfwfqE^S0Ds{#v-NmM&gVQxyP&X^M}Lt!yB zvEa`YxjnZpjm;MCh)?8ho}%Z^ID6e;*+d5=X_)A2+}TEoqXbI}KuFe03w*l<9O#kx z$(fYqvm9C4^`YCv1tisiOoCO9Lx-#cY@)t#J`ub)KX4H>qj3~ z2X~gn_xB|0495~mLG;&OeuNw)cr}#YFdfBq%qSm_FqnPT`Kq5=DuGv!x%qFe@;)yU z<(I(8xKyCsNm4%J_{7`n3hxP&#;&rW9Cw-PwchHH!N9RAL=HSxZOb$JRxzIwHEbCD zNac9~!zlAD0wVnku!8g&V!=KcoOYudnwD?YzBPXH|HyEO$&tu-->-}C@ekccmRbDI zdr~dVp~C?MXH3 zDbt$*rErN&B&`G18%S9SAQEJC0H)b$t)m9#{#Vv9vd$@VpA8Q;FVga#IcMN~K0RDE zmYno^T+jbN#@LnT_|@4fb7fY}3Q<}Rp|d3cS<7sCy!*%GTFZ8Ers+&hV299bgT|2@ zJe5RV9DAU+5L44N>T^@D79wz3&y?=^1tU^_@iju!@qUYRGYAoS$HqcDBv$b4!1Lt#@^#WI9H7JTg@Iv3KkVY6J0{+v8yH17%_{ zdk*M2zH795XacNhM`&kVWQGR+p_da^gZ3s~K)(T(CFb86u9yS{!mtvbUtHunZXYR! ziWyeU!pBk2K21I9jWt!Qdb?B&BJp81a_vvaB93AGHKy-zH86PQ_)=a`0b#aH0}qB) zR!BLlBI36)U0F**NzsdQ1LK%loe7eu?3$ba-cbt;r$FqYi-4&Lp6TXi3*kF#vPS*m zHaWWX-V;MD3~%vGil(We=zi3&V5bX=4{WJMyJNgZSW0i&(|>h)J-N0;n%`XcldQDz|%3jKIM`Xl;#iK&%Aco%imt z3^-KbYJsdE%i4Z|gMkcl|4iW*umqD~>VSMp^NyHjJBx!X6-_%Cd|%caV15D;f)8M6 zPJ!PNYMSj3?wLo%W(0oeP$2fDDSj!wRFVh(JEM>tQcw}1SPq^O1f3As*!%WROoYLd zhu!uO1dxF`3j(Hm20$VNQ=IC<#a!?@{Dibld^Y3L<&(Wh;owY85pNNtp09Y-RZO=Z zwS9_;T1{A;y zKvZq_{XMiIrJ!_Jgmia_q9_sq3QD(hcO#%TsnRurD4}$Bh=Mdq3?U`b-3{+P&-eHK zeTOp4xz4rMUhA_idWie4TBO<91izLOjg~oRBiasY_a*$UJVU91kD|6vk)+h~-qun4 zpo)$tx34~Ewk2~Ivo*}xBxlBE`?cW4oOfA}T3y!)hw%wq(TLwa@% zH*Ao@B8hzb{gVl&tCD`_&T&XYI zM@Y=hvL>>k+!)&Om|qet*Tv9C&GlqMK`1EvAIe)JbbE^9gN>^%RD=+169&t}VMN}G z%eR--Aj?2TF9UT_Fay9R(5j*g8Om-S-ez0eNnKvz7nY3rTd&u;GNiMe?gr{DIlsI{ zg{wbI=vNr1Cdv7y;=zG_RCouWZ-R`%;R9>juQDu+cbYP35_qQ`>pngJO$00MyB zo4=Oi!q08bB?V@(lEXOPPb9Y{`+5iS3huZ4O)Wzt4`v9jH@qVwrBlyVYTP?N;uQjR0Tp@NJ$Ubm~>hY?_? zcO6`LSlMhKqd-beAS-l9?=a4}NBmh#(9HK`;pDF3A@{F0mHeE%<&UX#ojST7?;s3;L z_*##jStY)=scGO@75ppN#BF(es7RSD8zLR=Fw+@C?bFFX#zkX z%zXLEnD=7!Zw2!obAj-Sw=}XAaU$I+8ds}iDi6dB9o^5#Rzg3{>qvE zv~#!TioeGGFs;LpXyITJ2csn;xod+>%-i1UhWBXijeo(Au1`;%q<{B1OT9_YQel>| zg)c8{PQ6>6{|wI-StYRu6Vxr_IAO!1G6?(2lw%0JwX)T+?)a-;qtrDkiZ$d#|L|nt z)63zNF>rs&xu?@f=NNI}#yj^!@t%FoCQG6RGFDAFid+rJ^n#RygKEOVLSE+1{}ynvKn27b$h^MdNLghoDnj( z2kokULGU_&V+(d6AAUATbpN9yz$EHD@_uCdH9Osp*mqH%Al<-g-i~Yq5_a9i&ir9i`vGr4D%L0}~aN0p96fwp^3BPvr6C`cRPa^#6 z#yWj^;bH$@sSKD^zQe-&i8uk~xJj-lMQI`-zpWvsw@n6-vY-P7nBvfed>bKzPs37t z?@wlp+Obh^eTdJ{-I-=I970c0L^7Zr5Q(FJVP>V;4Nev964Q%Ws%X0okJH0m|5o^_ zL?Q<#OfqGU=a(E}()Yg=8!Hhl`7MzQy(gM_M^0x`WM(AAw14ZRBbKm_F=xgDXTp#O z<&1GRG0FUeS5{wskKER&!^BtRI&G`_D5jFNq)7T!2hW!Cb;c3{6Tc>RpU|Ct^cfX0 zf%-xJQ1V6nDu)aU?+Mtw@q^V>3d(Uofkp`DNPt;6U5d7_Zi^U!fR<{fH1I!lML3`58|3E!w1VcC&z}jL=X-v@Z$TQ16pvta zok@}Qqz6o%_>U8KegKyF{AI-pz;yUBy$OOP^kAv&PyKl}b3BxW^%rnvhRrlvSig=T zyhR{VN(_k^{<*7lpWgo_;npIdT9d0(Z^~y*9?W2&BK0CTgaNUYwe&G~lb+NrR8go^ zWG;0{8F_p5B{Ma&9GCYnTxDrfBDc&aaZNoL;>UfRH*?=XxANeZ{O8M06b#yQnqSco z;n!=uTYAfQXH8o$enzVe(FGYw#s6Y-7=)*bxJN1@LZ(uFA+k(dLh3Y|mxwYfb zzjjnWcZ#UDKvK2JBE@pW*y(L^dOWiD#^l~It*KW(I<7W7LSg;(Mp}vYaK~qSmbokc z_DHVZ6Yn7J^p0paa7pj%U<44ch%6ne846##p?sW#cei-~3@FHeS~vf-`( zj#SWr??Fj0SVx}3^UF^o`cvu5{5Ex0+cfS@92OK6DI)Dx1{dQmrxMn^ym6I8>!Wf> z^X=380OnbO-3VO68oQmt6Xo413Fn%Eas#@9+dwBsYWgHI$x0x)b1tRbH8GdFKe9S4 znJWl~DhK!7^Y$J^Z10h7k%Qt>(+4B>@uiGLfz`rQ=ea4iv}l< z+zZ?xVq=FBv590FIo~fP^3pFaX#d8D6%OuZ?0o{(G@F=x>VsKoQkU&_(ekQWo$ za_9j&YO^bzDd-Ut=i!7(&@{u9d$1W$%=(Z$qVK0Ta(DdRc|wH~NJ8vX0z?n4;jU?+ zof!ok%!n!n?4{I>m6SmDzRci&-FcTBPoBIi8@*kUXV2awBNv#e3>`|$<_aJs%CP1My$?4 z(FCXAMke#=1;m#C3a{JxM5OET&@}upan(^Q@);r3E{jhQfP+T1%6<6v;acr5`YPK~ zZW0U)so-v5E!__{IJqHW_vZ})IDAd1A~rk?F^wbt|7dLI&N;dQ(_dz+TyO?I=u>dG zl03b`S|2ucEmzx8n?L6JIu+N)>z{;~a~*7_BJb+oj89(tq!ZN@gt@L@68$Kgg$Je4 z8&&csjkMP99bLE!UoI;5yLNN}>ZaglDvX916YPkP_vZZ_dRsYYNJSLo!Ya^Mla&t1DR_PygLs%mQ~9JSIsB?;TG{{2yA#A&xm@L&^q2ta++{`!M zpO;l+NCdihTiP%ZmseDH$yx5bwI!%a+9S5?GkTt>%&6Vw$hXaG@fX{8CJeQhdK;&( zMFcZ7QfzOkF~YPybauy4#+I$EVJ>xX-tfmG>IA)><8763K9cQJ1&qp=s{fIO>IiZC z^NWPRSv~}$2KovnqF3Hx^72R^$OEGuJ2!W?1@ldEzX|urdZ0=X71po8guwHF^~0fk zJ`B;9kB;TQ@PD1)pjT$u#-)5d5Tn7C_FrS6`{oQ9)f9bcPm+cNNr#xv>qJ}l6W=PX z!^aEIM%C@F)dCd^SwWxz5QjpG5V`4U4pX0S*SZTswQWO8ze#i{DcQ~*{X#+e!&BqV z%lh_`{U@mc5hy%HUheix>=)g#<7T-#vXwX;6Ax$0;@gUFNNQEZ9GWJ|TFE ziJLav+ZCV8UA}vqm_~sb6wMZZ293XQ}BjO@aUroUkv7^Ee)m?pL+gn z1smnH1F7=x>a>*oQiD`_da*_F9a|_k3>0dZc|7lTv5;$B+R(e`-}Yfd`mM_w1fXWt zQ9@tO_B&qsL$LSG)H+oyKB;Qg{VF+nU~-;M+q(Csw!oT9%y)gu0r1^Yi z{)Qt4dH)lG^M#8QBimoM30;U-Y*ON}6dPVn6CaxDCfX#gL{6bMR6UH2E-^_zeHgtx zZj&7!_mnZiR$a1=_a&xKjvdS$Sz=;H-V)j zDDT{7GqPuRfLm2;Kt#$-4+fx>3nb-(+P3kNaZlcMxk8-YfxBA;PN8)*~ zamWf9k8V4-W?AqfvJ?du&cW}5hS#tOMy%RMu~9+I(w&wagd+j$tZr%8$0B^5yGd+! z-y?Uif&w1c5+m_#xS~NH10@7V_5NbCZamNHlU_AZ9+3Y{LT+Ay;_FZsR6gKh%KH519;wvcJ1mD>3zts5 zQD^a`u$DPFDqKBiqxsPMnI(&4s92z*w7;JgUUEQE{&{&_ z8riCuAGw6(@dC$q#0m4RDu;#7U<{=nU(8X*5aN(N^J_cXV(h9g&Jw;k1m_xRBGte9 z*&bE8k;R3vul#gf-{6HY99ktc$5( zhBn0$-@Ns>)@!^Jn=9Q^=YJmUPjog@+9~Ab%!A}rr_$Dh=OOwJMPa(oFA14!$*Gn= zivo={Dv7{xw}1A~ZK8qoK^psDB-pbi5zh``(CB$v@I*rGL?um65@Up?BVw5ClZA>Q zjMZ!$-QRXTP9jmhgUK>X>@cW}jTjek{Y#v0a^?`R0^j$QTW47jX0)gd6+dRkZVe3$ zwdg=+xt?FPq2Lt3u~1_Bp0ka12e=lLpWvv`JKS_!`v8f!By_u}^3 zYiy<+v}SnOpo(*){PC(|{~47RStB{jHcU?yryj35LCOT=yUPeHXc~|^3)^SGpM!2^ z(QWw)Y9EhV<4n~Oth4npll{i53uARnf*Q`>o`1LZ+osouzY-wc_GVWN+Rpj_l>}-e zJeJ7x7u$^NG?KbWMlVxosns+JXuMc5{?V~kvwx?uogC%0z%k1>Ymc#Daq<`NwH>kR zJO!I3_+gFOq8QDeTpKm|BvL;b;QJ0Yv1YEizXe(@6$Kp)|DUrb_&^<)Z9Z&Onn?h-I);@maCSh&7EBzxK?cYV6{@OyY9{mwha%ErZNC43Xb))UB)o43*EqNM0r}T$ke z(xe=i+Or}FITu|^KED3AEp})hXN&4#Jg*>ik}#7}yPeQUi%IA;HLZkf&`-C9mt(y( zZZH0z$#mdnQBQX%+A;Nz*hmh9y6Gobl%(Rq0y%j}I6wTBuH9$!Ps0;FSa|5>I;+YQ zt(fV+&}Ql(8D%1nf2c68DX%~1*>Te?KDwuvj$>(OLlkX-M}AaG5g^~788AY4!KO)l zT}v%=#$sQuGnnGm-#@<-P3EHQOb84k@)TUXJOX0&o(p;b_yA!TAl5kWc>TeGhUb4= z>5sIeDHB#nlcnxA2#7&}4vw#FOUfr5T$J*&eA1v-ge8P!3~kM&{=P#438n4b)d*9} z5$YXVY**8*-`6W-#8BEvl7*xupvOJg9Olyuhu-70QPMC&KqHilp0EkoKPs~t1CpXg z(wa5_*5P?31-|BjTflcng3i`rc2rwzvB%64YHEFl4BFbyo$)~`vldCOY$P?7A{h4E zbuiy(HG1Wqo22uCf{GY+pi9rf3HPlWU1jTX4eM}Qo<#Rw4Yn@G0V#TtvNOEqzGbr0 zaM!wbPQkSyU@d^nOa{v_b}uGICoF`)XzWnKvuj;Tag>a;u+lYhHKMc;e@e*u{fWXU z$v^VK-@$xWFKAI{$Uo!OP@w&YBUaJeQ}BsrmX@gI($mS#(Mlh*`TlSHz5w4laZA%x z{XH3sSu;P2S%x2tJ@9<97Zty4IQ62`#WRuBTCb!q>I1nSH~>7ziU|yN)WO@WQzWsz zaj+NlyTQ6&Bii$a2OO~jhi!9YPmpk4=rewdKHFC9 zHqw1@oW56F|KaXzp6%p^XN?tf9;8kA<1?B64j57o7aMamvgTx+Yd*NI7>3){ZhD>C z1_vDJUH|Aa!s3`Gt(upV*FVhXu2TCpF2VwR`Wt z6@|&*{%%A^!i3wwu)I#Z>QlY1UNx0XoU>)pXLPauYRhei`?!xadB1dLezu`e(_nu8 z-BaCvTW-;xYT+0-HPdiyY=c}hpXpBu5?TR#-nxw-ait<&D0od2dUa*ObDojGbwE84 z0B(qS1%t&^7*WAC4vY4yurQdY_ePqZkre7vKtsEbLmY#nB^<38`11!R9hWc{n%*1k!jg&ANy$i6AwE=kOjY5-e?d`%V|igwzXFUK zb6CnI)b8I8QCFkm>bKFp!%^|Ukhm@Q6Roi3TphYMvs7_bu`R2riUzK8?01gNN4&Qe zs=jbq`!s%e8fP_Nsq@~}#)LN7kkF(F@2zbX1Xx;UgodPox^`Kla=)9y}0lZiL$xfcejpi`Tvxv+_H1HS)}pwWLRjiDv#It$653 zH{F4efAdmk6ldYr{ZATSm2WaKC*OEN5pO%_mChh2gomk@b^8QUh3Q7zhwZN+JDmm;=-pnfG6pU|RY_UY>h7gyXQuu&A@skTk4C zYu`XIu?rKBRx0x;?f^z&eJi2=cDzmaETp4z$Hakd6u-MRfesqlA9)tilH`dB$Vn)Q@oBKOX7BcP zb}+D%!cV(O@mF$fWku+-9Th6uFI+JbMCJm&#Z|^()c{`xkR9@k2;8B|$t_Bt`q1w{ za#9bZ95?3Ok5S?T&kjk5y*zQsD@b#!c~IDcUwiD^>DZfcz01QQ1xr+W89kSPR~_L+ zj^e4kJDD)bcysk#=4Y%+`kDEleSj9T?i^7_`RlmmpPNs$Jv^2=$=RxH$dF8Iuiu`a z3tO$;B=^f25^IC4p)n#(83TV2Be;e*Iu;+E98jt_FuE`2SAsqJ@AGwgsUo-47rIXE zx95(R3u=2J6!fTf`~hM(q824=+rKCT@P?6?Xpv!s^HT~Gk!<6+-wFCLF99FThL*^d z^|G^enZvv4!qMLnQS|`^k|>Mi;$OIhb&6oG2Yi*D*AGG;t$hYNLwB)hi6@fO4i-w# zO+nrNJouhXWdXI7M$QDZg|qfQ#Xh>KcV6dGlaD@>#$M@peDqFV__SWmRgXE&C_nIl zcjUHLSY})!?WcF-UhTIN0MnfT;sz4E1S5xg!*-gw-V8FMsH&19GeGG}7$^ic2MhhK z0{A~*MvR?{>mHye0G)IJ1?MIqG=!1Ad4iNg!F6B;lE1C+$(71aPQthLe`pHu*ZIr| zqMH*Mc5Z*bMS8tK1k8I;PK+>20iXii8xOjLm_G2+e)#qF&hyAGzvMqU=5R6beABhL zYB*h9W{#F9a^dl5IMWmru)4s5cPdAg#*a%eK0e-BWR_CJ^lnrB{^z`#L5BF&yR^1^ zF+D^YzB?l;=#D1L^u7CER!D`Fe{OxenQf~%71Apo&x+O>DR7b4)j_T}Z(g1J=E&TB z6wiZtK6Y`hsN2P9#3FC(=YF1z5bnJ|xu#gGk+;y3BpU`pL&{3foI5lr4sK^Ag_2EX z51niL=s{a)F9>qB=+YK;1P~aGW}}4tOV-<6SOZ#Qb`O2b@q+$uo~9)vqAhS49>I#J zJpah;AZaeQ^2yC%xF4>yT@5BQNM1fsq2=`vG^ONn(x2it4fSw1j0SF(w>HcS) za2`!|@z&}usM)Hy#Y*5VdCbqwUWfGfuu1fffn1HSx;c|*=}=hP^a}4QK5{H~pC%+6 z9tD-+1M3rk2-$I|&{thT3&Jd)X%Vsb$iJFNbke7E{?vJd0Z}7U>}oEmWX>#+OUe;d z$vYkk(hCg~AG|H?6=`IK{eOW7mre;jzyvt`BF?;8GI(D@T~fCsF9(M_Osw$rQHPeJ zCi)<8k>M_3v#GOFS^xcG2AQ+s=oHs2fBjSD?Qx=JfeJ=?f)2%HO}>EXxK|$+SG$&g zC(h$*Z1C8XXsY|);PHmGx76^*`C;q;2?aN;N#&C?C10{*886vmpJU01u$o8BT7!#T zjQ<5;2S|x^KTLz7iOf|H(?mTdxEgk;FJ_k5FlIbcj=6UxE6RpGNtf8h%Z#&_*OO{;{-rMGC#Ht)n>~XDxSBD|Dum>@qF|!{W~5JpA7N2^qp`m_uM^{p`9sqy z{T1!APCUNf1vGSD9_qUWKPPY%j`@s=C!D*=(#LPq`0}g=QzKC8YRCTY^Xb=*`!{mB z%Y%ipTvM%6c0FS=p2WNiWFl0)N})mjpY62N)0a)wJkDHX)HHL6Q<8J8Xx}xR6JY^a z26S+zqxiG53ah@FCBVu(eYzF+2MZ{8@rChHgTnf`7Xa3iJ&;?sxA@GZQ-^O!cW}CY z{-H(I7q3YaB@ksoGm(`6va^{>SkxwC)=^IsYdn?mdmmlYzswUW3DN&Zc$L2|BPr{o-uchUx*ERP~AycD{l% z7w7SAw6HcY$%O8%VPI>4H>-f7a~VfaZTZe&)wl z_SU_mPI;DWZ;Rz_NELS79t)ka7?sigaJHLK7uHDIhlOr|l1`o$vjn|RAgsa8JQJ*x zaej`_J3u0_UeZZuH44N$U7yV#RX}Zn{q27cg3#ug6L>EJNS~Q)^m*N(H|&rLmdC-7 z8@zV;0zRKfD+xl_L>;9id@ZOU2C6~ae5tPA;VhCcm2L!A5n{4+gb-s&uis84bG22$ z2v)Dev>oFX)t(s9{!<_}*uJ!ygvf4;Xqn<4p5jTqbdK0`Pr09^!u;5LL+3zdpj{*Q zHFhXDXpd%IHEZB1HFb(37J!^ElEBHw&>ia z4h?{buEs4H&=Wa+ZoNzCQGWcvTFjMv6@OI3v^1BodH$1zvUkW)l-t{^=B);N8vy(n zz0q)4N7>a_CnR7B=1${Qd(rrbv=N_s$ii9*Fg&(gYl3omN-tlth(wzZ#`UmOpljY9 zU*@Cuxh*{0KI5t&Ww!3b^NNu2u@es8`n|xLr@7W_{_}~Lh14>6-ExE2j5c?ClHps# z7dU71@B-?1ux@^Zw@5330~NW~F;nFN>pOyJf-P@n#9-}r{eN7bJDA#9dJnRLAHDuj zpC2a}Z^gEt4{@rJGI{F~TV8dlIxnVX`)yNgq@0<^T2?s13~m3R&VO(9q4HwO?Qy;F zs?~}ycy@VNu&bN5?N74C{~f(*@XUw{srm++vHzLMq^_0u8cFohDGEKg%3uVrQ%Iqtg?*B zRGu;%Ribo15fN;ZPr8uhrvEKJ6fMlXE$T8pvrn`wLl#c!*&{yB5YIh3gEM(2Y;y>J+upCSxp33Pyb#m z@Bi`q{?!|NO$DEdtsYD;wDH?;-{E<(-DxVI$gyx&1@lHyN$~V#n(7_734=6XacSbc zNb1ydGp(~c)kC$a|Dt*_R0HNj!Ude8<E&m0PP%E};9 zMw|Vv#{#4YTj;An5JR*43#mYkNQ5fzNDE6}am2yYw(*(Qw|$@yAps!nJTNBIHiAM0m#uD#(TcxR8rR;*j#P!4Gf%E(^u6qrr*DFM7BGh$tL~ZZsB~< zUkxdJH)H?FFzMr!(*Jerh)xmyaq8p-2?Ys{z=j3!o&l4Gc4}goDSfs0w>q{yzD4Ph zic@4h9>+S01m(6Q)N0I6S=YCpz1`A)Ua}gbUb0DY7sR)OLH2Zl>>-Ckk}@l_OLv7iFyJM+gb>ggHZ3%|))!HUI`1 zvCDJ8mxWdANy_WJFmMkF9|_~J(U9D@77i(0`s0{p@_3St-d@q9Tc$TkqlJDX?7i(_ z%%|-2Y_Tw&id^mE|Gb`p@f49PdQ}`mEfqb_jw!%Si?IZJHVi8X@FeYVyu#>FfZg?E zp1q9m|Ft62ZtLQr3b{J59kkn8=KjDoMv&<=M zgJd6hgl$)ef`RWjTF;9eZr!2u_9(lPsX&V;TL3BtxaFkmMSUUtCZ=EFanWm(@R4bn z&+m5ab1$+>)HnmvI1vS}f9A~kR&2t>eKRFH{af`s4ix?(?X6$3p5r+5r7I(rupedy zt{bw2a}Jxb`YT^7x(+c(+((o&3{-!QU?kc!*gvIqn3VHp_~O8`mF6Vcsm&$Aep@3tGxOoKN8mBo+TQLqw}a#sXmC8C!F0tg*K&$tPruk| z@`Z--7AkBgSpVY)fBUXoj%Dggd8fs77KRHu_IK~HMf&FU=FL)_dAApf{zCzP(Drhx%7Oq!1H(*9Uf zL}86B5PtQAcqan?M$|31w5$yGxFSc5cDdD6WD|iDF#?vR02-M7S6>A``9i%@x;k7n zzD;iwVR&h8__&pLwLv>jdO8zQ3iP2J!AI`{OD_b->~MQYbZqcH_e0JZAR37pR^W=> zjFcbBB>Z#xfm8LL7#og~bs+7N1{mY<5ywRREBht)tZ452W1i*_3v{G3u#q3g9$iMb z{MvS~pcR8~8eCB~+GNiz+czAt!ny-FRqN`cR{m5|!tBlyU?PV1qWQ8R-$4O-B%mm2 zJVQ>p#H~)dm6BDW3J2wYm+rf#Nd>do`+l9(?NZ{AMY41GE3u|gvKPzZHspLo9A8V6wzsyFUtKMU5nHdVt<}@HF%X%Y zn`y%t<+@~Oh>68>m5XWq`&58+?V+oO1D4D@CdFBh5oNxeIDeP1k?V z-B=cfco=D9EDA#_QeCNf z4D27#wh7QqH8%00P>8$!>=1oUTXhAo4-?t>@%D}W4%)A*t((S7zV78>GjDz~;aJq}#Keph+_3&~f z6CK~N^#RnWP@ByE**IB)Lu`!KQoaf2WM{YeOhDm5l!Z>s+M3;o*KA=%;NOhzx z_Sty&t%T0%4x`*PHom;|Ahh%9^O&)r$~~`4>oh`A&pheu>MUncO@TmPU%h!D7RB*g z9I5f2k^6(&RBd8vhbbKE8~ZmvH-P?uw#97pnUScOa_hhKyDMcB|K-csWOwLS)sx)h zo^86HqVkEZ=}%Wah=S}a0uixB8UHn_JU2?AvP2m&5b5L5pq>fc%~gL$?_+p$dHL^^ zPg$3hvbdYcE99-ey1|v1#E1rYf-wFGHIl#TNI!-`_%6Q_|a3W_Gol8KX~{&5iNuUPZ>G8m}C3DaufFI?c?n z3m)?a|Fz8^Ed_o5S5c7YPS%8PMs{B;Js{9UBZ|$eBNrONG{&%QHm}6KT0T+Yy-pdw zEYD8$4G4>l%>>je(B1-Wud6`8w-zBBaO1q7|Lj>PtSk|b86-8MjPB?Bl1N<$O*mo- z#lymS^qdmvVG!G+M4B7iSij>3Tz;&~9-e?{|NfQ|ICBX0i0bOqB#9b1S%qc5SAoUt zE@&zU?&u;V>l8GQlYumWkUtSmE=1`2D7}V38e+PX) z+#Eh|lVNr-NYNV@9GQK=SwEWJ6jb6OG`x31AAd?e0qGy2JC#FO34M&940?^va8bw$ zCxwKtq?=fZbT*N6iTT%v)X>nbzFe)uQ{wdB)0)rVO=(46kMbEj9_7i`kV&?{Gt|!X z_4R$o`k}yin5-nC%tZm(%*-gu;zdRt(lI<^QB8Y6z}D{fyJ1RfrpDTWY*PYX7jE!f zts^g5;_|e8pX2AkEm(vSOB!V{5pGzI`;B3_j8Xg9ZHfyRX#36!gv%R(5`wS@V4C5a zD^{gCnP+uKPVRP8aN~bWii4MQ(MK`<-4vaip(q0xRD@si^z?*R3~PUGZS9z;{wtRF znm60AQ$?epD=lDogQr46A&Gtt$F5Jgts&}V6nTL)9ZMf3t(&H2_Rp-B#}fjJGMjhQ z0r@7WpX*jo^o8wc2LCVFv^jmdDTWKpqkQ-^3KtSa9kiQY#>)kjN7VT-{1f7_kMV{Hc>!1Z$5!O?nXIzx?@-M z!%eSf=Gfu#NNR4~*Xi+0SdW_BNjriwQkJn{BIYY^zvr~plu;vPi1}z_4e3EKiFuF%{=_D$!0j3+1E%)ntxIK-wp+VgwMVW7e z?zJo5xEZ5@Ba4mvVfnA0T`N1NiG$jit|~bwxAm6%b0&M)OChaxtRDhr#6k(OJHkn> z1m(eljA}CFfcm_aFXe^#P4BXnilQ$xaL_0B{(%=VurFNP+;C}fcpuHj`hF4~Kk$6{ zGKIgPYWiy2&9M#(96}PwhNyx$VUM%8+taploarb6r3L{Q8j)K3sOp zNnmLfsV(a!^vzv_VaA2sqy~dQAp}e$;saaIW&#EVt4C=;4OXUCR<>~^Ww(=hr&daP zTj6EC(MoR*)q_{yZjlucUUI=#20e1ilD*iP@yJI8sVoPJAryzgKMwts8zuQz#NiZ~ zQbw^2p#YHhUuqXx$6gAahv61+=we-zbDVp|^IdJgL}3KDPY+=7M%?^D&*&uhSkL-_ z6P-*|vSVCgDvS%k`q{0^$sV`d-MC z{y#bvd~Bt!Xz_d@Q40c13)t-S=)Fs1!Jf{`a4^ zZe3_69nUejs#&&rvHaZyG6xk73gh1E`eDl)NqMHHR!ha^4~oyL_lnRoCr?;Ev=&Uy z+hh_l#lB*IX2s#*1zcy}20t}ZxbcM^wk{Lm;*`$gzy#!L8=pHG19K^A0)LoRthcjM zFpv+I2*UROy}ru#*FXM}#=Jq25lXq%QBMTBIN$gNqSBdO$MHQUXcJ%FTw1ouGc6zx2Z z{h-=h=eg|wwFe*TPMTZ~A6BsR^$I*YJi<2GJ)-LYw5Y++?*z#6iZ6LX)g>bqMOXN(eBEvrpjk_X6!`|BOiEYJe%p3iT9`UF&!0@e{9z5q>&9@K9KQy zO!5tcOSFtEUy}!Xt;0*=717RD@GK1cm%ML$0oeeYG_(vit&!=pRHO03Vgt|{EV|04zqIRUT* zBiBg8B9G|N>^wYf#Z0@y(7!ILI;w?Px`DB=aA@KBTQO$WqW*v}q_juk63oU$$-yvB^rG!YpF>9)_!2

    HV zUawMl{pzM<11gtZkV6VGQ6KmESz>_exgVwV+OrL4(KlRMSW@NCdv%m1u<9itxEk;M z#CHOzWoSv8?|VJP8Y+KE(SV>~`P<9N1y*y^j;38AJ@0k+fKC#S2moHNiItVHY$qp= z1HotiA({GRAI@t=-H64%K(m7Q^_Hn)B;oSl^dsl_Wxn)YSMMPcmCxYA=C0H9D5rFF zr^%gPkqVJ!E6xx?&H#cpzED&es@t1p!#8XgLCV7K55( zqaPa-u5n{Z*7c-m$n+DaQ`hNa@;yajY`ahfSBm~jP0frBLs*-oK9~PsyQ^#PSWTp) zD9%p%%T|BB`Z`V}PmYH0vLj{jdx7lKA7C48@o)3G`gV5QvbEw$kZCw2LT%YI59dI( zlQwlGM@Ve?uQ>%L7ne~=DrW?}(%j69^|omjMx)INi%LFAPE}P^tkK!ZswCqirr<}- zGjKKxudhYCg1x!_k$vVAC_MItr6J);e$s;qm{;aKB&q3)&n?qwO6VaB44<@2!hO*0 z$#$AL4GcOba=@)3t+ZsT9RWjV`2;SZUVCWG*${;yx&S~(E@0mb5VOJ^>`mItH^zP* z=MH5t?qfFi1p_v4i9Dr}yae(PWg60Ys-5hg-7QDz4N9u2y~Q2eiS(k_exL5?+EIz^ z_%8o@_p~l75sBLg92WC6=I?A9ctu>uD_B@o6R*illVSvHFkKtNW*O$x4n^;xnO1iE*Oy{L0e%{Kd?7t-?($!G-Po^4j$2KWgf%$0v%%~{u4asX6 z|6t2Pru47=tWCpJq-tW?$fs6U*=}6i&Gi#{uV%0H&}+Hc7 z_Gbws6Ai{wh1zJUmH*$4<>1JOSm|taZX=h;rSj)Mt@52Q-eb763U0U49w!C+Qwp46 zNc-@19K4LQ5!~w=!81&H6r(ccIDY!{-yOAazM`ID>w3-{r7EY-C0p5A zK~FY>Ch(&uetaoq-lPSH>HNs;d+tP91(v6rnOfgFW+{FA|S1`=vg2Z3>0sRRKWn8_A zj5|R0u`@9-@@A9xl{;WLZaHA(XP@zf>AV*N*K+AvVvaMWZ$ zCe+yz`A+E*3;&Og86cvJynEQm=u3JsWIuh{26Tco z@Wji!>^_v5Rf=qXX1N=kY;8R@z0#=-{j2}UyekOtCBuu|`u9(_6Fo4Z3DQkhb|D9^ zO-=jw9+Ihq^KOjB$vZp<{keuj@0H9D0KO@klKX#us}fOpxCe2j7o+3uIXiv(Ggo6S z-FC2>#=c+F4ly7L`;T#3mc`PkRJ53s$`-ihA0I}bN-D*V_)6l;^|B5|>~xweu^<1@?-Etbh4TXnHBF1Uew&`=YEC|^Qua!e7XZ-+J7Zb{aYS89V8{;NNl(8fh7$HR^Ugf86V zYd__l-OIMVJ0%diQ^kKoLz}Y_-@c|2%v&`pc_~GTX01RG3L=N8$jC(FFoqz>itoeb z#F8sWSS~ytNk1GwXQ8*@r&O&wzEOz%3Tx-4*~8;zCMMs|)zl+(TCn^5VOvv^BqZnK z_1|ZGR#pa*3TIc>7qBmw{r?vzjQvr3QrDRPy7AoRbV5;t1Z8VGW$R)w!&5#Er&t-2@ zM!g9l)PHEbo5F#NeoV|zOIjf8QH@sFXyG`_sc>WrEm+@>CV%>`du>x{Tqf_fxozW< z=R%zwGcGQ>)q4=**%|mIJ~6R(6wo%D#s$Z5%(F)yG6?t$mr-~wRCSe?E1`V25;5x`URDr zH=rp;uE*_rkakqg z1_E1BLH6v8WuvUpmEN8Mz3;=@Mt^TkHLwmo|2GK>^q~LFWf|8)N@$ZJ2?sy?2V3~B zYR2Lt*rTOgq8cfKwbq#!ajXLU1?faig3rXhsX*R{718(j2V>&4Twg6U~XX*nKy~+AkaH6_8SW76{|W{%PI1goKqnt(<1PtsI&nlGtvM=!YM%_xYdV*rKKud^DZKD}S<0;DYmI$#-A65Mly>bBk z-DFV6*$H~^DYK_FQX;}+@1^_wF+j(N^~T1D;y|1Fzi~Y+IMq1^o_r$ zdv{2g_H90hh z4pNpVuHG9wm(yR&BVr(5l5-%>V&5<|?Sb3{!fl@?kg)gg^srX_UZ|Yflcc{0Vt!pcT)fQsrg_}=8WDZ`2H!du(hIkQ%lwzfM5%Q~nJo5VWKr@h`@n^D#7j1fna@!_qld|*ZkrW#;Z zSHhkF4ZXgLzte+bW6>nKJ@@YfFPKf~L>wKHhbdaB+Vm>PIfLBVsih7scv=OR_TRGa z6PG%;HIYTf{|v#Xm*n@SZiIfJ>2~iuwe_vWL%~0ETQHTZCHYjV#Q?&_9)^z0^bAQU zK>lO*F`1|0DK!03js7Xe*L63&=q;G;&Wn1Rt+g$3ZzGB`a$@Q=|ko?blMKv3ix}7VC;xJpbM| zj5lRIKU@oXYd%nzsqW$G*B#TU5q7*bo*1Yx&f2c(C*B;LUhTQbjUBJmqKAFs2*b=p z2s0HTkM<_OzR|EB^)=Buw-h-Gl{e*m$o~bZB)-(Li;J}5hOVw0gNtSQVu%BaYbl7axyXztsP;{X`^OS)6=hjzymbs z%hXDj-2f~PH2p#24Rl()GX*Yq__^x|s zhM2iWVqcZL(VmJNSLLhBxP%iVL9g&nBk5I}I6Y)j!%ylMN$h#zWUz@Jzi3_$z;)cv z_?{0^PLfq$N3cjde5;_&qw4SzSCU_Ntk9`EdvjIwEq0PY29=>q^r7mSb{gV;DXVPt z71ub-lpFn|&4Ri-Bmqu>Z;5VO!;7`=IQnzhb)qp;+><^S+aY2U86wM^aq&0L zIN7Ob4}!LpyQ=@!fw zm9({i+cLNA5r;;;^HvSt^Qn? zV0vCyO#HMx;*rnr&aK6))+*n-^aO(+k(^-wkKBxrY%xOtjZu273xMqWadx{a`)Xil zC@#34_rI0S0Ck)RPYF5?50A)|n$W^{`8ZeUTp^~uml0L35#mCas>-ifb>qi1Sm)i0 z!29wBgc6m;r$;;d(vpA6UQBe7QC%jih9B{ZD=K#UL*7t7>e2}6UVaAey=BG6NC~pi zkay;DDR!y#=J>RU5q*7q-;5v(D7rFl$%uUtHoqQpkNMqS9UI$k8#tajDHW^mP5th( z)UJnlG4}&ryZwmE&kf0(HEWjw{BvSa;d5h&7=fa%r=H*_koYkT25PVJ#p4HFxpy5& z6wEmR#hRk$-QVi(jM2ah2I1$=tf*kbOZv02!l)`N+(DcO$US43-c4SdFrdMdQR~eu z+ZSzmxj#!v*HD8`{qgz9z&5Lr z^~u)OcA#&-Y->?~AWWspM7^ZZjta0BPbX@9{T7;c3+3KSmgGNJf&219u{{|uH)mU3BcNfySv#&v$aJq^t`6d{3u1}r_8g_A8yBQ zkC2$`16O0F|0e9}C@xkmW=@rxdMc}_!OWDWDlh426V@<9Z21^F z7oVQ~Qk8;p6ig?$u??T!pdtMC3;C6?5ba`6zyPQev$Ev%^oWRkZ%7a3DwFeLNUq=v zsS?}<g^Q&kr37aG|>&+dNn~x zjJ1bhnM#PBAm5!fPQw^lu=97!N~TyQY%Dq~*$KlZTBQiWvyQ1*-%C;XyQs_jBX=C> zWcvWKMVG5MivY2%!9jEeS|#0eTSHJ^mBfFNqQw@Gl51{16zQ{ZC|PAtcQmQPk;CXM zLXspg@HTu3dQ~6;#?Aks?MIT696z@y&0OSpIdjgzcY-YQ`#UYP1I+ONnI6xI+jbmr zc$s0Dzr%kCV+Iticm;pA@uqGku3r8kwTjXx8T3u;dq*(Hp?+C#_biq7|Ms@q+go%z zEEyTE(HYn(In}eLj z9}%fK?iuN1WKz^L!=I~%-O1==7kN3l!Z>U>bgO9CTy?DSrJ5|r|7U^w@ zzV@(WX6A@u5PyGQwY6rkhIEjS<=2V`MtlXkAb#dDYLi=|w@V`c5Q>`N`!!Zp!bnM* zT2m?DPMUpT+#IAof-&}Yuo%I7Rny|V2XWW&!TETyWB-SAuA^E*aAvMw-+Np&nJ>5x zNz}{#8M?45jQ5j&r47P2Vv}{c`iXr2YVSK(r_f#u!w-}ZMFr*=ooA-Q)EaGR!oNcO zVQ_TZNz;L(bwltm+^(V}8cZ@4G*2!){~jK0)$9MEjL93rsP4PHr4ZcB`SZ?UvG~X7 zO?y9$4RwzV2iwkq`74boZ|-T|3o^#mJrSPcJ(A&+V8Pk(f$T^)k}v(JJ6Uc-F9ZE| zi#88*g4vIKk1!(wZX73V_e6NtW)o9Wkn-G*_)#hu;2QveW~MnBm2;pqB6{A^mgyBK zL4?PjwmSR!OuI!FyMr`8%hK99UfjH3J7v~t`{HOxvy9p~o7wR7dA;2a2pMda&N$_N z29E`aC2_R2p8J&8pLF3!oUjtscNP{FUgURMJ3Fiv6C}SYG)3=n#f#YSua1_eoUmT| z!>DKbvdd9kyfMkqF4HcuOEB>ts8uYTWwr6V`M2JBezgQ5wW`2~+@i8LC$Bw=+ii8U zykQw4m<>)6&+@bu;+FJt^~`bY_|=Wb=S<{xf zPd~9mk&1@=eOQ%jmswW{3wAUirb&5Zc&x^-(IOZ^{j;cmRoOzgQd`0Po7Vmzc( zv4Hk&qjOoO&$?~|Flhk?zOJqgoPs4KC2Nn@mIC%)FX$@Cx0AI0*{w2)?j-gLXUqXZ zKNxR=2GY$eX?iK!liPo@enoxm@k+G3xs^^;L@chL$W$u@u^$GFW4|VDMHd`*u|w2R zsg9mLPQ9Jp+U;q==1}i?Eo9Y;oYM2cw59 zx4_O{Ak_Tlf(`gPwMspPYgLa7a6qVxUBHDm&qXJheztRB&22%*`+^vK`DUyA>ltBh z&Bb(vnNt;E;kaB;qH8&Ni)>^-a zsx}L{Vp|6B_XjZzf>rc+M(C(RoAd(7VHt`Q+PA*?+VYoh{Ew*n(m87Mn9#;Bm*<#c z$4Ue`)(v#LAwE)>_t*PzZ^Pcci3y40tN0G7wxE%&Gng`5drhlCYR&p&=iNYT&9%%| zbBvZrM@CYSXCl>iBJN-NzIpx0GgxeuUGi*!9J?xqoE;;U{t<5b9TNW+I4-lwN$QJu zyvIFBV&Nb`pppay9z?`YoJD0mQ*Nm_F%~#P2K$MPJx;}Ku#xJ~$-s#N447cS_5)`L z6evD`wgxb9ua5u7YHMqYO@N!x&YiyAyIOdYb><&W*H$tUf-u0nr@z zr^7(sh6wk%wtg(Hs3?x+^P$Zm914nCm5s~?{LJWsingTW-Es5v4{lP!?}1+g{BnQz z78{Ew^!YOzG!!+kPeSkX7QxlUUnB~nTm~IYjWhR#n%*R`4(1LZHJ<_qQa4E}T>FJ8c({^(AS z((cVO>!u1jVBj9h4LQ>X+F8QTpDFu$djPY3Dx*yR5IJRV*t=Wbrw$xw>HWa20*a~- z+51P|;(7P(&Gn(5 zM&(eBg8wlLP%~a8N8mpKd5yy5YBe2=xbcHQ401f6NCq>4n|{G(5Oko6{0qyvQpkF8 z=+>4Q*W@ZHB{^UK-Rf&}G%61-FUU532cQk6zrMc8a9#Cz*e*!sqVR50$l^-{hYF#g zHg)Oj5V$D+>qXSJUq~Cqz5A=EMb8lV*sl?R6LQ7>9dW>#nT_ppG-z7aJj{HSCg4xA zi-?%;y=Smof8Bym%?L8b`S>&65P740t?RgfUrczvGn#=|V|Kci7sFc8$hFZt@~08~ zYb4tk%y+|cGc98Guh(^2mMs5CbqQ&(0nz^?5My|H@_;Ke`~TtTJD|D#qyCX3$;wXl z-lXikM^^SGl8~KE_9iRI-em91&)zd53E5`1Ngq}Et=P$UFRhs(aD-^2Ee`|K)$`L_4MWS~se$q)5AfrgFPMV6WuVT2S4 zIw5&S|9y+^)SPZ;5mJ6Y&oW|%`8)d?6&+m=&^p2I+YdG`XpcovLj`a+ykkTyWY1Er z%G)K~U#Ih`Vit{kB$o3qB#m)@L=){$XI#-d_fe?^ijyvGQ;aC@YTWn!eAGZj#6H~g zEN>aIUCf&nHN!Z~V?|dS2Yp%G(PgJ4G6u6;UQH13U|G$6xXBkgK(nlrahsX*!Y0G>S@!d0D2dOBL)dk zb$@e!zDWNqiz750tUXm|HRUViYHruGY%z&<#=~O#_5l)SA@CAp@}pZPKX;sg1g@!& zSP>|EWlZ4ZP5NU`x9|JW$olHVkv6XbEd=A(GsD6K8Hpk+{u#fVjM6QgTXX1Q2UGn( zOux>blR0%y5Uc8>F+rjQ>ZB`HdEl$&ayn0^f!y%s30(I zhL7S@^yceZLa1INbver}{p%T~9ViIh;iS(hg6ijGuq9m#4o7qN2y0k(?me;hrScwGf7DDk(?@4&A@wx-VsRXVA+LpFrmADLnMZgr2ARZm9J zjZgEd0&>eWzL3wizr^+JS@G8VD-dIfN^#^|Fm#@=;)sDB=Y7I=%eQv;tfijm29Q}sKk%ctn) z<`qkW&$Tmk+h=}NBA)Y{+r49*_ZGJHzU5D$k}7M39=qnHfy<5S2lOXImuW6Y^14qS zV2~Jb{YPY8<~mFwHI&pN)|`5}_7?gsmx-NRCP(qiiFGP|Ci!7k5IJb2}+(iFxB3>+|QxZKk!e zQ0l`4$d*WQa&mw%$)gv%r4lY#Ivop-4>^_*>~Y{SyjEAI2_dxm;KZk|TI1G7`LFHu zMMr64(709?5seSdwO=*2Ot&I{=q)3dQ%L=u!aA2YTTP53s}v4z-OcpE7=Gq{k&Icm_`V(Ki|Xh4y}0i83ylb{Ahd?yO*Ro6-9C3Q3UV=h@nkU^TjY zHfOMUT+~fb%*4jfRR}HDAESf3Sx*&YJLy99%!CjOv&i|k$6w%Qx+nxfi$ zqM46_$rs{oHAthh7|}V>;x^dWv&PTC+(C@@O9O*uI{|2e`$*wY`+ zbg>l1W;)G|rGoYNx0_`?`>zTAh8)R{cwwW)#u=1q7@4SVxrogcN&bWg3%1qF%p&l3 zjT~If9XqEs9msx|vt>%+w#jX1_y$l~u?c|jGX*f~7 z8Y2L|=o{8AUuJ1;CGOuKlg^*AD_vhOXp`*z{oDSIOA6UpJb0r1^ult+qyOz&o1`H& zp+kq?H9d7}e+ymB+K^HoBiHS?vLq?ZqW|argw|iER72KR0yj4xM)Wh$a8Pm)zuB{O zPgl}3?-O2zyxe_=zE#!I>WyP~{S%CafMv6?zJ9OFZITfsE+K2`z4l8tt{U4&ANuW3 zC#K?1Ax1{D=;xvBwena4&fXUx{qB~{O^3-2x&1nhgz-%K$ztOVf&1mhJO zg#B2KGfkGt0!rpT&O?C2!DP8~rpsk6QpN`rzzGhG}ABc9*4IG<`DGTG5n|KFZF)`}U%1yeY$| zOA=5KzI+KZD9r=H0|Lxkx7^OG+~(##UV8F@M%(gwZ}DTJ>ro|l{mPPj-9}+pS(8yl zad8AtVWC}wEVHH!+kFWGQhBxpdeg8P*XP4eZK&a*ucvyaIxo1=;f6Om(B-wB;7|Lr zj4005VtzskyWjqXAUmPYbjfCCCypRNZUN63t~g1;Sd-^$41;(Y8g$y>LOZ=nw7xJ>-TkTT8)?7pTDu)-i*>+ zt&4mcy?GffArXLM_b^iQp^$iT`p@m((leZ)3w}-`8@J$5sj@K>@ z-!Z6=bM2|;D7WDLG!U8D?|kXk*Wz54Eo0NNm6i4b2m9&4)MV-Sx$&PM8TPaPoi*Fm zkD?P2dV;a3=ouMJdLp02U;*Jbo;vW8GC7RyYK-yd)hBMv<2bU8?9%HWf-~plba&TE z`1g>EhQIJ`&r}A@oX!k>PwIj}RJ+hHY{n|Lx;p+2o%-~;K+V+bI{skU+~lP>uvzQ| zlS9A(ux_LWxGHeIp#y4BWYGK#yqm{oX8J}mI!qT|OgNGJB2&q}PU;cw`h@rn1^rL^ z=8ubwh1<0XdA11DO)tw|y1%`8b_A|gIuK$uur6ts6a3$ckvsr{qW!K8U@RavysWs% zO{xQiU``L2(sWblSbpS#KXo)c<*+r#y?*zNxi`#nYU|`Gw>tdan>->?73 zK3*ek88M|W@!JWmm~5rh9R79~vAbAJaQJQ4V_dFvS9M@xAsb7(*!TyDgoP#iopla; z*xcM)RGLqm=bHJfokENu=qd=@V3K^(4eij?_1V4AiJ!fziHTS1#kJ?hKa_}g?Wqa$ zY!QL)9YY9LAi2?juFdH4w1IaDO;^{Tz@?Rt$I&Z63 zS7X>-BW+3;>|3m?0q)+>si~0ztL;DxfMCLUy>S#KHa4a2U=Dg{+FLulMT3PZlSB>D z8UUbM&n~q=%>n6pHkTjq*VhhZ^q-xrt@JKWO-)G+H}kFtCr90TK$J*?tcIBQV{~G| zAKq}_6&V3_=x(5TObq{!37@vwa=PDvt>H3$28}O;)oKLUVa=-TgLjaw&EwIZF0A+O zlfBl}WqOX`pDCRzzWRbu?H(t)AUX$T9O8^`748>Z@B#!+3|J0UE#RbK9~olVyi9ua z-AUsyk(iv8s1p($yU97~S}J?Oz?5Ehd}QkzYhf~PcYe&jCm;(UE&Wcpaa3MY5=ldf ziMh50Zm`VaKQ+@_C=0y~pCGg}FQR<--JGPD_nh;VR^c65BXfpWW?@(tFK==SuLSL| zg~j5TaaVw{e6aACGNWN<^^q5QFyo7OYY0g)U6CP0TcCU72VXtUH5`HcSy_^LtF6!k-<^3uLv3MaTB%qb1xMXOm4 zqvmgncB3a%*uoTg7$Y?ZjJZ_C=E}o(YS+asX!^OC(vOW243zj*vRI<~dQ+1mD18QQ+W6SbGiiX)B zmlfG#4&_~WCD<&AyWz;P`ak+bxgzK`doaOO9w%rP*Y-`k?~w&2Zt)bV^QLsEF!m-^ zGh16sZ~BZDW8^#*agbkX3`LOm#-q+=wgfeVgAnw!I92SLv``HVi9*h$0+{AQlr4hI z?r-8=>!(fVXD2B{RHT?8GxcXwrHyVdWX6{t6fwFV>V4^DWcj8gv-V4-Mtc?OY4wM0 zoaV;`gnV*Db~udWsAibkie)k*Ee_i`V$=Xfm`uH`%Zo?L9Nz-O-HmwVrOfterEqblH7Xji`F01I>?fw`zuQQR4jh}{7jaCrXx`(9hi z&oA{-tbiP?*moQ2z7h}y8xyN_iU+>{xhtHI11YRaZ0Da&DuXu)pbuRp88g!g;979} zlK@`^99i&-0#rpyr=J6sgMvXq|7Z(niU7_q<39q&h~#7vP(R(($25<_hwvGqyIjUp zSi2wDCbo&ZvSx{wqPqQe)>^=&O@b?|6KUb_^+^ zx6Ejs%ZhP+0e@g>L=l}kjzIt~N)myp3@ph7sxr2qXPDg7-Z_l1% zGb>8Vy$dgS|KFBC{FiQ~nzpN&{aU@6HBOVlK` z#y!qMFvddwlVUj#=D^(mYY<se*#pDtJl7+cBOyVl|jz4~Itvg%)2$wTS~;lDr1 z;1yy~T@@1(L)iyVcR#HA5@EjpJP7y&Kw<&VVSGvs%f%PHN{bm9y*v4wwRHwB?}r!Q zk$s;%;SrnOD^VXjNJ9Rx*=bUqKD}k;!bR>Nf}8{^)y) zn)%#uXJGmY;g(<4Y5Dn+7CVAs6A}P;4Z7;Eb$Qn*E>N+KeJETPr7@>*^ZX+-+3luM zvVa*{jMBR#3o6Cz<~w4y{t_Ov#u*^Vd}OcE}Un=7w)SYCfzM zEJxn^Y#Kw32Arb70$EvEs+FZ5}behh3hk8Bi3nADt;1Up2Lh=WM>r|mW zIU8z`C?ad_yQ+(bueD=N&l4VvQujz$j;gjc8_UprR2~{CE|3LO&IwHY1Dmk}I`7^G ze(9oWip6Z>#$<`?9$||H5qIjhuqdz!KOfOPDdeSl~NVG1*mP;36$6R|< z5mS$G_FEsDCih{X_M0@=lf{Tq`ci)*iI!Z}`Wy5vj{a26u~ix`GAl~DsGOSlTfF~s zNk+VS5=#>-zR)5JGh0W2aSEix@GntVQ^`I=GlaR_hb4z;QP?hQsnH`|6;4i7r7D^u1ZNZ4j_GBQEbIko9T}}UF z^(dV4QvPC&;pW+%D+Tr)HgU!N`H z)zo~UOLg(h5D$`Cp$;b%{N^wsm;f&x_%A>luJ^#50-dGyw-~T+9^o^Sv#>;fG#yYj zm(836t*Up}>nY9#om%j8-$}b35wNbnQ1=!XN-&)4wp@OI3O(R^|Iz=c=2Lf2SAH~_7=`YQOAE``H%E|uEOF>MN3NtcHSs{ zK0q6Q*@(^a3=#!_qksV4jE;`JOFP`Ae?ZCCug)0HJjzFc0Tq#hIARh_kbO0KzCWDafa@` zMW&r~k{mkBd1LR+oiy;Hh|vEWh>-vHr@xJvOGHai>s-jvepf^ULKTZX z+9wV+%pV?4=nPyalV%1P29%7)gJScaX@o&y+0Kk5!#kEwZRwNmEXJyB`x){OlwZH@ zfL0hJf#cnbG&BJqPP^kp5l6&Kpgy}CO}PD`r1{)_1qD(cOnn+)WdrI%bd-Crj|_KT z#d`~ZGzdeF@b^!q4e!#Bq36iH{!ETZ+;Qo+xi*xpTJCt|vTOC;%ddRW<0FV!q zz**<*KVg-_OXg4L?2m459xRd|XOv)Phn5{3x(Jw>nkp+Re}YMS(^2lkUoo%4h~4OA z67cfucY`lhfC2a61IB&ppyy<3!*f#R=AYKyKJ)pHsj3!}0{%A;MsH_yidclg^nPN+ zBU#+ty^-1+IfOxmM^qWjURlq%e@pqZbbI9B-dWbh-?IV+hNdiyC;KjSG+61) z8KU?H0RcKyIdMF6V)aN5WLx;1_tuX3VtLIb8C`GU`sp~R2m<*wIJ{WL&f|U&%~*TA#5_FVJ^~)WNVp!3hSCm zcxFlBLV#WuAMZwA2aOTWOjhBwik{jpdi(&Z``d-RVjn+=3eZ~Vi|C} z$WL{3v;t(q{p12xwu?TYs!K5+cXl&QnfJ^0W2%^T^4s*88lp-(;T|*fKO|u^jB+Bo zXn8_Bc4p}6ok~DSkI`5DRTEodJJy%R-aFe?>LVkF>sJ%fcS@qEoeJLmh75G=YLvA|J49` zD+%$^>8u}{0N1VgJRnV{-_B#R$AdD`H!_ki#RsJan!iM7h%*GGXd3Q zWMt&o%#QuaZY)N>!fn;|T2nI!$VFYSW@TbAlNi(g{1Cby=3#bM<7*9Im#3lrlGkH`qCLIS`eLmcZi!i(J97tP??Ugyhxl{hSAQ=y6=l=Dq;xI4$ww!r zKBVvT%8Vh;awx_1UT2d3YYaqTC+4-j{D@%CYQpaDKoRhO3@1yw%ekwZ;>W(CavlD1 ziXUHAi}dZzsbM?|g{q5xZ!P|9r0|W4BHt!;5uFb7$&W!C&%>W$`tj|d+rXBiimHFLL`>4VUWD`cPBdLmC1Yy_0B0JzX#9D^SwNjd^o2@MVH?py=w#@yoKSNQ2&^eji84RlCC%|C1yrcOU;C^!u73Ng(NGx#xqP2sEc3jWYL16dy3SfQQP9Ioa1S3`VXuH)BY!5od^q zh+upL8Oeu~_mCgPTqkS?yBb^%yhr697X<%)fx`_dWF$nPYHw zW>TPajJ?Z-5vMsyu=}&&?YD)(Nwu~0AM^8(L+@92*y|6M^Dn_OrZ{8I5V2-&5{ zlEU8J_$2bFm4xTN8MIjrnuDCNcd-4-zs*=X{!xfPs4jpO)IlLjBl?z}Wx*c@K#ATm zcT{W(i-Lly_5To&q^ROMg5>$x?9%q#nh*IMmb(kWNv(lnBeqb@s!8y+l6R@aA)DN) zrc+Q4t5+;VMNO>}LZAaW7B^nwP>~`>kIk|+ZaAHoYa9#44AsftH)~6G)>}8+J8zgB zp})S3_m^{4aY5e#`*dkN=#y4SW*^uaxwr0OwG`^z1r-&2b*UuN$j4ac4kXfm)QXU3t) zW<2FjbIE>{>CF_9r&aTM%wMXAInrf@z$ER>jIAUSN2YA3)|P6dJ`h^ix89H%cOl2; zV4v-CGSah!cr*)K-E!hK;S_9qZaGuk%&5~$K*r1v?w1cHe<}6`wZOig$H!9d@mA|af3 z@NB8`iBcyi#-Ms8kj)4TTzt;v-IY-Ar@_wL`d5`QxBJf}YHn^#ueX2?DSTxYy=erQ z!^P1$?4-IUpekXO0gPB?O+E^JQLeE~ft-d}HT3!&&wizi0p4ZgY z0w0bt9>&UNer+N^PybYveR$!)shgFPBZ-gv;(tt9pa6eaWm!HiSvI545W#w!dCr9P z6&zPV`^;%M#T*(M>H@DZXp~#4LKvO+3d&~c80dnEXKQ5d`;1e{UFlm%0|SkVI0r|Z zIg6SruAdgM+CXV^&s^4y12O0xAHQAW9Q+QL-KDak$0fsfwg#WOPFbz(IL~L~=LdWE z`GA&Y{1q+Gs3kx0)1^4#yy*^agV2E?ZYp}#T_Z>)M&83bbi3G^@Kzb=q4OTpTi5%z zH$Mbe1#~!IEYZ*)*7X_&NO0TxWm$@-AaLu!5)g2|NY}Yc`FMz%qA-nn!Q(ZUM~rxa z-~_5a5Ul}CAW~)V4d`;(w66!8|L_V;ASG!4C|RI3fXfpA6ri)i=Ey0HFKf)J+!w8g z|83fvRL;oA%Ct{M36uo%V44<*dih1diyTe5#n^is=rsO#jA0ghLwACn_KnH{6{on z{`quVUcsOi9ggDDu z#SXp0!_YL99UZ4!xvr$SdMqpt3b@mzIeND54=)n3HJ~n7mSUqL^PE)u&^o^m+9l3h8WwHil8&d_vlef%;aLg5YVNXtKF=b?Ie{4D}S{oZ&@{l0n2Gy5@3 zf&=wF&6QgwT#*F`4BpwSy~hsvDv-rc7Zhj|$|@=K@VdVYqf^X=*9lYj3Twzb4be7I z=kfa&{twm7$QzZFp*uw)ew+tO{K3kRwc&WC#J)DGN1|TA?x`Rtz0FNycETsHs{7nwKw(t958LDQo6H zH~&K^%6Q;QannH{c8a2(93G{3R2-#v2yC8ZCr~Y!%!B~oWQ1)Dm`L`$!5?{BSSxc( zrIsj&z1Q<5bIFa_(w7RG=feAbc^p?zqmYlpsftNs$gr-YS_+ ztx5@{B}2wZ(UeVBM`4H(HZm{lja#DskSThYf^e zhIoHp^2m6Jz_M^gHijsV#|Qs1W|>)d^S3@z_X&Kmr++xNlT#73?;4tiDwmEQ%AL17 zW9*r*vDNL{;iJq(t!f@OvNiYhjo>tc;nrpgnS9SqqevMgs#!YPccb%NKL;;vn8 zAis8k|4s`raY)cW!x7jk)7}2PC=M$cG3Gz|(of^c-Z^St{8I;FWcVii;qOeI=yV#(B78>(lt%q`o7Vh1D(ZW~<*oZ^qG?5p;HPbRMnuZ= zbdj&f++I~WmXlMz-jD6V{5z?<=XGXUoutu2qnl0wUm*Okxe0w z+p4m(Rru|2UrG{xtSsjzd7&1M=*0T7-wtQ)t!YOW9)oW;pI{syb+_JL+YAey>0P8$ zh!k}0d7bf#Wnd`@UvoX7RX{MB{I0&O7%oD979JTHNi8P+5W>8nKG6wZJY>==$%b{d z61A13Bj2;-o~ZSM9x{kn1ya`_WJzk5o7`Wt{aWgMy`?>iK}Lsa<}*F5^-?&0x+dJd3ee-|508m`--@gy*C=gosh}`kmES^%6Z+E-7xt-6SwX(IguC68J zyoWSVXiLD#ltj=iPKKINoiLN7boy>31&~B)Dyg=};LuRc*+BDl?Vfp{CyGW`{JSEy zWSxsrXqWcR5b(S2 z>NPYra^T_HkF@#m6l=7+u%n!xVxS)8e>khJ&8Jdy1Do ztTG82W=!b}B=b6K?C!3Cs#SH8I#||j8~iiF46jTW2NG;DzW+_6K9qyAemsf3{0n=Q z35xSh>!ayv)?wRJQ6Rt7&VOVQzC0RPslOdCypG9g$olOuFyyE=-A1N+D`R26pyI$) zBGNaIm6sPZKW~sYr>dJ_nWL0VKHT>k70a`ud;CiumCg7zpG0O_))`M=6j(j>ICSBYSTmajjj?=2U&) zU45$iW=N37nS0T8;$+ovi-d>?Gfw&Y%ebty$*u(jgZAePGMHM)3)eYbR9MdgSWzN) zVncHi@q3@MqY8`oFCXI(@;IXaZr7w$H1YdO zF0-@=&%t-DAve59>Csx0=k+#1L(0488G{v{Zg}xGgR{ef`*Wp;x2hgiNf8$i%sj2; zAm%=y(@>oWvcM+p|BcRT*gl_cC+RIl_4K6_-FFct)Uba#(yeyT*#n0p? ztpq#&u}#)D?zQjagHOx6e2j$34GJ2+I)}YEd9_C_az84A{Wyo%TM{~mmk$%ZIf#O$ z0p{F7jbf95FD$aAQjGo`#*9o%3<|i>caBJZCkxGda?8p-+wu&)Rub%b%>DaQmx=Mw z+R*mTa=$RPmam|}yu)+HbL6$_Y$<@P0#2o{y=uQtpa(D79|#3D-yF{gClgKutOOpe zyJe9rP-MPn~ zqs1z%jm^#IE+I1trJtL@);Orh)FByz+{%Gxp-b<0NOEgyxfTC>9U^>;qLJ_g+TMK^ z0nQ$B{4frSC5h9fLo|epjv(H+grLdyITaN#M%Fy?En>B0;zC%;o<@XU0k;vrbb zelYNSQKH3g3z5al-E{&<=98=S>YIGBm==f%1{etZx(RosE?fJGBJyh*)g+xy1>rY3Vuy4J0$XNFZC(SP#K-B#}@ z-JFyrFMT}v6+`p8){=mmMl5OQ?Q>v_RyjEzwSt$*K0|HN@Gzgf!;Z-BerB8yu(khs zd8#MmeX@S>W{XUFramT}mpcFi_xx^g5{Jdm@)J3_k}q z3s&xglQ-SUj`OY)zrBT_bE#Y(UWGN_PZ36}!MD$Od3g_iJ%M;)<}f2e>vb4rGM94D z+NZnxhMEm*^r8qLnN;`crNhA>8w0jaR~W)!tlIvf=0-=pL!42NdDAaq z2hzbw<=d-uVi;9i)>CAY9Tb_y-l_kx)Tsdv<7`IheA<9t!$$1Nus#tLMFeqn#okQd zxUf!Q(&zU&W-7WDCf{j!rPu}XADPPSZ7hfUONt3Y&-@&1ckt#jt8#%@@Pj0~4CY;a zTXde0PmF$jep(@-RcXZ+6)KKo`JTm;70fN^g8vL~pT{pe#9*(s6Y~WGB-j zrQ@wZ_EQrg6Wy>&WzQu;Q7fLLf5*<8n0_l38GCj9oy`&lr5olr0NC4+R`}g%k zo={iw+5AA(!-0guLwkUip>0b@E3I2X+igBGAobW6wQzRWsh;jfe{4MYrd%t(u&`tK zz!r9QCUEX^+mHgM017-I7)@AMFx(NByTgfoyRN6u8C!aC!GyoEp$BjQG&X=s181Ko zj>TiMtK~q_v&n6@5aIW2&t?7Ul&-05F$=L|-tGM zQD)dM$E)h=59JA8TL3jACGHtqo%-W(R9;?B#>9R(CIg!iW(71c>3j+a#ZYB#h|B`U z38RiK7=_fP5{qTVl8$|HM-hTTa#>AOk4=TePLn1C&9p^y*pwXFp@Lj8|;Oe+PT0st8VZ@p0u1cY1*J{ zAanIcYEJEj;}a-*Q1#$5zVf0^d(cRl4WJYBng>(KyiEs*BMAHbyz91?8)KbK20*r_ zHa*1YX`D9^1(<)D|KRertuy3RvX>i1hH@}q=Ix8@N>?WjBL{_jMQ#2hmpHKFB?U_^ zub_!A4|N3UP^Dl zQ(Q2}%P}~lCZs62I_6QgzR1MWcr+@zl3;Y|${BF(!-GHD3$0{ua`u^;Kw{Nhd$PN` zo9%=zp$kzr_-F@yOD4PXwNbeYug@iwFb$s*gM2m4KO0CU+Du>&3qcGsR(Fc}+lmx0 z@1yHv>1B=qobKxUA+OkAl5o`Y&EAXdD2R?(hTt6Pf~TFX|F)lxaF$q*&87;-JC89f)gB%XkN7zv?7VT zdXH}AN#1Ni@xyDNC5&<}_nd^o#14m?<5!CzzteR*XTiVek?~jlTy!#l{~C^Y>Axvs zQEtWwej3yt?Vp#aRiMGnC|JvtM6MstAN%6QSHA5i={2UoH<5QW>RnzN)o~DeeUIzw?=Q=AmzM=H zRim{z_?SO~s_HyRPErS34h?(Dyr0Kc5`aogP7(HDCY9!=6TF=32|{owX?7h z=iJZOH@h?18tyo03P+jb?F<4&@tY?wmFSO~Y8h9mbTCoA?h6#cEj zmfP2lfQxFXT)S^|c6lvuy79(i?{Z<8!1>lU$$3s;hrgOc$m1)o!`h#uJ$csO7@xqr z&~%7cOo+@zLv6Io^xW8fR>>13zR&>x%(k1rXkqNCRH`$mL}z22l+vtb(PVW zWNH2K27Tfg&wtyM!|iV?$L8jW>AB{WsFAw57Sg|ezssh&+Xd}3boSbs?N@_t3<#xE z(vf9AbpXiwm7*fX|6uu_V86F@BB#q7eV_ca{O1B?THE_-6VAl^+Y#?k-C`}U;aHeg z{JFC>?dqx;O*N&CD=AslpgafFJ6tMDtrY%-kt0hg!UPf!MAGP5p-dcajHzj8sH&?6 zz%~_VvN{Z+$%F6GeNNa)&Bxj$f8YLh4LQg2iDwwkd@uxrPs`TQEP1T2E!2LiP*m!| zT?TAa;T4u-e0)6fT)7_}-!tK&{6FCfSAo_GSF~<^J{D)cJ90-nBk5oh?6OY|bvdiC zQ8zF_Q%#NC_0TkuR8S5kkK*FT(94fyNt?Cl(9!n}*G34~jgd#*NugqNasrRzBN?!TUu7m;-z#I> z#Y@!Q05Dcyk25X(;|*=51cyi4=j_q`zP{)cPdHfM0svU1s-q*PtxW{`pxm08Q~wpA z`+lO(^Mi|qEVT--Le$JrlEkym{dg}~zF=GVGmc4v zg6wk^$skqP=uKYoT(Wn>tBwUl-zRp=sKl3D!n>y_IVW1Xf@v0*Ugne~P)3~Kdj3sn z*$(RzdQGYu+A8_S*;9YPqyL%#mD)~FmG$+jm|Q*-lZNAIN0C!1-C4mohfuYG{8ZP@ z|1gRdp4X=_Mx|IilV18t=sNYcL;8kDO_sz1mxA^7AyN(*VllP+-^=R*L@}!2Za3L) zGULmCgYp;bvyvG#jt9=ks7$**@0V6vawIOjV9VKxhR23ue9uBNwbLD{K@?C_Kix(BOpo%TSB)kkA4Z;t^}pr|a5n z^MQ7jL3cCKJ9g^-|i;TOo8V)_pj#zY!|x zm_vI^$b#R{sHmrM1P2{ub7v=~s){S5 zS2;7M=KiO-M(5WC28wefd_tZxdAwWh<{bUJp$7VF|1<;v4~f~|-Pkait+5_V;*N5j zcMa;|cRpMx(Z9o)5ge^&#KywwaI#OMrR)Ax{Q&iR!e44**OjwNUi%ePx8_th!W3v@ z2Ys-oq)hmGCTR_`zyC#dY>)$U2K1KG3lHXI7Y58KK@mHZ^1(G81E}oDAAecgeQ{=W zfrBrg_&{7JD7>VBS=fkO#=+sYSO5EJIWrJhFIftaRVxYg?UG%Qe^|!T?O8S##IRf* zsN2j#2KT=)_tYGd?lOEqS=AE{;N?Y$*NA!E-Mzzxw@TdSZa?6jyH1IFpb-}i|f zfXaLoG(&@j0`LH@d@Jeo#JEk3zjypU*G`9q&>t^ zormO3pZDDqcel0SV2P%VSw=Vgaab3nEbf@Iot3UlS+{Jvj7aJu@PbJjq08Ib*@?eg zFk;`IEcJ*NuDOY>j4&rV^IVvmr1AS5U?TTfi#GNl1P{o{7|YX@u*_&g<{Pd_aOj3} zO{%`8H$>_}RXK6g39zds{?qYR-YJs>Esp9zrKo8(6=P?E*^dssr}q~WikuOGc}4Q% zb+3pO3?pj;V%>N**_GQgt+yPT{w2wYQngN(1rqgtRQtth_Wg=**Gu)o8z&##eC)Wc zOGI^)j!vUrld3AF$Pw3*hLfMq^(S-f8}lz`l=@yz8|p`Y@GAaTwVgdN+Rrf7Kc?)J z7W#(}EyIoymq@48#{|pQ_s{5i%<<18uOb+VgW_tGk@{6``ke^Y1Dp2fm^EQ?E-L`ZK+$4#K{CS&}Hm>gz3$V-|QiqIn|w7qfu; zqHpP(IE4B0Key!CsH~Ps5r_XqQ7ingIo}{t_2R%I$jlB51BYK0c?TojH&4L7@X_y2 z%z;lMq+scv<<0S}qOpJJqqHP%1r~j%nHUQ>^H+)UTKdc|lUl;^qCsVtI+ku8?B=DX zgNv{fxRgzqFaZzS3`aI2fL8noVY&~BHp$?~NRT|+eWMAd>9z)^@fNy|M?;)!qDC_n zb@rxn4Rt$%d{blWwLUick2A~Z-BMCp9j^nf2oCEr&QP|!E040su7gwfo#Dlet??;~ zKw7D((<-HV&v_umF0)gl{S&cvb_i%d^z`&#%F9>MxGR5ryaM{{O6?{W4j4X~4WhbC zqHobqU-4^@@`p@UXQ#@3f=aLjo^{ z4J<=?W@_$Q8?_eYZ>X~`f}g0$F>zq$v*5}vef{LJVejQ71pUFz`iFJ%OYd$x8qKog z)eWbA%LWtpST*kePP-#4L;KqM1~M*tm&KB&DQ~F{+aGNUUOPIL6Gjslq_<#$jBRU{ zyG9}~h&OeSgAfm|vo;Df&beOiC#_Q8Gyb}a@1d9X5H%#Tu+X8qwcDP3aCxdy`z~7G z29ZQikSl_ya+WLtup zVnoP4$C*+6V`(8+PbN35jQE**Gv8kzgEmUb;4c_&Ph4zqKkz$JFG`^5Zr$2DU2c(+7XZ4h(bmsXeJ~pmqpR3FWLtZrdk{%Hi-n2fBVIT@QB8?kkN_rrkh#B zp~)SJUb~V%%2sI4tBn4Uk*f4og+BO^llOB9lEC+`;=kLL;+2t71(x(N$OeTUvW#z+ zIu2-_iM~2URTVvcHDjRK9c1FQ>e272dcrW7?`4)$5FF;Xz%)y$$l75`5gg&FROIy3jFPfW+*8XYl?sL`A>OW%ESzkqv`|w@e?~?!xrA*tD@y|MhQvjP=Ph%K~42+6}E72da28pVGztE$v+ z1a+vgC28-1Hn&qr`J^M3UMJ{xJ6KNjUd7&Ncy)D`@9Ri@`Goq6fR}9PIeExK*xSB- zLZ_;yr@%$rwPfG7{n$8%x+vHmNxFXTzV;VTlKlCFkcXezFaL_I{QR&>;NGywqq22FlLAPdJmFxycm%*Got~{xKS6ICKg(N%k|0h4B>D3*>g$Vr%n$r zIkR#Dp`U;?ylJE;yx6tc%vzsl9zSk!Ih(t}+*dWDnNEnu_WDnLB~T_gSk_;BeQgaE z(6F1K06qYmupxZq&$>?WX2q~1DL?&s$7TPoFz+ay%{$<=o8n^qzQfmu>*5PVYEJFR z-2dYObhf7D(Lx0lYd1;MfPT(&Q}80Cx8z*Iy=893=Mj- zH`7R9Za}J4%mdkAe5<%?!-O+y#dBPYK&N&$lpyzhFkNdt?`?#6ot z2vccxD6kES(Q|5?11Ih#FwwQ~_m$Oqid;?=>1`K*`-8qT31+6)KI+ma-#@_;l(<(l zpMq`=+12;d50bK4+v3+LtscrF@g`weqlqc%-9t{Kn1aYoSraZ2i~(yb`IAvWg=|Vz z6u)ewV9s=|SB-S)M=nA~zX6<)|}Dn{x6)q@J)}s6h5XwXZbt*Z)V;R|aL-b#2Q{ zNOyyDr*wCBcS(yPDIuwJHzLyAA{dl_5+dCog3>J@-S91*cfKEv&gclkb)I{#bz~J9 zR*l!_R^-$=LG&v^!p#Zt3J->{PiS2q4Bp!0H!`!-PP==k^91VIikGdHu4K~J zQlM`ZeK1G3oz*@R%@+>3BI6wTWj^mlLu=LY`_ARTdO@`cZy&Gfl~3k8`6SIY*%L{W zS#AP>ptGooNkn$CehemN_I|ZmJQibDJYS=WsGiqd@0&OJx&4u(dKZM+lhz$NEJF5* zDdM`c9a`dtM7OJ*kL;1?&%Q3dHgi!qHv_*Pcv%+SK7D5m)F#}e53M_pAh%Byw&iTi zXVi9rS*wq&bh3$xn$yE2bq2uy>)UGS)J})~1s3}_3ZVor$e28?s;s;-xwiVB^7@}R z4~gxG4_*;5+SHMP*YMt4;6E3`8q;nIpFiETRJTO%1@G*!1GR5(zV=gCuFZ@N^Bzm- zZSL+m3}w061S}v>1+L&pR!twyy%o4xpSb-uPjH(h_3`Ev;{&xjj9^&eloIy)oQ$27 zqvNu}k;2GwOH&O61!V9At7i)*udO*aDKJdws7T8fjWT?afzcP_CTZ#Eb&kWq?hDcn z2$(f(dQ%uDrgEcy=c)y@nV9~2EaOa(Gp^G0m|^3%{(|~8-{I2xPo6|pObj~L<7f5< z*QbZS_X3pGp55c+mNVXtDy)X@0Qp&JuRKsntE;QLK5}Q|3VD+$B$_> z>$$PDO=Jz@Xp0Z6KAMUsi@UDHBi?`Mn=A@K(~Wc;`41of z2?~jw-U{Odx^UG!N^+&ZG$!am?uxzac&+i*k&%ZnO4X?yj0M!9HBg3ZD|-s>xRxfU*gX<+&k zhmc5$Y$t`gc4C6DMRlTf6$mmw(Xr9cuD7&F-sr5>UK`mw&)X#B;2}kFYF4xNDL1yb zk`W_RHLYJHQ#qroRA5j$FBOH-Ia#4)2rn+5IxQ^ntvRlIPd?ED>~LVA3hQ4DLHGS}tSwIPJv$aEPV9Jf z4!C6>ML0Q;;uQP(`!l^SHu-NarvIKV;+(HO@c9?pvR4Z6ptaLk z`UCu=m>z^pKkmZ22?+@wy37gR8L0oX`tSR-suV|}y5oe)9teZ$x1_Pr7{wfJcTlp$9}l;ah#MWzCLJ6ze&@k_{$G|+;2l6??2e~RP*tbIHBi^YWh)cc6%#i>-#xw z8{V_5tX#rCw~x_wi2ASLfD#XR=_xklLiVSp_P17$-Sh-|Lfg<#v5Q>9C4AW#WY;o* z63GeJ0Tve7_^5UQjaQRKHP5{iGI@$9ax|4-go*cD`?tO`3v>~~{G)}x;Aj;i4>yi0 z?~&smR%5B~;~~WaZ|k8!1BDTXVy~GiNR&pnw$-Z-J9dH{!i-1AQ&Ij z`UUpefro9vV@g$Fdx7M>eR_$&uu0oS(uY~10Tv+=c#L$B>4sWB(x|%2{>}V}gXf|H zXwq3YIZM8L$=+Y?(bLwZ;R}nvC?LgOuM#%uzJ;L!RPpnB8HQ#{zi9MXdk{mql-C!l zxrWO8$%wcoR6XP+O!wtm&7Z{kPWV-59?RAkWRw1IP;I)QCM;K}(w|4e{O&K7KAGkh z*7PgF;UPoF)W;{Wnd&q#!CP&mrr+;BsE8TuE0idnR}3`}!<6^KWGu3Kh#c^VbM(;~ zS%Ruuzo^QLp`l9rFXI5DFS-&1$2p3(T_2Ch$;hAl_mDtAo~aLoGqxga`}NYLzPG;V zxXjfTq9>Sj&YvVQ4Q~|LJl5>+$Pw}IE7C}|uHwFZ7Q-2|3Go>NRxH7R|$?m7m6A7W* zD9I9kln3ALV^Fg*CeV=SCQ~MbY$yjxc?+hbH6-)5|M*2pD})k`msNomN2Atw(8tc0 zjIghB19JSuY|o+OaPPz(#G@Bwk+QU~B15_+sQOI;1V}L{TTfUNTk$0PDyb{JKju$? z0|4U6FuMfEXv&K`7`4~B62O)!uks- z=;Ky`#Yv)* z0$KJa_%=|Hh-4h9u*)C?05a5slF|OtHaF+M=x=Ijf-^@MpQ|#q-gXpwC_9Mhn}3M0 zlx_DT{(r_x2#e#e3F&D`#k*hmlHJ2$h~EGU?7`p8R4Hi|>;y#RELEYVTsqnrin7rd^gh&}E zG4I*~vj&X`Xcr2VgJDC1W8N_@P!OUJ9dvBzJ=X^i7UJV6&@$5g9S&)3dG95h7JN(_ zX8OB})O24NgT0O$)Kh#?$_Z&H_z*yG)>Dy(58j|nN=}E_Dr0jHyqb*LnRlOo! z{#tM6*|%bPalaynT2)7Ml6Nd#eHe*3^=xFzU;X}&@mjdO{Wrs^pIO*5eSb+g(DFaU zy-HwQJ?%SAi^(aSkbh+u{7L`6Lh8&)b6r_nyuPJ>Ob_BUcqlWInCLtgn3Qy*d~~Oj z^{Tn$MUYYG&Ukg4P|Mqm8fq9c$13)PID_aShGGA1ZTws@^@PP^;bHdDbqPnwd1FFzK!)MJ*%#Y`+x_Bxir?Q3l==dqS zBsM9W(h!aiWkm83P=fcU297pSqyuo1;?+N>=Tbe+6QgJL(^bI3R3|QuKKgkOr9~U}s$YaXB`o zE0Q8a9Ba+@^M}y7-XpGs-1)iA2qVERxsOUU%Tw+R2Q@qMg-dxvkPiV$Z>+D7-|*t} zw~xr)m&3-b%BnF_Hv9itEwx~;1}0J8$Oz_%yAqJIoxPw~Pzz6oSfmNQ_FxG>1(*<= z%PMk+4G$y-gyI$Btp4(eE6ZMTNm_B3Y-?GfD@l9Gy=-(zNGb{yHJj#Xs+kC@B+ z2h`>M44$@#Gi%FUeL6knBnUlK9V=ej<=`$C8HR-it*f^hT4(;RA{qVwPFfJ!L-fb^ z?5vuK3K{?hK=V{c{}_yCw>W6E{I%Pjcj7r*^7nW;b9U-`!c_olP71(L@;MHHc+wtn zD;=zVBqC15pdOA6K>GL;e@EFXG{T}a=93mV#V zKxwMX@Gb)00zx7pmGGp?NEaJUp3l3#RFgj_S8@|GduYffUm`TzkQT>(RDhmX(8}xW3*)dDa{$sQoA<+P)vN z+MH}!^l34bZoCO3&+VuYLMW!yNqoE~je)!c({!NmQU6s@B*Pb(r zc72J1$c(Vga1=8}sLn-@bAilrmON(iocIZ5QcM}=BYFWO{YtF$pKagVbQL&%q$cvr zfap5z5mFBx=(*sUhdci+=nvR5xGtR3=oJ5vkdQ!13p1xFyddqlhfmuMcYWS8yIC(p1S*0(|vi=H+-Pkob&CEpF3*J`q|)04VTU$(1~Fv@-X;JMlp=?ygG7UA zHQXQ`$chOzTsUZAK%kdx4%Rn~scXm}8XVNN=ytrVkInqx&^LPAVaX1M(eQ_!&=Gp~ zZO-<2Ef&HQ`i^je#AtSg`+`!bqMXqOXYy_OARG2K$y-sqx9Eg2`(kKyA z)4sRxoBi>V6G8rmwsXR4Twjt-L_B?2xfA=P4#~j8svN zbi4m0{reN)>rWorsBRnm#CPAF1qlQcU;J2K9^e~#wEg*+_{C4#J5)ad6D1DapS5my z_wcepjV0vXP-P8dwjHcexGdn@Ue7zXt&tBz%hp3K#ono74&~W<>*Fn&{@0nnHmm=1 z=5cz#L};nnFKWMW;_Bx=I^(?I=hw(;ZE;_@kPSZ?=7_s&kMjd8p?_bgZ-0~y2fcnj z9V;;U=Ynr|rN>367EaQxLb{4H+!%ECU2;qm5c2+LWzTS26YmTRZcJ<`@)$X@WR+a z{!mF7t)SfWv$Hq^fUlmfFEdo2ih~R&rJ5+_HC$6L6ZHMtbH2o8FIe5L{up;rzTj&n zTY-Tz;}=aa(C^BG%viHbGoCT@{jLAfR$PC|Bw1lnDOb6@jaspQsDF9U?@PsxSQZNT zhG~>qnEv`w?y^OrCODcGc;tl-%N0ynVk0UhxI>vz$Erh9aFxrPwYhv~*dMO$A(}`r za(>VxX(&~R!yfJuRBhrAs3`d4V$xYEANz^tT!e8e$G zb~b7iQ#!6%tDc(6=sTB{uP2L}g{!X2wqMAeQzlK->(FbP|IWj~*Odq@^^@!s)H#%y zW0L!}@2g1pEs{b-UUBJH3Df$027!B9+p7k{FD@H>>3WX-BcI<)xNW)24HB%QCix#b z@y$I98i7HXPbuv75(Zoti``m&-*r%*UYmecxP>`-cYm1Gvc#=+Ng1AF?Q8mK>*Pmfc08E5!a`kZON5H)sCW+u!iB42&rxRslRY zhijwPyDj4TT?BI;+cn0odacg>15aR!`LExDuT4JK-NF*@GuRy4ax&jN7MoF@;Pw2- zd%<))|A0kzj@$ zHt3LQeKhW))kEag>zo0Oi(#eS!S3y28-DV;SE98w$C%@LWkP~)Qo5y9WPkX$L#NZH zC1qpn=zJHvmFxaoDj;5k3UKdXkZ?c z-}Tw)0r&%OPIvS`Bpi`}3x~W3LTkf5A6%`>k%^6}jqOMq2OZSV=LN~*VIKqy63`y? zLBIHk+pYy&|63o*gCQ+>CrbQ{GD8Ouh2TBy%Z;MBYpL7N%^aV`e<2vY);p$x1GyR; zxcTMfTG3Dk#NN648?+>uPg?4*EJJGp&e_vi^&^g-u=7}Os6;bPsL4(uJajr>_%rih z`0tya{K@b?e{>p$e8;yLSHGR+zghl#!_Zl|GV6Wpd2co*o`aVPfb`nXSizqhXu)2Bjj7ff6>ur!t$N zIGK1fq1}&Wf1va}G{$r!JFa&rvsekgpA=tvw)wtCGI^!7mGEBJY(l zPK}d7fxZPlX*t%h=#v?0tW)33X+^!FkEwlKyll^Iw=ZTDjz7Gb<^OkH#lSxHfUhFz zzCA_Xf6w8RC=H9K4@O*lT#iO$KikR3AE9O!<)y47Up(;hv2OXX?nm0cJO(48{tq<&V<)?Wx?7FN3x)nltShyp8*xESgy(^iv`MA$U4Vzc7QTlcs&N0Fzi8hsncdJlf8fSp#=7!EA%;u%eaX!w?*C&_qfUf4v0#KN!<5Pj-qx zmj?>bwzX5e7mMMPW=$y@sam}L+lH3q)y1G7lC(J={Ldp!q_NZGOZ(x0&*}WKBnaTwhVzC2B@=O5P0!|aq2z<&SfSUP%Z{QC{y>K) zTz99JXpx=jWPIVw$6EE3ZbVq&SV{LY_L{S2JRJ@ve(__Wy}gr5E)iAh`SIgMM)V?EgW;E3Y-n zLfzi5*BE+0VG2U~-;ITYkpF-c0PxlHImi-WOYiOPPxV%$HUbms-OGg%%1a>^ke87W zIp{!79uHjX0KC7DI8y+)>dP-CAI`opX1J|e_~_{9&<;<-rVkogh9=^jpE7cR642Nf zaJ!aueh%R_5Rc);VX4kS*a4yZuFtw3^MAk9OriyiWTQD(#RMb|0nn=1Bk_Q=Rser2 zd_{yi3RC7KTj#f9KZ&wD_vV4p8K)T)Gc$_2rR!S=a*FQ;sGS&~?urlk(?HUkoSGU6 zWVpizScw?->16voJv|wd9eFd04brE#S5Mp96CXWvu{P3QDJ<%wuMG{E01varjBHbB z$h1hD0U6Kdp zm}0E|GR8|-!b&mD3=;>a)vb-6d8Km}Z_P$xnIfh7@zWe}S7QrN*fw6;KD3^d+bI(b zrq$C`YE76yN7-vISCH|cp`#~wJj3n8$~u;#rMfD|)c599QlGc#Z`YdSD$`5V*kaX& zKQj#c^)hyk@rbtkYu}bD8^}|sPepv`!H88!nbpZM6qusroZUi}siVVVd53=E(lxrL z9Fs~NxDq4Ww!EDz%0hX88s9h^uyjT6`pL_8nr0;h5xi$+9AdxA&!30h8(Z~eEhvf7 zh+O6=41Rxl`y4$bvExw&0ow7&MgD9fHZpyW{1fOW$=48#^{*bo*B@GUmM2l0<0F`s zj>2({cAATLAnG2>=%RF-@$@o{f*P?qV)we$-v*|1HwIY-N?0#@YVbO&JEB7rSP0j? zehY=Vv5!`WPp7IEFScu?&@8CGp=yc)2g(7>O279m?`pjRUij&Pb?rT9gs~xs2SP5% z#Jo8&7|?h8gRg9x|M(}ie6fV;0bNOHph|&jx|7*d=#_a~Y?kqXZDYXU5RG$6)Jv26 z@q+bqXF$OjhOm`KJ;*A+gO~c(AnbU==VZ@uQEU%9;ly~c@~A$~-;0wn;72QOliN4e z{yP%N8YH}Gda3Hk*b~wtOeh()6DtV!)L9kxO-jbhMRogzm;{PW-i^#!kF%-yo%F})< z#nSu#wE$j{u#W-vVpC_V*<2|N%=F=43k$oyW{M)lJh*j&FDX))H9DZDrtk5}fjod0nv0^>UVv6=>+ADZ=da`N0S+t= zxbK}qPna4L#R+nU2ZiSCAg>kX8FUN`piEZ(Ep`F}{h1Mk+4*Xs4E1xvp=Zkj;0!?Q zb@$_7`VkF4)SubbtiueBMJqI~nPmuNg73+s#k)pdA!=a{&Q-DqPC{vvPz0YP(wJ@= zV7+lMQS3DnwBzsn+(8o)4L{DFaem!Z`aU0jT?;<;@iHxddJ|zVg`I+7^j?>z)4?H} zUJ#rB+Em6FI@w+<6hy-+gU@8BNRZM|9tj^Hz^2f}2HKXF1If^UcPCRD9hG4zkR986 zPATGH_w&+-^Kg2S={7eyCuAzNsXiyMPtAx)*&d_7AZ~ri-vE6MS95?PwJ7%I{bY}cY;PnHU=^lVJBp7%b9`xSbev)piQ6wT)RX#x*!BGDaS$~Pi3cK)w9g6e0}ur;j>@-r5ah^QyA5jkhi_I^9vA)x;qN`xt71{6useh!WYd+fP1h{))crb zxX78aziKa;-!@er)pUWzHQ?+8C|#Ux^~EBj$n0pX>?|Q8qU|Z~VwPb1{O;`iQ5GwW zI2U3CIs23FF&rt_oKHF$USu_hcwT4zJQ4&kI3?pVNbY~^!dSQH4J7)#RHp0KbA776 zZjYGJ2Oa3Rzr5V-CK=^4@i1>l+_(kO|Lz!i`LXlD;cu33k4QAQfOA9(6Ii$t{F1$@ zJ9XAx)-V71BqLLsI4{rLTpk{d(cTI9Q3?$Bi_vwqnTS^fMTi~NEL^Wen2PX&Zzs1` zJ*tQbbz%tQLm;#xN!u7TWXbcz3vnC4qFBXDDOalGuGi@40nMp#q^PMy5v}p{V%--_}2g7Tyu#Wb?sTShh3o7w>(0q|IhI^s_N} zUy{0(8I{etok4aS?o%}|%g=_$6z=R)vv3smtftt>z&QYb2vB!m5d!|AZwM*b{diqc zse5gZpCP3u>+M^(^uO($0(Q60%+Uk+Dc>I9zN9`qx(D?L4qL>WDSaq1ZK%4#puw** zW}roM*Oj(gxp(jrPi7V>Ri`ceLANXm+X=`Uz?%YUFMwP(;L1>^gcI~fHgRg zP<25%@x-X6UYY2qMj-L^TLuHk$RF~(VI!oN$;o|^Y(%34RLHfH5x>YQcqU(lH-~M> zxogEn2F70JeQ|c8{#pEhX}4TXhLUA%616B})||3aH6-G@e53Dws#PiH_3-fwV-o9r{h zTA2)#-JI(2f0>fLsXf@gyaqUUlZ-lAzOm#BC3Jn1%P0GFve%CAzu@(1@$uZfIQXPB=MUKrmbIX9%)lI|%wxFPah3f1EQ?MGqaOY1=u9-9 z3~tmMvi1J)%vFGT^kz7E=VN{*WJ$RI!W$9-ne}dvDr-a5L9|nPB_=}Rx-~Ynx7%9g zcAc>c1Gpye2eyxwviDYAo4GDd<^4vNPW=?EWh%*vu}@9H(1?`q;AuhOlK9QdspCUZ z%~o;BOES&d8a_5g7)1`7F&U9;AZzfti0dVG#6)?SC7+LU&i1`fed8#b+LQ@p zIlE#^t=jE*oSJJ<+{`kjoQT2+!)J-AZzhR#;NMfx(ZEE)0`HP7h_M5N^<2lcB;b@t{!J96F>iGq10h8x+ z81T~?$r<9$Ai+e5`9}|G( zH5HM1(be6CN4y(Z$6cat9sKj*|Db(lNN(bDsT!M-ePJRpy5BR8;?xKYWh+d7L*Sz| zmh=-bM{mFW?RtJO-8RI?&IPt$!22aH<-u?s)~)`~6VrzpqUQ!I!GW-4tfg z;(h0Ia?-)On3^gUC$KLtslC1Z+v@X%ax&-oxJUEs{NsiDowWVOca$s(Ow#)y`&{`hiugLp|H&sIsq&$x>aEXR-;4(C z&AqGG-6V_0A6Q&Wo-hE@=HyQ0JI~!yN&+y`NaGJyh7;1rE$of+zY))r*q&Z~SGhzU zDfgNAoxiK=MM0jjG@U!O_vKEC9m$8A-~%hE#Rv_detx85q2`Q-e za8Z#qwzuhVQNdjcp&k%+$Jw>)J|w)1$pz)0g`+Gz@6395xZ4Mwex=Ae$GjC^L;_Sr zZSPB}7m1ZRByv@)4=f7({vE($%g*>c8lqp|B%zALosysL79b)LmvzH6AeW^C;TA7R zF@#-$uA50KcL0b?ASJF=+JpZ4n(|5Q@vV#4a*(K|sS?_#KB{veJ_x&isN*Mh>gef( zmO23x+;`Kx><*zlunZJ^_~6-I`)QPeTcV=2EnrKE+WGa;w=TC128`ZV7Nn+xU}2kY zH>TpN=vPCZ5)rYcJ1)_KMtc<=$IRGoiEcTDekwcN;eOuECA2^(I^$O!9v2#Jj&$-h z>Ce^n%F|%sz`p4Q^Giea`w@trT4k?JBSQkx?}yUiG*uPme$C=0EtiH}w z+Q?Y<)@R6z>$^Ew8_{0b+PYA17ukyAPN~S9OBCG(dN~KjQ>M`Oja^92dm!0h)9tCc(g#@@Im-^L z^#@41S+HrpCy@2KiUswL+iQ8&?JRYQzW?d)K?n3;R#wz7MKOH~7Puv$&fZ5@Z+8!R z{Vew1muY@1jq&2W>)!?j{O>HWzW!2(rQzGANa{d3B1jGSO2}7?pzzM*Xs#= zZR-ge261)rvmLW9#(saahLe^f@iiUMQ&pBT9VxRt`g*HPy~_Rhap8_RKQw!BILMC& zH`C1LniRlsO`PaCd|x6=8$}T>X$2aDJz*_%A_u=4^gxeUw47}L%XF)eH#9BioL^cj zpE6@Z?SJxhuBqq!i$jM5F_-x28{Gev`1uLTx;mm%Fo(V1_0{hXmhyG`q(s|IU4j zYZI&Z1ih1p?{gAk?E6yY4QHGb4Cwd4-ddRXg+hnS0D`Rn*Sb6Y${+K`%30X-T3=5cDz$YSzyTw+KUCD z8#_BtacVj;QAAG+QH~Oo1hgQ(RLvbLsnCf5zo4as0u1AOoYMiDwEm_V{WeJoH*b^Vk%d7~6$Gc%@~21s#QCd!2wEz2+ls;Lkj1H?LN6I)&F3x^4Ey zSi*cg`BqluX4iENXjrjv;b{@8U(t<3!^9A+8x#YZ?S?;vAS^41mu1^cjVG>Nbjb6x z=F2#Qyvd@(wd2yUg>V+R{mwrzet zG00wK7f@oNfX<@Y@&mcn&rqQ?#d)y^k1#EZoo|BXH_EZf(;iGk)%u^U#U$4;65kVWvD+J?i|JN7o^MHQO zK6W-A{OGiOhoLky98UbK`|{%EoT0;7nW6EQ%W$PA?mVB)4qYWy*QrrJq&`I%!2aNn z9=B0>$by`Hr%{!0?nJyDnH_OS@4EttPizgBlqhZD4SipXED z6H9gVpBMPakZ?C*^K64<4384;s< zN_|q5K4LdI9&*dC)tt%mJ{HtKe9vNF>>?c~_>G5j#V>?k5LY&?L&@NF*ZfjDyZ?&JS_kKfckdB;@7d>)=-!tj(CtQ@y^(I6G z*gka&Zo9KAia`Hp{rHiQ!En>h_@ye9kH+i=?q|KNb(_rcFK$i82Bb41!KDQyj_gh5 zk6Rmv1Fj+|Bt-^>@FF%`$^vocqGG!WJsqL($~07|v03Zs3VJGy_&NR9Qkg=)2sqT|O@ zH(`#Q5*iIQfDjv#=jc+wnpwS-tpn_Jh_7VGY{sdiwe zm~wrz=#Eix{027zsh28R{+``WUK$n0(OgItgxHXC2qL}l9IiY5Jo~=dOsT#_EcPc# zc@;%y=i=8zw?}np)(u9zmG^i)SYDYWUCG|NjGP&`z3k>Le=AO=#vfDa>%*|*8 zEx^m_BAeizhaygx+ajU~m{qrh+^?3%VYLPj2V^NgwstP}EFYe4O!0p==D34Y;}u!C zxR^54@v$S_g(-CdI5;`G9X|BB)37mh`OLtdoTK43XJuo=M}rIY>>tqk-s(6~1Ji8> zL{k>e@e0-)rrudV46UY-F9P&FfJM|~ljgus{t{~Y`gv9LcTis`#F^;qBVJF+6gI0> zm!Xr}n15e(?`t<0`m!SaUpuPPXf{fm)^t8&794aPJQ%DWQix*U^YGvlaY1}^|pUf++ z>q~j=xzS-CSue11hQB61<8?qPB6GZ0y~vO%TCjW-KrFvxuVuWD^j}7c^;c*9)?D?HDP|V}6IoaB3H~sl+wyfE4$K zm6=NJZux(N;*pLKUMTlTXjzoHu-V zasO&cO7|g~10~&^;sPicQ1WN!4S<9<;A+38%Z6u2>h_8@maIZQ2FN}5?E7mP{)ocA zk8mqZs7~RE?0f}^#1FM%qM{&U3(}4u`yFCV{GnB0#k^bzk*8;5bJRpBY&}%m{>R{p#lHC z-Jg3OD7JUC-G1=v>in(?>s_K`ifx~>VE+wz%f0<3T=sBOn%xIB9ObX=E0t-G@HQH9 zb)OZ4qDMG)i)ls^o{Aw$s+K-94GK05>L@qGmhnp2u{NIX*C&=(HdR8j6T_q*^ zu}&GiTzRUd@3_(VRd1K@t>;QqK>AB+Rp~nPA`*>2>f^2_@4kMQRWYioMdW;f$=JRm zZD+bs!2I$s{NuJ%KjX_4S=x1>JcSfoD~}!5#&z5G-iOapCwneX&TB(@QgpP>a1(7G zQgBRisY}#`&LppPXt(uu;_-V#lU#Tma!xx&uTz(;Lm+K4CbwC!%vkdw#HUGAMeuX6!knq<__FsJt z9XNAQx35&u<#*HG^CZhyNqm`ZK}?G zin#BlHVzUp?^@$tTBhu1Lb+3({(=}```3dw&U*RHoz?cUgB6zzYC_hTE2t>+IvMauq zeU7b?a+VtO*JwsYZm2jih=NXr?p8}2I~mo;z6*JhSUE1kS6mY;IvH)3TxCt;INNo$ z-|beZ?s*JEnMa}#FhQ-==GGP+RU!d!WiLUnJIWvL`sX$+4$ZmoeSPlYhjEeM z7=zmzoPdTssD*z((>omA$PY9vD`vPXEvqboiGePdoPX||RM!FN$Z*I8QKWihnvChH z`_gI{R&K)3L&<=TW(Z~4WH~w2@jXqeiNPyH6fTcI(+*=aD-%c;Kz130@L|GnbiQH;~jvG#aqP54kWyBg(HCoNKaQV`DZs*V*WZM{$gxuzw{#LSz@ z#)rm41IowNEL20fBaK(T`J2*S2vM-&2fsIQ3^nlCn8lSmUz%^?s6IGmwnB~yI*)Ro zU)dbjz7Qc*ER>aHY@YPKPoLi{7#{JAMD+WC!M%-V$%?80W3wbgV=iszDY8`$7`8s3 zr4{_DC-N8y&13;L7u+iuBNat%y+=nn)0v8z)?_b4t71?Db-$bV`! z!Gk_LgD6SDml%%}e={uL*5sBs_G;A`iMYf~p!D(Ac*EM2Ldvg>S1gJ=FCPAP znto!F-|ACod;}xV>(o)n{AO9{X&IlI`N$1@!6dpSAWY!1TzuHW(kX<=kg9SQ^{FYm zh;-L%+6!G7<62Uj8Mj+T?Mo0Vu++T$&USyP8?Xje$d6AQtF-Nmz`6@YSTBgATIyr3 zwFBHc;Bt1}0rW%l@qw2o?vn;a?ohgN@D&jUbEC5)!?KV1=HLByttY0IzKh6h`|+-B zP=$2}Cf9y17l`R3<}m&WxuHUjF7qIqHv9RQ3TT$4wr`p90(9RU9`th`HbLweM0U7! zpfS5aUDnvtlpx)@8=(@_+}o@}&UHOg{XQetGd8eF0^PXj$c?JYvpoZ%;x+5?#V;dT zL14K8-b485p+gLl*4plXajZODiaz1Dc`4|Z_BS)V!}Xw2`S^m;- z*hZozi~fHtfMR$YEm(~lRtr&M>1gQ;Zj=~%hQx?p)>HJ|D`ue$Lm}dTIk^Z)U2bYMfwaPDZzE|^0H}Rfb71pgC-C0HEg4+e*0TlTO)erb`M^| zZ7tue3IdacUD)2pcUxTZK4#*Fgf}|K&cW?(5>f<$$HLU|>S%eogJ1VUWuPt{SVdzF zMF>EHcU+g|?~S+6E7$vA!c57Z|6-5v_P6F!vn;|!{wypXiwDtdl7DW-GR{=BaO#XP z|0mO~CFGsxL)#!hmp=)UoR-s%it-OF|Bkzad=yKzv?q&XkP#b$YcPS^5woEM7|Y63 zN;Nt?cr-bPJ6#&|{y$C$o!qR*MzpBiHat*`_a*oN#|E0;rxeCxOJu)Pv`9*x|H{!?&daBRX>bXlXjoER?Y*3T83^qR70J&hZ`!HNlo(_|c2|k5^Jb1W*-!->D@N9HKbK1>RW1av?x26`R`%_+H!ESDAIn>9Xk=@|A6~$f zPe;MR5+0tq=p5iPAmi}qptJQCxEA4H=y^g|MB2?vLboh?+k$_=*QpI@+m5<*^mygdcY=CDxvxyDqDSr7bu-(B|xm}ii` z!Xh^e2Et(@SS;?Um8NQ~ASG!%*yCtasXy?}f|$;3VkBRPAckl8F0UK{1BsRdH z%?f%r1eFuw;0ogyLs?_(UYm_PnZ(|%306I~i|dqpViQ!LDS*=JTuho_S{D@9AK44K z|MhHt`L1mFZhd<9PBQ^GzZ7ixQ$Hs_f1pSejsn)|=z%CmI^%zfUAFi4Z!sv4;TRo- z-gG@Z0_vbMT3E76p_&Ru^6X`4DHAvZG8jKUz*a6znfr3?kW#_0D#ez8bgjb7NsAk` zxE}_m86-6;kDCAVi4LG}w}7Lj0?In;>vc_EMOTLVigU@$`1|`e`R`fYJX_avGGdg+ znr0(mT*EiaX+{Tldf~m_AMuYd=yP6P;uF6iXn09#ec;>7jLN5Rm6bc^zF)V4J2hpbY_(q@Oe*5N=s1^ zdph4)v=m1%gvHwNs=(n;TZ_{^A1wXf*Fzbs3=SkVk-`QG(Ioj68fg6F z{+OX?8uYIg&HE=-H^)4SNFH3rPAKDb`K?s-X*>R|LMq8MpE}iGJjU3+CgINAl00bB zrn1{W(>DtGqwT_H?4@3CIh6h_Up80+g+5TJ&{gsJ`SR=kI+UY4{9->AocIU_k`IZH z4V_QK-m8o%FnqRgnq0+6`&fE$$%uAcPU6;v`r^7GuOg5nc&n$@FFPEaEHpfXqDD*~ z)2PwaIQJQ1`mZ-H)>hF9eT25UY8A(bH7UkJUY%i6M3c*AyDe)Psgmm3*d5nOb**U;X|)0Ows+Sv*6}hEM{&A z@dyJ)HbA?I?#L!|)RpE~D6x&#fctehQ9~hj6B~CIfJ8?qj%%kie5ZTT8DcqN3{yRu z#n$74ox=W+#6^O7a`J5HOO8^PWOt7e7lDnq?RU%|xWqmCIUC$&>@yJDfCPMK-$w{z z-Uo-lrSBB3c2L1%?zdTzGQbDIJ0c>oi*@h>HC^4XL;fgO&ESoin40pKGI6Yf(ndj- zzqJHVP%h#r2xtzx-`y?^&=bJDKO%=y=dr4~Hjs(<6*9_|0s|#9%LpPnzd=_@Ho$^S^)YTxt1t6fjR!yWCDB{|tn=R;^X`+AMx&VJ~e!Yv{0kQ z-TfJ^;;ZPMW#BfPq!@lYh0BvJIseNS%9h`nAetRj|It9s!1*^0E`Gp1Ax9Tb7J!HV zVaaTOx@0>Sd7%F*^x4(}FCNiSC3+6FQU&e*xcqv_FPw9=L~_a#c<~%$3RH=afBxhX zdP0O9oL=z7V7<2c6agKcgy=90sY9QQ9j`US9YR9M?WboHNdE=AD-MfnZmBr+y@SVt zuV?2Qk5bfN4?6li(W5~<7dE}S+CLqXDJ8ytpR0+#^>1~C<$nu1Pu~?hKd`&;?PUaC z=?8-Hi`n^~(?5S;?d<5vNJ*E{A>Gp5CEXy>ARrnTp9p&6SG?GDP87@>&vO+lA@w+BR^S{p57WOjlm4pWvm=W1#iL#FG zJc?8p?wy;eLe6uye$F}hxxdOR{b@r~NlVHz@p^*3^rVPV3cVbPLHQ5u!O;zS&G-EPaTp-{r}n)uA_TEYc!hOzx_u_(93>?s&wa=SZ}8w&60l2e+lsX~fhfVe;$ll6ra+23 zkmbMO`txP%K)`b{_xqmuhF8KAk+Z%Uqj8DKY6PJ+hCXN3cLP2_aA=v!=8y(=2a-cg z;CNDWEa7Q2EWW3?`{4r;pqW2(ETS9k zS8Vr-K&AcsqiV-R#K8r#nXbLlfh8wXefso``8?Cvl{dk*9Q-#@*wG|J!e&V&#v65@!{czA~gv$)4^P);4>s`AGb6~W&DV-N~j1E@J`>C5HVI&VDlQ z(g_yqs;dl(C{p~X0E?2|=E+T*yTgnxe#!D3H~vB+)JEmDHHgRvAzabJnz#K;LRpbI zDp)BtF5clB^;;T$)3WMg@2sZSaKVyZEY6hMa%Kj8-d+vexVfK1^^d!(_x7dm1yC^v zx?lSTx>#Eo+GL|)Q?0v2*^W3_qjH767ObuGNf*pzMPhs3S$zV#4<3`PI5@PhNy{04B+hK6dTXKmNRfICsKA$fRYS zKTk=v$=6{7wV2oQU@dvR3f^yRZTcH_EB}H@l^Xl`Zg@KBY;>3c??1aha5x7YePZ6i z=pHhg;*NKw$6?GfscVdgjjQ?Lj5%%SGRQ=B$t=YZ*S8_wLd0 zv1!fx88ih+(EOX;|KnA*?Dmq);C4D(yBb4c!qnDB(9a^&JlywuXDmgXNU&5m#pd!V zWs=Iu^-&WZH(S!%)VvD3>f*FP5YDbu&NB zTdWMK3MDz5+bMM!i>BANudc4<0W&mW90}_zh`s93*}kTvf>13Mz$L~^l7Yg_V=Se| zI=kxzFC&m)+ksL{oh^TtYY})Oa1#U6OhZ!>x`Ey|5A!xXCRq+b$n&)npGnKo;3sJi zMD&m~*bqj+W-t8c*9n&TSxcxU$5FBiu~ipqqX@4rTFy>=F9bj&hRy~q+{2T6M?$sk zt>k%yUvc2{jf9Hi?77HQ)wEuv6LqEa;EF&Sm3zd4fh5PKuFtCxPb!~z&N}qWPTlqq zcTD!6$!+|LtRjBR?f%^PE_e!m5I2T*&xW&Y8MJq91c&*05=9uW{V%0xtUY9azSISh zE*?fa1viVfb{qw#+4uZKl_*|nmZk}HXKJmyS;}osE#9|U_gU~QI8f2~|IPQdD@x30 z!IVlr=hoG`Bg9WYOAB06KpaVM(`nyU*3$btXmwU3o=7HEz!Vkw7jI`vA>uu@w#;J! z>&G~Wedl-Oj3hhq$;LdkLucDc3`gE#7dqt{*8ae*9c4ONP!WGQ{42*TJNQ?W6bH>S zliFzoZ)!?adjB$A@}j*rJVJ}tVMPyb|63!Wk|C;Zq3-Z&6GZhZcjAT@jY$S)f0Jqpr)Mrr4r;yriXP7Rd z-iKq9Hetq8i#elo7ez46kiJYa=2IY>b6c5U6e=pf57>&AoR)w-1s z*4o|b`C8a^1%wPVrwBC-p|jP&JKofTh**O#6DSXZ9=`dA2pHo?dt^`UdwrN@=R16l9ytSc6IcH`DUREpAAMERMu>4ze}&}$B4Y(M0-@(bf}mNCgFZ%xk0jnq zcEJG+tL5fuZ)VpmS#^`T%J8uvqF$}~9u)|EEF=U^4Sq@bSL`_Iwwak^ob6-3#yv+IlRb8{7%m+u)~QNe>qa_331 zI9Th8Mk0FGmL`|2;P!987}@KjQrm7meuxVK8ljmcgGCtN4H%V@z+af|(U6Dt&#s@R zyPM9U^s?YcvSA|Y;?-xUGZoU%hWZWRbp{WqQnCL_oto(#SncLEz4UnY%s|1ip#A#o zvQ%`NiH@HOoRvGrV{nkdQCpi;o7e^E0pRZP_(OTK)Q-s!X|A#M7G3K32YJl)rtEA~ zmGRpj$;^I(u@EW`P`RUZ3}C(u9Sw9~1M!2)3+@8trX4cz?1ecs)3klA+N8HY%|iq| zf+-5vZac?3TXDLHM@@S<3E~In!!0M|r|i%BKa1ax`SD{C|D9zwNH6*1UfL9Y;d{*L zP`@t+t2QuVGyc)@G&F5xY=C3k*ZA6)qw$v%STB~H^g=lD^}^t{vc2dPW6jwRM#*l_ z{lNVvbC1GaR)nUOW;+NhsHH8bf4O@`MyI-2OB4fiGY5FV|vP>zaSO|!+91pfov=!{99l4;xPdrspyOdhl9+3tGj6*}6iW!{^&TS^oUV%+8foFm zi67h*xd>Go5A_w3?ARUSaeI1|wn=aghktfaq9dIq@ET2E`XGZtSgY6aIhED&o*GVv z6DqcM8U{YoglnLgz19oY9(g;)$U_edJRYnlYE%6`-?fT=-;fT_n`|jOXu^(vBT6MK zZZ4QPrQV5GUh1X&z_#Ihbv%^n%@=0xxBg|C!H!o&My^d#>b>svOxg8?51CA^4BsuB zjriT)9)F~xuL~3s41E4@Wczp5+)eHLbkx#R3F*sr^1}Hq@{b%9PDdRy9bb;QDbmiX zV)2+4in(v}MTwo6G5yP?T+HZxcd2r&(4$_!abQndJz&jAKcyRRXW#M4<;l04>a3rK zVV!tck&fCXy7M|WB|6nOB-?wg?B;}p_Fq(OH%d%vJh@)2m6rtF0vNHFL)|(tG~yi) zTr~?ycO}Avv1=nL+0co}^U}_1B`6IHCruhm!m1Hd6;2eGc#YT&_}r ztEn$s;3rcd6=+aBDgq0gpy?^nM43R54)HEcpb%y(`2YfB5bXcF2u7;oPm%x5q`D1q zq=z0$w?2RQQnypmP`jD>){l?O7bXR_oJM6yz~@nW@u%VJ`m{w2US1HoA^ULmv5TPC zE&^8t%>qn=q%p}=@bn9HuzRxv6P;c<#Fr~yza5xj2hPq2*!4UvJvJ7cF@yg&L zVty$z;YyU12o;wNKszGr_s7Bs>d>4avf!dBP66y=ezRC|2Hu}&f+-ID_Ap(e<)%_^ zZ2L);XFPFa7AL0{L6laO6^05kDo4(;{RbT#hPBM#Y)!kyb6dqhD_A&~udn~7 zZ(n?mo=>F%#M4m~bjNKE!W&|`+Fn;Y$r-cXp?~)?Gc&Qa#DXHkuM?ZzDxJ*^`!`;l zxG{f-jgRkV`vfyec+J__*`a5G0~iq(S&@T=bn{eg6bN@PR|mUmH;LGdCx{O6IhvP? zn4Et%8PnFj^A2Ype;`bBEJtiatn3S_vHM_bzEp)hzewWYi}UkDF>laf)V|v6n+?@p zx&1_H2W+G_$#YbRUy0`E7gt^$6B=4@$56N|dLuP@&)Hn2=Y4b%41=^~u^84EGq*x2yNFxhQDVFOX^re&$dgKHQ*@eUD#g;g_Lvi^6svrI&_h za(3}Np^qB>V*YE}_pc~pi&BxHtv@Nvo^`3uk@X9$$Qt>oIGdLB$9m1TjeL?`oNnWy z!z??$JtN;X`5?fIt4-ChFS{m_T-k#B_eDAh!)*iO=Q{FnfvHquy61U2TLENE9vP)r z@7e>x+J5JS^*U!Aho|01d#2X@!rdLR>3M>}rq&kndOfJDS@TeUe8Tm3eml}7Y+7LH zS(M_un*Dci9cOmJlfb$HzHhN|wofqJ%|j+;$zN=3HyTdsTrQwL*>-t*FX&F7*~O!f zC_;`fR14a-kF#KOGEsdrNh~*i|1O!?7sHdMw)5N9hj;1a=CN+Ou4shZ`(q!@#hdi@ zeFxUu(1ZD>V6^mr@%JkAgV3&zU8|kE)G6h9$r}p|bxZ!3xB32F9uB*7U<*+Amr%a> z-y&KPpN%H57a3jKKz87iJ zf~U{r=HDG8_nW0VKdvZm+PcWh_+dJ}JETe=Mrk~(g(66S10usZmbIh|cLqFAJx zUTLbrY1tg%4Fh{WP~Z?&N5o_Rq;U`hV2Tf#z{<*s+GXvDhX^pn2MR(3ekQ82#h2tI z3YJGTH;Vx)8pig|Zs6F1q&rIwJ_HsFf|+dgC8^({?c-WRb@~5}5W#QTQMNXon3{}M zX0UXs{b~bW4~a=<1|pw$@zVG6vh>`qjuFF~khGiRzh705E-yaZ714VZ(&xZ9HP`RX z!UAgMSid|vtX_nJ{GEI@Bz(C9v4oj@ooVdE5dI6WHFq7?Pd^Fl!3zzQpiL9~M;DlW zz`j42=4$3Gb3*b2@dmoi{w=+aVP>gFw{g1M|3YWVdCoY5K$Al41~m2fm&Ta{J=hMqmYtlYaeXBC2->RM*o%7}4p83w>-n}m zy1sjPUAuUg^;|r&Iy-(~FySd64rT&yxD10zoU{w_6AedB=G+)?ox_2ebkKGu*60;l z#MSW4-vCaZs8ZkEm++KcyABX*Mxo!NmYavjW$`q~pvQgwx^E()dUdkvjHUKjkb9>- zxSveo`Z;zeiMfu1)<=n!8S0XEwI?fLOHP8>MA;tIg~$oBc2-cVBJyt_V7S8baHA;Q zHL3?}Ru%2-w}8|-Q$jI)EnyIQ&8vGN%`t3WjwSYhbFIKK=z9GXlVmEb>yVhua)#7M zq&B%jI<*P~HkvdM-+_K2MVR47!>h?t$Ffx+3e?XTCW0TD>vw%93vazkK<}iobv0&Wf_H$g!*N&-Iyw&%WxRB_jm45{k!*=B+eQSZA zbgX{gfu;f;n860a!9Fg3DkmHW7XCW=Jq#J#$VxD7Dk`$`OKhvKoOu`Id-Jy0dBOFC z!zp#~&`hN}F7A_u8}liP5TOPHKpGc(*l&ep-P@E;vNXt$*aapR7yjQ1V6{^?#R?`a zsNUtN;m(I3a`77O8OO1eJkhY17p;Ta#Icg$4GIpbAJTrLsED)nxY3dpd$v0WnQ=oQpk<-*(@`pqQEFb9MsFkH3HT1shXKuQ*bH&^*gcvSv^wUtYxdwxd%VZ1#};42!s2I%jV;pXE&S)eIq4R4rz&^{`?qZi z9Gc>YLP-d{|2&?ub%>AScyCSxMT8&B#Sf2ev9|n^t@pWkd;V3~w0prl>w#}$Q9G!> znNXnsJ;9T*c(LqV6=Q0zGz_I@(ykHgsgL+jXK(=)|9jee!a`Yt^W+FAQ@&8+tM5$dnk|=3y{^xVvM_a*5|;ITPfT$DNCB`pkc-CeM)=5EUItNOBxxE9WLSRAo=~p*X+@K zSUgEFO>)s`k~HYRH=D3OBD(ipTMcXT!s=UuRClOGSC`4aA^s*D4{Oze)hP59q}8U8 z`B9}~(zvd2fBh^6wrUCr)O0QRihiBCx)-anQ|k`MBrx|({GN)4-tO zy^6F1QOIAve%<)^U6r)!FGO?0FbdWtz-yP6pC6@-)F*=+Gy7e)q~X)lorfmLs=biF zp;tVGqMFyU`s&=@TT8WIEq<^D?;{#C?_knX!k3;w37#DQ_ooCERToawD<^j~T`0w^s?)$H=&RI+UE`k%#y7viwGuzN;;PKAm-A+Q!;^v10!EBkN zV<(2;PaXsihbp{elB5b%jDk`Wq#Vb_SGSeoi`I*4hFY!069xBc5WYhvLGT^I<)OHr zSy4eyIU6>-i82=d;7Ml3#(Nmd540*-6Zcm2pYV{TiG#!Co|@rCFhU-h@bc%J>ppCMI$kyLTN*r zWiQI&Q;BhVDkVX9fe|1D#|e0Uik2YZ5sEeEz~*NQAQi8j9Rh>+En{~RKuu4psxJSq z8k_zYSF1dD!g{tmM0s$fzqpxu84GxsiZ{o$h8!e_!PH})S)TrP&P)4X9zirSU~z0N zb7jpf)kpE$%**=s*7Gq89l~+#)@D3=2;NdLl&0XJqv88rdv2C*``#o>9&VT_=9F1| zU{e_fk%%GctOWV;p!wog@)d)*LH9xWmSi*cpZm4sV^b)f`(*kKhhxCbW(&F7pA(E$ z1~EC;ex5FF-VP0b0uh1H&`;3=_8Sms?PglXj(7CyeMC!BU)`2XNjdmQ+nt10+F7e{ z$g9OIRlK3jYovwA^y-JL(d|fjP4rjU;Il{U4zy`~^g_<0QTXVcIh<)`FF4X7h;bid za=Yz?x9gYp0bWGZLCEht2|^EFpn5m=nlM>ZXV!~ny>w4^7Qi`DR-ANWk@b!5j{NO% zTe2iU*ff}~Z%!`#VV+}p#wgnH`x;&XE&^uM36hnz%c~&a`?Fb6-Zj1QX<-us(}vgSco97aC_f_26c!Z4&#&c;jg8;vcytB< zu)&!Rk|#V_~v8cmn58W z^9>~IaUeqi$gzBW7i{VXYBJ