From 1c427554516c2616cbd41426b3423531c6fb6b7c Mon Sep 17 00:00:00 2001 From: Jade Date: Tue, 15 Apr 2025 11:33:42 +0800 Subject: [PATCH 01/42] Make Vision pose estimation examples use all vision measurements (#1706) Resolves https://github.com/PhotonVision/photonvision/issues/1634 --------- Signed-off-by: Jade Turner Co-authored-by: Sam Freund --- .../poseest/src/main/cpp/Robot.cpp | 10 +----- .../poseest/src/main/include/Robot.h | 5 ++- .../poseest/src/main/include/Vision.h | 23 +++++++++---- .../src/main/java/frc/robot/Robot.java | 14 ++------ .../src/main/java/frc/robot/Vision.java | 34 ++++++++++++------- 5 files changed, 46 insertions(+), 40 deletions(-) diff --git a/photonlib-cpp-examples/poseest/src/main/cpp/Robot.cpp b/photonlib-cpp-examples/poseest/src/main/cpp/Robot.cpp index 75c72d216..3ce3663d8 100644 --- a/photonlib-cpp-examples/poseest/src/main/cpp/Robot.cpp +++ b/photonlib-cpp-examples/poseest/src/main/cpp/Robot.cpp @@ -34,15 +34,7 @@ void Robot::RobotInit() {} void Robot::RobotPeriodic() { launcher.periodic(); drivetrain.Periodic(); - - auto visionEst = vision.GetEstimatedGlobalPose(); - if (visionEst.has_value()) { - auto est = visionEst.value(); - auto estPose = est.estimatedPose.ToPose2d(); - auto estStdDevs = vision.GetEstimationStdDevs(estPose); - drivetrain.AddVisionMeasurement(est.estimatedPose.ToPose2d(), est.timestamp, - estStdDevs); - } + vision.Periodic(); drivetrain.Log(); } diff --git a/photonlib-cpp-examples/poseest/src/main/include/Robot.h b/photonlib-cpp-examples/poseest/src/main/include/Robot.h index 96af16d53..de874ce73 100644 --- a/photonlib-cpp-examples/poseest/src/main/include/Robot.h +++ b/photonlib-cpp-examples/poseest/src/main/include/Robot.h @@ -51,7 +51,10 @@ class Robot : public frc::TimedRobot { private: SwerveDrive drivetrain{}; - Vision vision{}; + Vision vision{[=, this](frc::Pose2d pose, units::second_t timestamp, + Eigen::Matrix stddevs) { + drivetrain.AddVisionMeasurement(pose, timestamp, stddevs); + }}; GamepieceLauncher launcher{}; frc::XboxController controller{0}; }; diff --git a/photonlib-cpp-examples/poseest/src/main/include/Vision.h b/photonlib-cpp-examples/poseest/src/main/include/Vision.h index af3713389..e612a5acd 100644 --- a/photonlib-cpp-examples/poseest/src/main/include/Vision.h +++ b/photonlib-cpp-examples/poseest/src/main/include/Vision.h @@ -31,6 +31,7 @@ #include #include +#include #include #include @@ -41,7 +42,14 @@ class Vision { public: - Vision() { + /** + * @param estConsumer Lamba that will accept a pose estimate and pass it to + * your desired SwerveDrivePoseEstimator. + */ + Vision(std::function)> + estConsumer) + : estConsumer{estConsumer} { photonEstimator.SetMultiTagFallbackStrategy( photon::PoseStrategy::LOWEST_AMBIGUITY); @@ -68,9 +76,7 @@ class Vision { photon::PhotonPipelineResult GetLatestResult() { return m_latestResult; } - std::optional GetEstimatedGlobalPose() { - std::optional visionEst; - + void Periodic() { // Run each new pipeline result through our pose estimator for (const auto& result : camera.GetAllUnreadResults()) { // cache result and update pose estimator @@ -87,9 +93,12 @@ class Vision { GetSimDebugField().GetObject("VisionEstimation")->SetPoses({}); } } - } - return visionEst; + if (visionEst) { + estConsumer(visionEst->estimatedPose.ToPose2d(), visionEst->timestamp, + GetEstimationStdDevs(visionEst->estimatedPose.ToPose2d())); + } + } } Eigen::Matrix GetEstimationStdDevs(frc::Pose2d estimatedPose) { @@ -149,4 +158,6 @@ class Vision { // The most recent result, cached for calculating std devs photon::PhotonPipelineResult m_latestResult; + std::function)> + estConsumer; }; diff --git a/photonlib-java-examples/poseest/src/main/java/frc/robot/Robot.java b/photonlib-java-examples/poseest/src/main/java/frc/robot/Robot.java index d47e3056e..95fac0e8a 100644 --- a/photonlib-java-examples/poseest/src/main/java/frc/robot/Robot.java +++ b/photonlib-java-examples/poseest/src/main/java/frc/robot/Robot.java @@ -46,7 +46,7 @@ public class Robot extends TimedRobot { @Override public void robotInit() { drivetrain = new SwerveDrive(); - vision = new Vision(); + vision = new Vision(drivetrain::addVisionMeasurement); controller = new XboxController(0); @@ -61,16 +61,8 @@ public class Robot extends TimedRobot { // Update drivetrain subsystem drivetrain.periodic(); - // Correct pose estimate with vision measurements - var visionEst = vision.getEstimatedGlobalPose(); - visionEst.ifPresent( - est -> { - // Change our trust in the measurement based on the tags we can see - var estStdDevs = vision.getEstimationStdDevs(); - - drivetrain.addVisionMeasurement( - est.estimatedPose.toPose2d(), est.timestampSeconds, estStdDevs); - }); + // Update vision + vision.periodic(); // Test/Example only! // Apply an offset to pose estimator to test vision correction diff --git a/photonlib-java-examples/poseest/src/main/java/frc/robot/Vision.java b/photonlib-java-examples/poseest/src/main/java/frc/robot/Vision.java index 81e505394..d7fce3947 100644 --- a/photonlib-java-examples/poseest/src/main/java/frc/robot/Vision.java +++ b/photonlib-java-examples/poseest/src/main/java/frc/robot/Vision.java @@ -48,12 +48,18 @@ public class Vision { private final PhotonCamera camera; private final PhotonPoseEstimator photonEstimator; private Matrix curStdDevs; + private final EstimateConsumer estConsumer; // Simulation private PhotonCameraSim cameraSim; private VisionSystemSim visionSim; - public Vision() { + /** + * @param estConsumer Lamba that will accept a pose estimate and pass it to your desired {@link + * edu.wpi.first.math.estimator.SwerveDrivePoseEstimator} + */ + public Vision(EstimateConsumer estConsumer) { + this.estConsumer = estConsumer; camera = new PhotonCamera(kCameraName); photonEstimator = @@ -83,17 +89,7 @@ public class Vision { } } - /** - * The latest estimated robot pose on the field from vision data. This may be empty. This should - * only be called once per loop. - * - *

Also includes updates for the standard deviations, which can (optionally) be retrieved with - * {@link getEstimationStdDevs} - * - * @return An {@link EstimatedRobotPose} with an estimated pose, estimate timestamp, and targets - * used for estimation. - */ - public Optional getEstimatedGlobalPose() { + public void periodic() { Optional visionEst = Optional.empty(); for (var change : camera.getAllUnreadResults()) { visionEst = photonEstimator.update(change); @@ -109,8 +105,15 @@ public class Vision { getSimDebugField().getObject("VisionEstimation").setPoses(); }); } + + visionEst.ifPresent( + est -> { + // Change our trust in the measurement based on the tags we can see + var estStdDevs = getEstimationStdDevs(); + + estConsumer.accept(est.estimatedPose.toPose2d(), est.timestampSeconds, estStdDevs); + }); } - return visionEst; } /** @@ -188,4 +191,9 @@ public class Vision { if (!Robot.isSimulation()) return null; return visionSim.getDebugField(); } + + @FunctionalInterface + public static interface EstimateConsumer { + public void accept(Pose2d pose, double timestamp, Matrix estimationStdDevs); + } } From 537cd7c56443f0d20c6c86737307031b4480b319 Mon Sep 17 00:00:00 2001 From: Alan <40917647+alaninnovates@users.noreply.github.com> Date: Mon, 14 Apr 2025 23:42:25 -0700 Subject: [PATCH 02/42] Update PhotonPoseEstimator examples (#1903) ## Description Updates the PhotonPoseEstimator programming documentation page to reflect the new PhotonPoseEstimator. and add a more comprehensive step-by-step tutorial using code from the PV Pose Estimation examples. Updates various code examples to ensure they are matching the latest documentation or example code on GitHub. This PR is a successor of, and therefore closes #1765. This PR is blocked by #1706, as the linked PR updates examples. Closes #1757 and closes #1800 and closes #1632 and closes #1773 and closes #1465. ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [x] If this PR changes behavior or adds a feature, user documentation is updated - [x] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [x] If this PR touches configuration, this is backwards compatible with settings back to v2024.3.1 - [x] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [x] If this PR addresses a bug, a regression test for it is added --------- Co-authored-by: Kevin Reas <76408202+PaarkG@users.noreply.github.com> Co-authored-by: Matt Morley --- .gitignore | 3 +- .../docs/apriltag-pipelines/multitag.md | 29 ++- docs/source/docs/examples/aimandrange.md | 8 +- .../photonlib/getting-target-data.md | 4 +- .../photonlib/robot-pose-estimator.md | 217 +++++++++--------- .../troubleshooting/camera-troubleshooting.md | 2 +- 6 files changed, 139 insertions(+), 124 deletions(-) diff --git a/.gitignore b/.gitignore index 68d549817..63d518c8d 100644 --- a/.gitignore +++ b/.gitignore @@ -7,8 +7,7 @@ __pycache__/ backend/settings/ .vscode/ # Docs -source/_build -source/docs/_build +_build # Compiled class file *.class diff --git a/docs/source/docs/apriltag-pipelines/multitag.md b/docs/source/docs/apriltag-pipelines/multitag.md index f7ed78a9d..e894b955c 100644 --- a/docs/source/docs/apriltag-pipelines/multitag.md +++ b/docs/source/docs/apriltag-pipelines/multitag.md @@ -23,30 +23,41 @@ Ensure that your camera is calibrated and 3D mode is enabled. Navigate to the Ou By default, enabling multi-target will disable calculating camera-to-target transforms for each observed AprilTag target to increase performance; the X/Y/angle numbers shown in the target table of the UI are instead calculated using the tag's expected location (per the field layout JSON) and the field-to-camera transform calculated using MultiTag. If you additionally want the individual camera-to-target transform calculated using SolvePNP for each target, enable "Always Do Single-Target Estimation". ::: -This multi-target pose estimate can be accessed using PhotonLib. We suggest using {ref}`the PhotonPoseEstimator class ` with the `MULTI_TAG_PNP_ON_COPROCESSOR` strategy to simplify code, but the transform can be directly accessed using `getMultiTagResult`/`MultiTagResult()` (Java/C++). +This multi-target pose estimate can be accessed using PhotonLib. We suggest using {ref}`the PhotonPoseEstimator class ` with the `MULTI_TAG_PNP_ON_COPROCESSOR` strategy to simplify code, but the transform can be directly accessed using `getMultiTagResult`/`MultiTagResult()`/`multitagResult` (Java/C++/Python). ```{eval-rst} .. tab-set-code:: .. code-block:: Java - var result = camera.getLatestResult(); - if (result.getMultiTagResult().estimatedPose.isPresent) { - Transform3d fieldToCamera = result.getMultiTagResult().estimatedPose.best; + var results = camera.getAllUnreadResults(); + for (var result : results) { + var multiTagResult = result.getMultiTagResult(); + if (multiTagResult.isPresent()) { + var fieldToCamera = multiTagResult.get().estimatedPose.best; + } } .. code-block:: C++ - auto result = camera.GetLatestResult(); - if (result.MultiTagResult().result.isPresent) { - frc::Transform3d fieldToCamera = result.MultiTagResult().result.best; + auto results = camera.GetAllUnreadResults(); + for (auto &result : results) + { + auto multiTagResult = result.MultiTagResult(); + if (multiTagResult.has_value()) { + frc::Transform3d fieldToCamera = multiTagResult->estimatedPose.best; } + } + .. code-block:: Python - # Coming Soon! - + results = camera.getAllUnreadResults() + for result in results: + multitagResult = result.multitagResult + if multitagResult is not None: + fieldToCamera = multitagResult.estimatedPose.best ``` :::{note} diff --git a/docs/source/docs/examples/aimandrange.md b/docs/source/docs/examples/aimandrange.md index 86a2d3173..417c44a3b 100644 --- a/docs/source/docs/examples/aimandrange.md +++ b/docs/source/docs/examples/aimandrange.md @@ -1,6 +1,6 @@ # Combining Aiming and Getting in Range -The following example is from the PhotonLib example repository ([Java](https://github.com/PhotonVision/photonvision/tree/main/photonlib-java-examples/aimandrange)/[C++](https://github.com/PhotonVision/photonvision/tree/main/photonlib-cpp-examples/aimandrange)). +The following example is from the PhotonLib example repository ([Java](https://github.com/PhotonVision/photonvision/tree/main/photonlib-java-examples/aimandrange)/[C++](https://github.com/PhotonVision/photonvision/tree/main/photonlib-cpp-examples/aimandrange)/[Python](https://github.com/PhotonVision/photonvision/tree/main/photonlib-python-examples/aimandrange)) ## Knowledge and Equipment Needed @@ -10,7 +10,7 @@ The following example is from the PhotonLib example repository ([Java](https://g Now that you know how to aim toward the AprilTag, let's also drive the correct distance from the AprilTag. -To do this, we'll use the *pitch* of the target in the camera image and trigonometry to figure out how far away the robot is from the AprilTag. Then, like before, we'll use the P term of a PID controller to drive the robot to the correct distance. +To do this, we'll use the _pitch_ of the target in the camera image and trigonometry to figure out how far away the robot is from the AprilTag. Then, like before, we'll use the P term of a PID controller to drive the robot to the correct distance. ```{eval-rst} .. tab-set:: @@ -43,8 +43,8 @@ To do this, we'll use the *pitch* of the target in the camera image and trigonom .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/abe95dfaa055bbe3609f72cfcaaba0f96ee7978c/photonlib-python-examples/aimandrange/robot.py :language: python - :lines: 44-95 + :lines: 52-91 :linenos: - :lineno-start: 44 + :lineno-start: 52 ``` diff --git a/docs/source/docs/programming/photonlib/getting-target-data.md b/docs/source/docs/programming/photonlib/getting-target-data.md index 7729f43b7..69389eeb4 100644 --- a/docs/source/docs/programming/photonlib/getting-target-data.md +++ b/docs/source/docs/programming/photonlib/getting-target-data.md @@ -86,7 +86,7 @@ Each pipeline result has a `hasTargets()`/`HasTargets()` (Java and C++ respectiv ``` :::{warning} -In Java/C++, You must *always* check if the result has a target via `hasTargets()`/`HasTargets()` before getting targets or else you may get a null pointer exception. Further, you must use the same result in every subsequent call in that loop. +In Java/C++, You must _always_ check if the result has a target via `hasTargets()`/`HasTargets()` before getting targets or else you may get a null pointer exception. Further, you must use the same result in every subsequent call in that loop. ::: ## Getting a List of Targets @@ -140,7 +140,7 @@ You can get the {ref}`best target `. ::: -PhotonLib includes a `PhotonPoseEstimator` class, which allows you to combine the pose data from all tags in view in order to get a field relative pose. The `PhotonPoseEstimator` class works with one camera per object instance, but more than one instance may be created. +PhotonLib includes a `PhotonPoseEstimator` class, which allows you to combine the pose data from all tags in view in order to get a field relative pose. For each camera, a separate instance of the `PhotonPoseEstimator` class should be created. ## Creating an `AprilTagFieldLayout` `AprilTagFieldLayout` is used to represent a layout of AprilTags within a space (field, shop at home, classroom, etc.). WPILib provides a JSON that describes the layout of AprilTags on the field which you can then use in the AprilTagFieldLayout constructor. You can also specify a custom layout. -The API documentation can be found in here: [Java](https://github.wpilib.org/allwpilib/docs/release/java/edu/wpi/first/apriltag/AprilTagFieldLayout.html) and [C++](https://github.wpilib.org/allwpilib/docs/release/cpp/classfrc_1_1_april_tag_field_layout.html). +The API documentation can be found in here: [Java](https://github.wpilib.org/allwpilib/docs/release/java/edu/wpi/first/apriltag/AprilTagFieldLayout.html), [C++](https://github.wpilib.org/allwpilib/docs/release/cpp/classfrc_1_1_april_tag_field_layout.html), and [Python](https://robotpy.readthedocs.io/projects/apriltag/en/stable/robotpy_apriltag/AprilTagFieldLayout.html#robotpy_apriltag.AprilTagFieldLayout). ```{eval-rst} .. tab-set-code:: - .. code-block:: Java + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-java-examples/poseest/src/main/java/frc/robot/Constants.java + :language: java + :lines: 48-49 - // The field from AprilTagFields will be different depending on the game. - AprilTagFieldLayout aprilTagFieldLayout = AprilTagFieldLayout.loadField(AprilTagFields.kDefaultField); + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-cpp-examples/poseest/src/main/include/Constants.h + :language: c++ + :lines: 46-47 - .. code-block:: C++ + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-python-examples/poseest/robot.py + :language: python + :lines: 46 +``` - // The parameter for LoadAPrilTagLayoutField will be different depending on the game. - frc::AprilTagFieldLayout aprilTagFieldLayout = frc::LoadAprilTagLayoutField(frc::AprilTagField::kDefaultField); +## Defining the Robot to Camera `Transform3d` - .. code-block:: Python +Another necessary argument for creating a `PhotonPoseEstimator` is the `Transform3d` representing the robot-relative location and orientation of the camera. A `Transform3d` contains a `Translation3d` and a `Rotation3d`. The `Translation3d` is created in meters and the `Rotation3d` is created with radians. For more information on the coordinate system, please see the {ref}`Coordinate Systems ` documentation. - # Coming Soon! +```{eval-rst} +.. tab-set-code:: + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-java-examples/poseest/src/main/java/frc/robot/Constants.java + :language: java + :lines: 44-45 + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-cpp-examples/poseest/src/main/include/Constants.h + :language: c++ + :lines: 43-45 + + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-python-examples/poseest/robot.py + :language: python + :lines: 33-36 ``` ## Creating a `PhotonPoseEstimator` @@ -35,127 +51,116 @@ The API documentation can be found in here: [Java](https://github.wpilib.org/all The PhotonPoseEstimator has a constructor that takes an `AprilTagFieldLayout` (see above), `PoseStrategy`, `PhotonCamera`, and `Transform3d`. `PoseStrategy` has nine possible values: - MULTI_TAG_PNP_ON_COPROCESSOR - - Calculates a new robot position estimate by combining all visible tag corners. Recommended for all teams as it will be the most accurate. - - Must configure the AprilTagFieldLayout properly in the UI, please see {ref}`here ` for more information. + - Calculates a new robot position estimate by combining all visible tag corners. Recommended for all teams as it will be the most accurate. + - Must configure the AprilTagFieldLayout properly in the UI, please see {ref}`here ` for more information. - LOWEST_AMBIGUITY - - Choose the Pose with the lowest ambiguity. + - Choose the Pose with the lowest ambiguity. - CLOSEST_TO_CAMERA_HEIGHT - - Choose the Pose which is closest to the camera height. + - Choose the Pose which is closest to the camera height. - CLOSEST_TO_REFERENCE_POSE - - Choose the Pose which is closest to the pose from setReferencePose(). + - Choose the Pose which is closest to the pose from setReferencePose(). - CLOSEST_TO_LAST_POSE - - Choose the Pose which is closest to the last pose calculated. + - Choose the Pose which is closest to the last pose calculated. - AVERAGE_BEST_TARGETS - - Choose the Pose which is the average of all the poses from each tag. + - Choose the Pose which is the average of all the poses from each tag. - MULTI_TAG_PNP_ON_RIO - - A slower, older version of MULTI_TAG_PNP_ON_COPROCESSOR, not recommended for use. + - A slower, older version of MULTI_TAG_PNP_ON_COPROCESSOR, not recommended for use. - PNP_DISTANCE_TRIG_SOLVE - - Use distance data from best visible tag to compute a Pose. This runs on the RoboRIO in order - to access the robot's yaw heading, and MUST have addHeadingData called every frame so heading - data is up-to-date. Based on a reference implementation by [FRC Team 6328 Mechanical Advantage](https://www.chiefdelphi.com/t/frc-6328-mechanical-advantage-2025-build-thread/477314/98). + - Use distance data from best visible tag to compute a Pose. This runs on the RoboRIO in order + to access the robot's yaw heading, and MUST have addHeadingData called every frame so heading + data is up-to-date. Based on a reference implementation by [FRC Team 6328 Mechanical Advantage](https://www.chiefdelphi.com/t/frc-6328-mechanical-advantage-2025-build-thread/477314/98). - CONSTRAINED_SOLVEPNP - - Solve a constrained version of the Perspective-n-Point problem with the robot's drivebase - flat on the floor. This computation takes place on the RoboRIO, and should not take more than 2ms. - This also requires addHeadingData to be called every frame so heading data is up to date. - If Multi-Tag PNP is enabled on the coprocessor, it will be used to provide an initial seed to - the optimization algorithm -- otherwise, the multi-tag fallback strategy will be used as the - seed. + - Solve a constrained version of the Perspective-n-Point problem with the robot's drivebase + flat on the floor. This computation takes place on the RoboRIO, and should not take more than 2ms. + This also requires addHeadingData to be called every frame so heading data is up to date. + If Multi-Tag PNP is enabled on the coprocessor, it will be used to provide an initial seed to + the optimization algorithm -- otherwise, the multi-tag fallback strategy will be used as the + seed. ```{eval-rst} .. tab-set-code:: - .. code-block:: Java + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-java-examples/poseest/src/main/java/frc/robot/Vision.java + :language: java + :lines: 65-66 - //Forward Camera - cam = new PhotonCamera("testCamera"); - Transform3d robotToCam = new Transform3d(new Translation3d(0.5, 0.0, 0.5), new Rotation3d(0,0,0)); //Cam mounted facing forward, half a meter forward of center, half a meter up from center. + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-cpp-examples/poseest/src/main/include/Vision.h + :language: c++ + :lines: 150-153 - // Construct PhotonPoseEstimator - PhotonPoseEstimator photonPoseEstimator = new PhotonPoseEstimator(aprilTagFieldLayout, PoseStrategy.CLOSEST_TO_REFERENCE_POSE, cam, robotToCam); - - .. code-block:: C++ - - // Forward Camera - std::shared_ptr cameraOne = - std::make_shared("testCamera"); - // Camera is mounted facing forward, half a meter forward of center, half a - // meter up from center. - frc::Transform3d robotToCam = - frc::Transform3d(frc::Translation3d(0.5_m, 0_m, 0.5_m), - frc::Rotation3d(0_rad, 0_rad, 0_rad)); - - // ... Add other cameras here - - // Assemble the list of cameras & mount locations - std::vector< - std::pair, frc::Transform3d>> - cameras; - cameras.push_back(std::make_pair(cameraOne, robotToCam)); - - photonlib::RobotPoseEstimator estimator( - aprilTags, photonlib::CLOSEST_TO_REFERENCE_POSE, cameras); - - .. code-block:: Python - - kRobotToCam = wpimath.geometry.Transform3d( - wpimath.geometry.Translation3d(0.5, 0.0, 0.5), - wpimath.geometry.Rotation3d.fromDegrees(0.0, -30.0, 0.0), - ) - - self.cam = PhotonCamera("YOUR CAMERA NAME") - - self.camPoseEst = PhotonPoseEstimator( - loadAprilTagLayoutField(AprilTagField.kDefaultField), - PoseStrategy.CLOSEST_TO_REFERENCE_POSE, - self.cam, - kRobotToCam - ) + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-python-examples/poseest/robot.py + :language: python + :lines: 45-50 ``` +:::{note} +Python still takes a `PhotonCamera` in the constructor, so you must create the camera as shown in the next section and then return and use it to create the `PhotonPoseEstimator`. +::: + ## Using a `PhotonPoseEstimator` -Calling `update()` on your `PhotonPoseEstimator` will return an `EstimatedRobotPose`, which includes a `Pose3d` of the latest estimated pose (using the selected strategy) along with a `double` of the timestamp when the robot pose was estimated. You should be updating your [drivetrain pose estimator](https://docs.wpilib.org/en/latest/docs/software/advanced-controls/state-space/state-space-pose-estimators.html) with the result from the `PhotonPoseEstimator` every loop using `addVisionMeasurement()`. +The final prerequisite to using your `PhotonPoseEstimator` is creating a `PhotonCamera`. To do this, you must set the name of your camera in Photon Client. From there you can define the camera in code. ```{eval-rst} .. tab-set-code:: - .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/357d8a518a93f7a1f8084a79449249e613b605a7/photonlib-java-examples/apriltagExample/src/main/java/frc/robot/PhotonCameraWrapper.java - :language: java - :lines: 85-88 - - .. code-block:: C++ - - std::pair getEstimatedGlobalPose( - frc::Pose3d prevEstimatedRobotPose) { - robotPoseEstimator.SetReferencePose(prevEstimatedRobotPose); - units::millisecond_t currentTime = frc::Timer::GetFPGATimestamp(); - auto result = robotPoseEstimator.Update(); - if (result.second) { - return std::make_pair<>(result.first.ToPose2d(), - currentTime - result.second); - } else { - return std::make_pair(frc::Pose2d(), 0_ms); - } - } - - .. code-block:: Python - - # Coming Soon! - + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-java-examples/poseest/src/main/java/frc/robot/Vision.java + :language: java + :lines: 63 + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-cpp-examples/aimattarget/src/main/include/Robot.h + :language: c++ + :lines: 55 + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-python-examples/poseest/robot.py + :language: python + :lines: 44 ``` -You should be updating your [drivetrain pose estimator](https://docs.wpilib.org/en/latest/docs/software/advanced-controls/state-space/state-space-pose-estimators.html) with the result from the `RobotPoseEstimator` every loop using `addVisionMeasurement()`. TODO: add example note +Calling `update()` on your `PhotonPoseEstimator` will return an `EstimatedRobotPose`, which includes a `Pose3d` of the latest estimated pose (using the selected strategy) along with a `double` of the timestamp when the robot pose was estimated. + +```{eval-rst} +.. tab-set-code:: + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-java-examples/poseest/src/main/java/frc/robot/Vision.java + :language: java + :lines: 93-116 + + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-cpp-examples/poseest/src/main/include/Vision.h + :language: c++ + :lines: 80-100 + + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-python-examples/poseest/robot.py + :language: python + :lines: 53 +``` + +You should be updating your [drivetrain pose estimator](https://docs.wpilib.org/en/latest/docs/software/advanced-controls/state-space/state-space-pose-estimators.html) with the result from the `PhotonPoseEstimator` every loop using `addVisionMeasurement()`. + +```{eval-rst} +.. tab-set-code:: + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-java-examples/poseest/src/main/java/frc/robot/Robot.java + :language: java + :lines: 49 + + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-cpp-examples/poseest/src/main/include/Robot.h + :language: c++ + :lines: 54-57 + + .. rli:: https://raw.githubusercontent.com/PhotonVision/photonvision/refs/heads/main/photonlib-python-examples/poseest/robot.py + :language: python + :lines: 54-57 +``` + +## Complete Examples + +The complete examples for the `PhotonPoseEstimator` can be found in the following locations: + +- [Java](https://github.com/PhotonVision/photonvision/tree/main/photonlib-java-examples/poseest) +- [C++](https://github.com/PhotonVision/photonvision/tree/main/photonlib-cpp-examples/poseest) +- [Python](https://github.com/PhotonVision/photonvision/tree/main/photonlib-python-examples/poseest) ## Additional `PhotonPoseEstimator` Methods -### `setReferencePose(Pose3d referencePose)` +For more information on the `PhotonPoseEstimator` class, please see the API documentation. -Updates the stored reference pose when using the CLOSEST_TO_REFERENCE_POSE strategy. - -### `setLastPose(Pose3d lastPose)` - -Update the stored last pose. Useful for setting the initial estimate when using the CLOSEST_TO_LAST_POSE strategy. - -### `addHeadingData(double timestampSeconds, Rotation2d heading)` - -Adds robot heading data to be stored in buffer. Must be called periodically with a proper timestamp for the PNP_DISTANCE_TRIG_SOLVE and CONSTRAINED_SOLVEPNP strategies +- [Java Documentation](https://javadocs.photonvision.org/release/org/photonvision/PhotonPoseEstimator.html) +- [C++ Documentation](https://cppdocs.photonvision.org/release/classphoton_1_1_photon_pose_estimator.html) +- [Python Documentation](https://pydocs.photonvision.org/release/reference/photonPoseEstimator/) diff --git a/docs/source/docs/troubleshooting/camera-troubleshooting.md b/docs/source/docs/troubleshooting/camera-troubleshooting.md index 9c3f2ba9e..6ec73b82f 100644 --- a/docs/source/docs/troubleshooting/camera-troubleshooting.md +++ b/docs/source/docs/troubleshooting/camera-troubleshooting.md @@ -12,7 +12,7 @@ If you haven't yet, please refer to {ref}`the Pi CSI Camera Configuration page < If the driver isn't loaded, you may be using a non-official Pi image, or an image not new enough. Try updating to the most recent image available (one released for 2023) -- if that doesn't resolve the problem, {ref}`contact us` with your settings ZIP file and Pi version/camera version/config.txt file used. -If the camera is not detected, the most likely cause is either a config.txt file incorrectly set-up, or a ribbon cable attached backwards. Review the {ref}`picam configuration page `, and verify the ribbon cable is properly oriented at both ends, and that it is \_fully\_ inserted into the FFC connector. Then, {ref}`contact us` with your settings ZIP file and Pi version/camera version/config.txt file used. +If the camera is not detected, the most likely cause is either a config.txt file incorrectly set-up, or a ribbon cable attached backwards. Review the {ref}`picam configuration page `, and verify the ribbon cable is properly oriented at both ends, and that it is _fully_ inserted into the FFC connector. Then, {ref}`contact us` with your settings ZIP file and Pi version/camera version/config.txt file used. ## USB cameras From 5ff025fdbfa4695f8ce3bffe59f0d718bff66eba Mon Sep 17 00:00:00 2001 From: Sam Freund Date: Tue, 15 Apr 2025 09:46:12 -0500 Subject: [PATCH 03/42] Add documentation issue template (#1907) --- .github/ISSUE_TEMPLATE/docs_issue.md | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) create mode 100644 .github/ISSUE_TEMPLATE/docs_issue.md diff --git a/.github/ISSUE_TEMPLATE/docs_issue.md b/.github/ISSUE_TEMPLATE/docs_issue.md new file mode 100644 index 000000000..cd32f2ff9 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/docs_issue.md @@ -0,0 +1,17 @@ +--- +name: Documentation Request +about: Something needs to be documented/updated in the documentation +title: '' +labels: documentation +assignees: '' + +--- + +**Are you requesting documentation for a new feature, or updated documentation for an old feature?** +Put the feature you are requesting documentation for here, along with whether the documentation is stale and needs to be updated, or whether the documentation does not exist, and needs to be created. + +**Where is it?** +Put the location of the documentation that needs to be updated here. If you're requesting documenation for a new feature, put where you think it should go. + +**Additional context** +Add any other context or screenshots about the feature request here. From b8d74522bdcc66a9ddcfa9dbc463ccfb8c9997e7 Mon Sep 17 00:00:00 2001 From: Sam Freund Date: Thu, 17 Apr 2025 11:45:08 -0500 Subject: [PATCH 04/42] remove core and server from javadocs (#1911) --- photon-docs/build.gradle | 3 --- 1 file changed, 3 deletions(-) diff --git a/photon-docs/build.gradle b/photon-docs/build.gradle index a9a985669..e99e6c697 100644 --- a/photon-docs/build.gradle +++ b/photon-docs/build.gradle @@ -115,15 +115,12 @@ ext { task generateJavaDocs(type: Javadoc) { def exportedProjects = [ - ':photon-core', - ':photon-server', ':photon-targeting', ':photon-lib' ] source exportedProjects.collect { project(it).sourceSets.main.allJava } classpath = files(exportedProjects.collect { project(it).sourceSets.main.compileClasspath }) - dependsOn project(':photon-core').writeCurrentVersion options.links "https://docs.oracle.com/en/java/javase/17/docs/api/", "https://github.wpilib.org/allwpilib/docs/release/java/" options.addStringOption("tag", "pre:a:Pre-Condition") From b1f8598a03ad3ec6302b39235b01ef24b3b780c2 Mon Sep 17 00:00:00 2001 From: Alan <40917647+alaninnovates@users.noreply.github.com> Date: Fri, 18 Apr 2025 11:48:42 -0700 Subject: [PATCH 05/42] [docs] Update PhotonLib vendor dependency guide (#1915) --- .../programming/photonlib/adding-vendordep.md | 26 ++++++++++++++---- .../images/adding-offline-library.png | Bin 5361 -> 0 bytes .../photonlib/images/photonlib-install.png | Bin 0 -> 130783 bytes .../photonlib/images/photonlib-to-latest.png | Bin 0 -> 16736 bytes .../images/wpilib-vendor-dependencies.png | Bin 0 -> 99800 bytes 5 files changed, 20 insertions(+), 6 deletions(-) delete mode 100644 docs/source/docs/programming/photonlib/images/adding-offline-library.png create mode 100644 docs/source/docs/programming/photonlib/images/photonlib-install.png create mode 100644 docs/source/docs/programming/photonlib/images/photonlib-to-latest.png create mode 100644 docs/source/docs/programming/photonlib/images/wpilib-vendor-dependencies.png diff --git a/docs/source/docs/programming/photonlib/adding-vendordep.md b/docs/source/docs/programming/photonlib/adding-vendordep.md index 414bc080a..517267cfa 100644 --- a/docs/source/docs/programming/photonlib/adding-vendordep.md +++ b/docs/source/docs/programming/photonlib/adding-vendordep.md @@ -8,24 +8,38 @@ PhotonLibPy is a minimal, pure-python implementation of PhotonLib. ## Online Install - Java/C++ -Click on the WPI icon on the top right of your VS Code window or hit Ctrl+Shift+P (Cmd+Shift+P on macOS) to bring up the command palette. Type, "Manage Vendor Libraries" and select the "WPILib: Manage Vendor Libraries" option. Then, select the "Install new library (online)" option. +Click on the WPILib logo in the activity bar to access the Vendor Dependencies interface. -```{image} images/adding-offline-library.png +```{image} images/wpilib-vendor-dependencies.png +:scale: 50% +:align: center +:alt: WPILib Vendor Dependencies ``` -Paste the following URL into the box that pops up: +Select the install button for the "PhotonLib" dependency. -`https://maven.photonvision.org/repository/internal/org/photonvision/photonlib-json/1.0/photonlib-json-1.0.json` +```{image} images/photonlib-install.png +:scale: 50% +:align: center +:alt: PhotonLib Install Button +``` :::{note} -It is recommended to Build Robot Code at least once when connected to the Internet before heading to an area where Internet connectivity is limited (for example, a competition). This ensures that the relevant files are downloaded to your filesystem. +The Dependency Manager will automatically build your program when it loses focus. This allows you to use the changed dependencies. ::: +When an update is available for PhotonLib, a "To Latest" button will become available. This will update the vendordep to the latest version of PhotonLib. + +```{image} images/photonlib-to-latest.png +:align: center +:alt: PhotonLib Update Button +``` + Refer to [The WPILib docs](https://docs.wpilib.org/en/stable/docs/software/vscode-overview/3rd-party-libraries.html#installing-libraries) for more details on installing vendor libraries. ## Offline Install - Java/C++ -Download the latest PhotonLib release from our GitHub releases page (named something like `` photonlib-VERSION.zip` ``), and extract the contents to `$HOME/wpilib/YEAR`. This adds PhotonLib maven artifacts to your local maven repository. PhotonLib will now also appear available in the "install vendor libraries (offline)" menu in WPILib VSCode. Refer to [the WPILib docs](https://docs.wpilib.org/en/stable/docs/software/vscode-overview/3rd-party-libraries.html#installing-libraries) for more details on installing vendor libraries offline. +Download the latest PhotonLib release from our [GitHub releases page](https://github.com/PhotonVision/photonvision/releases) (named in the format `photonlib-VERSION.zip`), and extract the contents to `~/wpilib/YYYY/vendordeps` (where YYYY is the year and ~ is `C:\Users\Public` on Windows). This adds PhotonLib maven artifacts to your local maven repository. PhotonLib will now also appear available in the "install vendor libraries (offline)" menu in WPILib VSCode. Refer to [the WPILib docs](https://docs.wpilib.org/en/stable/docs/software/vscode-overview/3rd-party-libraries.html#how-does-it-work) for more details on installing vendor libraries offline. ## Install - Python diff --git a/docs/source/docs/programming/photonlib/images/adding-offline-library.png b/docs/source/docs/programming/photonlib/images/adding-offline-library.png deleted file mode 100644 index a5e7338edf4d320b9ca9dcd64e010cde75774a0b..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 5361 zcmb7IXEfYRyk5()+Un7JCm{`sO>|4N4XdxjMwF=k5WOxdN`%O(M`uOU=u4C>LZnIv z!3xW(B!rM4O5)0Szuo)k&Ut3$H|1Am&U0qwOd84>$;l?d1_FUN&CQH$K_D=2BL9Li zo|LXFs+=bkledAD0SMHR#eRf^oU~a1Gv^Qx2uA&z8HR&uZ=PtWp)AoRCxidrbbNgL z`t|GK;o+g-7gQ>hLZOf-gZ=&e-F*YSy}dm>JzZU0ZN%P=j*j;B_J+2umX_A$=4L`; zYkhrvU0q#GO-7 zZfMCt14>gecj83e!#0>m%dF_{1mJ#P-g4M{CC4qYtMWlsqWQ;3e6^f?5p zh6CiHos7ykX7wxb@(OZt^0KmWGBUCeML#ffESu@$vEU^78QTaC38WadE+5FiuWR4h{}>c6K&4 zHda8ZTVzNPJ z%QBIHy>NN(>7l?@#7U(X*m;>Dt-BeXX zbTi&Tx44d#8}}rP`lKiy3JR*51@Z)V8BjNCreWUwwQ}HcmEKV5(#J+)5Y3_cNhf8$ zGA`%3Hx9JD)}j`pg^AqTmfVnm&g;=$xqWFAS8LvwyMbqB zsqe0Xj9R7cQh$kW^IIw5J)uJSAhu8Jr~d_Y4~7>o=uXm_YOs4P)4dGaTLWYp=}>Vv z-Fb38t}N;Bmp?FfHR@?8atrSYT1M8&W+09Qa{w4U+3lHWo%BIoModzg`_j5ESmY=diQ zqNqzjOIx<~u34QU|UPpASLZ{}g}sbxTqeXZ2ggXyj`XWO$F* z)pqWk7|CCB0%^>7(}O~;?vYuE8fz9Oor1FT>@=!Q`&%++)p$1)Gnq06KlLwAI&U}_ zlA8L5rcRsbf1^Qc8tDA<)PhBbgNg#_Z*sYSE_C>seWrRy+PhBwKXvLcl+Z##(IXyXa|N zkc;`D-y=!@@^U^1SoVm%j5mVglO*xcZQd*r+oD&+NXIEo3*4Co23U8VmQ((z{-c9g zY`LRl<|W^EP|W&K+k_`J?K|L0=?n*4oa9^~6jZLq!_v*6d%#NO65-_JgF zLH$SyZe1nPa(J5;2 z^uc}4NPNm}*pY7%$E56YmRzgBaMuPI-n@>`al3}REZ8&>@IjWTnX&8D1SX>`>;?L;tNmTr=o)Es5n90T>YLJ13&BQW%6!1rx`y31&H2aas&cdCy z55yj?uujVp)%)K$a&EAWX(5wVux<9Atld6I1juf$SB4=pmvmZUb%@iPVve`v+G*c*|i;}%3mzwVJoH|zH~^BEjX z+2II9d#m$?8dJ?oNW%5ytq_qeto5RV+PWHPX*~G|N>|vhiszhZ!F?Tuwv*h&vfV)% zwySBvmnKL<0_|<`0J*MPQhYTY0*iI}QCa?X)db9ikTX zt|w4+l$Ic@QIlC{|AmF(DI6E6MXLvt@&OFH9M7SPXcB)loiSgHZhNl=GNnI-e{FR({U}`$mjk;nY$w z8r#0>nkmv{W6v1ae%@*X|3GWL_T{fv7QpH;<7A7Vl`6T!4z*@@s+zo1rD%O{54vT5PZ*)|-a!l4K^eI4&>H4TTE>(>jQ0id_tYVB!(GE;l;;h6utLbvtW&z^FhON$v3f%N{><5e!3eCQ!?x0WUzPGSjYh z?2E%|I}{=8yMp2K;IG1%Z>Jxl&Dr7iWIu{-h`Q--f&)dCBrdNG2?0X){h?JIm0rVk z!3CrW^sO8ytVZv91%v7@B`7$0x^ao<>h z`|^#rKa-@w0wF+wnRb0W7x$Q^&pmXU!g-G`!cuvO3?x9tZ?u466j^t63uR$ zG5qqa-KC=4sHkSP!;vC?ukBgmxWf86(uf|)-X79a2X?f_oxCzg_V)92brQ@?d(Lu) zfqBY5=X9E1o{yNj&aCGfhj|xvB}M5Nx$;=a#5mZ(lJdkFH%rjJ z<$)=#%7kR|_b)?MDz>;t@_rdsd*I=r0);=9hqFLk?>Z*)FcCC{$v4n0TvfoP^~n7c zIj&kTOF3yuDg7fYv~38R25Box2pLKnT%09sZP&#?Sk&Upf}ogIj_W;)#D650KFl#^ zn#sk*7|p8y?tW~FdYFT=SlN9x;(M;BUBWOzD(<(c2||;(x%}MF8C@4IN{dxNqSa{< zLGw$6xuPZdJepZtjX-VF(I&F?b=`f~?c}FQL5+R0d z{i1T1fA$6cwM1|Va(O|8OBl~&;UdPk68xYFkD6MK$HPNlWdiVV>5hn?dKy^5ZbX)0zG)_VbNz!o0|mqn zB5`o%fSs6VvmOiENkP%q!-X^R=~o_P)2OnTrCK)Sy5e3o$9JHMB0Et|a36``<#nm#4~_^CTY-uX?&SPV9k6$Rt!tmyg-L? zbp4jW^yl#6XWk_Ly;QyfEW5AtFC+>n{Gv73qwYiY2&@CJWe!!eP@r8M_(;!qG#;#K!xe6ND%XpE&x@vV ze51U%*%#XN$x}VewQlJeFF)R+1-)kk|2)VIE4i3koy}}$L-${nm{5W9QO-R{XXSni z2}}Wcm8O$*ZQx^(lw@Flmm+W*;paD%EGik&A?8hdBDiG)pIYQtsSFovYE-K;B&r$` zyPai(1Z{h<;Tqto1pPi#{-Q9%aEGyfRB5)bn`%stNF|cC@6ZHJ;=y(Rkf|zGZ#Z*nR-%{SB>}+vo zqKFz^uSJw-uH^t1j`vHG7q6kOLKgpxSy@ZhItLG@8qIXh5ijSSt9uWYB6R2oz)RNRLguI=lh*hRbgl)z$G$X zT-6PzRS*#`?1b}TPr*!{-tov@vB=HNkChSRf$6YX8b!0KVVoZ!W5<%&rJkL6Ou@!0 zZ_K6vDV{!ETSmlD^G3buU`L*}KXK$|k0mIP7r7Lbw8{TmppTRCDHU=LTjF%+6Wf?P zj3KeLTGPt!3wL1Fk$BUPKi`)r(U^uUb0Y7nNs5WV8RJEDNk!W5z``ecb=l%Fhq^_X z9tp~uTKNIOLa_GI18$~~+tIvlNAGwFzTIAN{mK}fdX)JHMn|2#+3u{N|BHZK^~U#F z!0#9tewHmRw-ec)`@VQdnm-c-H>CeLVuV%zcnS|25}GW_pZOr4b?E8vl%p)1p5BuhFRg?rv@LomPG8PnDC2z_yd%1NYgeBjFsn2B#5vYU zsaQUwY;J=!ypfCB`n7Id<7z2zEqKeI0^kmq>UZOnd!I8nqu}^{S+>D)1ans4&+2~B z#r6cl?V>Tyzza)16*dyHrQ8*c8iyc7-Y9aM zl%;T4h2L89LW$3tyPZ)1r6XMr|2@2fe&g(N$KeGrJRb`qJCcr3{}Gi}_iBOj%AiP- zWsizf%Uz>)PhULjwuDr@Y;T|&ABqHq2pFS0Z{H5*6r@xzpS^v)2Dr^EB0>h=V$tv~ zLi{l40etS+;Vz>FpN>+yeRSnx{|T#%OujSXa_fmOVM3;8H2OMx+^k!J_w)4h%7w7h z{n!ZcjjJfQm`Bij$=zW?Iy6~V`h+uog%i$jvmuql{^L_-$ut{!VW0mzh{ZY}0RPNj z&<3g<=)0B)L_mMWJTQ9PIlWP>CxaO1l^@S2Rf)U&qQcHKHe8x!0uaAdoLOJL^LNgT z@HGy{DAsl1TpJecJHD!6T|6*(-m`4s*07T4X+di-6fq=tb$p@;PzA{yBaP@2T5idJ{xbk;&vjHd?r+lMP#uUj(z|7J;FIg+XxtJtr6$C7Lc)ibfGVBf zRvaan<(Bywl3n-Y<1^cl8!r=?=)lRW%H_lYh@kQ>XIUERS`ErH~YVU~+2Ith5~%lZ6=ovV=h zhsSMDKNF3M=jt{1-`NC^t86)Ky3Y|inRBb%xtJ^eU;D8z(wlaxT*X5RdZnCt zeI0XPb=^xuT3G%5ra63`AyD|QK^Dpr2Ph(yz}8CNXZQ~4_kNLB{iu^2kr43pq12W1 g8b+>i<%baszkibECf3GHhVF^~13T=yMF0Q* diff --git a/docs/source/docs/programming/photonlib/images/photonlib-install.png b/docs/source/docs/programming/photonlib/images/photonlib-install.png new file mode 100644 index 0000000000000000000000000000000000000000..ceed13f7260b995730e832f2c778b5a20002a02c GIT binary patch literal 130783 zcmdSAWl)?;*ER|Sch}$=0t`-YcXxMpcefDSg1ftGaEIXT7Tn$SO!l+)ll{K+eO0IG z{5mr=)ji#7wXA#HE!Wi@Dkmd~0E-I?0s?{{E+(V^0s;p7eL#hV1g7L%P?v##z)PA7 z3d)HK3KGdV*qWGI8H0d`g(j#%sVV-%%+ypM28R~nlQ@t@jz#5@fTs1kA^9dD1{Q>B zC?Hpp7Yi2}k|;*r2H8>&GZ?%X*vCas?+!k?T_NG%4{DIhok^~2pt)96 z>{JbJOYgejiE?CEAbvvp=@j4L9Ef?KLDtD)hOa<~B#3Q!SY%84%82J<`Jsp_6}I3p zY!tSbF*>GA(Xe`hA7DU?oOyH;LH$J7cGMpO;EM%Arobpee_OAPgGclzVo%{vqRd+W{~735y^S7mNROw_yx zoV`==yB&IRm5_%(GFlQ;18WdDEt-=$RRfbk5;7g*=w;{~tz@RIAh!rE%EX0-WY7Nk;@D9> z0aftEChWo`S`ck+8s_%;lx)avqD9iD^zFk{KMV@8CErKli715QCh<>0J0kFlL+A{{ zYBWTNp=8}})ZXRH+L-7www+9>Jjk3bB#NWq2ZO5DjN1ZAKYB8uAH3gs)v9e`gV1=h zN#mm72)_wa!9pwbN5u=rJ*Z(sAB$hV7%CasbDGO2b#k8phGA5$OpphEUK>IU?Cp2= zmrM_a=ex_>Q}bS4(fF8sA13qyKtpLEgQ)R=TH+?d*ZMU#ly$(Zmv{t#5DxJ{B7=tb znCJ-^=thI<81jQYppl@&AVpoDA7l7?4f*2tP_thW6}52q-MsM>NU*xW+S5UQV876r zDk8(VAp+&{k9Z&?xYWn!!gkP8zI*rd@p~P&BSKrBpn^0pnu4MU_3r~QfM)n+7LK>c z(~L!cSmjgAv2C?#NECH`7gQ9)+C$odAi()+oXkGQ>RXZ_Kj$pc(S+=B^ka8LcH!r< zXiq`s;s_@D51W3iUG86+0qIK^wW~gz3F`U?Q*WB!yj(dxoMC7X1@L(f@>XA?W~*oH z@Rj8Eo(5lvy`=F**<7nl4_;OYYXL#li*k}yC@vtJAsKyideUm#disMkkmV4ZrG0^) z&%`&v@RDf@C$g-HnViPFd~1iLhBGYEIWjtmpRR;vuD++ma;kG^Q;ZLd8rpAS3HEJ? zgGZ67jmwNzf>3qxmM*NM9dw+-_E5b^vK?Q z;59-gD5gP?4@CZAUr+OkJ0?LJkV`;@$YLVC@(uL@VtcUP-h^Ir_ zM0j$rOQVjmMT#*vP>u6GGQ&p-QfA{Epx1+F`_T!HOiDOmX@q170dm+TU2Y(j13{$_ z3=ImCKMV{stC1x}6c{pEv8qHQ7$m6C&O>Kivy|f>_wZ~9rTf>}K{W>mUbt!b$#$D= zOI|p%!B+LkZZBMfxUs!O@{wYrp1@>+6X<^=4x~?z6QUxwqWnmb?(bO=co8K=#uz#; zs>@c_mwm zk1XLF(HbHZ1(`YPc^&eKicE^va^WgyWn;>p6<5k!bWU@YMV+mkIh`v#!de8pOP&yK z(T-eaHzv)PKc^DXrX-4LN|Y65y$d5&NtIAcVKx;tz-GjjAXe!eKKWW7C9X@J3Ob6+n{(HFz;v`*O=gv-6-ej zf2VS)xEzgx-J9NR42^w_vx04kjn5&3Z;78NlPD89Zj+&sVWVxWjkN~8X5NC)BI>-7 zf;|)V({PVIiQ%5fmXQ~M33mX80=Lmk?XZacy#K1BVt~gULi|LE}@GuU1RTM7yAoS?6VIY@J}% zFj=~O^rIn@Wum34W#B0jVQgT*Buu(s%vm#+c7=7tCGZr3b9Q`=Zl<#5td`s2+yv0L zp|`;rK;L5+WF)lvO%w45@neWr2yRG7l+>WzpunKVU=k^<2t~9O!`14LtxTm1yUa@Z zS=2NE21lu#(suE}xXU=$KJ5N+o_SuN$OO(B{Zm4Cd-#xX-iWp8*JHJX;L5Q|-L=&< zBbx@Bj5Ex$lC$GA+ZyLZ`4jS!YXWd2-)MFMX#zs-HLh!}d(XGs-OYs4hMD6>>|=&p zhLr)XJJ#zxPuokId;Q1!C#yU2dzRbXXO$fxJ=Y0CZj*pL{9P-GiuJaUbYka*CLxjRr}Z|C(#s8OVQRTA;~JGtO(g0R?F>^ z;^5=@#1Vex?*#3f{^Z{NFj$4N5xbSD@ZG^N;5Nt{jZTU=IhpD5fb5CvE&oGF&}`pq zMv3l2?2CktEH1#>TcgSEv)X4j;v2L|OqZ}W;m^Vo)9o{=g}f6N<7x?0DTit5sY~R0 zVI%!jwF0%Q#_bbPqwBG2Y4OQ*lu7Ansh(=Nv_BKmGp)GXmv>l8+Uv!ZdHNlPQ$MZM z(l5ENlVlOu4$b)UKGDMB^~;8ZJn}qZJQ5aCNO99kTc#Rmj5xI(h8OXEhNgZnhU5{X z&vP$49Cc?R9N!vUX2eU$U~P4edQ69KQg589RH^k%Kvmp#}G4CT)aDwyS7Z5Ah`Epz2_{bd`KDfN2-C6b4Q4YLhl4X4Jx zj1i7$=4o~B3%KfDM1p<$GjG2hV^#Tf@;CoF66uU=NQ+=iuzIRjZ+pB;+@y6*P)R7z z4As1D;#o_qK3xTz=$1C&Spk;boI{L6J(Z>A4lVAFjxxS-Ce3BDgr$yae`>8fL0nvu zJCsZ*_5b06(p@@#X4w6fvl=be3*z1w{of*lfe9Mf{>ymp&%dx{{AU>zce z#Kz{qLcp=*W+WPKuGlZXmNyb5A5HsZ-m`7fZ35;nv@#xtl8{Z-qQlc-wdA-cPqrx& zhSTxQYH~?&|I2<<);-ULQ}=bxuke%b+oV;xxrXM(k56;A3xX9k70yX(05+}5=IKS& z!qY|NjWWtA2rW*}4AZ$9SII)uZCz`}_pn4Fuho3-%ra-=3gB%=8 z1v+oiEV!O2VUlp+Sw%giCZ<8YNy}%5`(AjO!F?~K(=&SpFy{m!vc&3{0e2UP#%kgw z($XN*z&JDr1Sl%V2Ve{o_yqyQ1%dc04gw+piud2R0w~qrGGHJeA?6_9f6Hh9!{476 z;18(%claUhD+mPkD+-E>14Bha2V-L!M>AWe?vJ0g zfeA2nV(N|{AeiL8f1u(DWEa5g(Tcf}nv{^KSwb8@od003NFUFlqz=xiNK0SxTy>;QU303#zUP=eOc-Ns4Zjn>AI z^go6CQ;v|aqoISjos+q(4bks%^$l#Dow!LzepmG0&wtu!>}LL_CL71Uy9MkZ;CBvy zfsP*Ve^PTYH~GJ){m%K1+F$+pPjy_s3*%6BGWf=pr#|RPdqH_%ztbB@0|amrurXEwlA#z*8Eq_zchb$fkVOA(bmfOw+WSP z%$;}`xd8vC85tZLl%Ee6kc9JP4zW^Jz<>q# z5fMQ{{|;h2kH@3ky(O8!YAf)>IC)z2q^FJ`9vkI-+~A5g$Fhlz&7SlIun^97** zm3#ao9RGh-;82q1S87s>e+&ce?p8H4 z5w<<^QY#h5kiu>c$majzecMV7>65_tJo)oGI*0R7y=97-aUU&d!uRiDp`k3KjAt2~ zu2YG$nxxZ-%p`wI87sQk6CC~>upylF^?Gki5(WmwX>6|DeCNP^ha#n=@|?Uxs<^hKMZIO35?0+~YDm?jSn7 z$h@w8wOS-ztPD*to2-H>@AdCz$=}+=#BCW$=g*Pw=O!V_Wm}m*C3&?j7HkU!320b$y<8o8-Yg{f_3!rZ(R1 zOcyvf3!s0QP|#j_Y;Q7%Q7pSBo>3Vx!|l9xg0oz$ACEgYZ9FnYG277*<%1&v zR{1kqG_zXarmos{gXigb<4wO{#r0^uL>kck@KIZ$T?mQira9r1b)ddp$!A>gVDeWl zv&V_sLQ03G_c8b(rwsNlcli5EmX*#@Q`eRnUta3|c+=t_zWwox{by%hZ(b+x3bh}@ zG?jO^?e+(g#2%Nso$8MqYZ7)#kKR}4xcYS)paaoYoV8$`vdm0=$IcISjNY%OF)?S_ zNi%zkJ0{X;liVN9|{35LT`AncS;)jAszb2i&hVG!>R z!%$`dd4{TyIn_{Vw8C-j(H6OYM7*^FU z`6_O6XoB<1gDu=P#Ra!)MWboe7CbSsgCZrKKPd*0gvcZ zu5bzA@%aY^1!U1Y?--vctZk1wo-Y|i63T$gp#{U^nP+N^YCDDs&Cc!;T;)oopC}U& z3Dhl_O-dzkN_ig6EmvV9v)q?Yc(zYkq}M`gEiQ#21Z@*f$tmu7AN_YVZQsIq-frMh z*)5||r2PjFr6%uXRCQ#wDPLqZeC`8fwVMJ*qdv=JjXH8@BW2j?$etttRHG`J+eoFe z7{YlTPb9UatZ$uf#78&zc;RA>keaVqaj$yq264$HzT348_z$SHx!DUmkEO8`kcvi4 z>*{(-d*_d$ftT7QI`%+M7&hP2EQ`E$w!H+jRE;|76HZU2vRF=zyx)I(eHjsBL7^Wx z@ceLJAkMKS<+xm>uyl`evQ|ck(6&$4=}9;WvMj{wgU9mqE5iHFk{? z)4!O9G15bkV!%ckXqE~?&@E9&QU8v zkK)X>KFGc8NBT}W0*q*4pY%NwF0<8h{q7FZ@c`>Z)NH`JdSrC z$*qH4!OjpiLtQR%S9~}9;>MG$4_+ra9#ZH0O=tB{RHFU-d#nfv+smGB4DzP8nJt{` z6a<*#QtS_Tf*rZLhywM&FsS7GP#=5Of6QQnO`R`JN~ACr9JV)Y2RnO+T_?O;7QQ zHpwM|c{aH~)@U{hO||0-;63p7w}^u+IiEFWI@s(Ml#$+Bu76w573~kl+V=FpdF?{& zvor6L?UW0K-Aw@HAPX1lAjGs$#F-z#h(PZgHurui*GevdKZhyniX$IECoPymRe?Oe zIoNx=IId5mO?_ric#sRYJ6ov=f3$KvSv{mI=pK8YMT?%^O>&mo|JtnUE96Zr`UukE z;?>36jRt;m33W~tDjQFcS##*sbPDKTPy>SCm2D z;T;a4vsj@;-IMqbj=wn*7a?z33~?xZiE|m|5i*GnGMN&UX`G2h($y#l`qRbsMEMpz zXMNq>wmuZALN-ZoIQSg?rsL)&zcS_#CuPgm0_rZrIK1Y2k+6Cyyi#mz9g#319M8MQ zB=rV&85S7xF!2}>a|}#ukoZu>5$RMeWpSw(l{jVT7)A)m>Y5%=nEdlPz2laI5i>2D zTgJ4vUiyi0JXU8L1}6dT!AmqsC5-yeP;s)u2H&?37vL+D3Vz2j)1FIeA7yvGgr^pk zv%&lRcCN`I_5BPh`EsK3MocZo#&&M{8gb?^cKHZ~44Z@UCmzLDT_0{WamuyXv)Cg^ z7t8&y5f185O1q^->()7Mw`=Z)3pAR9`!>h&2zVDg1+Zr-`d8Xiwy|udhov6@vBU9{ zfC;_p;*CP-G#FOJ)S#4Uu?JgXhxw!Ykr`7@s$eWkD{{WTke6(1ko*SoHHm^>NC4H< zw(L(d9f-jfv3*G3x1wC~?Jdqqu6H%REUKB!rraF$I&bf1_@xP89)YTd{IC* z(~9K?X~%bTP;J*x_H+kc zp6b5mu)SR;I#`7&b&k2rm*0Nb;|lVuV%06y?p1I=}JaCJMFmOBZ?%-Ts(wXXQx~ z5&P3nOses0XJ|Zy=BSBoqb37PuGPUM|2Cx*W1ZI>@h?!cy&FeEGGqgg=?^zpqlmLy zvH1lfDr#eMRk{nyRZ2g%7eOhwVi1t1^;~>@^*|_N9i_+>d#|vTx=Dbi$TA4VG3n}cZ}oDNyTov zBTG0{M@m?zJiBvs>>q&vDVu&%8jW7TW!6bEYHpba9td{$QUPownb7N=_Zc^DobNzd zQ%ls?I*Qf=f9akmJJ7C|lUX6ZfkGSw_TqH5O3Q$Bm)S`i4ieNYm0ziX_pW%R;5wm{ z8k?%^1*@7CWi=Czx!9IviOUx0(FmA+)DGPV~{8JC~I}}{+ioq$T1b>-=K_lK*WKwdHD_b%S#ttrjfdchH9I=eC*ZCx@*DxcQydY4lpXO@0GspC zSBuYG9pYR_4}29mB8b~3T60NmI%B|i9%(KX^+!<$UhqGCu zg%G&W++8$Vfol^YZ)`WMD$-mi$hhFq9l)8qgfRcnw)2_aq%|S$$nubRYfd=qX4#V? zQ8j;=WhE5nug$oIm8lDn#`6pUfVjx9%VhYIS&`z>YC7cHM=pHiZRjHox6N*PY;Z`} zpcHHa3Vqh8hLMEfe(kc4jML7&$jdTr`u^gfg{`Hp>34>1vc$;g6!abqmgJu>V7SVO zYC{-|st0l}W42I-rkn+ZiqdX{l&d^ zs{paypCF4ka0>j*=NBHuI1ImWxY_^el`k>qk4Tk!#2EHeO8Zo#@Nq=&sDRhtfVUC? z`m(6!(!`M~G!{5MOo%y-ZQif zwp540P~ofKAYtPe|9- zIWE|g{U8;ME`7}v4p%d`;na)h((_wY(oA03&g?pu1+-bQ6r5g^2SJ}UM}DpwBehBG zSg3i;P>%EUymfAQt@Ixz=czk|DvchxZw~Rl-$;%fr_pz*s?sDoRUh>Uc9=LK*Fz4Z zBY-*Qm!h`EC-A&dw=~E;ec7s+P@kg2zaC{q`)S3irvSQ4V8Yd)H%{mrif&^C!+<!H@i-*q3^<8MeR=jc%(6Q& zX+-?U^EL7z^sM<5Q>9ha#I|;li|llN@CrY*-bjN`)B*2=yEQfmz6Y$SdX7nX|E{BJ z9>%`9OHP0sKJQu#Z7Z*Pl0Z`Xba^*J@8DXm$M2r<>{lE)_q2CL(n^!%V;YD!{_JF- z2oY1WnJBgya;~s^k{CHTd1;5?X`A{B|M)?XbAD;uOFsnIg~L?twTJU@F^|7JBMboY zyMHMZHT~qMy5krLy8$7I2aP@mtny8p={e75qE%8P?(8W{}R$NN4M!7j%fLIa6{VlJqXMgJG z(u!cc_o}O1+hVPA88;`%pxQptz^*LsWw9lYdW6d79@c`}tBo*jbD;>xV%_x{jD`08 zU>XI)D5xhk*$?gab3x5#aX!_}sBr@Fveb3%wxRsnN5TCra(hIl>0$*kF*9=E^Ucw|mrIvZlY$W3d@*J$3cd(^FHzOr5XpQp6 zxHVaCN9tl$=L(uoZ95cap2odhK6TE8P|rqf2Rc1lv(5Ov-6FLdN3E0}**bg+HdCa( zr%BwHLWNok@J|U)5=5hL1Ms|;V<>q2_JO7ij8GBh!>MrF!JVRxE;`{=hh%cv^3PVXJ)t_!>Ck^jWW0<9nSbgD z2hGQ!@T@|i<}b6)kpN-BkPN`ujPC7le(Tgfy7`zNvLzlOKfVkK*}IQ?y$9I!(-<+^LtN(EntN3sdb66GRyh@^(A7fFHRz zSRIt@^Xeht4Fd^l8T~6HI@hH5ri7?lz^_N{;2O}WLMU8pMr7=VORhFN+I+)K;?C`q zX0yU~Pm)=qdEPu&QL4*fg~$7}0~h7;_DwgFn|KoY@}u{|@>$^Jsr=6&=s1Qn#t&<}iWs|@BY;d#CD7DndhUbQCccy+`hsvUo zmE5ss^P-9*m#_h^;k4q?(`7t}r7YJgm)U*4zw>0?3Hil?2t|Pgv296XbzJ{Y$L{jX z((@xb^CR0jnhzMOX*c$psf(6LR{FqkVqsO_%$L<8BJBk@r2zooRikhjP%4isdCV8E zE#yA{Edr7$3!QawusxwBd6Rtl8&aw}Kdw2d;3gdOKU3ck>;bn`5^`El6Z9xgp}HYF z+72P~9+rhYX=n2ygtX-t-;_yZ7l2t!JAhh`KY+Tj+aR^0yo-f=o(v)MTprXPY`DzQEV^zWkt#wX({>3pV9^>CXafnJ zYGglspW=Z>72_ooZ~-A8#?mkOCfA8vCerqWOZpNG7Qz3MqN&~Hrr^y`HdL`rJI75Y z+q-z$B9M*m39ff27zBky?eKcMa!QP)hC+ zXZedw`ioThMgVq!{SL&5WfpW@X`zBTq!^U+N>`x^p_oj@bL0&NsDCzT{tzpIBgHTm zD&YQ?A~aaFtpL4#Q0R{~L#W+Jr81RVjct@D@O?nKDnXj%g0)=Em$>+7p`ErIW|9ac zDl>8Qe`&LWU38>28q$)je>xEpi1LkdZauL=(|mti zn<4N8yK1}626!YjLso|DPZ!vs{F@E)K~58CYxE0c3et0x%NFD;EHuV{ufPDQCG#&jk^L_^alGMs>|ZqGUu+~_#BVxrz;ER6Z^9B7 z5bYBYMJSE`NcknmUMvCkl`kjEU*mD2SqxKJ%2yC+s%C}GWhv-s_Pb4j|8fIrVJg&*jCquG?s5dYzAf15#-6ljLZju%F^KV2Gv2V=Ni9+9Ff z_+6qAqJLD9Ywpu6Ua5#o7LPD5;yaHcf`m0terOJQ)mM;qIE&3+#fnShT9ramt=>v5 zb(!sxpn3Y$uC3v=Xqp3j(5+K(UpUlG#e zl5DtXp?zMBzu+%+PH;rc%hZ|B7Q1A4ls?YRD(UCvLe$r%m7##3*^6f3!Uo!k+7_{B zM(wL{c{ElP52%z_5fh4(N~T?niX|w!3l5%V#}@(i)ZlNrf?}t|hUQWHMIzG_*4x~b zb$-T?2gf=HeR}A#n6s2qs907Bo-P>a3yQ6kq2dI-4#+IvsAcFmM;PJ7cV)^n>AMlL z?cQi59t9*$Cp!>NdJl!gk(^CzG^`3gUJ+w1;r>Hf?}&lZS?WaLF3^derg@MFu{*@r z(^Ki^Z*7u@Vg1YNJV}U3+fUrrwmKGo98qCd0=4GrYJ(#b9==X(R1I3OR46KWiIn;T z4K;9E>~gkPc%)J+7n{mzEB-xEWTnw2r$UqMxjrRXDI7K4La{p_*lcFtw%&UMGeA0q z;+Z{~jB+Lv?ac)~7#5>YBBA}2*X;r%gU2~+^+~zZ$=qVOKDd^0rQMU#dZ{fI_%JJE z@h+|3ULH#<8gSdN-K6Iz)6v{M^7_!^J1UoI1*4)_$^!`{7{k?Sef$hwS2{gBxm%So zop}2_58<%sN^MTF!8_}yFOXJZj1c}>QG9P+?#1eBaZcZrZCCE{HyaX($;puCDs<9e zv4$m&n=-N;vD(g?;6IznW$V3h%@UP>XK=fQvYv6_DETs)F{&EDktTemb3B1ss(dwe zlHR~8N9(*F_cfb1)1GH=S*|}7^M1ZHw1xV2f zQ|q(^C49|j_jH*lBJ30m4oA;kWjA7MZ3jxlSo^L z!63`$rqa3G)#L6+P}SwA5b1EA&^KEcZa=FxyQ>7m!v?7gF1W=TckXIz2V<|~q7Lg`#N^GWu`_Fz=LI#bbO z{x*^S#^!>yFPgTGuxTe3*+)*7?>x^t-V!`sLkzm85dNzXU7HKbXxItfArsT0q^wid z_srRG{a4R?U`WkPAy#%qQ5MRdMJ6`1vm`J8T@$%YxY#B7Xs*+JKXi%`&fk~(uWCdy zC{B>xT}7SUei=|BJd6lr6f`#7l*@Q?suI(?q;}0_a5%>DJR8H&>NpBfj?9CC0xS?y z;>e);;J^Y2+^3^M1va{%SM3+tZ-DEh2YUII4fm^^9DXETeeuEh3hh%;oIqws_<)R5 zW^)_zf=fK(Lqf@NL&yDJgPC`RxiQh#>u%SlGz=2V;ieXZuU?0McRS?#W5?^p* z!1;-=NMk5pSrp6dcszD<27IK@v(0s?&|jZFowthi&NWCwJnb7wmpH-bQougyjq54B zjb;#3Y2~xGO~;fEy>&d_$Bz~J-dpfUp~L1z8VFxa)w#|U=_Dy%DJA-f0!K=RAYs&P z1W>WmY}}weSZdbzi>Z(x2=Lok{}0b&R{bB%4l&8-EEme_ue!g?mK=M766ZlnHc2F1 z;+onR-fjZvqjHWt#3u+5xc$}MX$H>Q&O=sDg~dTy%?5c3uC=Zoj;7{gM+x;7yNn!; z17#w8;k8hbH>=Q(xPW^5o8ot?>-A@Xt8Ner4MmS&OL~u;3FfN>!USB!EI8}?Bku~H z?-jt2coCUOhdIkYgUH*%_CUnrF))GIe%(hhQssvh@sS=AVrQPLbU1q|vo9}#hcyiM z(*Pm!%YBAQyURxhKFQ{{mtWK#yYX{QUzMG*C9Mej4PSKLCZFFd*Q%MxRX&vtYwftn z=9!%2sPbwG>PD_g;JKtL9qJXI9cU|_j$|=`baU?8F7a@&ZTLE5 zIDu^C#O$B)7@_R7Yyzu~*9C7TQK~F@K7FD-Q)154SSL|5Z@pZ{JqPJ6Hm2EFb63M; zJ1&)Fc)i*4czv_MrkiI7L|%-<3^To+Aj-rZuQ1AAN6(nem(%TdCe2OK*WHg12n(+o zd|zdkz7i8QD&kCS+VZGIU=RDddtL6TF4>H2w;(`Xhkb6fYYx{{VoF7sv))==Ca_#z zRj0xDD0YkI2IeE;F#6;LoK783!I<8^2xYzOG@P%tnBrx0+J#mgYbhh3>A1kDxCdw@ zepZg@^73yyWf#_sUM{@5WOH~T;BY@8S@TeKzSXf(X+j^uw8M znvRH7PI1+k1ymeuzdq72Ia@Ym$}Ls5r?zc^c;6^kQft;b3}4(0*-tzVS_$5T z2F1p;5@{0AUo{b8paqX_Pu4}A4NdLLvLRZf=nbsC4E3s?9*zt z1aauN6iCqZ5Ln9X;&aE9CuicapjB)gFI3bdLwufET4C%=f0F&O2j0Y8kNCSrQ{St z!_RoT``OxjuF#O#^if}<{s}rqhl~m-tBK#h-Z%sTLq9b4(OW6P9bx-cEFD1EKpdeY z(~`>WMuYQXN7o_dA)h_p{M%l&hb)tVm}T!#`_K4+x^^Y+eyKwTIZX(Xigm^jt!8BI zOV`#r{F04ZHZ(Hr6yhdh^RDc9n$-N%uc=7XJYq9lLvJ-k#QX@QFz)n)gGdn=C-o*{ z$r6f1FO}g#D!}!y6?8iLaRS9st=j5YQZDM-ij2hqz$c*;V;;=P)kCU0E&UVA8(jL93WuOQn~A&=;0~QX3K>?JCCbW ztf=pQ<(?LS3XNAL8sJ>G?+mtS*_9Ec7$(U3oLA`&LlwipTqKeg!J|XYKDrXo`^DbtO9P%@ZmvrzZek_R`s_q|buS?ez6H)FhGL zqq^vLr3Ci%(O+a3QKB=tX6WL_b%{kJ*Y+h+<4-Mh88U?*SG9valk|LzgR#`HXXaSX z>u%%Fw<;55TXE@jNeFoErv)ky)se$tJZX>{7bNL7&u$ubg9hQmLQ-^0cgop3 zz^9+#a<+P=ny>Z4K}ACX7VOF$=aUi5?)5L#Y(0Jq15ko^;AuAH!4{HymCiS=bULjI z?_bAWOTgoad-17EOvGnet^4saQjQ66xz90Py~EaFXyeRVVK5dZ^~FMLa0@ub};ntaTlkjmR|{ zmU(LJHB<8Z^DpX>J#a`as@c7R<5TzBuD}UjOwG_{|4Z1yxOezN8!(?8wfxf#gQUvm;(nDl;y zi$SX*g)b2Ku!rY+AIj@IJ@AEet1aetF9`fsJm#vw3=lJ_1%t`yHHC}8q&aN9^T1AQ<*hOcksF>$DAc%4QP5%F~F_?Y2Jv`IQUV`d2mLw`hoM zyW(r)c@U+HZ6RVCbnI@2U1~Kcne4_BckNbf;Rk+i)BB5F=Tsi=T4m$6m!;V}Q$lC> z&{;S@y8yJ3N3!)8GQJK|9+e-tL03L3aM#PXhoV+{_f26br{MW%E_b?3XcRtC1fSbJ zbD5c1I?(1urgUKJjt(vGN>oNmPI6f9{r${RY-po}Qy5|;2pu*8D_?X)f_Iity$_R>)%m)PhGvZosjZ%1m58+{=mI zqC@(LMfX<%!b8}oh{VyoHBJ4MiTiA*4XR!N+gb2xbk zOGp7bx-QF$IM;9V`LA~yY{-dijwr`a)MdnwWF`}{r@rJa&Bn3kSL zMf%&K7o$wdYE&S$9lbQl_PG&H!5lsWP9pmmPlrwf8HpZ0Imb)lDXG)Qgk0HR4E-ul zBf6v+4d;@dWBBxQOg-Ia`xiT(wn!Uhqn75E>P(f59+&D0AL-Rv;0NFjaWIqS;e?L4 zfJ4F$2v8q*8VMFKbB)k8!;Yj;r<3ER?~iRHuT_Lqg@lx+4iPxPo9RQ(Bcf$;vmwZQ z*9+#YpLTDAKd(6vJ=$N*%8aVmbRs}wHal!NP0Jn0KHtdE|Pclk<2O^HxDg{3a7ocKY@0+-k3 zJLAs$;AL~LQI$ZjgwxBSJfUWR+%xQ)Wq(*g0*bo>W7*D^Z|3yi%GS3QEYL2Fp7&Sb z977)6^|Z#|{$fOvjlP=+ASCuty1yb>KF_pzaNq;nY2DEKp8Bn*2IQ=TK#cvL@D#pl;X%u3l!+|E%rp> z@u2}uP!{EGl#BG%rg#OTsMyQi&jGGU^ZOrU_TsoWv>ShK!?nRTYnm(^56-92ioilh z{jJeYYJvnrfe6MVLp&}!i2uU-ZDL%{VhE%0a9?v=;?gta;NNK0Ww76(SpULp%z7U* zXc4)J-c0bKl)&Ga0esca--M{u^7FN#1VA8H+^=_(ZJwaqVt)mHgw#g>jDG$v+7%Q4 z#Fuii$&DT1!F->uuh~s#7?J-2llYel@+o<$hqR}w|G}eb*};0mjIZIS*8T>LjMWm4#sZXC?RZW^0-8CZLV_ov}oyGtZ$9(|`l!?{d|k)4w#cmU}3C@+6JH zSO6}`PP`|?&i^j(Bl2Ra4ZLx%Q%}z4ICN5QyLS6ELuvOiB}osKdCG)qlni!93BA7$ ztA9fU!x|?jLW5FKd=nrq;frPb-X$pjvnvJO#fQ&Z9o9(um@0$6f^yAI@%y>}?Vf1@ z+BERKKtRBM+VcB$fRQ6`KuQ_|WIO5p%W{an4T9*&UiUu)fe_XnmR!rfAT0F|ph5oM znVm>?K7-@hluo4_JAqm`4i<|}O86nfx?2E(-9?NVxa{{I&tw-IjKVL<8;qI?MWbZ& z6)@-j(an-(tR)zrlhWh1{(*D=|^z=g*%`J45muo_8PL$EShw6P529 zm{PGEG4&{K@!N0`U_#!S8-uvOVk(#YbhReF(Q0kaTI%i(_{4_{jpE;InvaT#3Iyp} zlnNw_EzPjTb+frW@21zipAS}lII6U)|FHW-0z9*+fq%Btngol!D3I`3HP=G9Ou;_@ zLdhdCl_mL;WHzm4 z^c6rdO0hvyhM~ zFL5>gJ-_`U&nE}nM@|aSdl7eH4HdxfxZH3YfGb56ym=YoqTh@du%;A>+AnA>F#M+q zJ~~k%I-C;fgmwatR+rPla4dkxE@Or%1uQ=YOE-n2*uOl^Uk`}Ei%|Q%z0lxL=R8Fh z=={c;Pt;SLB#ZcMr|#;`5d{%fyCWm~x}?Y0 zC>1VsutjdXwm_<=*fiQkjXP|(PB_IN?L=Ef(BS(rQU0MB4kd+nK8 zLRzxm63wS5o>H-#uE}yGwR-XSa+}iZtPMh?<-`qzN~awA_Z^0QTAHro`pS)J|3q5d zLs}xw06s|QK77)IL;{D8gokS0G-JCa7bF;0qS-16Bn_4;U#XR-WPu3n9+Llw_u0rD}4~w#V>!Jdex&s!qIb3r~m8sALx_Sxom|0?c=OTZ%kN%0VqeBY@@3NI zD~jFgC`v1UN5~;q2847LYCW6iO2LlRZnea zRAvLC>P{5eaqIV~>q-d=C=j=2b2Ixq159wAIL{>Y^U;NPe1QXJKB(*ZzE@jLFbL{>EELtUctP;s%lS@mRzJLgGTRYS-oPZyx$x1e@Tp_S6(>9^1t(JT&%GkxpTi8S|2M6}Tfix=?Ms9MWVgV=saXHQQi{D^4R5!h4 zNP&|w<_E;HrFzYATJr!Lrn~1U*d+(`@Z(aCI?L6T zD*MECxweglD2-85E`y~b9|PGjjUlhysXd@ttKONFiO&QOjekq5jV9~XNb)=H9W<={ zj7uYbS=`3&9RC9t^!G5zzbq#6z7p*M7gi|9?GrZ|!f1^}j`C@hBuYsQ*MB6;=~tPS zizOu!v&S!w3U=q;HeN9uPcGJ58aqHZg!r(EUKl7o#s$%DFzzH8LP*cWj%rs%;2Lp1 z36p`sO26-6Zri<(ewiXbGzNKW_uzBxqz40nMhpS_OsPDc^|hzCZkPMYnDmS9)%O^J z>`n~;ANhlG*N7%6%KYuq?TFexR7I1ALm;uidm*I+zhAX@vrv>8p9YvNg%vE|HB5!7f&$> zxm2~u!hMlx_}>+d-DiR~#-u{0vFK7Pd|fHGu3?Pn#Vl(`;$#po(r@depW=S~&9wRq zGnsqFrRQKhu(6e|#r#!Y)}htOiL|#1O6uc=CFw)q-Xf;VSqY>^ZzRu-FYdY%{OL}I zyA9SkTud0oPdxu2aD2c>^0fgp>peIpAj5Kzg$B{V{jMnvgROEn7BTaW3VrdTxczjk zU%>Dub+#+GmGC{iMfo1(0RsI=!bQz@l}q(a>D6IYs4W3{rPoN9XfDkPogi+<)v-L4 z*}Iuwe~p)0(ywSaJehEEPpsvRH{ZGjXAeccayvQ`UrrhRsCDz|$<$~He}ZQJ(q}49 z{W+ar#3qWC)K{X*X*`Y5%tF=O{f|6@{l(gYkoT+c@zkar?V<)rHv7*+m9p5jE~;Uu z#SVw|bzn29Y6L}hpy^ZMzl7iRFFfxCfBetO!8YY7;T`t$6&5C-st#fo3K-_l|{ zpcZ~u>bS(9AqnX)&1pi@L)iOh)DhIQyrYG%YrY>&tV+xE6FB)?^ztf3AE_4Hz+8*{a8p zCv2e#WC>)S$`Z(b>sFxE)or(GVmTUAEOw0%2VFA{SrT{oO9q=4?8b(SzD$kIQ$m?9F32$kI(KPsvjTj{_c+C zGf3lCo3-ZJu0obN7l#W~w$oliuTmcyxB9wWowl9A(5Rj1ETWvBgVvQdNlU^Ey^=Me zG1Y|-+?lR`O<$n>Q!h6&>j=_rO|VOeZ7#6;n0R_^6;^-1yq!9Tt7 zF^`M>ODGTMpr1LD>sd3=I9+5vHLJA+xS^+u)ytoKnhwVHQGPLVyRRYlv!Z7yTzC6- zli74ua9P8W81bjQc<%Iyt`QyGiUZ-^LWd>yYI{}|1KumW;fY=(tuL7r-t&)U76j+@ zhHZVOB~==A2T#u5G7^^9?Mn69Y(^((Ro1y{Nx=QrLCdY~#t@3ZoELdNu6Ee**isgS z>@Iig!%M#w%yH7ARXdA%-+q|s^@XF0faV~3OT^w3z9#kgJCN`$_+{48@8CStQ;~6M z;2k5f!~LRW_)G(KnV8IgEqGkpOLK?L_VMlV$7RC=Ud|c3vSF{N_0z)7OG3;T`7}OEl5loiORcMsGD&!j8kFkr?o9 z-<&0Rw1S>ZsbPtmKYT!b`R{Ow7}-Zo5Q`13meln-C^lR}&R3@r>t=hYR{x>SE<^&N zl^-yxZ_@O<7dhcIoz(E|*2U(aq!7teCM-e>OZ5DIuizWaOMP`K!~UWIPA$_w>8d-u zyxR@`0D-)e*@*RfA-rSKsr6Z9pBjnZsrSckm4em@wD#qOjhqR7TLJGD^ zHS?NrwIjB7zZ#1{T)$Y-W0#C&~pLWqQD}BPMDy5%Tw1|LsLfPU5cS!`k zIEj|KiRqz~F>)VgaPKdNjrOP|HgVlRagE+PY|@$n02Wng^(kA^Gq30Y4M~Xlv^dYx zJfg23PDbyMX1e{}f$6fi;5ToBoTd>|pFlWlDmddTWub5x{NaKVHX>H*@5LolST>zNV%W)INr>&kBYeQIB4{kZz z=5c(Svd~(NdqUOvi*jrq{Zd!V=-X`849f6{++*EUJsSE-L@qQ%K zR%(D@ErqJ_vE68=sNEsRTW10j|GN3;xY3^E^S$5?#-9RG0T02PG8cQ2P|3h!TzInL zu$c5`W5|6+6)91MgvJl(r-bN&o!8$`!yV4Ir#k|S_s%id?YG15c3X&TrF+ob*E2`O zYeAzwm$#7{jSBdMbC^H4Ww@UgRP6jb+DksHczeY_PE+A&PnoeSK$4+FazlW*D|i6jj*Lqbr6Y&L@v`$BS4nP1RuYLC?D;AsD)w@* zL*_?p?I!STk^ml*?rbrOudZ8yw#gy!M&6m2l8oui>Jl2Ut@eIxonx7hB=AYemOiTM zT(Gf}?HebddFSVQot8D4VjbgWa+|6_59dCWWtLnf1PCD+v*GxsYAwOdnaz|W5&e}d zhrtBl>P*e1;|Wa;!vj%F*el`M_&Zy=pP&jwbX-UUes~U7jxo0a3k96RBxEQD(#^pOFY!jwqUv$%)5%RU;eV_$k z*BO~24C6{mN!!U3Y2@0FtYJ$~l|TbF8?@wXuZapP2=B9VgCffox2e|bmPIqmKypzB z;OGRdi2w%K|7V{$7>kgR!XK{BF*lR$GZp#O8(DxDncscokVMvlcFld&L(9U{#7IEF zBRH=&&k=ILmnO>w%r?h{5`~?{VkpPu{^vIz8Su$yQnQSZ^5l2jOXdxRJtiq^sx;($ zPQpOmt(TxxZr$^|0iO<^Wk0OL{fxUO!;)?pX1jfGP@)ue=7B8+XPquiYFIz=+_7Vp z@iv?!B?TLS%rA29<{Og45gaT2Fmy88%1of~2f>2~lYmyXpB!C}0Wa<)E(Rj}RzOJr zG1?g#cNs~=LUbmxIN0nXTwZeDyIIZ?TIYIlB85a?N@KIW?a@2ji4yr7H~Vo&bB~z5 z=Y~fUHHC|Vfa1^$f;kr?h$w6l-QwbU@8iWPxg_kaxIItzl2qT%<#?zSp2~(p=d1z^ zHl?Qw!?c>Se2WwK%)L<1l_16(oB>th2|>--uZz|Tf%n+Pq=??S?AEK5O3(M!x5q1O zO#aU50>a>|VAfI?oWX@QrO)vj{Z4@|Aq$|`qLTuXyv0j88}~9?$dBu5@NSC#<|EB#q7_O8oCMsRe#Z~Cov zX0l}?_@pVW<-P+BF2;`H@lC=|K|M~og54o-XsVbT;8VU`%Tn0s&+_R^g%a<(6N1;2 zVQo@bZUYj?XdItb_~Bt9Ag&`8B)?2xc)->((U8rxMO^{xIWS0_z--jD(F12*s`MA}1W3h!upBi^L&Ur=Pac=gNd#c`z z|2`6u+S3%9)F=Er<|X?Ds+I^Tjb=I-r|bVAy@%Nu!IW77{D&)K5r*Rl1Q)8?rK4{m zutS}#5eVaFJvr>4W1BdNO0v1$@!fOQ70q+9SsFRkYtvG#NJu|RL-VXv66>=(jn|F( z&osvqo85p7@xef> zj{;(J*8geCe)8PJ(o~M(ytelU8F*NE4lK77>Ybs-#W4xR*79bKXhp8`Ar?^5&Rb)x zhz=lC;ea4`QkUnSJEV|J7^p#w3y&i7^t9I3=wIA5r7p5LTx!*vszMUUvl||b8bEIe zbESe+h~@k$IR>5hf>@>NBB|c^-XX?hz)PYm8%_26ee_M`N2R|r_*(o=7Cfs_d}9a3 zWgjwq=Esdl3oi~k)~|RXGe$Lh)|mK2p-O$9hX!)I>%Z%=toTbjkAM)dcrUsvs~&o1 zK<*d8;6hcF84`?ISHkj)O}ju5gO6$|IGiTV)=6$Sa1L7S)l@Vnw+$5^GATQI8@VxK zjo8=w(WFA@&}O?odL1UfA!pqkji0&l8ME$}uw2uBfWw9IvZl~N5+o75-f;fL(a3O( znu%>dtKuH-eP9t$wtoUj{wSvCf>a-Kh@p(h;WWQ^OJC)jA-pg;vP?2TAg14*a;zDJ z=2;P1YR^y#w;Ad=3$%`$Q3WBif;WCVKktZRMDA9mck?o@ZBE;i7}GDnWQEw{4e!F= zKvbG_b+lw9QQ{n6K2Vr9d~y~1iqDv*Y`6Wkvu~`NR_Q`B5ck#}XVU>12`xdKQ$gQj zTSZB6_x0f;CLXX7GJ=0<9p0!^b~=YV2}{f!YcDli!hn4w)ob=bAZnO?Qf(Qit^mkX;>rT0Wq(hFcz-e_2SuHdguhb7=^d`{f!%Oq2X&gE}@S_!A{f4b~?JZIwDYIknB4IH9e zNTl2kK@np!q~&)xsJNX9rQj2~E<2sB^!qT^TO!U6_0SEzu3inG+`p6ns#Hv(WYE%J zxYC18{UfQchM?e9YMD$}8A4UjX&9Q30ImFL~{wx zJB;A_;pveo+$!gm_68V&{`M9adWS8ON{%?szO3{c<2*{gN+zt<`GbX5h4RF8%=H>K~FD%0*+0XJ6>3bh21pv6ZHv=LoM@a)*Rp*{}sMqYp51u z>r~W!g!*kUC`PyeD;l-pWf$iciae^ zKw1*`WLUO3X5D7AQ(t>BIsA-*biO|K5ItlLA@sTwFd-*CzD$2}BfmwYm+p^TGSV+) z5%}kx_aC{~LWg1;*?mtbERdJn#RaJ@N#()p7_v`G$|b282o-1s^6_ZIkCy{7O66@E&M{XBRH0PEN-)#<39)UhaG zss4z8332M+MZZ*6O3iA`nRM~A7f1dc;uC=LM36#UvEDe-?vV_U5^RfwNHN25scZ}p z^)Sh^Sx_=m&R2#XT-|EBzSco2X1!c{-tj<$U~7||g5JhOytxL??f*Me_9UL`TF$

r=!53ea$r?moqH-xg?toA4H*>o9)crI5TckG_P83N3eR&^lS*P$P z)eh%ZP6GIH4i>#{604Obf=oz31oT3&i46ZV)zfm0`8MOuaMZuE>2eE&;sW{9%)M?f zraH#eX21p}89o_)$)N$MM`E0ZjJ(DZ5`^aF0YDW$MS~iylK`i$e1CHAXE< zEsWQ#Z%6ACoPf}dZ5EqgY8menmoJ-W0n7N#dG`H6ya@6bUdBSCo%LcadGkC;JB|Pu zK-d@rF)1oTKfq388a>T0CA7AvyBQ@1s0m_>*Fu$jk_$lH0H-#m}Jhg(@H%Z@?Qu)*G`$c#-B_;x!}5w(4u# zIZZLTeZoZ9cEP9=p%B8IMlnShfUZ*L3n;5b4e9u;d5q&GA zc2nnt%=cUf3+-*OmkDj08^0Pm<2G54+|!*6YG$R3weLDkaC;+}4VqVO0{Xc^utHNv zlG~I!N@v=vtx08BZ78i8X`1qngl-?aRq<3ObNd5D^!}bX7XSVbnK8F`Yc;aPGRHZY z$Ds^!*eq;T5mL|`nO7%U{pw6?_twGE+U}^JFV~X!O_w~>-&NtLdli&}EtNpv2y?}C z$A+7k{kwlS~x}0}m=kq7UwD?^&{{ieGp53pJKg6l3X62 zK9sk@uI6JrI-JhA`hQJbHjKb!#sDYuUPKtARV>f_;a`LCAEz1L{-sa`H>42zxQVz9 z(sseSJQ@v?4`_xo;Hv!jB~I5d3z|5pNj z&Sz97n1y1_h+qQ-$UL|Xr4Vi0*s;y=nwbX z1q)m)r)S4Bt4(qLQoR}Cp8QJ-{*U4P84gr5C1Y~&qpXutn!>{bhT`=iI<1;_=ji1; zFyUVH|2Wr>+MuG#7VRD(O4$q*l9|RLr5m|ZF#y3e^*3~Ncf^78S-a0-j}s%cb!%W_ z4>0FjdkDM3^QugAR*kaCn{9W&I#Sa4?D3mgKK)>*V!gTyk5%`y^FDDtiX$r=rgi#e zuS+agL`fXNHpWyFo@qIhIz99^MkGH~i|sLsQNuTEK(bU}7PI>_KhYzfjL8b$?6@3G zc*k&Da8~~#ee3Uair0yr#9NT0>;+P->1whS6H1Eeh%3^O126EYn!LtTcI=`NXk<}@ zRAJNs9iA6rI-!Iy)*+CgUB{K`^gt<|sF9;%m|pNt`<&!FFgo2-wZn#s>z74cgKZ4q z_hggbRcEh8iidoUIDoIZ>f9FCa;gLW1t{~)NYjFf;FQt5?&$BduRPoC-u^Oz%mRoGiJzG%GDE%Aw`InoVtraPXr z`VH>z)Fi9Kw$K@l%|(}+$6!SAo!;v5aq>N3H<;6h<?bhP}y_C`6npFL*3Dzc$!4n?veRPCGCP87Au}xrxWv@VinW1TG~H2|MY-F1=-ezp zcS2^v4&ooWQnQ1C|=ff6J&mV5RRnYqQsPmLKISqjIg)n=@!jnZc?$aLq>Pu(Vrt$Z) zZuWZ_VzaH$d8R|oK4V`&T+C3z|j z2v7y9<b4z>%jJ%(B0tTOF zv?{Qb3`3hMwQ8$;Xl9R9==7$8FQJK117Y&G-tOwgL2G*iBR`;QBo*1d2{~OC@PnE_ zWuqnBwffF4w+tr$K_Ile&4hOz(0)a*8Nj=Y{b<~avaGp%+yP#Nl_LM$Cb#23%>zdc z5pq_Z@23#=nS^zp18^X1HKv8$LqCcP*7$9-BP{$4571Z`E-^+K+LnqtN|=(=L_=Nz z8W@|`dQpvp{*?j9g`jL2=k0!7co}1?Q2eTu%9?*wn?0d=BOOl+WFS%|_dwxig>YBe z*5ld@p;4tafE{OXG^GA%y|(lDH;2LSovMUMbNw4+<t9z+2x#Y2 zF9)NrI02v528FFUxG^Nb3~1AP3A-F`$PxY$pI)zXSpG4N^GHfN)n*T<&eTTE9iV@u$3Z zVD60Z`;IC&9GUzI>boC@C9Fq-wva7&( zk`PlIP6^;>2XXmKr&t1OB&}*I8o7*7tFJ6>Dnq@I}R;1rwuZNO#HiG01ktSmu2EfM{_YgSw@jJ)Z2wUuI0TR0G)k%Fcm0>GIU z>ZDIJ_?QA%VPeM70Btvsl5*yETG8o-!0-rE;1+!lqrnPuV}p9H?}@i5TgRn9`7A_K zxFqQ>X#2F`A3=syx^@&L_oLMwngjrMB3>AzR&xo)qKLrm;v zJLysVWwsq9b&@?Vxcr%D#>!P*AwMXlc=Z=n`nF9?_+gi=J9LfuX!R+C?`z;(`VJ3L z~7N43Kj%03uFTyiTJ? zcmr1hv#hLAg*efV`*cxG7LKZYu{DYe`t^LX&zVlGN4`R7CAI>?rb=G10puFS zJ>ZD4f*5Kuso2zvAz(iiKaN^{;-7+W|NRXpL2gVsj1D!Dlz6$yFN=3v=uz`kz96vD{!i>XO}CV3u? z_d#i`o>xM8T^4bsg5(t9?J#~2)!$N~o8;ck*KB^8&|*)xKUBXNNNO@@YeiI6W-L7D zG+B^TKStkC?xCcL0=XHZsF=EpSzKfl^*_JNxKS)dksX8aU5w;Zsw8B%xpuo}Ldm;= ztgaKuDj?(u(W{^o=q{s7n35pB4><-mW0{5N!P@%lnZZO6A!j-p`aGSEKBcw^SFvaG z0O?CTKI!BHy|*Bbz_6$Y7X74Bf@iN2U$f;pLlDA}^CPbP#4^-b(%x3ZKSK{l1;gmv3h?r;u#I*NV*i(JX*`oIT!LwewnUjGhQ~Bn!4|WbFAxO>;1V)g zKut^(9t?!~%3}#F6$&9W9Z#ueE>s%ov&&c^T_p;yKoh(1zC^C=0b))%2+toq^9^Ve zoh2N`dXg`eLRn}E7nJ#`l&9c~EFI_z9qMeq)f@&?sSTQ-3Z{V4lK#Na)6l?cz63y+ zy$_n9xyBz8M7XV8=w;dSUPQd*v9BXOWcN$#)d_TA@pZ=Bpl%PPfGW6eP(4iVCtb(7 z|FQiCNYVF!_`12w02R@j_941(tCtNI^NT;rDYB?Itunmm7S9 zf}bl&ry$kajdv-1jw)#vVkeu+MY?S3PV6Vu+U!>4gzxYeZ!j9%+1+SBHM!%g^+zLNl3(3c1|kaoYKx91E4+PQP9;wS2VmDwukk z=TN4jw`(+&bXV=MuW$!4ZXrVjBtm{Vx!OF47Cv`JwQ^kvoS}?t1eH#CVH}oIRZmcv z;)>5R0$q$9ZjTkks;DU+*-Ep4|D$wnU1tuzht;&~gkaN$+v0@Wta0G=1Y^E_KR?|w zyFVe~J%J*qfPKkT@jOuKw9Rq!BGy#~#QaQTchtNv-&XNH=|2(B2K4=& z8s;-wMC#xRaDbNGL6k%C!wy&>Xx9NAqp+ej=2e-^kSrfydwz3|)gyVSP6D;5?3})K z6Q!R_dO~N|>c?1~eU>_-EZ3iP))5$xDr&^2E830cp@Tc*uwqwR>@fZ6v6Fo#HKHEDPl~n_(R+fFEd#6 zQ6)G(S}6ni&gJ(rf`3KpbHUX{ivW0%3geMJF#z4hP+jqP^GWd=vM^PXqqb znHLd0ij37y!R0Up>Kg(yCW0K6liVqvw_zZYWWGaCjrLIlW);6fN+`^q~_@Kn!kPR|Q4a0{rz7J)0IA4tmxZI~jk@ zc_bRcZpFQ-{6p_HQ1`k55;^y(@2oLqBl2KcY5Vy>|h%$;M z9*MfZY0}xH>`=o$$Wi*T*&I!!8db<)ytei~{g_(t^#cSWLh3&nT)xS0SGp^OO3 zR8MC7uU5iH?x(#|Q{qbaCxS8K`dRW` z9{RZgT?je|4U)aA=xN3ed04wJ7zn37TlLsV7Co>DTB6YM%b?*viGcK_m5>I9YfzR|aM9;6&U+9v>n zab{N2@pBp)H^stJY}ckrJv|LK`8@aH7R~K_=t>^#h!Fs391n>-?tvgLNWw0Ab?{?D z=FwhMa#x}EDZpxONJO!odw3ZFv~|ZoPRazI8LHtC~bvx2$xC7 zmcuj|HoCNE)~F7I%Q08)tJf;z z7u2n4hj+I50q^O|2XkTDfAr$g9;>CN2n2^NXd9%M#ZNU}Bqq+BoSOQx>)H!d>DfQ| zV-c6IOWT$U)ksEg_L%(oinxlpd3v+j{NgFC;JJ~;t-XKkR0Z$g)0iUdwacI0Q zAAC%1$7CSJ^3htgFJqgXCa>HV(tWdp-_Q<|WwUKU)M9K_M^fcs-(c>L#C}4y=Y*g( z`Dd1CR)f_T4IFdi%`h*&3I0}$q3^TBngZJL=vqcf^=Vbg$fU(az#va==0ZLIQ;}B% zGaS1t-Aeqa4Ww9XcCXHOnX_)(B9(1p458o~#$}Sc)ty15JNmvWScuSAwNZg6ARKu8 zd+nll<8);n!x#BXFgU*PgQo9VJb^%7{*x;M38YT_o(f%|O8Zro%G9pLqg4kpiN>u% zYcRY$MJoG05Gyt*HIfo4Qo?~2pURd?6r8tc>r2!`Y&uWQaN{~HR0*}0<(;&q%mx*T z%k)#|i91-Jr}CDg2_peEGy{9^(W6SMmVrYBT**FCG{<4%nV{(VOas5r%S?E2nws0hp2sa~$6FNtwT66&S1%-&>9yFtWX0{ZgG z*WVl=+maD;cykHnhp>j)1S)pp%cU0l1QVXKmT5Sq`>CnQh@2X+Ob7Zd$U=wWFt8?- zbe_<|j|$Ywl~nf1A~$3LI!$F^p9Pk&zU zDDazq!|scF016->EsoZb0S@mEe5B1Z8J27mB-Hik05VqH_;W-3&Y>DQqs$i_%f{KV z5&aLMFsz{x@Z%OD9|PMpuCr%bHO}~037cIO8P3cQa8OK{O>T7Y)49!Qs!X8&X0%?8 z@OqSXJMKU%N_$nHw4ZtCjkZc;j*6K=>r*Pi-xAo1ofDDxB4rL>&0V5I?L?P(YSH;a z6^ElC8x8B37N-AVCtU5f5%jt{@gw2yr%T>tp{zVR^gz#Xy-6141r0%JrzwS_gsVWr zn&>}*7Hud8X@YB)4UFnQWTh_Vn-;7L&u_b9*%W4STxQWe*{v;Ku_ofw-{IO znDtV`G2;WsUJ?$GsVD|b*+))+3T&P#+x_XNPjf(Bll^*Y$W_+I(6H=>F6f8+fcV*~ z2|*A9@_@qB-5|@8#i)kxzP<00&WCls_;{CxV1f_y#Z2YY z20K8Nn+`?KlXsV?Xi}0}Ql%T175yq0t|R44VKt5k!q0sectRnj=OA}^Z2chR6IH`@*oe*GWb+p-pFP6gN*JqCSY9d zQh80*t~+)`HDPLKIFsmZFd=b4_d^c`!+v=JvmU!vyZq&zhCA8b@J32C`O?mz;&+~K zo%t}Lv96eP97L!bAt~b1pgJ_kt#$nxm8O#n7t8=4DRpu_FFkGB95Isie8F@l>xa?qUbBDT>G5)GTjY^l_Q>?V!Rw5U2;x&gNt9@ulT?*Z4Xm8@b8GdIgky zf1L!F0KKmIt>JYvVGAnqdF<&gNICi170)(}D3l-KjCt!#TDpu{`pzT#g*mPWeDw>7 zsY*tkI_E%?OVB)>j=MT$n5N@6rdL9=EmgWKZC5citZmznki+@er@08_rPUg4&S2T4 zD%@NL2lp(_ff&W(1Y)oh^LpXXZJyiJi&HEf87{#i^FBSo*H8e|xrMV%rKNcPi`ny& zOY|TQ<7BmaYi-Vb!oCj{k#*|*4NXt;+}=3-_3S5myu6}FZA&bk;Je55lTg!= zl_}~2;nWkbM4Wo0<`3xSt>EGI27-Gct;4b^Y2I|)d-Vtdr6oIg4DNu?;MuZ4 z!A&t6uFr6AOLw1Y*HfH#?u7rH#1YuGr+(5!>CFlYpYoKWt`H0I2Ou!b0;0|3>uxy6 z@jmk={s}fSi7Pfvom{)=s!Td(70q?SB5Ptn^35qsdPj-;b2u+RjE_28M8P7r(_9uLZzB#~>Nm<~r!3xkKj4-5u*@co}DVh5mq z-F67ts>A>0GbdfKT%?Y&`=o+q0pR6g8{0G!^eJ7gGXWU;eJXpO+Tpb#)5v7uxS>|EF~b8?+~@k5}M%o4!+ zS*y7yO^%kH+u^HE7ZXa?Uc-FBefS~l+^}#8Q+$XYl0?aaAYc*`@29@#x4n8)b}Vk% zgr!f-YFAZ#J*z+MC|Byp*DT?y{70_3V*?NH^j93({Wr(6?SwML+`&ak!75X5^~ws( zgn`LfQ95ZK<_EDps+kUV#%xZLP8$e}(dulzp}ppZ)5U#=Jmy7w3-CQe*ZU=$5v$cq z0pvoprE=OQ9UT!`@5Xs!>-&mzpuXt!{q=DdqHz0mueUAOe##PjgfS5P`gA6*GX@tb z*>iX27`pgu-ViKeFDYVIVsn;@vg=L}NY%ZngMws&jTs7gz?Hzlsk^-?qF#cU11@qj8``w}P|a8)2`%5!10MM{_slJWOD{J& zyfjF--6BW4>6E*lU2sgo-rUlQ>hxM@QWdr3^f#ZyC55q$l7-UdvN-?Mat2TVl5@g+w><<3-x5rPa>TDJn;-s2=k!3#A9 zeg!z%EZTOflkCKAL#&~4X&!i^Jm{2wMGLs8(4UbtzRo7vGKPqVMR+mV-z1lk+6Xch z-|x)qQgP-{@tVvx@a##5|=T+nCLbtzf zsm<#E*^^aC89ZZb|3kS}>4)frMHG|dA5VD#%w?kGcsQG;UmL(o-*wAV z#?D7J*rR)$dU>}MsmHv0A9%J^<;K_PW8?YG3vch=phjkz<3h{d>ZW*J6m!r7&)5InvCoA z58ZbSnwTw?nyXlsu5v*VGOE!?H2mSFwXYfVyFL&sA2ifxHsYSVhDIPblibd%-yIyE zzJ-L}Df~3yr)e?0Saf`?Enl27d7<{p9jKZ?8z@KdFDK2^LcxmijJKxsJlisRX^{l z))TvcrTLr?C{yx#q-rW{aJemD_W0n4S82>c1((S{A-`UyvbD2QFyVY^R5qHTkwcX( zG^&G@2rq=aK^;5=y;zMWsw~8wvA4G;NW**}YQqk+5sk}0GpONRNJ;Y)jU0pZfc0(k z`Ln+fgcp1qkt>|iIQpD)JiY^9b`CqHfbwn=ZwSkU;Xey&7R%<#^!pXH~e&FF)A z={0+-fvdzZGpF5wk2bNMH1t$z%cS$=%L$3n={nM9wA~AB1YJ!^x7)J`le4AZef(JS zv5y#;(Ch2sR<}Q#7slaTG^Ch5*vIW|tt4u65Me*H8GSlg))>=r%M*?I+h&&R>#9_C zH!ks4dymu19WS)Lm5{;_F!9fc(ou=RxQdGK`=0}7YCk;eoo!TsI)h(_WPfEgd78dp zix9OtPEULZUTbk*<`}Wy`b?bpg5zxzM|1dZRwk4P`9~p&mu1M*j3Np#a$#W}31&?r zj`z1m%__=!r(H2v5?-&0jVWNEiDqT#+AuOPHID&RV8iFqq={i(7<F|s79)q~ zo9>teZAAo^mY38H7rgR_V~@W439T~bhbq0rEMQLN`pcH}X|MNa4s0+d;!04jaX%JD zD7&a$H23ny?)EJu5&?#d#E4_uC%lV*r*}R65oBZOZcjq}*pus|;wt9fU#FCavcHc_ zPHH}WBI36Dj9|{fp{ls3vfpRl{rEEDqX$uBKyMEH7o}x-!4&mM9)VK%V|{( zEoSTBXjE$&(XrH=)RN@rtU}+n%_rs~xT=zWSQOUXk&1r0jYui4_a4Y2<8QxRKfjRM zbHk@r#mL6{eY|{aWT;CF_$OLm)=r{RpAu^5Tjc@?vK;TTUAdX=GaW5hoDx^;fmpK9QdBrd+f%`{1k5${6@z;Oh(E8b2zr zyPg!m$C%tL#%Fnk5qSQ{&64jw_y!lkIYa8lnL&_8#N$w9aX!8OHX-=Ft6V?(Y1?bv z$HM)KF*$2$K*O)VHvZ{+|Ay&mVS9N3U@2b516z5gnfkHo#Nnp`5BT&QaLMKx2M4RK zJq;IEuBNKLW`Jeuv`eyxh~$xkN}T9Lxn_itIaDo@K9l16+rxYW>6=x0Svy@Y|2Hs7 z=OjQZ*`&z|JNNUqlGW&(Ji0U=zwk%c$fi^dFIcabslj4l5)qB7aaCZ9tD#2lIwilR zF`viahc|De#h&dJTAC5U8;-MJ2)!C_gST$xO(lbn`-?$7 zky8|yvS4xM=IG0I;sIqbG(;^}25+Qw)B)Dd72iAXAth}X+&6j&fb(yTbCQM>1XgX?vzOP^#X>pcg$a7?iD{+4|6}j1 zqUzYzCQ#fpKp?mUOK^90cemi~1a}GU8Z_8q;lbU4LkRBf?h^EN_P_Tz`@G$8pYI!^ z2cuW_?Cv?gS@l&_y8!2%xtQ&I)jT3ry2j)DRpdy9BXHvf@V51A!Z@15@2RQiBND^(0_PeN~AFwDo0~SXMX*jdArCyF5L+N&Fjvv9GuJ5@*)OE z6L=3;J_Pa~0|5Xdb<=Rs!7B@S%A$AtcqnngB+=N@h6-w0fe`ttIh-qsq|u;CR_7l~ zJB1JuAJo(m_Sn@-;@x2aTOt9!BRAkP9}M1$fH7W!Ti~61gaE%CH7r{luNIyGLAl}8!Q^er zB?|HN+gq_2NJl%9uFpV(XWhij#`ILC36dJgcTv|r+U)8{7vT6GG zD3d3XH2wq7(&09cCUcaiytE!k@2ROvA@Z0&IqXM}UN_@ak4uG;+#ZuwlkWBpdS~)O zs3_oGH+o4BPEu0Rv{~T7%i+Y(5Tlvq@Ve6I;h9*sci7-Q1VLUkA=L?ACEb7 z$3w5T$9(IjG3%M}Eu%R%813T;W9^v3%OeTD^uuP~(}Bo`-(q94Kx=^b26gH$iMyL^ z(oD+^>ex81%-(BUK&qKs*!Dt+I_rJyyrp9j$u;27Xqx*f%r+(~BqR$O$va){mn*>n z0@`k=k$B6u3n|qJfq5lxS;5H54pxW^6v9a6T+DN`adaZ^dZFsH?tb!R4M1MXtsLS>i|H1H_T`jT>lu zMe{?PNs7IL8C|w!{*1iUznXt++9gLxP2J3T586*%>e3pJVnOcWmB&hFo)=uO`gyFa z(S%4HY~}4);u4bhtN%6LgA^rzN=i*&2QYf*##nCsoX4=!Ov2+@olQGRP66zBn?w?J|Y=&A1oDA`0k}8xsRkhiK%R%;q88&lc94X z2rZ0f27qNZ7Goix*wA)JgX2d7Fvj5xOb9%i--L)+_CX?IY2z?QQ;WBcA`CCIH+MW) zvyXj!1Z6IJ-yBQFXzM^N;Y+o7v9dx+2gfRgNG%k%K%c0?+s!vgGk;ER)2+7_ALn~6 zL<&gH@l%2QBxWRgLJM1;Y(-tS3y|)-TLqm~2GcaQFp3q2LEZ?y_B`yDOkIk4CEFRq5MJ@)x zk;KICgP!Gmuz5$7i4u_OuRlWCbt6~s# zTgb=DxZ(aTCopCVj67zBCY83@9#_MyGf2O{*Gjv zamM43KVv>1*?w=CMTz<%RkCa*iuWu15BuZPx%|))0`~%S4;F1`f`DQQaZ-w;E^@ zr3nB;^&V0~t_*8*;(hP!&qT7reF;*rZ;m%uQU}@%f1G$wv__(XWhyqWHQ)~z5DVcp zKJ5MD1yJ^5mp&&@Ap0;-7@id^=m8Ii#u>Gt*{tEg><0~fG%5Z%p!Fh|luLptaL;|3M>P zF}~ojd}@1?KQSbt#esrhut-6@#tkwrD?}7i3gZX5@G6~zM8w>~r~$bHLnEXPe~EpUutGLLXC#4rYw|J+EpUDtMA`p!kLY+x zr}hw2c4XNUXG`4NvSvA2X-onFg*pdWtRWnm1;ct!Wiad*29h?p(GdgKhC#oJO2&aX zp>fvz6%wM2mpKNsFZ&$$753|e{{M59tOV=X@{DlGLkMr{?j>2QZ$>8KZg@uI8c2nj zF(w39Py{_vn*R|a04|P!nL$D+Ww$yFw#NFr#3N;-<(Lg4;8dnB))RB0zVIo2EnrmatKVjqa;L(>cA;<;US zZ^=6Tw>uvQ4F;T*KxeuurRwTh+TE;BeL~>W#SKFMgY*4FjfqmF+(;>j=f6sYb#y3o zd)u4=n=e+@OAV-I-<6v=Cy}ej*UI-Q_$Ir#>UTnQYdma{iseB9jMRZU@2j~OQquQH-zZu0wo)ico5}p4U03mttyy5pM5S#ZGYOxxtUvQ6ILq&jK`52tGi5<`HxBlqFvNOq~w z0hc`&KGK=|A87{yR3Px+`gidN3soL(iSnWd$Fh9VKXg}G&7JbQ25Z*ciGK-+O*zAH z^7g(vE~u+>)mYmBbyN>o|cr-BSAPUSlm??k7G3@r@2^t8~Z| zuK#=e;&~cOD!ZElOnL*mVgPcz8IVO(UVgRL_iGtS6zv~E1PJ0Wf&q`&Fs>&&fa0@# z)x{;}P}Bg41jzGh*P1(>FIF`4%iiD-#&``_X2wg~HrXCO=h4ytphy0DvyNhaeyizw za!dF^Mn_wVOw4C~E_y4i z>bcVSrp4KrU0tJ>yb5UPRxD zFStng#0Tf<17qcqT%^@X?$49^3aOGO5xGCU;Q^#dE*Jqkil9?6C8E1_2^JMpd@<$m zoa|Ehud{xFu%S0t`_{*Dbg^G-XDh38Qnp9x@&XSZleX})c(C=UW zFpK}^W{Mw(KO#lMpVUMu z2j*#Vr%1_6LFx(RKDNq6VCu^Lfn(p|mnLZa98e(`Wu@L9vs!&GX;5(oqu4C-(y z^P8>dgpa5|LLji*n$W_Zp$H$2xHy<+d+6{wO8fVzs=Qt!*hF zz7g@hJuLwEJ31<)YFu30+5}H3yR{D0zGx90HDJr;RD{od7E~U9FiG>P{z+=l@khO* zlMrh1TeRXcqlbilE&EEfm>_2fI)RS%P=rrn!1Ox9!->YhUfu%qW5f19~vxRL9I5qT`=8U!jZ4V|3^ChSVtZEhX?n zpnU&1-)W0l8``jC+oZ*POq<6V2fQ7u>34AlP+IUaBau6~lMildn$B^PZGU}C-DFI! zFF&VAS%PkhO{aE!?ehn_a_B8R)>2{oD>(&aO_p|z_*;VrG~K4b&Jsv;t^1Z~jl^x2 z&Mx|i;X(n! z)SUO%$(^iAGT}85V4O-6BBomv1&_!(w6E0b0hc&2D=MVmOeQBVlgjK$0<0 z#s0N|b@iE_Ul3Yx%ih=XCa70QZqKHXwqkuf3UmqU<@niAslL*%w?3YUm3u3fofAy- z+5&SJo5&*_i9mkL#mUkHpp9v}HChzU&yj}pd}n*5CO`pOpHo~sAs#ZOP@OGftuN$M zBksqnvac(Jf$$zGzB1dJ&|HN%tyaU#M`|eAnoZ8zWUrYDDU|B_ZJ3w(dJT z*d#Qd5>31Kiv<9Q$_Dk&-M~AU{`~t&*1~<(*E?_N^7@;8R&hO zi#b{5&d_PF6b9JV%grCZffZU5M-pte#4&qcV|no&EyC!}@@JjEHY4ZE*YPtSZS}GH zH`&AEBLj$snzg`kDD`dZP4=6K#&}W;YZw6ZP?!(-`;+ehe$1i}Vl1IR(#mp*Ohf7C zE`25z2X&DA%xe2%%0zR9|MT+OIT4>CFa|5*`j(LGhSu}92ehW7^Rj>D?2E@jCEr^skmX^g7si0LCz9| z?CpypUUhVu3Y)pp=|H=5pqpPov$pEj0&593o1{#$oskcskG%9ycBzw`36JjsW%jns zrTH`(FD*Clw1G|CjO>^k#1R$M*i?gT;1l#=|ZTy*7`) zD|FA3r9-JdHCEm*hNV&`@y*$6bY=A+{j+WCc)i(89@CE7(R|1^0`bX&Ya7?vUv?ee zMqpYU=JSYe+I)5+9%)tYkashRYSL{193!JmitG)ek z{|9fG6^e~{F2!9m_I;;iq>j?dy3@K);HYz@4K9*JR$exhoEGL{26DS%Tv(=0S zIA1wT7z)Z4oxrb9aq}47+QTe^ny0|qQqq~XCnbQn*90Ifr^%i1(t@G_DqjYdClJt@ zKM|YVN<%%+s=2naHBx3;ZcaTjQL^CgMy!~{SAl{RdLbq`@QZc4T`Z38p$Q(#EY^)q z@vv7ink6au$05nf!CD)OGR<WX)r-1xHy<4V^?BFVo55ukIqb*)<;M#}zm0SY zHsxImVpm1MI}=GNq|k0X{>Or}Qaj#pp_;+Rp%0zc!(wEeKy2@IqyL@1j{)bfCxu>B zc7%wwN0R`X%^!V2cJX*q32;3u@$>vI+qGQSz;-*3PE5!qzDm#bXL5SPL`5ZhSP3K?T8}y2NU^{*SV2rtKATUL<)jFuQBR#e3lcFcF>=9hRsB@V!}`f zw8irxvtCEzlCcM6t^o^!ojAjn=7IU2+5ElWezrrGFJm%n~U(*RE*jJMs>J<3h z{TsTstwsBB3W{o;cs~xua4m;8E$+9Ng8EUcP}q$a(U2b=AX;;FC_SO0K|j zJBtbp%n~UR+hQ^J)eicg#`CJ;!N|yn)pQX&)-!EnR=XdbZ5i6z`Bw1zzn_gy-Yn~m z%DJg^zP_wvPCcxo?f+=jQ!kF6@iQvSE9UjOY*AMvLD`=WnHgw(_Qx&!m0xE=huolP z(_s3m%wI5lGgDl-7vwdac$ZeyvO3q&ajcIJ!cP%8!qvFdn9R1z=?A-yvfGb~qo?T$ zquR(Zv(Rc$(kHgjGV9kFR;<^w<6XXwq~y``>EhK82(m!Zxzj` ztpd@6DTAgkI56;8RgczWzS)NJ+xJ~VaKw^iOn#N7uQ9jm$NO`l71v+hQjb9RpM;T8 zoYUb2>B$!C87&pkKzx|p;(2i26B)fgM=+BLgoqRd=o3uWbl2&iLT)*?$-lzVr>beI?N>x@ zR#++|yE(Iz9KU(hIBz)DUKrF}TCnT$kJ0k)bc?dMtRE$08co(jMW9NNDAnY(P;tk= z&3L!Ytm@(C+gB1sA6e|emS~U*j*ReVRaHWmNBwt0S@gfkA*a8Q4^LMP{sD;bItDIP z*qG21`BOz6@6Jk@prNaT0WBeWE-@CKY^#&6MA#Al(QEz$kjA`2j6q}Q(@z@p3y2cy zO5Ng@t(9azmf!a(TqObT3E}TBL(^Yh`I2u*Mv76rS*(@v^SqWF#tW&2(U9qS ziem_9a0={s6H#YFvoJw8(bx?1j7Ox|T6eOMB$u`ErN8rj2G_}^)6Dfk!$TUvSU~co z`06*w1_ZX;y@XqCpM2I*q5oX@Dp|eY{EfAQ{~ek`PN2Cy2wT3De*0#BVd9d=S6}TB(Ji4SV zgyj}>ORC>|vm9EtA~#2^orm$Ck7nt;6Ik|c7QU=1#J4PP>PwVJiZ%Jme33z$0pcjL z5&EyrKV`9dSE@D?{)J4e2Xj?@Y3kxMxm^Iq|vb1=JrWSS+gYisB8lue(k}^9=AgdAhS8|Qt?gfG?EhSt|ewc z_AgkW81Owpp3t;x2j}~&?Mv%{4PG-ci=7T}IBi#Z{*NC3wAiOn*Wp%G2{#kS?m)bn zzL>9k!`lUJx?4kC9x|Hyc@lzZt@xurWPMaPI84V{$rY`1X7W9Ws&W2a)P$2!;-9MC z4IlD{>x1KtbUoR2_m>x^;bO2Tfo4|gPa^y&-!0x>7Hioz1k@q?zpndQT!smL)pcg} z>PzGk?V8^;bM77wqcO(ET6sg@BE-i}9AU zf6-Ix78Y~lNTyo;jzWoF5*iNmcK^NreRTu0W?vu)>Xp-dAJ@}>h12~tIHZ`6|2Tow zug5gb1z?EdNR8>5Jf}W+Bqp`eMP%sf!xj8a@2}iLa5E}_718>FK+FsJ^4`eu=vVi% zHT2Z=Q3}2+?+TWt+FBFUN`=c$T|O0N!Kk12 z1h3%Gus%}x-tS1e*}jMZ*?^arp!(?K4p$}#O-0`lj%=#OL&+}ty{UFd#i#@*tWe86 zcis1f1%A#iSJ$&gRd2{YQ-n=#m$H_p%eUloj`R_7Rj0wB5*LF5rN2Jj`=FO%N4FUM zURcu}eVbY`LHy}lRL0(ZqPQ@_6hEK^`hOc#YJ zuQntzu8*4v5Cw=S3`7Ak$#9l7sd2(DfniehvYYoW(!Og=FNDN=B6u#`8CA)?(A>m^Qf%SUPT*ZY2txq+*XbG(q7) zdADZfZS{?|2cK}di30hAeIHTtUhl`wrr&U(dLZI^vt6A<7ddb^7$|-bh3!dyxjlQ$ zn4D6jy_yskxrY_A2K+e6!ey2Pfu7|>( zY=z~26v9O=OgZ9jcVRUApe8$<2NC2#E_fmr8%YaGn|uprJ8as1@zGG;NTB|O#<^05Ipk`N1BbG1Ia`jnui>c?M&E}hAy-h8?`N!{yOOBWOJFhVw8{Donqac-MM5afiw?8D2pa3 zGK#;ifAGVGpu7UZ?JbAQ`!O&QxdVk-0KYAin(?5hl7f7nc#g@$!MufqMcJ35FWP1$ zCbW{C6DFD=4y@w>43FHlIbCv|wPit+h~4ZP*%oiot6v}D45t9ZMO%4k%t!CTblmHm z;Y&hVFSoh5C*jh7iFs;ra^JTfO`7iB4AV2@ek-x6gap~t-T*WQ2q0LYk|3 zFr_-0av0aL>-jn!p)^amrCzxCDZ{h=hU?Sdmx~;l>Ddnz#&d4mWygg;pSD&}ukcfG zf4R)aXxkvNW@{?vIeWnCORk{yg15H({RF&2najMS@$aOdps&{1+;~Bn$-m5jYNAv+ zskl6H#29Cd+f3|Ku~kXg-BkK*4_y}T0At<;7jkKSxC0?Uo_=@Scck=?ZT+)x!=ym8|x#Q_M5*Y13Y#~8PMx89+G3L==2K!xZ{L>NmRPBLcczhfO?{A2R4l%HYK=VMS zAJY04=$&|9UEvq6gp}zdHr*8jpnS=!$({V%Cf~e3UFO4uDJl`oSbAwtB-)adLPql+ zkUvN$oq`nH&eR#m;`6T|5%@DC0>?!b|2>A_@@Gh{2xxl$HJ*omf)EdT4ZQx9Z^-l~ z&+-31A?W}880PuixSh1`0j#d73XoK0IgzEJ5<4|hrrD00O8DO=0CX522I3D%0pNEC zK8G!c^c|Zc1YnpGt1>lt0EBhSz$CfakYiwC3f~+_su<@lqhqBlI!B{tY;Jz4pGma= z+srY$U5Z6+uUUFMNb~q?TUIpr@TG~1i>s-qY+iW*pq&J3v3&k!;-`npvZ@1s;m+MD z7ke&`Lr_dg`3f-^g1cVtsHw>>5{ydP|>v;Zh&9w>Ox8 zz1a9Fq;wJnR_O)NWM1umgi<|32P|A>GBGYTi8yc3s%Ds+3Uj%HB~@c5>TTxQQ>Wem z`lo^fim<6J$Y)wWd*g@(d{KLkUrP&nfWD>KKGB9;&ozFTLmwc#S?9Z}_TXX#B5KTr zMT_nnL#!wyMSO-^h9KJ1{(X&Fi?-6bRwa1^G~9AAxY2TT*~^}8(!g!H&%p#xqfD2Y zK(X%~Iktb6xo>V0PW$a!YqDq0sfJF-EFwr;RE=S&)teQt_i-l-C~`&ai8a6tAoF~tL}$KP(pMv)}%6O0mxxZfUo;9 z>UrL&1@QG%WtJ|3fnhojd|jUU!xhKP9?e7*HrOrxnz|w>F&pVr!fKQZbXL$|b$Oc4 zlB9`T;-qbG`e+>N)u@}sPSvFfZAtD68UYY8eLZUe8QQpXb?<(gYu^m1%WfnQ{So_{%Nx+-OdCc7D~s4w2PJ9 zs>j2PU$@b&r0yCE(ok1Uj*Va7Ga9?y;ipBM{9f1KP9e7XO_GCiW6_jC;gX>aXG{;D zRl=x+?tV7Gd2$VM1^+g;(9RozHCJyn`csW*0_^1 zY08U+Gnbb1)x<8ITv!E!IQM&dD~?;H129jNRUGvm?Ll%2c+T$)_q>!X$s%l&fiW|D znyBTgVV{s6SyhB_c5$hA4EA>0>PJO~BcA*qWnhgg+!MH`;1FnlE3oW$z0CR+D^!}e zQ-2h;wA88`>>{iEcyl6){2_ zz%Z?#(4@Pr)qMqSvED{81FSS9pUEX$dO+HJI8}lRbj%DEEJLF&+mv1y`QQI+CHb}U zL6dKovR2IzkbTk3&`>5$l_=zk=lUEfODOnIoTtsL(NPTbo|zpcOS|g6`hhRwyMrxP z9#B7h9<+=m5!B#!fPf>xBk`$=|6a>a6brXJtGH3Jie7#g#)D5nNy&165mTP7y|goh3-qRxn%$$ZrE2%7`3T9F9| zULRE=u)53fyJ0+b$t(d~+l8a2Uh%HX3;n zRtny@7LTTz7;`RVPz6cK_o+zf`ozJIW{$brY%RnDPk0Fcug(@)b7M&qd-J`h;Lwp? zKBLfbI7URW*t)2XRQfBayZ@yfRIXD&FFRbQGZdpa6&!^*N3&jSyDhy4)ST(SJo!x1 zQ9{ERCi9L*gJ$? zskIj;6B0ta>OX0YDk%p(pb?`lzAH)_hkVD-C*Hsk0yC5;&D7fkw^-+iT(MR?H0sXB z@h-FWxaK5geZ&3q2{y&9Loy77co3{I=hA8W8)?KHE9u^4d{lGi?s%mn2Qyl;lQrJy z<;hcLG<|)AIm4fqX^}JI4%k~9NYsTaTU*@O|}= zcrFsk8FN2bq+4RCwVU61zI5;_PF&BwTYV%c-I6rt*LpZk`Q`Akb~Z|P$o1Q#pcBz{nVkS z`@?k^S_)KA50HO0$iK5g!x>*z&-z32X_~AK-n)aB(yfmEzWO?bM|cg|6v?u5r*8gU z_x%M*wpUfv-C&!CpmMVkD>EG0oEsxzZoctfyl5<(&HC2#&hN@=+WiZdJL& zB<;u^b?Iy?kqwg_=R!DD8!PooA%A>-;;Y-Ms%p}3I<&dj6vx9whK&mN{rwyV`-Yt0 zqjk`Lo;ac*d-2=~;EDTe|E9kvZrnS0MDl#(oZ$s&RR%~^Gc#G!gGve~sUqG2iY&fD ze810cs9-PNm-%5o35FNRWa`j;<(wPAGMrzdZrcAk8kvE6xK*joQya2yLl_v* z|13$!?csTQuu?l+&mYw9ghFUX(hyo?O%Wz~i7DLP9F66|6>!qeW;b7_O(fE1CZmi- z$OWRr!+ZkBf@n=#Vq_|THWMSuGes`Mm2g3CpL?re7Rn-}626-sd^X<(&Kv}nn!3rL z4{ex2mC}UxA7NNU|CqJf_nTCm5Ga!uDw z_oOCFc3GI}ZKsoKPNOR-J~`5#O_gviy)i9K`^JeAXD@pD6Tx+z(Li2XJ4a%WhsgT} zr1OHbxYE_zz@skXJ7%XIF8ko=sA0QTMaodlA!w%C-xK75Fq*3C{W243@m9qhqiy=-p?~Qu79=6SUWzbw zoPRXID5COw3cEHfTAK3q_T>ZGW6uhIkLCr?2JjHO3+aHdY}b^SgOqK|=ev#GNa~Qn zpf6SG^Xl$GDV>d{3#1gg#LMd;9}{-3XECZD!A>@`+D15^L!^>2kyiJ$JXXHbNKn+a zLxMBdqd3K#b}^d0fHYi4&LX_8jaZ8&I)i#a_+IiG-@E#5t#oW$)92tqZ*#%>@}hYd z8@^N81E;u<&;^XIVP!ln1!?zX0KK+lqbC#vhwQDPHK|l_m`nTs+Y56Rzjvyk7@hXZ z?+6Hk%1jK1aomj~v~D(n0T_FikO(5fes`#(tW>|A9KBQS<6TlaXBCS)7T0UQy83;a zku?o78clYO{84;=^S{)I_Nj-!VeqR)5?1VsAE#^DVt*Q z+&Tokf5=P`o6(T;CFae~_qTZk^D+?h$Xo8BnaKqo0cD91v+^Lcu*m(wcbw~UQFM@t zlv*3J%9-!Ea>m2?&*edtW?qRnl^e45>1Z{YM~xWx3kN`RK0)!C z53V0`oE?u&DjWKJIs{<(I|u7$l+{hMv67cTlZ~z`JipiNtv=4oQ^j(teqqZK!>e{j zk}r^zGsN$G_ubqm@vw!6wXjEudnMFbF4%a9BZnz5iAznSWKs$7cm?pAm;?ThibBn@ImS52dLv4eJRGUuoo7Jm2`Sz3qrbO zTt`Lr$MXb)`Z}y;lyWD-1%t?3Z|b1Kw}7Uh6)1G1t;PH?ic% zmk5U+zId}%bX((P2AJ99>5wI`ID{ajbdhVxk^ZXUG;W2%I3@@?*Q67RqMq-Xe-dFk z8mS?G{78@|{n~Wh+#Jqe$jUI6oH;&9|B7cA7M1q#hUN?IBe2xvbx4q5O3BMJ&JDi9 z+6T1q4gEn?WO$NaVGicn28h)SljC7lMporsBoxBANcxLA25)W%@hD)~Dad=hDGU=? zfB5&9mLXc(jp+#u8|UUJGkl$)2jT@)uxKMrXh`*g4$-261VbV)IK<*r$aGpX&Nddr z1|gK-mgE=T=`&fO^Eu{bf`ZLbePYm~%Z3I&={@|Vzn)2XF`TM2lXQNz|r{04Ns2Y%TD98c6@#dYXHa2U^--wu9P+^N8_Uai8= z6Zs{tc3W#jqD6Do$(b*13=(8J!Bs}xtB*~X!~-iK+PcJdjUZ5dWyfFuN||vP`7beE~e4>*0pWgS3Vu^ zX8L{C#*xO+B*CM%LY4si{yi1Auk(Z>sG4@Vkeb5R0PD8bbK(+kRq;T9-S`+88L4h0 zn}m5m^MktD35o(X2$OsHM82Mwa+V5`k!daSw-_;%G80HibIY%%qMiKu(59;F)|KG= zN6;Z=$S(+Y37NDcUu_s*mpsGY=j$7t7TCkWoR`Dj3jaeY#jbg`NUg6{`>K+MPg2e1 z9qlq&8-`*ocfnf&@#xglB8IhzC-vZaQr!8ja}R5<7}o9O@un<37T&ab2Oa`bStf%c z+r=e9AY}bBj@WT}UDhBD_25n4a`XxLFolP=70-UJILY&dERhN_2w!F0Jl#0)X3J54B?%Q!oi@k@f!6?N0fACtbBBV6twc zX+*hO|K>KKw*t#Uy*qUvnY^26?W_Ddl=zEf5i^K!Ho2xRL8w8QbHpviqeKNj==|uN zbE;8hj;GP6|I6^mtcQqGK)TwwR!?oX1qR&S?&h+GgOx5J(ZE=#p%gl4AWS!CDPnza zJx0$!oxv&>jq%NJNBhmu2co%cd|WY!v&O2> zLiA>tWAA=Ml#9=nqj=FS7hw-3T^!jY{Ln}7^0q-@6d_GA{+y5h713+=fZ8fDn5^CW z(?qOazaxrzjz(^eF@#(=V8#(W#I&`n;K&D=kG^a{6gS#tu3zF?YKNHv`SFt-(5*F< zmXW1|^`O()O%#oBKTmDM3hr#ot5Nc|#vyC_nT4R`RqMdERcBac{rpPrucFiDp+DH_tmfR9f}-udL-rF2w?PP~~%| zr53xd;Y%Mk6>oMKHO0It>BAfzyhLj_-=nj7(DU;KVoqX_;AuRYMLDMv<{1b-;mj*r z^}M0aWbVmyTs62>jWO~;KmZTvwo)tROo}Jh)VzGJeo7kIC?6`0(UHF#pydqKEr zXdhRA&@zA!oL9BidN!wX2f=V1$6|66LrOL&OlF+46-SRm#UaJa%-nM|EYNKffiGW7 z&^n|vf0W0UiWD?b$GA9%S;uZHth-YDZc%9Oh#v;=HUjOLH}vN(H@ffP;betDq)&eR z$zJ0J9AwgSY!0Udv+Vn9PdTT1d4-uqcLy;>SeDeF!}>jn%jI!oTG|c<61g>TU}8YE zC4wfKw=))p#>i;~$}|Bw*`|`IVukN4qj#|>TA}c`j4i8*c(|0&?wS1x7?}t4dnum{ zCM>21G_WLnwRH7BkGC zErzx*=BN`6N|q-M7eDz}C}s_xa{julaYdk1Q0iR|jl207d({%&g(%A`^i)m_cIbS} zVPL8STRqeb(FNJTS58&v;>J$ZYMO0C@i7B3DZF)A)Du#$3uYOn?7R(}0+geu#I`wZ zO7-4?^YDjkkG6VbM$EcUM2wRj)eoudRlf|G9V|az{y-cymx#lx37(YYhjRnG`j|0$ zPLV?_FuUQNi((1yB;o6Wg`0-};ohWTmJ(*OlLP5Qz~Zo8?WmdU$X&jx=bPk%wW>HB ze2UzeEcxFyB!Tp2Z7wZ6@{LhkG9`+w)SlU=b!S5c3FjR@YNx6k9B|H1-xxD#AS~sn zdn>J3q33?(MD|z?o_U5g!6I2xU~cI`zPqjDEzt&ZU1y~B&pD`4_udnmgdeKN0-d4h zHt2^J6e6=L2`j7<#=x zJQo|tRNvLJMudpns%3)w1lN5FiuNS6VPo$2X~J^hiBL&?N)5!7fL*V04djSM2~**| zV^tzIr6pr~hv;{?d^@2hWA1a?^vb`1m@U3W_tYX6S5>@~nYM`_*Edm{u)u<}CX4Br zjcA{b`n}N8s?%tY zBii9b^@@vCgc%3H%$WMe=OqUiWN`sJBznZ4jV2D_IkzfPLt`sVWZ%Q4wK0_M1`epO zZOmW-PP_bA^j49gJb4&jwxQgP(aS(W3WZ-udKSBY!O;FA@$ zZ6=dK+sLtsV)j{G)qZURdJZs?%(#}s5+M=@XsvplL8t7V7>b{DHoDumcx9`cEI3dS z+xtvp9)3thR4cJ{Xl%$9g@V2F`B7Md)#1ow%=_+>$u|iBOTn@$xt=&2EC?z->N`KY z<}KMr)YuVIL!~**R*yhH$laLCpQYN0hYr<8zq3OGPKu!0Wz>=1tx>qDADFAAlA>vw zIAmWdP2;@8bU>;}`Lk*X?&;32M%4Or^Aez+CyJ#;D)|Z0fp-PXpxC4@j35+0xSSXX1+Om=Jk z7eY&xC;u)pgBH^-B3wDG#pqO*wR6@bVcm8N88c@^jS&MYRVbG_Q% zUTF&xevrrU#Vr2Wtfp}>ELt*a^i~N~FS5zVv zS3vLZg1t7-5WMOyheN2`dbtb2N?09ZKP=FzyJLLXl8orFV^08)hi|pX4P0#&sXJ{Lu;qNQE z-lL^lH)CPENz#b9bcz7Jpc zM8Lus5u4vK6sL}TBkFHKE|-l5^ZmjO${!M4#Qv}Es*fO$(1r>D7kwZxza$L3aQ>(@ z6L(mq#Xr(@n4v?a{4<|SYQq0x%%g>a4#|je!AD}7Anb(NJ2SLSTK|^?aO$L8?5yYs z1Bc6AqJ>@@HeOe2`y00 zyolU0h*Jhh$Y!F>x2+)xQnH+-w;7nP@4T*!a2P#Q7X!vj3f(O;sO};f_6R}>5l&CY zsP-P8{~CD;>PKnA9xN&#kGG=>O!mnX!j~kOU3rT^UxI80Q=wi-WB3y3X55s|Xk+9b zs@Wl(q>EpN_CF4E^4F+OR{)JtB@J1?sRf5B=_WDfpo%+5oO7kq`?AT1uN-ZOgR3a3 zQp1X|bdK0xeEKqOK^(XcnP5FySK8*fFQ+A}jBTPKN*Shd_Wu zHTdeoe^4PDG&lyxE=o!un;`wKU-KXu)vqAEbMaGd>mTl~YS%=D&dy;DaIt23;8ZpM z?$#7=b|85BVY}uh7;0C2h(wDCpgT%_RQ9vWXjw}0uCAa_2g6G7 znpl@SX*hpB?mesO2XROY(u$}!KTO)z`2jfsBdUQi^GSWDiHNyb*$O&RA;Fh-3F9H@i{uq6(7)W4a@1rZZ#_+-SwJ z3#wYX+gE+GI6Cm;2{*q+!TEOTI#2Ht2(mgM6_?+g79<<-^Yikgg{@0l2?iV?Wbza( zN=S8tmhtxdDZ4rhDP;J=w|usVEWzy-^+H+OcNFSFiWjd0N6*Eql;^&DeChh@F*=cbs2fnkqo+v;E0>u64sl2A@H~7R)vLy<=Ec47EV=PREz>H7LV_P zFwbS114CX!39A!K5+8`(y6vl95)j~l1C0EK3PvTQq_BcsQPr}-Zcq6|NakNs?u{-u zZ~p-@O@8XhT=YhxkN{<+qZga4#65{K4=D}N{FKFlMD!){rt!<$kS*-mw{nOH9t^lO z5PVPfFJp7SzFJ()bJ05$V-=9O_@D26)&d?z%HA_F$|X-dI(brRH~WN|1h^1h#Ep5W zFzp0?t?a(`?{27Ct)a83zcu zj!^dv*kW~L2yN7L9No=~d?(50c{sVzwZP0BPOClaKD3wnwN`fyYaI@jJpn@0PZ37hGp?gFnIj|ShJ?p*$kMrDnYs~!l1E2e~PxD8xBiZ zy33~7Y9=+S-c`%0PqF3a*SSZRP>3UzzxUVZ_jy+03CP2wlS%0;!%zI+o|a=(#Ww3^ z|2EH!k|tm~^KuyG2m+!{`lLX3gcYkN)F%z2-MF<-+_;V1aD|;hiTUuj>Lb5fQL8iQ z@xqU)a55Dvb{_1|Uzj*VOChAWJj13Ghw`b+<;?{JgkB_vwZ`Jr4;PN}aIb4lTP<@y zIVQB&#i!(op6l0^DAVGfIaj;}T8}40%)3NmP?AT+U zwS`^|8@lCG?}ME6t1)QhwpUo;HG!wgMStu$fI|BdIlR4?3EsZ)rKY1fuB#-`M>eRw z^5{*}&RFgy@?dKpUCK4j#@kElk%+-(s{%rpAJ-lxGWj!e!K<;NUSmM6wKW>tf%5Qc z!zqCKSN$d&okT81&R;LW@c`6cA*RjCT_{mLO1 zK%A>Gb$_k*#d|*$!-=RowmTCk;(QTg7`#ui!)jd=kh`YFk+P1&Uin4oFs z{nNT$_Olkv&NMbwR~7~kx+^m7^!#Wm1I?nft$a>~^qDSJ6NH2ln1mkI1(ZctH~+-f zK;i0OJp#jL#f!J_0a!(3OuUv>hVqZ%K3D9)i6b8a$d`i!~UoOUp?AkOcRNwCnl z%H=Loy5f@Jx42V9C>tm*$^CSV1cY?HXn_ak14%wy9Z@viIk!-Y)0}iqe2awD0$eki z&|X*W?ItEsEh1-Ld69`M-cbb+%AX&H>5CtFwdjVwNwdC5>b-n! zOJ0|SBj9vCbVk%KmcnWm0Gkn_4P76J zbL_;ltP}%~Omk*Mj^22o{q5}o0FnfDKgxR!Bh)?lgz+WUB5$2wru6k252W?WV1ctJ z%MN!)4*b@u*!R64R?|LbBwAE>*Q;Lf@GAnD^;H)%Le@3z^CiU3m((0#ko$AR?%9;y zSVI^J92d&d0^*ZLppoKhyJ6{e1Jty$n(eF74e25$pZy@_QyovS_22*otHpZPcF>^F z8Nt|VpKGXfju$0PLm;P5@7DHePrhM@>|M3{O3SSI2kif#KTUK@sk(>&Rf)nLG~D-em7oxQ)sX`D>YUTc+L$d&&y- z1Ibn=g#b5K65mptGaj%n)`7A- zh}v-jDUyQ{BENXdrzL_ujYsx~_+CTjG~U2XtT1*AzO0n*L*gp=CUd^KRN82ZV)*DJ zZx=36Hd*S}{UY7792tR+mUWMrF<<#QXKf|uNML`yH8aQaMix#D+2XMI!MA#~gOU0X zK2RrGq?ipvYmurA_nPd`r06IV{l)4@^t)bRSJtjCAqni5)z`yY_gsgCq}Ot$ped_| zgE%tfhBSJ8r2F0oK3;~%&y=%hBrgTZ1S^O2)Wr_{zvP|GcLuMs(DEu|1Ww`__iEZ2vtF^1IjVeOWaF4ro`GdB(d_ud`H-V!_LTd+g~wdQ{}^Gmeam7 zh66|IqdNx$FNkFzaxwT-rX6viTe@bHpcC=zipSZ&##EsIa(W}-a>AQTYx{xNh#gTB zcC}+UI;tM1xYTw|RBkGUgdzPLdr3vmS%(BgHWR3TCfciklBhW^)?~jCqs{y=db-qs6V9S6-@sdi%5y-Fo@)E*ZQDEw}n|$9%LN+r_m{(g{}9ifelhDhjV2*y`aS& zUcK4rAYP7|Y-D6)pG^AN*N@dwd2;yWZ^nPJMA9l|)(VQ!@qIigQa0lMNFW2@>>Wao z?@D8l&!)T02!BTFNzzI<`uzTPF&=$ru~fJgOjQ-aCQ;*FP#LC!z~VP9Ls2jE2XSd0 z7YBzAOe4d`D5t_?j1|I!-f@{HWCbu`q3`y{mFfG1@B6UeVC?6@DjR9_-0Cvn zjnEywHCGf|f*ds8ar)J!sHF>r`vDYcUMvBgcDG~B0rz)*;u5-n3OV+v)C# zFQCCSkp{|H7PYzW%8_6RxL(WJTB`Q>1J3m&lOr89d(58x828Ed|nTto!eS+pIUXm|{Qsdj^MVW@F=?44Ba=fOM*n zwt9(-LH#A&ZJo)^a%A7!s961&S#G-2ex6L%v$J?JnfOJ&mo-vh3)c-h(*dNuym-O|aL| z!_K#%Ua|GSXSDM?t6rK5eje!+65cuA+5&%m*<&jtKn{ z>x4$E4(zJ&2Sx=!d}Re87_k+!H9hS{wun50W-byR?rxYLs#J2`y%=X91%`Dm$yG*5H2eJywiN+T}`}k>t733YKVf9`(Nn_LA_@Vr& zwO8+(zy^eS(`RDyt3K@-_ZFj-RM)_sLG-B?uBDCySygM}0_C>fbEq+l!C!+WDKN}c zG)SEF8}k`>T7DVcv@tDsOFxsE&(LXfT&mpR-1GHi%iMH~zF4EU9M*j7v;H}w!A-j~ zQiPWBi9Tp+EC*cjcAgu-^usG~G3|T^$=VV8#Wvq-9~a%NE-UO1WygiJw4L_{(}PUw zy%J=MaD_$tqj@X+!%-T$>0!USZi3y{G%J7551~Bg6s>&`beY2v6xfxrmuAp@!3X5^ zl#20?_f)V{eC0q=9_#B9gZfBzF#E<#GGK6r=xokK(Ht>vI8P=b-v)dq1WRg7s(&uu zny~`bbTD?fWZDG2eo8+TPXDGQD#d;q4Cd+D_JHtMji??l5zEo(9$##l04;-5Gl$4j&LRI^P zG=wFeF)+xb4mIKclZqCEm}~WTh`L&*!uQtt!f;aG3atVlGL9o1K6L}# z{E=b70SAJ)s8!JR?;`db?}*3H)i*(Yea*WYlJa8E&PFQa*$+<|PapW!#G{8^^cN2D z0zth9Om3kEvj^>dYn;fM0Hf^J)pv<;{Il62s90s$vjEz4LC8AE z8g3LCupW?s)vR@&7CBAo+7@SYSxe__vO>J*zLuxc4^hrtDOSJ<{uZ)UkoH?l7D&Y_ zj@%e#P&iw3x)R**TR?G(j*vz`nO0LC1BY#@Y*6KV4>>kfCx!LM_T+jPztyZM08$r6 zeWkHp&a?3zZdk%AC?2i|Cby}?Jr|YW0uOP7r&*qE302r~hrcA1sJ`N(@a+KX04M6i zuD8fh+7n+L{XPD$A+!%q3-d8!&%#uitX(VZvDv1^-W&0C)?WbCF^sko>Xv=r1zAsp zLi>%~1Ok4)`dItgNPP)JVjLX;cs_$firGP~2m^~g*}$0o0C|f7P7W#zZ$0K8vi(j} zZi_tzI`_P&Tq&nLh_vGJ+++1i&HG33Mroe;0*KhL^ZZAYociNaNGVd+XAP59Ldq+F zuhqwngj@z?qEwz^?Tcb{u5UO9;}cO++VPgmn1!2L#2Y50>8%Vs4?~&yMsYpeXgFW*CJY}rOBov=)Xuq9hP@Hx_B!afsPaEu^Ij*H z={9Tb+Y4;ce0=`>?6TWIAvzxE>U7Hz@EM@`3;!-Qw3KOwfhH*859`DHv)j;Gjkh9bZ8wr{bqiY~vFhP)3{o_aNNF*2zkzHnve$9p6 zqhfNR8i7nyt?|0PM}Qb^aHxCJc(w+VS5|+_Z_HHUB+M6AoheO^Q?w5u8QWH`&CQi9 zBe1b@iFa}xnfs`S*B53cf0BQiM>%ZLIZS@rc=r(=8DL;T~C<(PCYK8(-+?u{&^-*)Rx7eG=$qR z&)D)kf+8Ek+N75if}M?@m=O>$<;eg|$K6(Wv%Gn>kN--UmtsDV-nveDdxkp<8Ctu%Yi7=b={hEa$@G>@5*9IL#|V=lPEqJzFua)cQo%gUnVUCoF5 z8T}19Vs8!-8et~4WJC!%KeM71F*kk?Q_9aWp)|J+XdseK?UlF9j4mJTG0Mhpibd*o z_f^QbMxz3sy7Ro4q=(y>3j9N}?mwEI60X3oO0bPILYb2BodcG-bw*^64(9Zi3flLG zR)-T62f8=d@Bn5On9W7)6sF}k@M~6KJ-M|pLBDq_g?%GwQ0Aa!aiK28!9`Ffm2c@$ z!x|$2){cc~dDz(e6%h+M$(b1$2V8FI=v_&*q>Df7mQbSXf?uoN$4*f(yxnD|@bV{? zzcnFh@0S4QZ8%wbQ@E#pv%n)h)v&j*erf?JvQPS_Jg?=NZSFxt*KKB-UjJLa5Vw! zZxV6PEJN*Y6NEr(ssEIFfeM82E%^F%S!Px7p@`uc077{zdr;^I>S&FGRNKpb%yZ(f z@pzqk|BICuD;1QZmk{|0UcO8=Kmjn%c8-c04&wg-%y8FIW7x z#uYAImaH=eLkKW2Un0X%qSDJv@NQ?dKHmIjZBowmz2LnZAew8-b-r9lzH~U$Z?dii zSC;s)Q;BVAMvtF@!A2dAWKcVcQ$rtnT)a9#Y!E-Sn{8SY2J0?)!r z&liiEBd1ya*ODkl2XuV$#5QI1UxaWVdjLQhH(#TW#r{hR&U2w8k5=FDVV-9Edp!LM zz}pT+Bu(U01%d?s`da`0I%Uqd{I;`fD;UjbvLs8B9rcN#`2?}VMGq8Rsw{CGrA&}R z6Z-btU%!@OWV)h$sv`Gq_(m%|4*=B|%G18fg#2v;GTbrXdu9|8`v2*aAN^mGkwyMHWb}o|v-aPWnqb^Y zP@5n6;0nF!=#@~;c6xZ`EaAe~J?(tAs;r7wvPC`hljvbIs^pI{#UlS1n!rS4Ev5CQS({YFA z!JuNF3@*W|IcVdJdyEhW%B;F<0Ywp>rCOxqW+z(K*gu0(Rlp^)+F11TwCq1N>=i zk+rZ)do^@IPEHyJt!|C+YuMNqg_TP!371mAGB_!vtIXo%GwaBxBpVF>><`)J4;fNwA0btvu zr55U5=2U3xFTw_nH)!7(2(f&A!e)!qQ9Q%`I5*#1(xoZ1Sd;=0*0XiRbC)bc;^qN2 zf6$`>j$Y|5wB2F{p75UR;{xsnReY`|W>yaMjmodfYLS08RTM9BLd*}kT~9M;CS-mJGb=Y) zsmhb^d1(k<|5!x5)vNd2FriAe3n{+ClFYMeu&7Ymu33RpEf98cA0sq*&LB3K-g2MA zMkn7=Yl!_bsi=c`%<;HX1^H$*UwDU7OGN%o;QU6VQbP@@c6L4wSYY$SL3OS&>=w0K zsOQ?eOH_URl@o5M*^eE?1Qg&r;B9v@87@6+&uTeE%t)5 zy}?L0QnO{Xp9%n1b_KwnDyLPul)OM$o-BvaflUa6(H<9V3QLUFBON`R&{^3VeYn?vj zp=`C+Ql|}FDPsG9pjSEC_GD#s28B+yeGGSpfWt2=Ak!j<2O#b+G}&y&QZ_WNk#co4 zH3>q26kR9``WBi#QyMi!hXTC0^E@!ibcz#UKg+xL%D@gpEo5p4DD&pK2WmhGPEBZ) zsy09bl*ks!(u4(g|KEaqoj4RaoNMs;o}^u zwS8-r+MNESf=VX~j0ntf9R7+#eNyn$vT4$Ii@DpUh>*?t__vwAk~G|!z3@*eiO{$aJK?B7r95J_53n?P6LTudS7==)!*9z51MDs^%Em( z35|-&YUmBu#_o6c*tEIFNpi3xq^x1!TKCbbyj8&aAc*i$d3BNAxx>zdh|6BXxD8{@IFCw`LGd{!UoumKhHcJHIAGia4#xhXxi1pX_QHA%Lk?M@7 zl&*t+D%EHDM1PV+g;?MD3addn&Z>k*+U@7_RLQX=;a*nw-wzx@{U5p?Nd}{T@~j(& zn$f*kH(2LUzU#d4f4u27k&7|eY+8p_&Z#Kh9gqP~?Q=Vo*#z$p(VJ8M`|h-6IcOzV zGwuNvNl*K!52$ib?05VJg3f_MjS^MC8u=`3-0=R!9o1q)nYDV(!2NTAQngO&G8xkx z@T97|L{?|~Z3COFDtNfw7NksjqkAuzO;qN8e=Z4Yc{~nAXCKDA&nypjIC$MFvH;I& ziJ$B~T3PvUHAINL$F9SjEqFuM`*`EwkUUq>9CHzyq*|(hdp;njKl@gVr$TxA@Z{HT zYOFxkTLJrd(|nNgPRi0jtWiN3(fN->u1ZRL3w2*sv9iZJMIxR*oRw5X>LG=%sIyl6d|!cU z^t3rly5o!rzVJ}1R2>y6$;)_?-dscW%x5t*G4A4Z66PQ$5^}DCX?3dC)9885jS4t0 zO==%MF{}t@WeVU2gq{~3_M^rmjlM|P-^)4XCY;V6#KHO5q&+=F(Yj1jXyd4TsQEOl zY_e;inDil45|;4jQ0KKf!(`C)d~q`%+3|kEFr~uZ&mx_#9PIM_8VzA9qt^dwRC#6m za`(q~(}D>re`Pfb2hGQgg-zHX22U9@GcLo0Roz`5Ix$K`H-(&p7O8$_Co9wZTBIOw z7DXz!_jXJ75cC2uOk!x3S5ChA7w=EKYOocHb#g}W(jhVA=A7&U3;6a`wty?qG)0Ro zeunVl@#?HwCy*Dn{1t-VOp)%I(DamwBmdiY;bMp!zRvjV;|@~ zF6+O)i`q^v59rqFk0-*9s@a0hL-4(McP;)mhBA2xo<%Yc4|}DlR@#wU4J+0Ix>n{{Amq&< zc(S8?LcZ1bR?2m2&(rm1tseFeV>^QUW#%a@dd1r`mJb^j8?a&qqH*3wp{yo-5f>|ReOr=n zGS9AJNU@GWIo+PqD$8*l>`s~3JU)6^gJi%r&%bSUQ8g(@`^jeUc&_wupj_IQ`QR{{ z&Wqj1NT%3k#uUjsoxYDXB=_!NiF=WlrPKDqK$CZ1b=qLWk+z}VoBSHvB%1Q?9jy(( zIlPp!-sk6d!n)s|m)Ys2YkL`ejU-orL;hp`eV*jH((m&0JA8s;5hx`dM?0vzLY1lB zKl}Qp{rS-|wKAmf4Qql^|71>_nDJe7Efcg_cQS|8$ILZ{ zW)aWqWtYniR^|Y4CKm=lfHXV|4WG4p1S^_VtVO+8&JDhI)t7%&W1U1bSV#E}Ja?3_ z%%M4unF-XSW`rAVe13^gZGDO@wN|#42Yc1v^5+kMvShd!EY!bC;{M^G#@aELHqcGu z!3n#wrYPo1TMNW;q|-}A-gP+H4jM0HEbD7N>>)VC{#LGS@9dAz8Kb6BwqgH@Y?%vr zt=;ZcPuLYfoB$IT7357K?DvlK5h3SePv!?ZKU>-?5aQH>@2&bSx1Aym?5&?)7!!Ri zdZhu?SOBLi z+E?b~=fPpa9KEN4U@+t?0o-9yo{VmG-1}TSjk3qL$U-6+EBx-g!-S9D8Ct=I*SwMcXA*EDya;3zlwuEOi;s^+=yZP)Uvt^6?ZZ2qD}eBL*7aPMc%DjVaa^p_74BP^(Y`SMeW zM@KPb@<g;reJon@E52nmJS-Cr} z-?*AmP5HVlIha>wumuS)_4B9SOIzf%kk85f{-@zIFlZc)=edDi*}*9ss&Zfbnd8gK zBdsZNasg7a`i7!#}95sM{>>UQ|fMe2xYLM`|YFsLL&=>e-@<_6mVkS5}ZMlkHJ&*2! zbi8X^>dTzrA!>oQr}_vs`gRjjKZl2U?lZ5^^dqs-&Rc1b9{g=;0qiW0u>@aa*>9R( zfcce>3hV++EONYM2sdW*;Avgf5QEJgQF z-SQ0fp4g`?q|tn0FWo+Vv5pEf7Be&Xc<%oo&Ho=!dtz8}}SnZep<2Z&1tv@Fe1 z{-yV7b%gQGn!hB2TAeKjSk^IdlM|ybsfOwO$`19w)Z_g|ekpDg|K!!0BLzyneTAP) z!sNGhb5W7MLTS;QB1IzLBz1nc^4&wA#ht_MK*`%W7AZE1OLxTa_!7fKZNOpPZS4J$ z1S-NtsCq>Xx82n(%FkJs&hfEzQ%h*Ej-AK;ca5Phf(0V2$WJPRh!!;~@^fMU+p@4E z(Q9;tLOaA4d^TL{72{B((_}5}@uFp=|0g>J={zLoZl+sWw%<{*r)0=a6IEu)de@1m z^RAD>>o#?@oI5s`M&rx%PWT~SvRrtI%yYm1QUXL|Y%=yN3nKh)So|Z7;x@Z^TAxa} zPKN_%L7Q{LzU;*xTw$y8T&>ND&4We#x^40t-9M`rS7%q?*Mng~c1f`m*Mg7uPI3ai zD@u?mA$`IRNZARx3j2%xa!ntI4WN4|On@_`K)T;CD+>h<6Z!6J0|OQ_XTUy9%o8L^ z7`DAp{`seo^8q0@9{iOOMS_9!)+U+``sG6D%vedgOv0VS^;OHwhW|t5rzV{v?ausT zp3`l@T(JGa=|rrKDd}A45{Na6ONe7AZ4F(}*v{HsUpUD6#Bt&6eX5Hq`TRR(EiGF6X z3P#+UiVPkHzp>|B^bqv^Ip}5^v3!GtueoxAlR&NT9vk;(+;?9EiNMQw`{2SpER>!v zcY(S0)AD>fF_AgGSW7LO4pU+zKi=-v(tH{e@kr-z2|67EQY@_Q{b=^DPT~P9zk7)I zWI;u5=W}j%R(;VLxUb5Dun%QC;uff1AAGJ%ocQw!U<}_pibBUTTh#Z2zxY2IxbA(J zC-@-SEDw7F{|P%#-rg(!edXKcHm$n3R(<`!4wsk}jLAv(L2H@LMKG8v8?R(UKizVs zL75B$c@eH$8RHd|E_TXDq+b$?CVZtmc46TZ-I$z&2F-apWfZRv8l(;`Pf}Ao$zwnD zK4Ombwk$MmUvOkR?-dv{$+Ptw*jQ#y36{^SX(TnaR<(Spx+8Ke9)RmDKS!c;GZaf4 zmt)o*YD5$&n4)q5EOMo+_ZM9&Z16f^a*$)<_pD9~ekbwtO>X0D>h-du|4KQ)pE4uh z%S7c*a0qavrm5{`?p_JICFX|f#=s=Fe|1gxK-2({)_9rYETfV@#H{IIl-C#P0TcbMhf5+8_inJOR1&~;bu&bNzvL#LYFrhk|D}AVR z;a1Xls-5wVlmT35B-9#$vqrD@e_ASV%_nUO_b7jq>2Kn{h{coK$?;x};hzKlIbP-Y z6JQZe$fec%?`?g338+}+h|&y_e|0rRa=5{IYlp9Ey$s?uEq?1?HCW51x5jm6OU5(R z#+k4G+v+C?FG4I&3)pwQl!WG(iSTXyZkbd|u2k2!`h@kbT1>x+toPnu>abU*+Gn+B zSsw>Z;PO|AiE+_9IXAdMNAfUR^N%4%wbL1?kKIx;8_{%)b^|wbOGfBFZ3L9&o&>?S z>cJ_#BO>y}k?9fv+Xl<(@1kdUR^NRm8Z?mESqXdD3P3)O5wiVPI<6U#MN2TL!qPih zTdNz@t$j!KWm}&EqRu}ZmN)-;zRszlVy>!PruY;3aUulS3TLwOi){3G6w$|W<^Oz( zd>5HmxKX?M2DUnzpDlkT(QyS8)b187?-38!9(CUGJY9~;{3J;UUgn`W|5qJC26oRj z-PcjiD3Hx?pC`ze;~FqL0igfws}YVT5q-P#?IrDh2NMtmpZJwkeQ!hmXWTrW1ksZ_ zm(7*Gy-Z#StfrH}9>tD-$BlmSNe|7*ty#|eD`^5(HZH11h2Z>))O^w@H=o4tk<*!E z@BcHTzz0@6DXbdn$$fu?(>#GEHPq9u&B@{Kl!*re!siHM2k6V+izHdXe=>)3$|W;e z!uO9PhaQe1$AcpNer^Vwo(;4+=b%Eu*T@q?%>KK+kw{mTLp9YOhenG2@>xi{OZ45~Bue76)vu4k%+ zH$Tys${|1HJD_*j=6!2-oVv6=T=8W{rb?&8{E(Yl8fKO2)9!YtF=OfTh9JEU3a|>n zPmnwec|TB8_aj9p)+ZJK&lcOZ1*=s5OdA7DZRldeMa!=t7L)_mfVAyq4?Hz$bo70U zWE2UW2%XWQ3eE2m4;7nJ zQAjE^AvIy>Bvm?_&7c@UZk6P>nyNsISmpNOKyy^1N@X+^qEMEVCxK2ltGQ9rsRN$T z%H{VrQ1m&E$uk?o`jPM3Md%I12e-S~jf>>|n7scW(TRjX3aXr|0o(kj0$WbzL`7^A zfJfhW1squQUGDR%tP_;q0=eGcA3&~Ze>n7(Od+!GE&W;vQH>hq{Sxj@p#+x&Fx$y8E*caV5db-1Q}{&Ez*S!ccJ_ zAPifi(J#WKC}v3fT97cEDp!*(<~2Vb4|0HJwHl^|S$Nxh+5eHrxdF_G#SZP3Lw=Ty zA|=>|Fq{&cWur7;r$pSs0Prx;*DKX}msul^)l|}i74LTcuy2&IEX{bkDb?h`MjMPHnsl42!Q5A;24XqTGp)B)I)Totb#&&7u<**nDq?c!#t?QpgA$9AyGy?qrk1A!?+I_c*fX_GIo1 zte6LC&`%$d5t=bs#=xkl;R*oqy7^!L=`R0k-=n6!XQ+Fp%YxJSw=?C=-4ewvFops? z1mYYGAAWMNzj`=mS>V?`bx|<5S_#=2I~`HlHajv87Lc<1*>(;K#t=S96B{X>>D(FG zJxd>A5mqLPD*2%!81Wk(j1E78T4)W4V$Syf`3RlLpWk1~Q!;Mw#!OvM_%g%n`jF6x zjb<|r8lu0d^s>D1X;DEZo;NIvFXXe4U7?%VSmJ4&Ub|lP+07p|3o|VF(;gbd8C*}V zHfY{NObsIQXQ!%km08Ed0DjHD9hN!g{8IX+Q2D6ywHu zTsC1VrbQ*?^Gpf3?#&+yr7+D)y+l2ibuIO2r_Gk6sntmBo|}3*eEY3P%Vald2b~re zHCt&ggGHpKgmRske(RDh^YOF*Fs&L%6zT%V)GOGy%HBmOpdb-HznoHT)52}{m3#79 zbNnFP;I&Di+;Yu>yRyYUy*(9&8dX}jX%3?)c8f|CsgX8&ruYC6ba(UGqE`&^jzuL` zVWweZnDoAQCpwcea_`Sfb$0@XBk}h!*^&?UVTxV>16vmIW0X%a-JQpP!k#2fnPil| z3P*R=erQth=X9@gb%0f>_&LFBs6M&PWES~;;%xS%I{5HHCC-o6Mo9q|Y|eBpF%q6J zA?!%@LuyHe4p1l#lIIE}on2S2+BdKcx_!ryk|Bt@N}DZZ}lM;RHP1Uz%1|};B^zc_#g=zRj zn_{vZR%gI^w5OlVT+M0UC%(YIhw+WL46~~E+YhkDh<5^ynGPKW%D+F@#NxSM>}gY_ zE4hGw1!Es@HQO3Izxn-~#A4?f&p<=e7fnl_cMBC&NA@6lGQ4LE|8epB?1P) zySO57O#6dz&QA$4z?i7Y0+wR9TBCmX6uKqOB^-8@mOOQ3h1}6$e?F-8ioX0Ki4Ge} zW7=PCoyo~CJ>6P|I?1OZEIArAdg?7LleeBsD$P{qYG>2Dr6>rtEB6Od`c(Pd4(g|5 zN$#_og*hs*bQ?by2N9TI?cDu`EabP@N@x?=(fsWnpcZ4x4@!=k>ffc_` zggj91WMevlGZ~d2NG{na`lsIa0)#%&EXP~}?Tf~3?huE)5w^lJ)E^^ZywUWtt$*ez zR`q(z*jhg__{14Y1$v}?3HRp~C93Cf{G93hOKb4vD+}olkIoXkrJgJ?g}tfqXqSVV z-I^)U1lI(_lCn~_OqEV4*Yn=ramXjgRQ~dXQm-_}&-)OB>x_cIkq({rHQES!aTslg z4)Xcno(nkw+H7}*vTD|E0`jz0k?-J-Q%P!QT;AZsjsJ1osEITxkyZSups{0GI(fBh zm}Kx=09bEuk~3yKqxQIr?N$>!-9t0^LmHuC0T-Gu@-lX_J_+zOSh0CY_bW_MIPGJR zm7ANet_-m9V-{eyesLgU*&$qw#;Ws=a7=cbmERWbtwEJSy?j14zz+6*AsDc5)9Qf8 zTq#6F%ukJ9RZgZH2ht5Yp?M_R+CONwzbqm|!(&n^d;RzaGr;XmY{d-n=VXp{m@w1q9K$`7tOs6#imD?oy zSj9Cd)_~^d_Lj*rV)&++4@(TGJSqayM*xodC;kru-Dv97y>Aa|gxCN zYa#T~?$eq(Gg%QP1U>|LhwYcl`(5izBAC7sVF73wK{159%LC-CdHt_c1KCCyZbzCiL-hIkle|&jl#IHrv%inE7H8`u?ziAIeZ05=R=C!^Eol42 zei&{Qj9vxvEQ*@E%{H;BZsj^(iE= zSBMMu6LuHX6QMN(+o=#S1)``1>f{r|lP?w`O_C=wPBX}RhDKx0T|I9YIPu{}USf@P zQ1Dusr~eoW<0j}sPTR)l?P&+X21vRrh-zhSOt$txkuH9+y*2vnF%m( zK$Y5&kqdw~frOy&VuK{d0L2K~n3&26pdDs)uhB@d4=^J$uQvill?UsCRactz64}eF zhwtVEww`ER=(nt+qi9QU_4J6c0*y+Ss-pKpMY4zUChGj-&rksY`@7m#r3H{RuZU5) zfodo^ay zyo?O2)Whv_Y;%KoFE>+rTF?9NJ8EdezhPnJs_KjzGfXd zuzw6ZG6`sN?ep_eiPP5UFhE2y1%sOn!j_Kioa~(J=p}RJKR}wWVm-U zNgtt9Lzr))%vl9xW^MDzynYSpmMrC3#HFa{INb`^-xebU~ zA)_sULT9<^rZICA?yLSkrp_`f>hMk5(jg5J(%mqC4AK(PA>G~GUDDFs0@58LCEeXI zbb}x*-SGb0-FNr@iBH3E3`{)FeO}jj@8%!xw2+QvK8u$;OtdDot9|sOQcO+AU-ejz z(nT4ja38eeAuew4X|mVGX`Cjec(xlF;FcJgKM}9Ir~r0HNplDLV*%--`NgIfYw9OqqJVFtnUy@ZjU z2_!BxU+zf~X13n1x!90P5YF^z?#hfg`!UI7(c=d@sW&kuh0GE0e_lsOpT;;@$s%{# z)P~n!i>O|fEz*PNs`eRg>mI1u+gEQB#2K^heoK?w#`!lr>2oZvEz=|oH{zDP;4p45 zwJZ7ipf_jxE}^~EIXs14#Mn{?tYgq6#Ssheg|Yy!$FDLu~tzT-RH`)zZa^Qgu*K=(@7ehS;#t&1sGM!yGO%+P2Tl zakakR$vA_Wt@LWJA9yZ?bhFu|JDNus9DS{r&8LSmUWw&~O07mo=HksW%wjwChdH_> zhKQN8{vAiS9ZAs9r);N{DxRaEDGJWZQ7!C&M3H7g)95!F@;uz6D;a}x&a77 z%ENGQCw+R|U9gfRR&9B*rX2;zEBE|wxEpqec?MUL=L+4^<94-+ycel1uwZ<2HKD51$cmSx7cFGaTHg6+ZMY zwowV5;GLz=-k^QJs<`c`xJHGIp|;~DRE_K0$Eb0!_>9Ud9Z99$r1_rP`j=qL$NZiy zAr#{qQt`6+xQ*7r(fRHif#npG8qBilh~uFA%uUG%{Hl9+GzXZo<7#+%Zj5M{A0 zz3$<}YYO8Zm1>soWRn9Eob>iYz?J5f?R=gzO53UoBV@O~Ws!i^pQI3>HRx1m9UcnwblpHy%sm^0F4m4MJ)4<)ep38 zu_GzZ=mwrv#vuj*B*Dd^YFCe`(%P-|*&5#~_AX(67cK(OpnUNMTkE@Nt(AA2gy%me z3B>7%W#5O?q##`(wx=$2=~G*Nmce3L9MK%8G71h`uN*BlQ;#+vko6A_4k=L)4%@`4 zIQO;+5A@IXZzI>yZekNC#aS>|NrdoCt>tf(6pgmOGe+~SXa80`mnbYNwa3!Wv@kHr zfdixQ&|8PxT8~^33~7+VQSQ-%7dxddOp*FZQCLFg`-l=o1SNKT60gN>7gpq4kix3s zS{aBTw#wC}Y^}|H&^KPv>t}w2NCxEjKOPyBg_E^y^!68*U^-@uYvQP7EohOfXiXS{yS^XD0Qc&l;7=|af5!vCr!U(VA!nj;pS2mSrdDFZrfWHGSYDF z94-E)wOxK$i8gF@G4Zbun@*!{)!Z4@VTS(le34e(NW^WDe9CiQ-S2iYPRD)Hrc4i< zRyG^lkB=2zIqabCqV9)t-BO@h>4Q8$h)E?$J}kGGtlLi!IR$%8Ilsl1NDuCJJ&Q!| z@Xx?W6lkMb!{M0u3Dj)2>+-gBwb?9@i!<;RC7_CrDSZg=)o}3?9t*KFVq+GiYlO}^ z2ii)%&8f)_V%=yjpkf_1L9a4RgT6d&t*p2*-= zR9p@_n7Q6n;1}*UAXqsCb@%6>zv|AXTBpR~j$r)bTSyDe8cbZA;*Vo&lfe>Udz`sScw$Ejeks(CN4@cxqWJL6(lqMbbX6r(w<+=_&>z&-Z8r);+ z`6VtKsKZScs&8LWdnw*Yv(tV{U*U7w(u=m~YF|I=zHYx{_*e}HGLdYzw^NSxQZ7NT zgbKY_n*#6l_Ke#FzURtH32~4OR5a%{+OL@t>h>h`T?8j=XNX1N2h`9iTt~y>L{L^- z9-|5-{rF4n^M%gj`^g^bA&Erz?UVvbd?JEfii#?4-;UOkx}bF6`BrP|)`OGMQrFQX zdw#}5X$apNHM+2argi6njuDQHx&}Yj*_zo~tkH_*EVitD!pyU&33f5C9q-{!S)`2I zP9U@F;eBKB^6Q5U&2*Youixp$P4HDH`yoo|qaV_5c^Whg7SDn~iP-(H5*L5}p8l|a zo&!bdg|dGu#pWOtj=bl3CRTOe#u(lLrrI(be(Nd`JSA}K>mrEvTkL_Ftb=uUWMIV+ z?8sZD-Y^7c9E4Ga5559~Iu^;;#!4YFnWf62||oDBd-_p@C;8xS04FPqn-BP1-JGb7TSe zj+sMz&j<4ki<<~`i?zf2ac<6AqK;m26pKvs^?uT(?{g5&_6%};IKDEX6`?or=w61! zWYu#`C<@RwZlzDj)cyA6ym{GWw6Ep$$UV9zJd1tw?~~bKUu^fdeWoGxKXLp;d^OIs zM19(@Kz|<GImx}2aDfMmD1q{%KKl&6Mz zcj6QiQRgR2IPZS2y0o}tJ0FZ5EcPYbd?gT@3n!Aoq5zC8ss3nGI>u@9bTD-=P#``U zqapD*#-uT}9r>|7d;V}!(C2(PfXV1%Eo3``y4e}YvFQyy#b!XXh2s5iC9LZxBkTV0 z?7Y;9{t5IpNH)@8|ruEyz_rZ zFP;tfgeZ#ovHKroA=H15eRnfG8uK4$w&maHn=L5O;Qz2L6ASFm1%2Qb4zGEx@wur2 z{)lmZE$CHoYlV6Z#_9uAv+}5fbsLAr=_M6=Wr%P?sRSlcwDIv~+v zOT$cqoa_dVi1DX}XY$nOLFrY$V0fK){i>$6y^wQS z4VzQ?7caPA!i(rSX<9$#P&yWL`@1R9p96RV0Yr%1Ee>J)69|U{JzevW*`3b<+vQgi z^7hP)OEe$f)6*c+M0UL^kVt<~p-gUP zs|~V*Wr?21X1^xv^;%1TTvG=w&lHrrKAx6my|=Q`o?$rM0T>5* z(iq)rGP7#izt>EgXIk^Jvx|!q)BEW1`0AQV(o6|Ld6u_#N zS#B1EPe-D*1lbuZnCU~cochtx^X92Wx zUJbx_^?a}K!0x%+1aq^z^7_ci{KryvyA=kSJzy>^^GC0s$MxYy{rm5xdlKlx<#gIr zo${Sx^a|hQI6YjQkLxlIE+%q?Yi^F0vQ#&0WNp^?G^T}(nY~YSo&ADY3k3cv#FU_A zX6GeJA9d?&__ODq3 zx9lGI&Q2q?SrmYQ<9#O!(Q|Lv<*y?D%rqyx_v@GX2a?&NlaewSAD*Jvp(AP))IDoa zMq=TmFVF1iuHV_Z>wWLGRD0{2x5{!}FZPAGf+Z`TfU0p|iFyGmFdS6)-C%RHl#qZq zur-uGZ9TJc#?*Hw0zaVF>Z+W=9DWw=3(EOtqF%6yeb1|FbVU}m7f|;JlF5oYCsM(s z^$h2-KeJS4alIWx4hKa%z03vMwX^`Jt{~@3!fuk=YeX_|3?6N8oDWmtx6E%(XwEd+ z1#rhWuu#%KC-Tie33v_0gaSUDwhs~C3m?`CgAh)PoDgqSN-)km@BF*|R`6aXGp{|h zZak|yy#m%O^?;{YmB1!AG5(jFRyh*6lftHTbfBa3*F*71yVGP#Ixs6%yz0PLfe&&fdSHmq@S22axu*mG}%H!^G0zu_uYNZ2g4i@7O3EXoFzkr=< zH|l5qzZ2SgzIV0FC8l)CUfJ=Je^E;FC^0M<^M-wZsxemb0 ztmU=iT*(XN*L5l}H!f5^HWai;I0U8Q|pdfQh_1lq*$DNkj&ALduQ>La~+@_KTTQUj*br*G&YziZ1Z zm8WlaRuB%s!w>teSeR1_r^c!w;l|;RGHrlMq?;0BG>iN{DT@AAZ>q{63mOV z{suq)D+KxXJQy;@bOGQVGj(TY(ObJXF#2zSi>Po_mouo#l*c)QB zY{{MBM*+u8THtvfSn;2k(4%j$ zb_=iuuG$7Fn5M@!<@;C4;%+D&ixmLL35J#0?E_M#Un-(I9~Ej$y4EALrmRT~)B?Vu zH{4~$w)osu7ayyXC}i>75B^+FpbkIcGBcMLO=aiddemFq%#0&Mj3x58wbz5@_Y0@H z9z2O{Lu4io4{cHqPr{1*pCYvDEg{XfRV$6e5wnZTlEepa=VL*gIh~)zvu+!BYYaMb za_rQ3Zlk<+>0>fzeFv{*;MiQZ`%wDPa*1vyvia3^=wj4J1+k_A!M1asSQpaIrnUs4 zlC&%1q)1^G6onsG>n&npWi{IL^|)B25^d?5Q$sKvlA7tSTjn;n1?1 z`(B1A`$9z*Zj84bdX{rYQmUSfpiwCXrCaUyzDq@i`RjQY--&KA8;<5Q493-T8g`4! zV=^V)hn7#y$h6Cm3|mkoANnL=;5XSY!hZZD{8TG0yfSQF9M_j3LV}j{!KyIz=`JaC zBAdH&LR;o7v{Xqi0MiDzLZ2N%OvWC^%ctXt{kJ7(T|4Zb0acv#!G7plg1M}ub@17Q z@tVZC2(sF`7^cEs{4@%yO`puiYhUUH%em6LW*)-TiEO^iGyXh8cp75_rbJ3)#&P$m zk!zL9y>V5*9xnIy0i76Htw+fyv;hUkAIFxI<)5Tt-w*OtT6O9`3~IRa*=wWr%+#%- z$n}9jC+u~ItA4U3)Bn`wy6H~|L?f1C1Hr1~oy@tkOIZ%#j01KoUBeT8s{gWJ_NVI?F1641irNrov&|W6KA{SI&H6hZZs4lY zs97-4>U_ljEt&lM5L{U~pvxiCUI4X7t)4-X{f3HHPTG2$3zHT5l9wz0Wf2>+sXy0R zLRLtn_NMW>c$_QEQ!Fo-&-Dt8g^ha-?k(IdP)vpPEv$bCMn7M)V!6BFzg{sAHb+!I zL{DSc`LqbY9!^r4eKh>l6@c~>oE62ES7~U9lqz+#`%|h&6525yYQ?iD0h@F$mtWh- zbd8)@tDs}!zyQNqq9F?AsUU7C@h3ugRRvyUJEL@Tp$@& zZjl=>T*tFqOpkeaExt7^Nd`VK`eE_TP(V%Kw`s7hH11f-^SZ~`Qo%U7(5#rhLS6{2 zv_!TnE}y`@#rS2 zI?zs_Na+f8x8(yI&ZssiShMw9E3(W~oMvgd!opaQW&2eb0P-*+*3fMiW;6x{{RO?n* zUnMbLJMAc+1g~-iO`KfT9SUk}d;go2vngrr#mf>iQ9 z_uzCIZDS1cZCj?A)}T_iHVdK;cyfg<5c+pGEVh-uJoqD!C-geRLKB!aCYvJ& z#R_1)WuJT+^6HFwL~I>IIpYrEc7CdfKZo!Gjn&Kl!~lx*7n)8LMf=I{8HYrc8gD1kcdqf3o*K5J+ zCGPbQ+s`1YLEA1xNozp4v&XVWN(2t+hR2%8r{@0NYY%Uj9*01-)JSs5YMmF z^MW7>#j|;5_lK8bDqP(y6YaqOylgUhLvFNQso^+=;s3lyjc6c;*=W0le}_>#i*$c< zYe3!JFzN9124qjL6(5^2ily)cS8sTfX#rR$o;ADxhdW@C>(n~VU+)ZMvIAo&_hyRX z-Yq~(rZ))tH`6e!34jQy5==h)&*^XJ)YTLdTUTZxdR=`Bif{5xrU^ z#Lhn1DlQ*rWFqjh@uRDNmlx$D%gm1UR|A3a{l(cn*|f5c$0VShVruE+zvR6#Wad{` zq=aEtPlUD*y)Gff=~$j=?|lbEd#{{`5!j*#VouNLZ*T?W7tm3-XQ$IxV zL|Td8drf>zXE+}>DnRIW;fFCHHpZ{Wx}8tWJ-AtP4vv+KCE>1+ltk-X6~8<&+MSHM z+2Y%=X-|9y?JR2h0DQSfR8r%JKR#8;6Ikgrtj`pUnwZ6*2Al;mnkUFunz_U};RaWv zD^Z7Md8e`(7#(wPFfv5OPwDiWa^u@=bg0x&oEqoz|AE%|OQ7mj$yatpzYWC|5Agil zf-g}HU-9-w1nDESU)q{L*Ot+W_D!_Vxwv^C~Wo$ap z6p?pt+wKSh93f@k#U7sw55G_bAysROs{ZJJHtI&;pv|aE3Y0wDv=6o6#?)i;;CwBi}C7>TL^Oi@vH3-_kCPbwT2Zj&BTeM{=pSl`sdUCoRl%xw8t{&XoCV_iY zNrN&&!UK+cFuDS8l9rBLwtgtdB_byGn6f}1km!eeBdW{hHi@4&e2>;*RQzY`Z{211 zt2d|mO>~%nkn6WW@slaULX~2LS^wHtZ?~ypAhNKt?nbAe`HVb^+%U})PXTAS{dY8( zrRZ|KFbV-oZ9ChInSyisQL3i&XE_&P5%7Ms41RWKUkOtBX>C)nZj+m9u?>kj=QrMM z_c{$tYkxY(`Mb`E5{UijJwcQwyU`7W$N6Wz69`z~h3|e~8+&XdIZg;HU5jv7mGKr- zk4vZy*?L41wm-NMIbSy1(S#fc2}iG2X=9qanr0(j3e;xrBJD{veF1ivugvT2u-6E3)HBIU)EXs#;Tx6>M?)xzIOgU+n;_gB>H z$HMnOT#c+-i*}**r}y;~+FBLXwLD8}8Ia%%P2e;7{<=L{^Ipt0D@`HE$A0yrY0dU~ zhFlNToO#W)z0tV@kyMzjhVZXeCRV=12bcg1eo z6*h2M<#l$~3f#LpusC?TI`K~#SSa-rQX1{iSB^A^Ih$BIvK1bDF!Ng*W*5wtU*4u% zW_kBlzY1yoHrGS`&gVA6Oa&DhV*c?B_jqHm0p@z;ujnJ|^0%l!@rbjB`7DPI!%9bw zg2~i+Vrt`Dg~$2Gh`6sNQqNs9e~5|82X&4=k-hw${CG2%pzt}>u+5I*u_ztTa*Mk|uLrXwGXi$$|ogYKbBwcbO!pz;DNN%jc9~$(*-q|lZwwwk<>bRJSJRO$?Esa_8HIhRd1XVI1Z-ST{CBb3LCoB-iFKg`Y|#VhF1@e#@*2C9gDw zfA5r_RiNBlgzRX~;3Yb4%lqfKgQD_U)yneq#b+X|qdm^Ia^V-l7MII7?nWMAIa_SZ=3=0`Pm#|`CU!KFQ#`wW?+^#tj*up zt9m0GPj=xTnF6s$4tq3SixlrC>kx-sfgc;-VEHihDU0@?$=XDdPnVF%mh`EwGN~O& zucr>8M+z?%xg10uR*5Ex#k_U=yp1iW)H6^pZkI>9fKL43g96oBo972QfmwK5l(5A_ zCq*=}CtcK?<1l=`od5cFmA3TQjdP&oo8hd@U+C5{Uf_-)C^Iw5Q~C$G?`AMQDEX*3 zaG2LKVhC##NW_AaV_xribL9w?htl-D)MUfRKPXFg@P6lJ>SvepJP+{NKHB<F)8PDAsXr_UWGm@%*hy#) zpQE>W@gjI};Q{4dx8+PV!Ux>D?NMA@W#-TOacEmB_r7~+FcqHHtra_aW9V7tzc$Fj zRsy^)i0Z84{HYUBqh~ifuF5s}n;my%4}w>njk9;$yKy#fa5@+9de%>frJ{CZ-QAHN z@Rjx<+Ss#5a|@|#A2$l4Qep;^gVdr$&S;qOs=4PD4oQCSQ$N1RKSky@sGB`t%KAcbcBoI z+)y07MkeFYbYRu8*@<3P9_x&%yU-`MG_>AmI9*k%k6|HBD455mNzp=zC76+Hto)R| z8-zh7T!^?wG}EB06~Nc8Jtnc&6$n_4!)o3=4al!%(mq^g=Ab2l{DA&AMolzfPiJYOp z88<^zd4$moxi(ay{lN`N)$aR?3hNMCeW6*%o2kby?b=6tT)9p{-b6S02qE==-dIs> z{!C|?9XXlcpPG(cQTdb_HBb@vDi1FO5{<|L3|nkfR3x$tjIy3jeUg}u+y9}=-!Os7 z2QNPa-Z0<(uLKcji2gGbj=XZE^8cUnE|7&1Af>5aQ;h$Eo<99+h~5VbIEViSJ*9>3 zTNIG(l7R$$YC+!oah_RGqYO;g<|l|c%dt9Y6Z@m}j*tw%Q>G@=o9)Yw?oLWTh^D_9 z^>_>HH(=4PX19F3>6G0*56pX@S-1;Ik2fb8xqjHqH73g`rjV~NX;)ku@HuBo1WF8E z@PBj`N%MZWvr2V@nlVcP>bXVBX>aS;CX#f)4yFU)Z{r_>ZzGs=FeS8^kv!05wbbKOKHZktqo+TMssFud4D84zSKaG6H?6?c>GNBwgvU zcNCp0t9CtuNwjLftp80t3u`o97QY8j1rvRL`;GqQABL2586D>-eTddU!YBs-$#svH zy2plF>k_2vEno}H6)FJk;N^f_#UkB{p6PGBL+*OHMI0FrZwvDt%{b(fk6mB5ioS97 z*R0ZOQW$^a^A7&~c-pR`#<+SVSUW`+xba#`<9OCVI6Ug>2t3i{{e7P|4l5mN{I|Ks z%gs6s_DMEDmzS3z2^VlQ3uZWh;f&CcdR)xnd{t|I&VU(N`+}jegZb5ne28R)4N} ze zTzy>pe98oyYW>99;~H$IlSSjz0*5ETgs+XGua5PD>*X$q$gHUOU3E5bLw$&W);|qk z<{sy#R4`pR%NAixmE!C5ee?>M-CB#FD5>SqBosD8$G&441eU6mFyK&bf9(cD(8rsV zs&CD0FTzy{z~T0QuDInWRwpJi^Ojn;CcDXs_jbDkfa2x<8fGZwDo4@|okxnwTh+3^ z%LSutAZ|gCi4sfnjb=yq4mzQHZq~%D2*mV*V^m$?b6Qb>I!zO5YUMPOQBAX43KvMf zKcmIq72Bju6h9q8r+?EcEJBSczMjZ&_6fRK0xZjoeusPvV3K_e)lnjbUGv#uwArHfmsA zCPADa*P+_^XnHtgzI?I_J_GtEb82|$*4hoWL`r)53Z(5vY8CV197^J+%MCist)I}| zf9L{KXAzX~o|CznUREXBVjgw{|NbPXlizu53YFDaqBZ@`*4wrFtW}0MwBY~L2fR!L z)2$?u2PhxSSMgK~9an-?^#j44tHq0ZJ)N+oLz}YKk>#@ToaU^(4e#N5)%ig)FpJ}E zM7s7Z=X`?1BbVEDKA7Y}wlrL0{>In?InR%JwzlX!R;YMk*_Be-b>?;-7kNz_jq&&2 zZ{Wn-J-cK({4R$o9R6h-Lv=?2oqX$O1)|sLe%uy0+E0F0FaF%tb6-4G-RrRHsL7i8 zBun89sRAzV3h0PV?f|};^;z&dYjCWcZ0Zq3Aq%W$;^8+ZNWq#R@SEE1 zi}%E+g<>f=wT5|a!ilg6AGF2oF#VlXVZeSnW@2KS;T)gu;_pbJpR$A3n=u?GU{*m4 zs`O@NiI{IKnE08My3I23Svji`9i6W$8;91;bAT!W*5a~$>o(vq#A+lghIpKR%%$Do zX^n2|#YDnk79#4fUEz>k`mZEtMBGbp^RFbBwaO3vA7YJdo$|#rkV63&uVG&MxR1zA zM!aU3bV_wl63EUmE@F;nJi3XmYZ8DKcs5+c#9d{dNtb=LA0L3zsrPw?B@d}XjlQ4& z6nCQ+m=Sro-6;Z9RQnDC9$6J{f!$gcX!g~TU8~gMQftKsR@t6mSV;$FGT!70Rm%MrxVc1M1!--V5!0K>%qC@zy1L&bTZ*t~urHlNK@?m1F#hv@yJ_kVaW|I3T{m{9wB|VRId{0c^ z-E{c!IMDjpd%qHKWO8(NVTc|I;q(J39u3Z={}hx&GWBPb;?eeu7RTV9R&lhi7( z@QX?8W|w3HL0jt#2g#4)^;WamF@!=asIuz_>$e;QlA%%2F6z=d1aYe#%(y3eS~mwS z34`MO6)OXwkb24lNdf|5F#`^f&JD_w&p=UA*w+Hn+Bf(iNww2Q$H7VfUl&;xZS~gg zIV?usCBqWY3dT0*44-YL@#_YnOqK0>UPS6I}3KKXsWwj-|e?0_s;Aj+}j``(Tkt% zYd}+HmX4ZnwaFn@di0Qif79@+(YIfQ8pU{iwNA206h*k+Sbu>4BYjKgwG#k|@^?SU{svLWAX#GuxEBOWo#oR1;y3XQO zw9GO#-)^$=E|SmnPwntv=T@)bh$!hTrgz3!+x-S1n)l70>VMrjzB4vGzKm|Xi1cw2 zBEjQ(q3M|vlfgKm03qry1AAK%!!bk7M6DBJBAr4-04guYW?*LA+_wITv!X8N$eAvO z+Q{+Wd0a1YXkVkS5k}?kIIa4u0ft+EjmJRP;rxDvz*mJ2yvf(4@g8+;mih?TZdLvi zQ%C|3PpVH4yl|!Z-Yn(bp%9KRn1zvVw}3w%*m z6x+TEJBlqg><$*?m|k&?e_DE}n*7`zqslb2xWH=j{D3|oxK>@@eC6Xj)fQaH?@x6V zYhJ!K&k`KLy76uXM_qlepxI!OXR^&C9Ao`BlKHRE+kW**wPwj|`PKG=z=qaRjrY1DCTivsTLWhCW?QKD)uO_SZ zQ!o$`aOyi0$kLB3qx@1%$cQ+R849M3SeCeV$Wr*#pzp2KEMumEpNLl>bWxIWw2RfH zG4Zc<$C=UXbHEuI34HqHueXnF6459K2fTduHrpm9qc(XfqMTGir2nn^_Fql#<8pAL zbqZxRMKC&-9N+kKfkZi`@WW!?rNi8i(fU2WLX8kfiM!r}xR!48`^irYVfRL7Mn)YC z=$Rl|Ob{GQc<-gv@p6Z}Kamk!u~3hxw;X#{(B@l;#d6tW&AO04DZ2}l&&!BHvA9xz zbfXa}<6QZ7?B-7Wk6&;ntl86F`On&*EDe&^WnvLB>4rZH$5`_Gw;v&Bbd3^h)cv2x z@?o!Yz;eHNwR;F~5-|t?gp=}t_0B!-mgNhhFXuDYbJ(t@Y^@fG1ymd4uFkZrVKmc7 z+am8_Q$~D7h(hTL!0i2B*2 z2oEd{Q5_#2x2tKR?99|ui*2*>dEME~>XPA@W(yk*c zYi>Ybf?=+kRt(5IJ2(#P*wZ7pk|LZI^zC|pRiC)sQbiAIKJRE8dpsOpog=$Q6C?6MDYvJ^Gk1aW~$y9?>#B-eO{b^@$r{ z8qx|^H(qOfy$rZ?f5nontk9T8beiS20qH2o`>eqLGrqTkCbERJ%fCCNybQlTg+??L^Sq&604a zO4FKmowTIEyFMvO2pX!v#ZH`rpUfU$YIrv+Z~W6; zUr|}|zR3Fxs3rD(*)hMD|l)OqbX=O z9h*Wju^lX@DP$Baqjuc=gFX2&W-!86Rb3a2S5Xy2SjH{UcRX1}R0B35E`(+-p;D#q z;A%gAD%q-LIhrdgNb@aFCm6^t3$-R9jzjHzf97mYs}5c#GxDa02C?Q9e-ah(=PMcv zxc=s}_{+GTsb5f=S}|*#%;RjmU}Jc`c-F_T$FnMSv1+K!8Cs64RwSSMCn3Z4%b+Ab z)+JYZ7n-)Hn=vDqxttK6dlw>$lkwEx5Q*sX)zKgsM|$N{xi&rxd;_ioUMmaoGH;#*3b$tv=b~}7+GW4xapQYQ>MsPzAKi}2(qlXfiXov5i4d;IWecza>Bx~ zrK1$-<3R|G#%9kYqH{Iv~I(*1S^T^aW6K8Dk($jkmY|?xJ_RXPL zKaccyW7w%SFO}~D*b^q7U-67@j8HTJ}5qNVZVc|*m&_d?W!c zMl#Dd!vRD$S1Yml{G(3T6b8E@eg=Pop$32MJR5I-?^PCPK#9&BbzKrTj}^cr2{*n( zm{u}LpTwk#93ETnzD^mnY-M(ZbVhxa5@O{*PFCO6L$T|`-pD}}5JmHHt4pW);~z`< z)?LYQ9ukN$k|v``w}K9*MS?fkWQaAJbLx@%M^Ny#M^>VNjM=ZvpG}?YL9)rAG+$oh z7#^N(#4Vqw0<9;50-}wVe|ET55uPEXP1geSstyN;2g+{OF^f1*ej6kpCj&-;10^*< zu7*DAcRe$d%%_EDGoK0OKGj>87E`-maF(skXZ{c$Hyz;}t1CmtC8hkr9~>3s-6FdhLy z=|BE8uS}Ldy#{uIJwo-VKATi`_u%_qnX$kI8q0^_GS=l6GdfA2UT0OTZ;4<5&KGZp z81Z&X-Lfs38?R)M zltmJJr85ph3j^xAXutKLNN@qAcyH!b69eHQ1UxW!&tvH94ET>7MmFLp};J3s`H*ox%L zg#}gc3@a%@$xT{C%g%%Im)Ul!VsVFUaVW|IAc`^hs352j*RHI1`tn|lwgRuhvVj!0 zS<{a>Oby@s|GNM(G#R)y6JPe)-PHV*5M+Su6cLI$aCIf*$hc~sF~zaSxdz%Yo|NcR ztGv0nsKEpm>{jrH&?*b@ZV@7W*P+`WBe_IMbxN%svrkyvrE^U6D#nc#RwpgjH>#l| zvfgRf^re~A?dFxI45Dc8*^z3(wd^J>A?O6m$%`Lci}jVvQ6#@XzTG-g%dPUC5vO5* z_2__P3M!v*1)erW6&mh)PN6ut;c~Lp5J675duH2^y@1QAgWWZYwRRmI6~c1(+*7*a7GJw5?q&kA)bX z9S#aPs<6Dtlenk^0- z{kQS73#t8K{rtwILX}fmbZD4}E9%>(m(8O-)8{%p;5R-W`EVZ$&;`AnZw@_>A=vnM>9xWMfrkR6^PRh1Xa;@=s+39~xqx$cS{d$G<*sEl97 zVIE`2W;@>fqO#$A8AC^S-g=bx{gXNql~wOvWQI8yWiKehYY5CJxmI?&Xxu=}jDBP# ztPI5XKj`(tLOmDFXvga0m!{SASRK1K;j+d8lgaTH7Fz!M+Ivnv z7W5OLv*WT6m&p&n!N{V8G=s@uFU`QK8vUk+L zo3jV>?Rb8j`n+>utw_imN_iO*oTND{)L+Lj$oXZvjA+tDlqO_OqA{;E*~j5^Ft4T9 zgmUlA#7&$YEd2_j$+&w;NBtkHGSr*Y)PUPc#NVmseuBETwmWX)c$3tyL4zkP$YFGf zvg>9rJF#iss_9}oF{8q_`D&e#V|`TTAvgOSX`k6f`CY)t>11Y!^KiM;A9y&cym(Q?#Zbj9g zOZ0yd^dOYLm23WQG)p)Yzk4tF9L=(15x5%;&8O=mlgM<$O4@(57oxFtiz2fg^-Rk7{2)i9$N{JNKF^}fB)!S_?f&vAVVZVPDs)W2q zKOQa_lQ_G7&?(Ve;c&!ocEYMSwhc=QbKij*SLPB#A@exV>?d<#iT=yg1J>h|e5|H@ zT%%W!bSmy|=>B3CHzZ0zmkg3^+fUsadt3%7>+TR&`}yZQ*iRepw4N5;crCEiR2|N? zHVxh-P2A{we@h$oDS|`U)5Pv~Wk*C49zR4UB0KVDhLzaZH=@Nv(!VBY`W(iFQVFM9 zgf8_j_YrrR{y|Sx&kKtTf_|vaaNrupKB)!W+5jB6 zhQ0ML_9Nf%FuA|#uM?@*poE=$df)q6gKXM4P^D0>9@6zzUwm$E?Yp{)S;9Mx9*hPh zB8NSoz;SND0oSj)cK!|t@DIARH;kQ(IHdJ?bRUZRZLCJav72o3x*TVsppkuYJSM7- z8TQyb9ea(Z$5_+@Vqw$$AAv){Rc*98^kIXLc{SaB4-Ya(2&=a4+t=eCRtaJWPQ25 zheX$b<_rnP?ZrF^FO$MAORj~W`qZGDh!~f+kC{)iNt5Y5Fr89NppLHfX*rjvuisj* zQ^>|ba~W)!-7(LBw&hDHa@d%fRXkS8LB#`a$Vhbk<5#a>j{isAI|cUfw11$n%_fZ+ z+qR9ywv)!T8#PWE+iqjqZfx5&&i2Ls_g2KSE{7HrnZU4i9~^x9%Ye5#Zq0LOQP?jLkgR0Lqz;ql|nUT*6H$4&(!TDe()+D3!*W#w|7V6Q{>2BZw^N~ z3`2J;=+cPGdTfQnSDCl9&=(vYhSU|~yBi$Ms+g#% z8aPTlPYs{qC@ZTd@Kn`(q9$f$uK4~#nDK(>n&W3g(I| zQ)K*w0%O`-xrC`tYd6awLF7g7`S>Y>fq$I0n7Znkri!drcsMLpcuTi_l%-sr z{cj6!8%(1?#l zCt{Kg>R$g0y+7HR&md0eS=$K8IAd8wvqqhya(M>J2uaR|ErQ&_Q8s|aA~d2ZDdeQ8 zl{bkpODwp66Phq-H4WWKglp%OBHAgmToY$7(C5Z>i{#!5kOa2C%wMQy?`DbjGntaz zPcyfpk_ya04aZl3@hB+|@>i#66@7gyBO+99vf2^5e zho)Q;MDZVX^gZ8CtnrM5LcbxH(zR-IR#mJEq+l^2;>m~*g%NshG0G7hY0O-*4r;B` zTO)rtPx!Bjuph*9rX&tJQ;C|5dXDUeu54>45a?I*?$p>w}@lUMWrFvO$ez( z%O`q;xbnX|xL4N0^U~0&{WJ@Mf|@S+N6WZ?Ai$YI>5%y~zK?_Ijzhuf{{)>O0uF(O zYVY&Bnx|X-IROSNPK1aWw{*xw-)dwGMx``Ea(GzPgB_ #qE|QCt6Q+~TOzNBq|it&y)`6lZ&lpm?v~^IyI!M6jgk zJx|8SiC43m0<}&_tTCO2zy+-WLD#aXL=3*d9W%kb_^&Bv$NDmA9C*8;2PNwJ_r;iW zHXGS6Fr=fUcAB@F9lxd8zE!55VO`t9h@6acKdpM0Agn=%SGxniL)(Zm2Uo>Ra*zt| zagLVqX%t3=`}qsW=8TqBJh6r)$s0Y6fBhGy5kRlvq**LjwEGn> zb3sa{{4|(!WY`H1p6@)8%E(p!Na6TK_WS(a*Kw@3ie9KO+%W^x>yf|w7`RQX#lPv3 zCdNW0V7Bmw4sYqhEdfw1*DbCRM*sp|O+D^mjj&BhqeQ(=0L*>;>c{3JKIXbE`4mfh zN^H)^wx(135z9e|3x(V1s+0z&jwsL@BV^D&lKty^;ll)L2eGKx-p?WG8`lSu64h<1 zGL_jdezDlxE?BUGY%vLi6*q>1!%;l^y{63R;p<%Fp|hc}2=PL62;I_pUZcM9xprf4sM7J)3}lDY zssKD#UycJOZ?E@8uhNqD@Up=l?Nm#?>hUq;@>3js4*QZ(4=}cNYJFZ{>%g7rJIK#O z%qFp|2M-(HbwMUq4f_szFTnZ3_nGy6yJk)k3K3zUUh-}C8`%{qFolD3wEV`>XHNJG z)1Xm4j)6k>h_^SHy&+pP7(+O--u_~7{u)AXbPtYzk;&aq?CEmij?gkyRiW7${rZ#~ zynL@9@Y)rG;ZO9sZBAH5pWEK~dX{ZP7&I5N?x%isvDTPvHh!;XTWA`2P~wpPoq(Ke z+XayN#-`I8m{@~8OD?Mu^3gk!Ba``AS0_0HAyD_0LHMqf`#1{1LI+5g7wk~TAB$Ae zJ%_OS<1qT&r|#drMW_-y{bJXTIcF$)_sG~h=^24kE*ihQ#`Jt|Ha~1O&sJQb@Zn3% z+VK>MUlrY>0_650v1oNFGB&r`keyPsv!?G(I4n*d!}VPJ9`heCIy4erSEy!6)F;pN zd|ExvsO7Sm(&_b_^#o8J9t*S9QryWrdG(vr2OpQRm|ebms=4@mN5=1~Ws^A+smC9% z)Dr)JS24!7WeIO=HpGSF!dvMqh0TK zqJXJ;-p;74iYBUb%??%csFLG*xfP%wBczVQv6`;a?5L?~jCBCe?=1UA=G4+o|MK8j z!1Cf82gH;_L_vZjBcFuDaqGZ7xu2239WbKIR_V$hLUG=cwJ+_ebn59=cY~Rg{G`iL zhZrsW#%U8I_=t9+)9~%w+g5m!ekrZE()fEuW36vS&vqff8jOc*xA5{s+Z$Ap8DdPk z{9`U)TBMuFG5WY7;TMU`U}pN{TS!4wBmap99*b6~0Hx0!IYCF+U<9AHq!U}wVJ|%Y z@zEVDx66kO5@}A0yUto<%GE~QF~cTBRm)c%~tAc_k{9dv3>e$SAL7|)Rvt7 z6_5b`8#)lNcwq^UeF(Y(cP1S=#)RARxddcg@b2LRin&eiw*k2_)qHMM^I8VtXU~<=&tCC$l?qw$Ba&w;B*DCFu2_ zualDXw?WApBYxjvS}PJg5H{hTy70)aK=CI0)~qEz#(4HQyfj=M)@phEmgjWWN}C<2 z?BV*m_qlL1S#^EBQcI)nqRrm&LwYmPsh{x6pmq~apJX#?EZ zMFDqv0ZKWnDpXwd)-D~Wyu9!)tOQL(z_UVGYl=_a$B5j0y(zAtI_rZfUo4GpkP=cG@c_0HQ1DUS9jajFX|OkW4pbA zxrH(Z(eueoYp;+J%Qkq}#eN&=TwZu=RvOtq>0c%e3XM^tQ}emJoIikkW= z8ciJH6g0Sga~$I|eePp=Za3T^7cT_|kSomo+mKHRl$86njaB&Qg?i-3kP-3LM z^$=w~Jq&TC8b=BkZD4>lB5_565hdf}flZBVj;eihx83Z27CE92@Qp!{kr;iT;q{@8 zz@p2O7y7)tD-s-lv<#ly_gf(B2s_`JtiG#mCWqJNnU)QNxL69;98IS`K*IQ+5c8y5uwx-=*HY2Ca^ft)Tbq$a&Qc|kF6l*Mol_EutSYw-kC+S$kRJ;}`uPGr>Wy#9t$&H2< z&6MnVqOZC`aapCHn_*Nc=gj$8*9HI)j_4IRQ(5b~0v;n>pMkZEhcPh~63pf(206Gs z7+nwCedkh}X?YSPKh2c9Aib_*DsM%?z{FOsM5(+DHcq(?mm=2#Zt>jt7Ky}})bS_% z2cl1mJGpd^vO?+T!wvYK?-NScXoehb7n!oT#=CXR13hZIpRT2Q*}okMMk~5x!7lI< zoZfS#nK^UmYtN7-2#BTc(%9wPZc}xzPpw+m#I+;f)f!R>2C_Q#BcMgK@VGs#)vvp*?MGlO>np9Cf^ooSN=xpbVA4 zz{HJ|x$*xv8DJ(Z>e3e*rTBOjPSw9Gy#Q9mLrv2n}0d^y8S z&#uEzerJ59tfPaG&EjoV{o=>ZOT@ycEEEK5ZcgDbbnpgy3?p$mS*!_t9K3{M(kh9X z{1f9qCdt|Qjj@+G_Hp_Yf*SkihD@gUIcmw}{d^F3%VEX^R%3uwtQ%~ID%-9(qHD0c zeMx5!1IC(&6Ij1PhARJ@grv}U(Q@3!u;&!+Wm-;t{EQof!x=Q3pl0(@wxHh93}Ub2 zkE3_T$C3h6l>%rZ{8372J$FbPmTDKDKG!x8)mzUMVA800qKWl0>}G}jHf?5BtAD95W5~sC3ikQ5LbjNFng#Ld z7o!a71I9ydvRau2Q}R6`(vho;iYLILK!adr0o(qTm3m=|tN&SVKP3yPTQJ0Ox5&U1 z{ne6)Oxhr=zLr$gAsr;=u)gkyql8;r=;z>%6aipcR-Pv4F9qT817<0i zq4jl@5gq~QP9AI;`hzlz!H>*^8S%ZBMPpuK_pyN5_TbwX*sSAraQdzq)Aiv^?l&iU z_b_|NU`mYcF>X3wV|rILh_yw1z2~%6oSr9j(!Bk=N>y_o{yMzi~K8AuG^|Vk1z(FO>0*7t| z-Y$LaLWz=!c($FUbiavZMEqzQLlEUUIWhT4Bd?Fys#);yf6TOIMZ6H`soo z-QUya?wnFg5+k*YY6mY_U8;)U1GmQ0tf%Y@B3}T&QvJ6%m-*_% zrih=te!Acjt#Uc;e%)ezzV`@ea4JEN&AK!lnBTJ}5XB_7<3;ZcMN;dGY=716YYBC+ zT2K)ZjU&|B>X%7A%B#TyULi0fM55F^{$~BhShO0lb19pfA<_P!W<&!wyxMlu)$LHk zU_HT`zTAfe;h06mFA-MJ-o+Z91Al>(tVprc+y6lma~$JVUb%PG3$2iqMv;^auv=(| znud6Ls{UY1cUT=1M4}6l2|_ILOD^EF_lx&d9GXBA!em@9rrq!#T4+s27T>y_o@K_qWyGlyFf z7PZ(3f9yBgtZ4z4XW2{>o9v>L`B+Aq0a~PQ&Arwr-mi~w#F+9z42txt4T@MU!tlle zM$=}p8GhG&h!IQb89@e?h>3$B=T!Eq`$Tc46?POcltGjS^2$$!6Fg(1S>Ct9=6IUC zw@bzr@HXo$dt8v~r=Pcx|JqqaEU;GFh{qnbV?h(8Mc?*ZosLZso~6iZ{hT(0_A?pp0mQJ7b%W zu~eA#!QlCawb)mgloY|Q8Ipn}Z&OcO6?y?|-iO#QFk_+=8a!ySozD1|;nc${`u}!dtfm*v7JXq&j6CR&l4cqz(-x6;EANaV!!I+6UY4Tr+*uVPQ zM-SuzBG$Y}`2NR^?~?@3z>f{0qpW{2$-sfa1x63+l9T_}KOv$4R1{*&9S+GBivP9; z1NJ)-2>)U`$27}7mk)FJo2Y$6j6eUU5 zQ2^h7|F9+bj zS?6z<#7XC|GC}{jfMpbjq{^LICkj~7yx^eV8_}@X$h>;6$Hs%7v>P*7QTr!%m;(6! z92_SGl1BMQSPW}MqZ;wy^8;VISeS|@3H{lBZmWO`j1lmW;Dg9>*a(p{Z9kB$()ib$ zl#TJX$Y*||b8YLgSatiN6x}F{_Rs7TM1lDM1g-0n6w*I2LxI2pqPqtZN&2r+!hdJL zCm=upO!0XC#D@rm6NuypDwfngd^uo}GXmoUW=zWU&u|H%*aI^ok%Ts$@}J=f6g2p| z2p^Di{NIVT874TpusoVd0?lT*94w8&aK0$Salo^J8-r_6MZC|BRgr| z`r!UdyUy&48;~)}s-}(qA8ph?K}i_VBuT)mDJqQ_6_@pwz}_Tw3PPn$^GJ}Ss&t8D zyVqR-7$h7-+adG=;nxoDC(G`@klV{Y`TkF2LH|rX7_b18urkYP=TfEFa`TuR$;6qE zL@M1h$AjS==Mfq@^>dwDqhxuNdad{cE~z0;7z{eK4C!R5^gDXqy@)GRU<(@MxI2_; z$^`S!1EAO?AvHeJ|EppIf)bV{4u@O9vGGZ~P$pT)&1m7AuMW_4@f`W^9^R8tuTbW4 zG%2nz9YvE30%TJQ3rBzc35iTT9NwXLeMlh?*rNL|Ojjvnb~#=YvaDM7y+M3_BYc;{ zX3(oUj?b(UAyUX{n=RfTDi2^QSDy-a^QzpjICVbxlde_wEkA9&)f_vD;7*gZ1+||2 zW^YoV^L_k+%DhVFnB)4-#z!(h+{0AzGrH>d?hI;Z_I{<{H++%lSay4ws%*Izv1d3> z+7A)%BdY5%nOb?`)S>RJi%qL_r^bZ|u?)M=tUj_d&U^QkKmK)u$@wvRi{1{^@ zojfTBH%`*(j}Jw-z3yda!)Ki)8*84G^UZ9)em6P2G$dhFW}fru7dh@xYm5VI5M$5B z%UqWVw={tpUN(zGQT(0^R6{{$ei)Kg@XF-S8!4Loh`GKnnfK0-fz%p z%%G877u)SoA3(GT024oP?3k3)TAhd18^J zReYYevFB^;pV8N72lmC$Hwp?&mPbkF=qp$1ijDeZG=>?K_1d@JiDxNtTt+ijOrL$9 zZ>iSWog@HE^mWrjUW56!Wy;u)sx|$ZYuXfnbos1HTH{RF{^++QI2Bd?EEP1l9Z$(?pj(;oTq1>c=za^Os_|J0`=ALUmgoBeK$ z^G!}a7o{$h#ynmwWZ5%9{L}vOV7Y(V{8vu!ojKY#P&o+d_Cn_A=D^sLM{sQm>QPl9G#}t@>jQM)t8OX1|YmVT-09cb~*%oy_os}u6gn`(bL%{Zo;0A zk??$_F}r9oMJfmyk(4tV`FJA+Q1-UJ&~x)BCth+81<|5_VU6sMOfJ~n#SIqHmU%(S zJnFkL{&v1nnP6n=b-WAvyqn)SpwsDku_`n>xK>GhieQT!OVc`Arn?X+xz&*Zc5O1! z*31Iy_nUYM!FIi_+s+M0)UdC;&|z#PXg7W%eGUKD#~}w*l7lz|1(JvZb0k^ahJ;`? zv2-R$4Q{yv6#V&@vU|Kz`o&^>Bv$QCb0;I@TscL#C(8WhWt{P|=dAhz;MSZPo0OmI z>AI7uS(v0S>-V;$;GF(upjM&tx8jv^zScr5%waDm@O+rBaCF-2q=sL!^P?+iG`UUI zjnN6=6YG!TSsMe)z#GXNy%?lmD}3^Su_%YG)z*u2>n zZfv#juAf?S^$pB5wPDj5!jE1u9F43}Q~lw5E#K+1v9M63bb7=bZqRLM*X=zcax9rf zU&u0&F>Z?#{daH0u){U%%$-4ctVZfca`n*i!m9J}EbN{HRL|F7Sl>8eG1Ykqya@0< zB(NyxvFK&OO45gZdh&^9ohP`Y+p7A?pE@(kgA>tb+Lgu@^&{%`FGgF>0pKtW!|{bB z-`Y+%%HR`C@f_$-3=Vf23vc$vQWMIU!ewMD^3LJOv2xA@!4M~B?KhHFE_?6x4lXGvmQFoh7Zu;TTB>T@zim+@1yM8!0%;HF zg(|%}&T8a{8y2;CD`vlMiJPztF|eJPK3)%x6^&nWdnzoQEf=p0J+>beRWY-YxLuBE z^qF}@+|SPoQY>7wYsQ;kcE{qPj@9U7)t7EvZ*S>*7a%*ZG=7$=QA&E;m=ya+*iF5K zDu7|bF-x3hER}c~eIZCDoC!eZ2s&1XRW(2Ub|hTDSX%|u8dUhWG!Y|;<+F=^?~s>a z(@xwS{>jAU_*UZ2?{mz`6Bu*oM zWBrqKwjaL|~-%s2Ovbn-Zs41vKqd*TGM>*cyACBjeYR@I1o6TCY#huaToV}P0-hR zrv-L&xf^f$2W7`!dN;^X$iq^jcMPjPx|lPCz?rWj6%Io$KKf{6K}MpUx0NN(LVv;8 zy>0q1NF0Zr#ypHK?360*m_bmu!Bkyf3-~CU?FgX6kjrH&4mLr>4%C_}XdjfTIr#`` zz_#rWgJaSOe|HL}>VtkEvLn~5=p)^&bmQ-$A|qlvS*SGI=x>-U(v`^kX0w$MEijZ! z!f!f$PH>XZJX7z*V6`-oG%34L@6@Ug>dvD7>*dnU>mZa+YblvFOTpF2(U82%EUQok zYg+jJZaNSdg!3UC9r>2)n@~Le$AZ97%~`YOMNqcpWa7*Z1zDZP?pA^Qm_TMTm-%-< zhSp;DAiKoNi0oQER9?44^X8zU;Nx|T;i#SPZR~n)hJq2@<9XI@_HEj-X8aS(k2fC{ zFhwq}BLbi6aiQm>&1036aoZvTs8#*J3pY}Uq*3ggY((iIVo0YemP2|-;=8#(^g4t3 zlYC@z^4DChy-ge!tzRE^gt`|=p)pxgT^kh(#k2QwNSGzsga17FJb)I zo+<3-NWR1=szO-H4*5U7W3QDciU0;c^`2WBEiUOr@~J}Vi(FXXVmkv-B_hxZqYtkk z@T`uv8iicf3z?2rS1L`h)(w+DJ|3@jyWF;?p!yI7olbI1tG?8y)sQRmw^^r`vY6Y*F& zM>VmYeC;0;TZ68gE#9MUw^wRqr{D?l1$*nCU)_L3afLNV>Wor#)`f6EyO!QaGWGALDkk5LF7(?knz7J}23}_(< zcV(El0={1-lm0w*%IzrKhPs`6{UZ$2u{8xJHdWqt-fh)E5-f1$N_5+l<(_t4TuRkj zuL*!cd|ahq2j1(0vk1 zqE%HABbNZMW~c5*a;SJ+;Nk2iUp6{?CPaavJ_$-NY@ZbLZm=CDV3rJs@}JlxiGxI6 z@M+S7?3s!7h=2sO{d{=om-VQ$3TNr%a zUmG&5(6t!TSD`V;6aiH5V07ya?8E$<8?{t&>3pAKc~hQd90_rIA02IP$jrbd(wIWb zWYa5T&0A~`I8y{se+be%<|F&%W?5zuE|XZ~T%I0!#W-2KL^b-B)N)3 zuR>yw<9>t-cE56ASO(l55hfr_Rr4TWlEd(Cg_CX7RFhKbEQCJlhEXh=iWJ_Tut#5^x9@KB-&;d9m6GSQc|V%O zZE(xF2#K|<7F^Lw!Fjul;Cc8Ozpcq!sVvo8RlQXUEpV{piMP zu^74G`#>%D^bzT!?(4?K`}%cvpxNmgVYBSa5aGAZjN_kmha{J8`;oWRcF3CeT#nC_ zeD04aEsfO0(`ig`T8%T9(*>e&s}R?aT%OPDK3q2?%Y%L_KeLO{8wvkd3iV_^u4NW0&K(MkudXIEZg^HI~K(XgN2_jU@apL&S=ljowSddy{#_ z)?e-uuv+aF^FmTAqBDkviS2fLz9!IW3zZY47*>Lkj025*hlaOhl%ILNbaS*TeRBtuFio z>}R|TN>6_D-7g(zp_%0$$23Wyi-+pavDy}OAxry_65%JnY_34mX8bhIve`+z~}f-m1QXvuMh!n<%=+{0~>2U4pD5+18O031TD^R>;XMS0VkAIRTRtG1BN zm1!neUH<5l$6vXr=*F>v8ml{Eq5ASgsK2mGySPE?!)|Qx>Kx8Q;R{H@Z1($WoIb0; zyH=-f)CR9S1(Pv?uUvm*($_vvc-fOwBl#ze-`Oe(^9B}13pqmQk&;{f2h;PST3V~ z4J#*z+=2$fI;O};%qg>eP5BdgTXQN>vbWj&=E)(~C=UUvcq+#<-f8CPd2zAz6=kx~ z!iEhV+RGcEMAHEp8D-n!C^b>72!tmkvl#M%G(qshdDa?@YE1r)4BBHlKvz(WEv~2e zlvnWpRv@1k2R=aiv@6PCjNTqB6qcTc2HufHbK3E2AKWxA$P6~EG_KQHm*&j=Y2QGehCjCy9;svsdPP=15A(}3e zgyYhTD8V#DMxK|la(pd5vkvLS=o_Z0ZIZ_*O+yUNoga5GdbN~qa}fcCL%$k%y=7ka z77iF8KMw!&j(A{O7BvhYp!zR)yD}G?z|^&WY<3v`9K@^Xl9Eokb{?vmB%L)iFuRo~ zKrsSAdeu6CWI^ubY^0_#=d7r~rtpOIz$Y$7{G zn}gCDbW%CZXQ{XQq8*cB7B%Wig2CVL%jszu1q3OeSK)|Y1#I0??4^&JD+bT{8~cr_o$;Qh()(+sW^%hJ?_2L8k}6~i(`-%?TY#Oa zi2FfouPT$P5(f%0!r*axM6SP9%iSuiIL_t?NsX4`nU4O#L8-mhVyBhrG?TdgdW*59 zHK6=KpTyhZFZSI~-n%P}evEMz4kbp`aWg@j|h!MA3 zikHsY-hM3f_z9Lezv`ZJ^Q#a|@~8seN@D)es5~?xMh}5SYV9_HoTlSQ??>4Vi>ZZ1 zjA*7<13!xWQHoE7tPOM6Fo2X+Nh6O<0RYKUqwQX$8uEX0)u{T>TWnnu<;gNT1Bj)n zCqI8Kuaus7^Y(YBST4xia86c;s5torvY#xJ%P=?}=dfbAJNQhzH4jC`Y~#HaKHr_? z&%cR0hDhoA_3q~xk8rK)w>#1^!w_jTVTqy)Rxrrr#a0EW9rNDP)v0;8Uev_{o)mI- z9z?TXXBcJ*g~?qeCL@t+dNpQP#DFun+r~@ypn=ss#{OA_wJSCj zY9%=4=p`3)klO7xyM&S;&bX zKTrgWYfd(PL;tmvMDz3Nn)ObV|1pD<46|;eLc4Z)Ss?~LR_Ia8a)ua61;PU2DgarJ zm!UoH%^2(sS|-My)e_n%^CLFshO>^E8^{8O(!CbGa0+o_h+^Zd2J7e&&EIHUn6HuUVbUjxOPi3pgxUAD_# zb?`<2M}Aie8yS>I=BDhX8W~^q<0({tTbyHI3+?McNBg@uiO>#fj=nxSvZ}c2@^3Ey zJ>Q~|inLWbSIbk~J2}=C$(Ozl>gYHu*IN`!lZs{s5=zSSWwY7rxaKiIs)$*SqdkM z6BGnyJg(l3A4UG3-VX@hE9?obo(8GA3Ox96U+!_f0lpkn$NCLT->|x`=c?;vJ%2T^ zL+rjCbiQV$HQ9&ztfGvm3{v!Z#2SoEBamLI20?wD%z-czZ@1SP>?oxY)umCVZ4~x^ zDAS%Ww}D_kYtEB(6*Sa{8Bs}04tt8OS5&v-%^6^eoK9~q*8myU^_T||j7gu{8Ym7z zUsrzN2H!}?uPJr2=Z1h?1*(;yq!)hJSRkfNj*jVc-o<7a)*3EgUA?~8C(x;ezaE4M zrls9GM{0PxufK}b*>y&~cK!Am+6=G~(#%L__u;l#t`Xz%>WzDiS_mz3YH3?1FBT<} z;Dq#xM4&miPS!K>3w<65cDtUX!euh5yB_a}L@(lhXr5tB$j|P*_>(36UoC)H%J>c# z+U-TYA~iU0`H+YtS~QorZpD?-Q2AXjmSwN z$k$*!D3o!V3%8Tm9647Xb3gbG)yJ79zYyjXrq?*P^PHm_eMK}YzTN21935fyOGE!*(RL^fuA4rt2C5XG}L}3ZQGvU z>LU~dhk?;f+q31_Tp#T{nL_3pzbRr>NzLEu3(uZIk=;!WBzm3IKA%-FY9Y3CeA9~w zc67>r(v{FiFo!Nd27h}EmKsrzG5z_`hGIW1?noBO!YH6vo4Pv3@3Ecr?3H3n;&U7G zaRaB|@5;DhyZ!j*Jh1Hm!wV7zrD=xVTFu8!p(c8KNlD>piKV|y{6((Lo`oj0c3GAr0da`(Qsj=0q`K{9)>F$|0bfwW_phEbo zg8ucQxZs#q#i&8|di^)t`t&D);#C2^2h|0`!HZ#Ig>B=8li>WSK}&cR>cB#y`4ZiR zTB)0ISYzJ!@dG4sY1uS?&Bb9H!hL?;^pF0yVbspi_1^<^en-g+|_)u>9i=6Oh ztL;yCo?&jf1jTa!>|WaDO?+{S!v2K#GFg{n9286&g!eZs!Ed?`D++FZcEu?0jm5uk zQcS$AspN^NC>q;X-tDJQ6_od)rS7Xu8zi+pR%+DzT>F#(;UUMQ z&v5T#)-hH`*m%*U7}Db})H}V`Ql?rdP1yE;q;NoA!72(+3i4F(s6hjlyuhCyOs5kS zxJvxq`zevW9i(;7<@oYF4~G(#cpDGM<&ep=K`UhZx6Xw(kwg2!&sUIIdtm=&JsVl+ zdY0B^GJZmh>|Ml9$Q8lhGk2IzV**2%UWwz&? z?DucvrEdUPv3AD;SuBrHl0ma01F$ZpXJBV2$V>3AzC$-0GZGe@^acO!?u={Q8zS7t z3s<}il7OYRxhOK_Ej$%^Wh_BWVR70E3*?FKvBHH3TBVRIf0I9s_Y((9a|Zmdl5onz z8o}!0(eY!}KLcT~7{8<-h7m;r9a~)SIP@G+U2i%Q2!{5~-;5zc;|4pDFJR26(D)tE z2{Kx~D6diH-sR8l3+`xSAT2Ger0#aKP1b_5jcr`D+I+aD*IuHfs*bPmV7JxNZ`Gi8 z7%LU7A($glOh01y370^bkG3V@ZTfmW?6erV@puGzF88^IvU1)~_cwR8Vq>(33& zUhA8+R<{k|Hd1JVz8`{qfsd+_{426tSu5a<&omSVM%bX7SIbfuW*6O!6u8TjQL}ZW z`Zu^1OQpU+1Kh(7@XC|LgdgLh0%J_I|AnOV(Sj*{Q4$0WEl~6aRaXI2zgfmk9rHwx`2R>xk&tx#vo$`lna@F)1+X; zR$L4uau}*L=NoGkstK$g@qfTHshV=nP=YF!5Il zRsVf%0ITTc@D8-4Mym>bIgIE|2Yg(_T(QtI*}t1XVF%-&cmF;D+e%E8l8X{H;Db$^ zluLkmRPk?=4Y1A201#4nxtTCUcJUN8C|z#@J_>fI#7XO6GXDi*Sw?rASr1wQ(5O6X z^G4WQX{WmU6%ZJVbCz?Cb1zSsS#Zaq2gv_BToW7=p$vM#H-n8{t%}(SCQO{#YD%W} zALLT(9{}N$^yeby_J2H#^S%R6s1hLt#Q(867XJ%K6YmU~_WPee;rMwi@_jdZ%KX@V&X8`kLddoxk_7B`HpyUfM8vj4*AXnae4QqxW z>QELR51+?%a2CH0?mXM>L{j9rfIEtsCdLRr6ae5WjHlO@ij06O6&(5|np}8fWIi5O z%}j4-Ox{vdip6J*w#7Y2YQ;QGI_-D9OiqXCWAz#GC>20_lf&XJ%|)%{vfEUe z1+OXgMw9dDGkKJ@ghQyb*(rsyr{4gq%1%)wZ*1kAx=NTU z4@7--&VU|-gvWj%by?Fpt$4;O3HZ!mH{GaQ1U<6v&|we&Hd|?J9uX5m5i2tU*!vw` z#^tm6z4zn{8O0HYG)L1XMphsF*%@SYT@{UC59AWWuhgzDaJ(`t0eJ|gj1J!iZ*jju zs{{zc(Rh6OjcKdRPRiw2lZxKW?$l~^F#0k`Elv+ex-IUhu4hXkfCSH-Hh-mp(J#xj zvJfk?tLZ(0;355$@ig`#EjH^CTE14dLOrnm2u0=l892vtnSb1ngl)H zl^BOM=tyNKDrR^NtI5k2aC}G3g+=dF)MpWgvTpPM*q+vd(qDNT5_#MR{t}Z*%*Kyd z9cMocVk6evpZ*#596sXCv7!8bn0m+XJl;22yRq#wP8v0~(b!I7+eu^FY;4=M?KHM+ z8}I!7$GeZczdxBIbI&|8_gdFFmsShILZycnv1Ui*)K(NaniAiO} zLJB-c!S1}hm1=Mubyx*vvfWl!>DBYVb;SsW0FqyDCg=-XNq1nNq;jJqMjE4K^zh3) z59Q#Jn*SS&pY!NE&C8is3$BunlS$&A=Se>^i`G#>Tr4`R`H(sp!5qcG@NnUs8V;ZR zl|rM@zwba(C5sl&;Z>Y3U1FfU?}GM%ey}v?{vhBxft(s z*C0C`jUTS?;}Seuw9d(|Fm{{3#S_o{6=e2Y(@Su04-$$1o|d=PZ2R`!?s*VShiaEj zAxCh!^u!wRZKL&12&-kf`B~G2mExaNnq1cJT&_8Z!xiY{@tYDO$`Q%C-0CjA9_;LNJV8Bj zNwtZOFQ;NUQxS}$uv%_OZ8Y~#`)LAQY9o%=2Ghq-If1!u0>$_Sq!XJcfLJ(WcXaJ9Ad_C zJ03I0q%)3_G>@pUmcl-`mvUd-c!^7ITMwans!yjj6B#;jiMpRLZJ`OGIo%~4*;0$P zVgK29UOFOOfJ$Gf1@8SD+Y+e3WZH6X%T9Oa;{U({CP^vF!y#0kfH^K;auF1wnM4^R z*e0Lrf2u*R({T(0!=XX-P)W_`r2TZ2{Xna3iGJDbvOp9-e+p}?Hd^Tt?ETKBbSB^2SUEF+ zk%QAqos<$3!uL>16HJ~fR}(=ZIBb(jy=t5Qauy$8NX(ALA1MI%Higm9F#92tDDV)X zk=^~iuJWTRwDV$KlW|B}IV`Z(S*(d?iNwsz1i@J+S(j{qmML zD7eG5)_|BD&2lN!vgb+|?NW~pny*kog<2^H_Mj4}M{mqHkSF&mjk!-nf{@hz8)V{e zjCTDDLkZVtSbTAX(Yw5~-}jwj#x4Tn9CIo?^E%^ zqx@%7mLpB>$aK|`{^Gvz9OCopA$-TX4D3BiBIz7XTumV{cuLIg(fIuO46R61Uvfc9A}wyJlx&j}ap51PwpIu_y()fPi(N6|j7hjwsaESq z0RW3;=>j`0f|mm|?I;r26kanzN4-}+9A_Y_ThZZ8A^#!ehMC6}(rrj{MpE6G;cIZ3Pg%nG;wR)B!G^BU?lBu!+Zf*u z4w`;+Gndt&fzakn>?#2K(-lxTELSRy&8TeC&{?VVqOeW<3JHjw?X59S?Wd=!THbYlDUEc}o^ZAl-0 z=Jk>AdGF&>{|ZUCc$DQOiZA!-Ugw^4osnXMgQl7D0=&q?s!Xl-hERADJ{}QH(@I|g zn1{C4mIi)Z6a3mPdSU9tD|z%cfDkn8^AWN|kfH(GzF6#N{siZIRHYsLur1<|{sEiQ zTK6@Rv%=WOEsK$&`$fc7v|U&!VyOyD1Irk{T)n@*MU#miJvGwmR%JMi%@?VMQE^kq zW$x0SpL(Jn>DTdiK0{Y-)r84ra#_=(-rnebecJahG0^{NxJpv*!K$5c6ToIvf&=X{ zNz-=9Qrk2cPs&r>k+rzByrS>A4?)5|e>f*5gr@Yo7iFZXLj%G`d|AD#iKfAM1Qh0L zMHnlMf4K-lu}zRL4^scm6;02MT6{0@PLA0o6%iOqj(MWABv5W{7?3l6d(1qfs{XK| zVwUTaEg(z5_V+|2nAeSyxO%s@AU~_g4LGi!7IX6yFqUI%%!i*Cw1a~d>l@F^%IURINTfatB>)}rA1nth`+pRP$)WDT$sr0a#)mxiW@ z<~av5`f`;R86(=a^VKh~-ZDgrb{Zjv;L$t1(B7_g!AlN3k0QzgX<<*woekVhR>fVO zj^57{etMHx%vHonezAH<&Ohn0gF&!<IDLF#j82VA+RgK3_DZapY5i?Kf%Dd^^9Z5(>&T!0?#n zO53)h@_4*dFXrbwQK_eBipCdQQ}$sP`Y#EHop-12*gp*gt|os4usA* zI_6-}DFy5rYto-~IT!K3uK*iXWLpYGvBD720Fo_hFZ=zO_W?yKN5DJgltJ@5;V^Q0 zt0pf656lsOs^D(JcU4XRK?Jt4zUk-@+S2>#&Q;5b#~Vs%=6~8m%bd%Gmb&;`ohL7# z0lq?MPAK|20&+hrD8k}7=Uqn{WybEOcM zt4h+}Z-i6;Y$z{g^5Vzdk07Gt6RH_VA{u`-cENO`>`AjLBo=uM5B;nFn0shTKBjsa z_18?1yn82q&*eaMA?twM4fO?* zG^KMdGa`s!xRJcdGo1wvyZ2v_JV#s>-8s{V!ugP&n<5K#95sF$q2H0KNdP^ffnbeN_+INPhm${)<+k^=Y&;~Q?j zY%7CbpcI4l0$X{DP*hr!TDJ*9GARjlSDON0FxC_%Sf-AE-tq5B5B(LXa$>x5Cjqxu zL$~dmTkJLfi$mH8AVj8iDfmHpvOvpVdrA?h{WX3cs9t8dlgCg0O09n^s@ppwCRfxz z{`)Pu*|w8WITb^HQ&3OdO!ploGzoDN=AoVbkA(N$+4)pv`)66?G3PdKhL@5ZZ!8d> zeVH#vLC7|e@pmo@4&a%fBT`MdcyhQ(_O#HR;JW8~{igMBmpeB}J0XZh?qx_WV!dS^ zD`q+)<{1=VmX3xs5xu!P^Ud9)Aoa2#W?35B?6%ei#k0IY70S))B?P>T5RAmLCP$lf z(qjhFvL42uT14@FABn*MTP-228iZpc7OD){s!%&C^UjfTF+&ey=E?vzDUriB=Bx^eGc9?bSJ(A1*7frsKFfJ`f-OcH#|7s5v-FFUBfj_7r__Fb-jMh^cG{Nnbi|a zba#PY>Amml{Untdy7UqiJq_{ZPp8d^y8W^AECnG9ORwt#hk!-1e_Plm z)w6^}x9W?=P^4)oGyDz_@sXCf4Td~|^sP%8Tlxm#cUqVN5$CX_>B++y!`l#6+^p_J z3B983rr#^1zh*)h>HcD6y1viHsk1B?;95OcI2*z|h77!nw&toGCrW)aDA_O=`Iq{nIn)Zb%zp5SVC zLrz{^JA|WGBz&%l%W}H6{S!1U?{~6`y%onUmL;xgukxk6dc7i* zqLhK6L{SOB7=#Ru;$OXml0W3yF@JGEI`kJ2AH*TFcSAy}R$q%etxq~U03|jMg;WeG zp7qqtZhA-hQtD?RzFGf^zwOGdTZC}t&Jm<{;Nb)hJQ4rP&0FcvH!#Ct#EXR-h&zHT z_K);i<0klK1!Tb#3tt=-@~(l0oBdg?*IA=y>hF}iopuQGNN;ZIy1Lz@9-9KgrLCd^ zP5pO~9tHn9lm78K%po@wSX7FEUeC9b)-9eD>deUd3Uj_h zrXI{ZeRk*&eIoPBC%3%gY3(nZh#Z$|iAq9Y%7Vrxc(YY$wVoyn+NP1O5)takW$g;) z$=9&SeMJZA>CHbu9`c$IH|RlX7l;fS1rTOci|@lEQajXF9Su>LSzEj&=(H3S#gx*f zuUgK7YotHb_;P~ZTwL=Mg=Fl7QPYJfUEz47Kc|etM<2G(5i35n{~XqV_6;@Thw{95 z4bQWp4^5?zzxox9No7GRk$2~p)9Cui=~a@)qX|XD4gC()O~{)={21oN%kP2X1rKEb z-8F%{HbiIE&0ZZ)2vO!n%MpStkb)0g>_F=Zqb;GnjcsuTAQb0|D=NAX-~%Cr8+ zfNjZW8gk0=uA_6hB0~tUo`)+x#4ih2tK!ZrTbzPCqR9P*I%iCH|7=X#y`fuireL%7 zhWKFa*6#2|A{kcPg*j=UOfWNtraUtBYfJZA9>1;r48$STkj>FsOeC-wVJeh1WA$TJ0@fnM^Qx@d{0o{lJ%1rd)}I(26n_b~3_2Mt;Ag+?cL@ zE!C1%=@daK`S0*_#+jaKAK1Y$_-zkYm>LRNHq3_J1q>!V%rdJL^=jQ3f>h%y$9U-y z&6wydj*Tr?rkop-A|qKF1dQ5!_K9R+2f6N76ROE;OzQ|YLW^5);jE>vj_$(<-VnL= z?&zrQ8!Px;aoctaerK~P>bI&Jd>|tyx7&z{JkZaYoh{t5A3c_g+P6@q{P8WPItw5& z(&dOw(ZJmiOe{iE!`vbyO*&VpaiEre_XRfJavB)&F zH_~?|(f{TH%9e@eEV>RQDB6aeP62&!?aN(&?urZzZZ^o-p53d9nDGzXLi=iRa{|2a8lu_f~vsCs9|rbt07 zpYf?9?o2fj+JU0Qw?_b!GO%?U*`=mNQp6LF_x^%5APuYP5$qAepHf*%o~e^8yA)&k z2M|`kAQKl}CTacMRb3l9(yTzDXm(*zL8DM+Nr_#_Yn{`ge}mIvEV@X+3Hol(4@W9l z9`3Ni@TVlv=BPVcCjX=Jd=QPvM82Ubpr}H*@{Gk0-NkKYh_hL0YFya;1cR#hxL@^) zIRJu_i6*)}EN4xO<*wB9Q7oRv0+|W=%?7LEHO+Jv+yv3I8#<7~uBjwhaq&d5Qw7ys z_F39kc~sfyx2QDG+&;Y|gx->J3ywy@XN_VaA+TDya4ek8>VOjwKA5Mnbm(T*e0>Xz zE-9F7zqI28;`f?+25oX?Go1JxjN}qQJXdK(c?p#(IdMAC3!zePH9|S7nCFcO{om5d ze%N<85B%3n5`2Zp%sxXR&tYJ)nU*$d1?rF;CSG|)+9PXE`gS-v)9eR7 z>udOc-f1&z@i`uc-H4?BpZ1|%NqBv+=4$&oED?DLt@PI53~nTPjfpcI(BH9kN&p|^ zH4f9}OEIL}oBV!pf&1=-A^Us%mF$}dr>+`j;+(mOTm8noR({p@fA^Doei<*Q_14TW zFP=cG3zmZMDqo3!X5wS1+h>4~EZ%Guf+A^d7nj|3 z??rgf!IoKJt4hn6o7OaM{MLiYPOGZVBx<+9rmH^!qkkeUtIQ+?Exx?gyhL6wE6MX$ zknHu--k`L|^VsvB_23uAQVWdP`ulA?B((GwhZ{IaWQu?jG2{jC2~aewj6nTaQ2X$E zt8!obPzT5qpvn#Mz>Hm?maR zK!WY-$h4Bc08+cfl}e^++DhrF7^(*cRTfpMA zegKC{hKAThz8oK1U4hYf1@!&ZTbVIrHnXj_a54-mBr{F#0x-*yh*2L_n^Rkw3l2ia z)6#9cnKigWN^&8GCCyJ7C+1l|;+Hp1{GU-NfR5}t$MwsaOu1~JvfU)y`{`qh@?JPC z5(2yi4+#{Kf{a}4r>O6MutVjbUNu^gh%~&vEjo)F;pZ`LVeLR5mKl9*OC6#)*b=Dp z{YVLkFm?VW=Sef*Z5p|OGwggjG^H(G*6R9`+$@*PN53`^C4iqLtpqSo&q#KTIO0vG zM5K_Zj}kZOsYoDZ0~xru5~45B$h9N!k2;?l`La=(eibnFY5(Q>pRvB}`;FYPrxBm!;(ZD3k0aFaHccKBMCk48eYf%S(-ooKgE;Xi5eLN?K>tmW62w$@h!4NI{0r|% z*MR@f{>?JY3h3q#m;I=u|Hu?KbUgjWZWQVMLpN^^rWK2!C51NQTP`K5cAx0^S}xb{ z0b2jKdbT@qsaii}ie((nKM}wrcf6TatbEg4LKNtDm82ibqUFZt_Rd(WT8p(=CaQwT zJBR!UU@pRO<6r~zYnF&!GEinB9=Nh6pG#9eUPij6vA&(SIr? z+};>OzoXUU<>p4S>6-0Ur(Hr%q&&Pjg>6aCL$wCb8RQIsQ;I z5!0g+7U1@AcsOPCDW1F6B7&c5xS^4M$#8>9Fh{cVr&X)rnA5g5>FyF=XXvFwr8KGJ zV&aYarS_^=VNE$+-iAe|9J*WAnyf@AJE+{S0GO~dCv&DN{Cl8pTMYfE5@_JQv^t8l zG!$}KdDRqhVJmbd;P8f+9YkEgBQt7?B=wU2J2w0OJ+?n28C5Cl!9?QR&6K}dZ!3e( zCujn_t`3*;c}pynSb+h1t@Oz(;84ZYwOpReqnHW3YDU&&@KZUCBfsD3-iLL2oP17cmv^A8aS3(|zp}?_BEDhX^M>(l zbQ6x!Nob!$3KUT&A`z??i}A$nd#1%--i^O4R<1dI?SPTXzEJ9JdSdpD#gVqp%5L=H z3SiL(zx&G_y(Jw^su94ZaSy)8J)uagnNdFsf03>`2XP0 z)G%j0l^UI@2;cbKzqAt}O)u2zkIDp{u6sUB6b`EIBeK0pW*Nkz@Y(yIX$TrqDzn+(lt8=S^5!NoK>3S|67QJ?hhFt60@ z0R)9H&3IXA?AQJo_Q){6F1fSo8BTs>-;zbJyr7$yI-PAr^Qov&--rcf`mXcJ{zRc4 zX-hL5&vaGx{hI)h#-dk0+^J6jm{`?a>r%$t?&sJtpU!FO1FKiFt)vU3+M4(P=T^D$ zWuZj@%mP5SNdobPrZy;5kWIhf@6%4kT?ELGv@Nmn_3U4m zaOfk`VwY^SS*uS!RXI21>N{Gm&R)aOsiXnbNXvNe>g9By{C>TDy2R<9qgzVnlI`;G z1KrG#Qb1IdkZn1|?|cFtVu(7xHyO69P$`FWx|mfzP_MCL1lZn67iV9vSaiblPp6~x zfl|k0je~!9`lo+&nTIJT=vX2?)p5kzDa{n0Fq_;lZ;Hw|_dpGOeZJV5V6MdIgEM*I zm6pF3w)lL3a5?N#TJI6APHnU=+%#Epn@w+a212R9VSYu@|4wpPh9vUh`)M76$2*jK z#`Fj9{I|X2N)>olBzuU=lTY!A1jYee`hpExe?@pQ9ht|NDn7@1GVRn0idWPql*#W_ z33S+DDn({jd7nilOotNMTM2urkGZA2d4E1r#EucDsG^G2d_MCxqyjl!8E7il`9-F@0 z8>X{HXrSsM13)KEumOux+U*NnFFY$(Fih|S%P~OF`uT!xLV)N^)Q%8k*!0?udCQrD zvs-DE26bOnH}bGPH)P{=xd~qcRZnd~ayPTmo)n+~XDmQ?2k+Xo$c_2a*P^)I-Ku|Z zDF1H)7~0$UO6C@bN%rJ>3FsWQ`qU05!E!hKL35mYMnD0EXbL`0;FgRtY7pDM zVnNUB#4kF+?|AsdA_jPV($#UGpU-V=z)>fK_MO2lp5=r_d{dHv6y z;>mP{F``1OxB*|ic#fIfH8)@`uRF;SjMX`3pM!IeqfcLdnE}#|nvW>H@lL4jpA- zx-!nxxXk9j#GyaB2c7xv*Quk;e@>psVU-E zDrvEzA=WmQ6@mB44g_Lwbni~@2h>>i?qO8AyI?*%rG1LIT?pa;!8tBGn!VlC z^EHGXtLc#jh?}k`UW~g^<6AqsgHmPPSDkNc*-?MUd>*+nqH{+rmUFu1s1hOLcftTW zD+}oWya62*epLg(zHdpb7$oc)typ8E(mT4U2e2^s`Fjw=cC+Oko zEI3bG+AFGpyz@17GeGj&lQKEXbN=`y=>UWfvV5r`-$n1QY4`HHI3>2<1fcQ>vqGVM z4vzdAn~wp1UqneqT$PTskBbZukVY=$Ie$_}u^twAh6B;vmTxsN&HmxzpUg-g{tO_f z?1juTas+#&=+NB&ocYFHPqds{x#@l3q12CrCPUsU)yKphB8XCzdh%}H#j=mr3SvLs zYu}meGele@nF3Ta>KpZBNDwerjS4bkK#VmY)e!|l z&rC$d4Ux}WeczX}-9jl|ku;>dl zDl$Q8>D9+B;J}XDpXG9^We<6uzx@(0U?rY$;Ts(KHjz1(C7Qi`CWXtp4aA`j4i#pv_7Z<0fThz1LRZ7mFyLa-Kxi)b*Jp;@krpUi6 z$){T9&?!0Gz%!sIGIuh}Y{RuX9DqlN>k~Sh-kTeLTJ{)8`GAmgwjJ<4%-aiyWzCP} z_KV?_3m91~^G+KE7oXDhc;R4J!7kp! z%%k{mX)EMJ-M}y`gMiQ0*A6$e8f{h_&<+7%96j%aXbcBrZm|$tpm?A(`UXXlWA2+W zav7aS0?p)x5%1?Kptj=W8N=CM_s^an{zk?KQt0+=dysSH`w7g4qC+0J^L(>JleeHF z2mtN-jz0SEwZ?tLPZi#|we;Vvv4)1oJ{jKMpVA)$WYCv0g3~Yj#};9-|ot5 zYVXE18V04m7aCh$Iy7&e<}Wi%yHrBUz?;{S)x-R~^R(=GruONZ`=qp-lT(nKlZ)3` zI&7&b+)dU>F_1vZLmVq`?|@CV*6BM6Wsi&#Eu4#PbES>vr6(sNM^9br6ap|WjHpo13Sc|9&%0e`;)?R<8tNF5?;6@vUia`O%-_6k6rtU~338upJ zpHa9Xs+g7Qp2x*TPW$L^BU8@Wn1?ILy4GX;V}w{1Jh|2v3aZ+@!2Pp`rUG(!PsL z1sAK~fPIdrfDkoo#*8MdTv!xt2lD{GN#`XT<#)#Lx0>Ns+5vmf5aPH3I7oe7fI^=M zShEp1Ir+NEEDxTHRGC*0o$@=qr6MU zu~0tilZ3y^jmuEK82X`6`bymDP4tVk+!0BU`SR3l96M>c2hPIAt-Q}X7xE5TPeVI| z-H3^!d3A^twg>x9yUR;T-+Q^#F*w4BYJTxlxT*`esyUr63li4jvN^MGhetGi_i(A@ zUa8T~e^Q(d{s^w(f$H9sF&dzRBW2JcQ-t74P@v3G!2Xp_x5KZ)_g_tU+WjV!zR2-C zEoux^-#+z%M8|nw`px8ZG{GZMFC{vtCm5-L@FgH*B^^9WmtU$qA*<$z$H%|P9iF!>%)f^%fVZ;@hQSWLczukKU9*;wyJxzz2J}+yR zZ9S(CvVVSZ+$Xt%1z!YN05m}VN1z5s3^vg7UV@K6O$nW-tE=BcwEL`lP+QCl=?NiI z2D0Kna+1=bDx_a7t(p_Is&98?9jK3-f8f*kS+vBT&vk8;0p6V~M)I(D zzyk;|3mZZ*7FIf#5l}J2k-Ekfi>@S%{*u4oRUbyFyRh?De-##@6s3EFiI01?eXd%P zmEMk{j1mxVdD_K1DGh+J_I)EWV3;1*gUCgPLhQJEcRavIcB}nkH&KFEmwFOHh^usx z+JEi!tkVB0-N0(6hP2&%|61}zPZ`GIb*Z}}ha{KYpuUH}W~EJr0u?C&0z+6lMA&ND z(d0#=ovzKU<-Lx0^pO(`B2FBA!J*pJVF0bY3E>^Rf z&_P{*kcHuLzvT5RW@`3~h6hpIscHA=Y z)AgT2Tj24`ZlUDaG&o3t1)+vUiW=1RuJXg=7Q=t7yi!M|;j%0FbN->0{GGusnV7;b zvAg~e;OLp1YJ;PwyZq~Z1T%y!aP{o~`LIQyYf==-vy>3V$32?GxJ{`t=ja%6oTnEl^#rpFR7 zqgMuu*c2ux&K~Pn4EYSKLje^9WPJ=T+=0D(_DQk0w|M0=)7 zoq-um(AB)_qsbv)MB^qVe+R$Q%d_}nvvRxjps@#wVSEMlL&R-ugTk z$Z0n7ZBp1D$>zQ3CqKPBnWQ%>=o2gCfK@BVj)ZB)$+Viih6vv@+=Eem}M3maw(R zkR+@*TPKcm8mOX`(`IuF{Tx82^Qq~sEoAt-Te#s@vD$6CNXOaonAKot`Rej8s3YWY z6<|JM48!o*^zf;3e@wMsB|s$4n!#~?h93%h4p@&_5aFol__{)R=sZV)9Q!k6gV=$D zN2;Pt`nT1+Or&wREFDANyZl%*N*sT=&R-tl&4@dk$e?cJhmO9_$XEV%7Gz~ z^||N!0m}1V@pZx8mz47*sfr5Vp=}yjTd`sL9ZBi&iGO1LUtd6%|(SAUG(+9a93 zCX1W{Ht9i79P}v#5SUE6jy`HZuI#_3%u{{a9j^wf4(X*prct=8C4|lAR~7kDAl?*k zx}!m^CiGY5fJ{OTJI66rYOTK52RWTup7^fb!Hr>-w1 z%IVyuU6pA=n9ftGXSmh>*eR1LPH zX>B%u^)iBh`m-0Kig;IN@j&hLyp3WF9bTMC+;PShx?^oFk^0!tLmK%}ptfL=CjY$( zh0(pX;`5z;M0&}1Y^}b10IzN98#r`hk6MjS$_EqNNScxa!LIqW=BgFrNgQ4gDojMj>7?PxkqAY1dI?l=U@9W$RGBAUC5Q zN+#593O`Xa5il-w!isFg3aiUHl;3=Z3H(Cb=;U>OL};sAjLp9|*1%W_k*<8?DbcU` zEPVS$r!65Ys633A_Oe1Xt;%#2I21L#Xu(I$g`JusqNCQCDp`ym5){NtQ6@i%YQ>+opuYy_8>dT>ap#LTWo8kH#<+ln6C#eB#!uQIqjvU0$5$Aa9ynIYE zQu@iNzge`h_~hZx8^EA|^yv=Eh1|muqhcw^QPm%44sblsMmP{2)s?O3f$cd(EBz9y zHuZDds3qpVFI00~HFE8Hc%nq*4#KK^BD;`yL&AP=f(PNkgU#CK*hw_%B+eYB=8VqX z-ck#l+U#Lq3nV`kDS653g#E($yx3DQWD#SEEz^X0h_{jLp!cysm&Iz!zqJc9(AWJy zpMBJ>yFh&GwO&OJ-Ov`=upopW|*AB#!)$#W@-$6uNj z3X6mxmIC5VzHKZt0|;)X>Fwmg`?4g7VG54M|NSqBeye`pq7|Puy~MQS9L}k>zP5!f za^$()4>Vvv)eQ>*PgH|Q%uh)et+#vrgpC=)rA!+5sC3k;ktwLNqrjcF85V%*+lL{7 zg!l^O$dU?Brt*2YkMjA@HuC0yAlTq|bziY%)&02M zlMBD_n{p(Pr|_6@#=LqA-py&WcsT8$&FHfuS>^Sxz;r&TaQQ||w-9;dJ+sm-0Y9wM z=`K#@S=g0&lZo|{F@4W&qon)+k(|S^HflQc7qBiZR1SWjT8N|vl$_wpr$+Y=OQ#Ww z71|UY?jlc(us_3OObNa1A|K}mGF?`Wbc2nZPJolugA?3S7(lPu@+s83;V_5O4I$a? zY`q|aw0>j_i9~n4UF$l^gjil6T8DGDOhFi5IX884+hn;kWmxd~bXDv=x@a{sk!|9p zk5R{o2nMNDa%M@zoyZ|7DHM13J326$8cSk+N63bB*GMeB(nF22t`Nje1x>#IQkz8p zL)nVDQ@2l=!vT6gXdBe+UwT*~Liw5Gdq&%8wX5N1YuT&Jwy~H3_+{stY)lyF_g}X) zZs0*Bz>hIbj~TljFc@H?H&R<(OFHJK8fHH+R7wbYfDw2Xt> zosiRA*|tLh{jUByE4odGV8{4>w_IowPCm8)$emkoj+h9 z*T%44hs&!+2^yg$w_3Vec@Y2my1KBsJ;$c<0|mQ!tqY0GmK8@|qSb6J|N9r!7R$z_ z46`o6y;wH$-c}8H+UxDHv{JLFwDWeniEiK0(V29iDJSZbh&zBC)nr0WyuiW$4%>&@ zV(;q(4y)|DZHo^3$82x%fN?>~%?fZe57zuK4dZjx{ojrA4Lml`^JZZQ5nj-j_X*y5 zxrNc3Jlt}{0rD4WA|;xLH#=fZtom5m(q`@6FsNpm&4(x>)A}x>f|38f722`_R?Eeb z{*ZtLJFDv!#k}6j)y_4;$QEJ%#8B2`vsT7tyK-K*hCzrmDoGc?bkTIUdJ~TElUJG> zHXkAdAxwjThQ2qJL;&xqq(ZgiH{sI5hjDfR?39>C|qXe1;Vgq8)qE-her%cO;$js z$5Y`ve5*AJK93`1;aPbb^m}dML6`KQ+f8x=E!Ndgjp=N5H{0j*swM*DF#pQMO8svP zEUb`SaI{8s$9%7!@TfAP@Iy=Cz04l_5GeWx&X~!kqd;Ri^fF^if$k|7bWftljOOd^<55`~sw~syjfP^iug`$; zJ})6InvMGwIMrr!!o=w#tj%*wvXaU>CSZ@`^L%6Kz@JpE@H<8xTW$4&%eg{pEDKog z4a`a=KT_e3r;R_wHr10xSzJzvl{)pRUY~>aDIT0_)(|g_6wYwLu35_#Cjp~` zr5|sG);s6+d+*o!zbWDM5csY--nyI(%xEJ6WMcRqYo7jl#Sx!q?%e#U3Fv+wzH`?a zdD{T?BAPb17o}1yhq2NO>zdpmuTdXUtiO?x-xW$(seR_5>U}cN)I{o@rqO0Yj9v#j zJ%=xvDd%w@3Fl&g{Pr0T!CHDZdh%#0nW=7n#MR#>{aB@in`GZiJJxoXi((%UUKYyQ zIxf$;`T29Lklg3q{wGydO+2=wbuc(AS_$<9 zY}Kj}FVHQ<$dFn%7K8&{(@m%G-|tmjX`fM?DkoS&H&fg;5fc1zS=C=3-Jf}LEw-O8 ztLcnKA3nQLU~XrO}34!X{9J}B=J{B(VBwnp&REFBihiDaW5*Gel6*71CgKE1y7 zwzwGNM=QUPrw6KwrmyRmvtoGeeV?+ytgL0SUA-x~?sO(zwBF)7#EE(do?DFwHvfXp z^S0RLeb$H7AreMUJKYJKQ?FU;4s~Yy9bsvTWqu>1w-5?|L|_SF>;}3m?wY{*^iWT7 zWspXt>NJWbW%5sJ1qV)4x(y;ivc8&S$wtXc(ES78H7=&F;u=rlk zh*dZCvI)vvf}2w*tAfH#=GvS2Y?Biwn{IDCc3MqY?kt%V=BEo{!1|Uc2o@reYuI)k zU{t-yd$;)C+@s66Y;Tv!Ya*;@tUJ%5H4Sx^_j}V%1aHFqQMv?I4VV=&LRwpPZ^!4i zr66zEgB4qS$}F0{cqTw2(E0gTz&(f8J$~n~4BfYfiKnKdAfOq$_%Z>vOiNaSHF-Es zhEO>3=ZQT|oczn1adUv-pUs9fS!TC06`I(QyJb?O)6csM++9v%cqpx9U7n4h0S1Ml zj=a8KAM2@>6Z9rfF+83=+wI@1VvCTf_24I1!`@By2ukUtrFob*f({tfLNY0MH#zJ+ z{obxr^vw6up4-UWoKs@8j_RwCl_kkL1JYSW?VoGn() zpDtK-p2hlOJCTs+s|x)&n*6=>#h_%3UTQ2>%g8_-`%9g3QnzNN9h315SkyZLgUeh9 z#jELhp9N}TXYC_D6VOvYAKbLx(3;qHjB_RYC9bRvqjV+B7%c)jr+)sN63UTGFIo@C zdElaMqfy^qlBcqEwhxrVa1 zbEESHm)Dm(JLI(Jf^VDK<~sxzl5XiH{~5cLbc?Plh12nj;8K_o20UYr3Gs?DCI}DO zeW_3P-2e63IG_3@f++bBxZ?bLP2 zz1(26@T)e=hAY9WyB9-K3R($q)xxaD7mj*J=v?PubCpuO(pSQ-Fw+TUDlR;DkR zX0^V+VV-?*d!i|_0Bfi%16!%Ps6;j5q>*Wg`+JSWsz?2WnZM)_8)63>C zY1L0tC+{&;sudz`5xI%)7}0IyxVPKK**xr)g3@V;@&% z4asJa4WX-iDl`hc|DIvd>g3^uYG7cn&8tdtV*(rz=N3QxLxKxuaB2S*7Zt^gsd=Po zB^Lj^G_Cx)DD9Cd*#GK@h{9903GH8hh{BlX83~F}@=Qioa~D}4xUulJ3Ml1G+->R% z-_8I7k{_Pd^8{%})CKb=P~OgTULoU@fLMWM!4(SSsLoq|p+j*)PXl?vG=ZpY)s?gX zC^p_)PHzN(H^XQq;wYx-<=#i-H)TjJ()G=du z$B(ZzlJ;lKE#;B!XXPy{Yb+QBonl@`mzMCzPz}?|a6)cmPz_HijYA+!H+EEV^G9m9 z=RN%_Cu1FL)2fV#k6P2I>&fC~yLZmqYsxoR5}~G;#OWG zN}h*Ly_e!byb{mcgaCar8UWdaRMkeP*gOMnoN&n$!IH zy|-0WK*gOzn+>Ra3@>Gt0Ns5`+uM}3QX45v@3oIOHzDw3RL(A`AAyyzTl zlkLkOZEX0*KlTKh;&>*;Tf_1dR=zs4=BOL~k7GuxY_p7t_l-W4CHkcgqK1tqSNSBl zb$#L7b>+@~BTw%qYIcOtR&nHGN`AX<>9C@FjM3i~IG>!lLH)^6C*DW|Q-9qnGzA>R zK7Y19XR1-S(8WAI5_#Bsp28dt?N34sncvqm5Sz`fGwI16u}p%A`Cx zZs)fOa=n1`Z*7)KmE`;Y3N-q#u>E+h0QAiX~({yRhew9xF>=^4%mGH+|AH1 z9+y!Itp?}^&1-b1h=hkuobhi<NNVts&_E2_c2n!gC@y_48>&Q4v|mbGE;wASnmuFn ztJT4-_4gwyZCskJccqET!XJrMX=$gUDTI;4muoSi@bIpz&l~-kI(!Fpf-j1A({0U9 z2jz*v9=XzRh2r&nfHM??eqgyqFH~_E$&Mwy<|gq)D^!ks{pYK%bkA^YNAJWf!KB+n z2NdE`E4xN)L6}I6JmHEd46T<8dR$k&0ebe>g)m6U=1*6k6jqf^@ljD=J%TX*#6@UC zwj-Lm)?7ZJkVkV5FEKOw+mH2m)Z6RySKKX8qQlc7=xyWN*`+p>-Z7ng6=`>%L`sD1 zd^Jn8)*}BxBR`htFghIiPD6(%QHZH-1e2BBZH$~QQP>nV&i?TgYa@&fDo=Ji!SGj2 zAWJC-#m`9RhAl-PY1VQ&F?sjPQFFW2qA||K5k_W ze-trJr|ncP{;^$^TK0|6m$US&s<*BZkY(@*$-;fKm0XN26;joERzFDi2L|Mo!-EB%7QJk*0gsxkk5+ z`(yQ0cQGfCw>4apzZtU`*@57w$#pQ^lA0a$8H;Wx%h;{feJ}XBc#X0TEE)d_g@xgTKtVx41Z|!sZYHsH6>-A#AUGl%^LON3gF&9Z zpDi=^3&Wa~>!0Pv4s8qCg=TX}*}8RQiN7t`9#2`LNq$;eJt%*{*agyB4NJ1=93Y*m z=%ezXeYRxpITW$Quw^cH?6;f<Av!jR#z1Zr7v^hIqb|SU8L!Nmdd~ z{UtMICBs-A_2y72%Sj}au6yeTKkg#XP&F9JJMB5nRQiQ3 zKtqky;)4Qw2<4qL*{P@ncmbFOJRrwv@(U&9+nm87gkp7L8poW0HdNy+u)k z36GC{!@08NZTkzvNa#vO^=21(LrmtE6OKobE z!c3_K;;^FDg4a9U9bbl7IV1tCD1v!$lfrD319hWne5^@kuhMZNU-qgKa;kZbHSfxqaSEhFUz+no82&n6iselOSJPv9cn^39&^q!>X3_)7d{Y9AwB zvMo6%i!nM#`b@o>S82i`ch5GjcGr1sSXHikn)2-%STmI2{hv4LoL(YlvFMF0D3!dm z`jA3Aa!FRiY0??i#TW5TpUW`WC5KAA&1H`g3J zMxJptR*obZCWl(XdyzI%we?B5|LxnC)&v-B@R^o^ysVeswG6hWFR1-j*YfRKuDSU% z{Kf4x?~jb=dTG2i+gfWrjphV!hn|wt%eirMj`~}*4)lZ9(Ukgolog`I<(-cp1S>?- z5f$F=^+=xlxeWZ1{o9t6hJB1C1qr^06cJUDYTA^n=#pZpc1Gef0=@c}U_QoZ*nyH} zwvbbfxW4chMKDd+RwDS~#kElMjMpDK2hdy6E_euEn{vYazS|E4Qr#YqtdmCCS_{vG zFYPUMGmlqcSrRIqARA2WC6FoP-GA++hM5%zgb&F(5d|>?iIObVcnGtO-YeB;CM~tZ zAGSd>jbGx4E~BRLP)*sqf?1W!;tXB;?K+cD{ zTh)K4V||)w=+(H zP43O;$H5$})oDtiXVOdS_YkgN13O^`N?Dib8zTZuYBt;24(d?GcPl*R#Bo?RN7Hm* zW~4GmO!qV{>Z*v9pb?hDuDi{yH%-e#)(PUr4>Z!cdN*h$fK;d+bUyehb=Bqcj_=y3 zivzAVA)jk*PC|A31%_7DVw9RdApmv9jrO(3fCk^5H(xk<=HP1fCxctq^fj>1xx&E< zDyRE+`7c33-_S*8^59M}^t##t$1(~p{yK-ogGW~TYqIb7qowa}>sl;_$kL~+BC#-S ziUut7GL(W>E= zM&MD>5h{$=`{M5q55G6_9W6-UOmyvTd3Npc|c4mh8P2rbgovP-s zWO~t$+sfvP?9nJbGMMPt3$Y%*^uBgic&R3TmB}v0zb;cdOHi)Y1MZUS$@~wiXo>d3 zB1Q;ew12yyb|G%(WRpL^iXw=7RHIMxcZeur_!umP-M-Qg3hIT z=?V6uf4He{)w2}j3X$|7eW@X>dOtjD5k5O8^A^@^?H^o}KHDYh5aYF$EEn(a($Dwt%vd_bw%10- zlE4Y(ov))Qgx+#CYP|`kU5*_3{y}4RH1!k2p!88=KfovcmrBDz`}yZN;!$OB`#((P zf2hWWFh5f`a`R_{f#3u6_`gfvNEea5b=CYg755tNbEL)sx%L#>zlgV@$B(yaw6Ulg zS;?PRVmv|F+a1e|7vh*x_`>%1mi(W4`Zq*Be8&}9Nr|h~Z zZlE9NGn^lgwmJqpx4%%p!vyxewWuO{`dsfD)R13+A2Q9AmnPYctC)IKKU?c9qtI|U zUTlfOk4%FhGn{^N%U+%L!sse@HgJ$Jn#HDLseBLofs$^ebE?T<`2Z&wsXAvozHq|u zm51wK&8BjZ?fyb>zDb>vudZ^INa5XuY2uaR)$2Tr!}IWg5ab!`PuqIT1i%UuxVCe( zPrrTO1z3ro1lCLnJ(+b&MQH-45xpK`F;wDZK53^BIzO2&Z-*LO*wtP~HyiLiPcRSV z0qU=cd@=+F=y#SBmc0(@hYiISfJ0@A-t*46l~fL(p#XV?@(j6Snt_IyUL=^+)$B?s;WXG zSHn`ZN5s`dJWIG&AMAlfKF2LsYBnA9MKsxM_{2n$%PO&|tBW?sG9rPTHX`o1FPTvZ z$F^^?(3gvf+4?H_O=nA3|Gf8>Ew@5!Un|N?u{I8S-*n5pa(u~eE63>e-51s)75>P% zeC1qEV>Ka{J!VX0f*J#QF@fCK$+GvsNFd394gpLXPc_m7Y&GU;Q4>KeKsp)m!}R$A z3cUpvF*J$PjjZNGr19Hm-c}*QFiN5_2FBwB z)MzEaAWBc8$N+TzlzE@j+jJfF$S0U;14--*{K}{MbGoH3t%gUxZwMI@s1}n*hns30 z%O`PYi{J6dmtJ`1T64s+m`ehNa)d0u@s(YYtaW!fQmzk@!UV@AOLIumdEK%A2jD^t zU!9Guy0P20LlZxL6zmGvjh!BAPUlwjfZIg;M$>9`5$(Yd6Adn86PxV1)jC^?UI!;| zwg_TQyuLn5ohQNTsL=SnI+tB7&z$#Z8if4#&(5%6cB!&nUExcJ;g*{sk{{1wqPNWHAL|g^2@;h5UdM?(cT~o7Dxsn&r$eOvjIJ; zO&;`qn$?@%8(JaZQIuX%O_LHyClie{P2q$Sk32DEZN4|o6WffCJ!nwXwm~QW3lUK> zrN_>iuH1Bd)>b{-5}x|94l+|j>9tM+!zJ97C16C!!<6p-GD#o=X?K@+okUJtmLTh1uo>%zYKmo_dY|ZY((CdY7xgKzu-0UoBxo1n* z`@_YdIJtZs7n?z{7%r4SLRfiLH@v37Fe_3GO?)dL*9vd|@@(~Jx*~h4cFk7R+TBcF zm5$)B48s=VKu^0Hbw@E}_-C$j)qWrtd^p=#(A7pGxS1s*I7x|n#8CkGN_rk-k>`1i z%*}h90jm(zt|mU{1tz!G9N0|~2fnL!*jAB1vG?b+trcSza8qN0-WJ?I80DDyr(V;} zNQegN6n#@HDUIrL`ZLl7V(f==0v&4fg^{GUb(sojP#7?G?7Foh=EkO`ysCL(n1#s^ zo%y~kK5+^8n)1`XF02y4q&EsLJ(MydNdYH@MZjwq%Y;#F!uLxYjfUURgx_>bHc_xp zcr{~aTo>`_cN$0oCV}}_>wTu|Veyf246iK9t;syjra;?rJ9)r8U>PIA*uO65yj_uG zO^YRIZLVJ1Q|EPVXW+uye7$Izqd*%?Smk@GsL#JAml=em`RfPoRK4NDPJ2eZ3@V)E z)j}+)F>*x?W^?3pdmddLRqZg%mNy$h@o(WQ%iuFp4;5q`;!&$ee8 zP*7d{iuq&Wez@Eh2)`PuZE&I02(`)E7MrQ8)+?}Hi;pQPU2e6gIxZb5$Gc9c{`DA9 zlK7h!!%@U*YeNAmtWmj3#he9^MPsoeG$dBEuBHWjX?#|z`X&>_1`=KGDlbf&%+X2$ zw_E)KXWhkm?bw)oRnnFwqebQ|0l@`PpK+GZ=jFE}=Cf#-*YB#mC^dU7Dk-9~EfmvH z7Z15cpcpS2-$?iSt@uzpaY1>AU@-qd>DPBR$9}c`B-|qH3f!v3Dv-$VAIhn>bL7Do zgDTk|BeDS5HUbVx65Xr?FB1}ymbMC(K+*XC=EPcB3N8&+WIxyJE7tdt0+PmK7ou8} zKaMNM2an8DHAO$)H?^ZpOtB8z={K^9;bw(Rdot|SOqE!vyX1o^h(rCoKviZ)oGV2l zLr6UJFGk~(b~NdH&0r~>SIWOmirU|ya330P0MAeh!^MQEjB34iw-<5*6o-!_IFQCyVLD=HTj-(Lyi25SP$xVv0*yzCx|kHi`xbI*Cj~_PF6&^XEFc< z#GF>+V!xL1XjPxW;%IS>%=FQ(oBo!U`*dbOiXdnQWc3s^FAVogZhFB8Y@5P78ybbp z-Hc6%nKVnU=Gx$~x{_iyv!h2<4%C~MJE(oLeRp0j%e#fsZ7eaq^R;pEAsPvyWJncl zR+RJe)3K-N;L)L#7rfxu&esG<2RrX9%RA50N{~P*;OfB6rxh=L1=qPw)zf|LX&cCb zPB)PTtqtiMs3uKyLI&>~7}=vfS6> zo#_4EIHO?clEz$k6#hg74R=)z$5|e?d(-Kmn@`u$I6fI`zet+Mkxx1P4j!oaWVH%E zXQf^4qb*L2;}N+6bOhy!gcz=xj71Trz>U69v%jpefxj}(I1z^gmhac* zI!w7h7+;M*P}F}COKyzk3w}n1Tf7!3-z4g#rqDh zS>7K)f?E^6f{%&A8(!an)X)VO!yuamgTQJ@+#mDTZgf52(BjTd7M|oJvu~*4Oeqj)^|mbHq2R zKT&=Vi!Ztc_faO>i}}zdjasVbU&gCneYMs_=aBR3X*_JuM-Gj{y3tQ|@?CZ(i-C^R zqhIwld@+ZP>>!-aRuf{XnZYL2l4o&Mxnf5cj2GtlUP9K=H2~FugzlC{^)<)UFezCx}fn&x8-&j>WuS+&ed?QCz9ik8EP}=oNrwZr39Q-KW zlNIM{6MS?5$gLS>Jv25fc~(k$&S=X4N_3hzldBI2hm)D8VbcmPh$-clf_e!y<_=Y5 zZmUn-X0kTphx4?oe;1CA3S?ngaS|&6Y~oD2d2L;0ls;}&Y{r8^+tqR26f%zHLlU%a zflef(N?SrE#D0{F2}mN%D_jPo3f<~BJ%zW7zHKwT`w*WiHOoL`+%U}*_KoBPUbI#Y zB!<&Ajq6CCJr%>6s!iTQDOBR{VNWmcLR;4tF_UU7&OdPBoARu-bdxRPFYG_7P~}=Q z4+$2e{cJJ<$J0Q|^0C;B9;>WWi7EePqpm1lQ>qsdLhP#Nb$+1k{+MxgSZX%Bhf;Nw zg}{YmP*zCFgF@IDm+>Sa>5DmSt0nEeu{`y}mtP{`?~zb#6WedVcvw3HP*IEOr(-GN zu!>a$^M$)>9&1lYhqR_f0wB)%(}@ioou;Hpz4iaFYi!lS>FzgnlugQiMaB=YqW%Fi zJ9-D{UH=RD_I`Xgt5iv@k#7DAB$v?v`?($!&6L=`fVm?P5NkH}Mt(y71?*#Y(cVb2 zPRaDv3{b$-Y;TDw8k@_&)^CaZ~^R literal 0 HcmV?d00001 diff --git a/docs/source/docs/programming/photonlib/images/photonlib-to-latest.png b/docs/source/docs/programming/photonlib/images/photonlib-to-latest.png new file mode 100644 index 0000000000000000000000000000000000000000..37bfb1c71c9395cd7f0048b94dd76ddeef2dc431 GIT binary patch literal 16736 zcmdtIbx>W+);@?F;9$XmLvToNcXx;2?(PS7cXxLU9^74n26qYW?)oG5z4v}!&HOtx zH8s1ccdzbV&sx2E_3qRCoE;`FD~1S%0|y2MhA1H}tN;cEKJg*@0--H^Rg8f%4Gefns$+wms&-g#$0gNHwhcCyx97<;p9v0^ zy>%|I-z$#_=AX)7`Kw6fFwjmWaZ(b;h@Bu1%pmXRcvV@IyQ2qlSZd0FJj`pb#t;{;%csuZ>m z&}|g9n9)0@P0=v>f*xSOjGTCNlfivO*>=<){Skf$g-k(EgvnF;Eg~7@tgikN4BZ#B zg0$YubS&cKI)%xK>@qJ#w77c24p2jv(j|fk-JQmJyLo5Ae{b8_`wG4HGgz5N5d*a# z5_|7d;%3Ud9KAO+=Fg{Bw^aLpneP0B6DJoZ%P7E_(Y zcnCTDh-3mmZu+)$yRkRZWiFxDu6lPRsp}(7y=emYxbwWZ!qK3L5DFf?TLnkY{+zMH zSNgv9H1zVrQwDd8&E==*!OJQ^EnT4XqP&z9iZd8jNLD|so{Sogp8ik`bOjVwS$_c4 znZ!moZYoXjWRBGjCdYA4pV|@Wkt~Z$&aBQKPglY-SBV*MTA#q6Lbv-800DV~sQrGV^eFB*unR2+(ojr2 z-0}d)Zu_6mi2*WtR6iivdc5V4(z_+>Fti|4yAka$tFk{`KsW}tY%=*1k_HCTBYX7& zYJ^WvOar4H2>ry_Q3FVcO2wgx1wIc;8}TamR|t>9(TKCuB5_1!3eyr=5999;O^3CM z^5$WcMIYsg{y^tMH7>woMu-xk$i+VRTo0!0ODi(^Thb9zBP3gxE|2ZE^9|H;0Jt=w zp+Rvf7z)344BrrBTU!d1&xuE%s+ z>cYMquDVZdd*LF)mF+Exp9Bl_1U4J+MIVnSfIdlH_$!$e1s-vxpGRrHMYK36W7xc~ zOEYFdsCqwkKUqIwKTkheKkJsE0aBRoG{sUvyF?r*@3$BwVGXfm5l-1w$siC>EK1Jql$)DvUNkzodWYtBNM9mAeiXG*76&rrcE7@A$ zu|#mjXoyx8W#_FIbbePLNg6>dzQ!aIublPLqUsOj+8kvWb02E}9lc?awG#w6$5MtKjv zJC#$#Z>Cf`M^<%_^>lw5|^yAa1w!C|ZoFalBIh9?4 zT{`cb;5K@u$kz08dIde$0abrE`#OT*gE5gd_+HqAW`9r6584I)QR&0z`$A$^phr?V z#aW;zsy!%e$hS?sJvTTM$t8nD&P#5PFh@Ql^QL!L%U*$}f_=`d-68BjMdp%}+<4@IpL8a6&?&rHAZ>1c%&*Qb=e-$z!w_u2zR_WvgU4WLGlJ zqNl&0bC%gDZU0!9aGrqJhuc3cFfRxYoy1R_CJv&~rt#MlXenNI~{RM#J6T|UE<_iJO8uvB#y~o?`?q#zZ1X`yTz3gpNpxB$%JvD%0xzo zSA}}xFj1PAjJ2qVo)j)-)tqm=Y$p$_MKy(~_Ons^MpHm7LtCeSCasdTB4D#$tpKIO zBgFShApR=c3EVmT#j_1LRE@n6x0SAtXz$>E8)%M3E6tpm%5-@^`b7Fx2w569+drFC zs{0W4BIzxMLuc)!(d0{|M&(L$gI0y%9NsQMB{DhPF{4_{H+eCkmNb=in4zA&M79?` zI#69JSj%eMF&RC!9=Dc}kXlEPl9`e2p_WhcD>*aUirZ~@hqbh$UVNE%z+oi)+gdIC zk~0T!4x#Pvj33_<4IJ)(TzJSM?<4vnK{2^B550_Kx{=1HW7}aw2_F@Z^1&FISBSpA zt@v=vjfr4lYiyYjH!X{`%`N&d6Uu>e4|=jPT`Vhw=X^o1q&F$ZcAsLxR!gs5@63OQ z59(b>vG6-7Rcpg<%Rj{;55$-G^8*E#)tWDrYHFS}{iTKVJEN#Q@ezD6Pc0|=>qUoB znkg+bE6thBTD32Ga2x2#R1GQ^6`t)DCuOa36>|gS8&zrbdxE7>hs6!E4dD%^#(#_v zkE!QrbnlC}>s~~Id_gO4$*eYymi{~U>SMKxqZvL;zQ)vLEZ-X(9+I3=kh6={ZP zUN`ZsCI38Kr906rYr?gnTY7T}F%t7omYzGbxIa3|3g$|g%Vh~qpV0o+R(0}eaZUbM zzReiPLGG8%Pt}_H7_ZW2n=_=94NqUM+`HV}p4$+tknrQ!)|+?qbRJM8By&TCgbQLID4z%az#Ys>rZMad~Filzg%*hl|hl2;r#xYUqKF zQ%79a^NjLI@p$r<&RXZo%jkJ^@)>9izuKtUU6;uGS;4oEN!R4@cr zo5E<-ETm_+e9oCWqKllLM+i%*t6)EZ-fyO~FV6Qcz&x73^`LGKzkvx)frVa!9UM#r zIBildxST0r5Od>NML(q{XF$Kne9w~bx$rQ9Pb{O=Gkd0E&I|a&5~pYOak>aMR+BK1 zkpZLpkbz(Ta2znG4+;Du@q*+2R~7~T3I_SFdI&JE5OXlVzjb6k^1oN?NBWETCx?s= z27~!1p?)OST!{Z@gHPl_{znG${b&OdP!y7o_{bFv?Tw9X9L#JT>w1=lJ}O}C#MK?Z zz%a=ECU6M_(u)uK^X5uwj%qT}oQAg6wE9N22FA3m)^>mGfN{HWeu&n_j{1bI)>bwS zoUS~?|I*<6kpEWG5flDP#nF<7SWQNrP{`Kan2?p0o|c}N7mkpSklWtKgi}FS^xyE0 z5)ZMNqoW-s9i5Ad3#|(it*yN&9Rmjk2OT{l9U~*nhX##D0zmEQU{nJllSM&ezWaIGf$NG3cy1y-S47Bug|F!)A z<^EgCDR1s-Y^5%2Zv8Q4A3k^)7}>f1rT>3x`5%w}3#s-$NM=^X|Bd`#E&o@fvV*a` zkgfHHOGn=S3D>{D|GV+uKyJFfPyW9~;-6vuSMA3*^TKh{{WoU3aNQEWi9W)JXD%$K z^pSr|vVUFtANQ{x>2Lm#u&_YdVYy&nm^%`}0!psnC)%*>vU5+~C}~1C2*1?6lU5bV zOHdZYugtl!msY35;|JlTb#nt&PZ!#EvP(yX|qlF4Va;Io&Nib8QTP zo}#bYyEZsH&RI_WJkIM(x`#A4H`bz4zLI?=<_Cm=p%6j{6H)?dSH@Snm~~7TY0`EL8mec1Z$MeGn zC_;??@;Q`kMzcGjt9Sl6s?4%veq9^s3#Ue{>Eszc#myP9$Nfpo(1%0xe;g9ZS3d39 zt2g+FmtIRrWplgH2)uNH0;siX#Z4w$`DA*V>n&JXTD}`{Y)1;l(`d44zD@G6jdIy` z5RFDnqe%P~({g!@vi~EJROot%YQJpGvAgL9S!?sE@%X3Bb~og_3$gNT*ibJ0sw8O7 za!OxLn5u>Jf%G0gtcbV@Cf?oZUNFpQWlqsuv2!fV0Y=S zESJ&4l6}^I!~jP97bbxL;^H`Vq0Mh96@jbvmWFgLgJS2umRZU>wp|y)gnifC?-F{0 zA{JL(Hr_u;OxobLW6~>hxVqA=L!t~*0-0^5l`OQ?DQ-XlxpFaIFv>*MH%|0RwRUTN zKjnD7#Eqq23h43HugqI>jdJW`z>kS-W!iSeyR3UNDf1@cd}W&&jvwe6jzG(fD*i#E zxH~<%v;Is_8{nHONq9F!5;9ESV+A)7ovLzMdt|@BGp_IzJ&UV8T#e#uLO*t3xI|x! z%SIQ$oqb9BV>-T{8!YH2S{RsAwyLB}+iOldlPPVQzNneh*nu*c0uN0e&Bsecf$7JU zu};N8TWw6|-*ZaGN0-P_t|}Q8zb~;nqRbPqQY_Ooswf0q*qR2-wn}}AyJ|F(7bn2A z+N|G^NTaGl%W$hqE|>oGdjB;yWW7-{rqiDtIDEF&X7oo6-Y8;9X;iiOw?*!69U@(? z$Fz2~SL?Rw_X*x-yu-z!6rR-vOVh741>Nl}8>1CzJv){AGc@(4vBe|RQkbK)#!{86 zQM@gBJxo^ffBHg-Y|pD|ecpL#a6s@fPub7uMcpD)vFzw!j*BMFTaf_pFeX&aF%k$0 z0`OFEv;h?1b^h|g7^!+oLgVEST`jTXAMKocc)2#I@%RE^6=e&<$PrikI>DYxIP&8Ve#E9sWS087=nfnyUXsm z?GY&Q#{9VxLbj+U(K7J4ijaF_P`U^~(?m;)-OlFrqc4d~E z$#;%S&qW>6Ut1!1cdn7kH$$sUwmF!ua3_@7TI%sKLON~EQPl6J3!kGjY$;K}x77XE zjNac~ArfLF)p(c}r=d4Ii~V{KYG)(wE)*0$7HM%^z(~eopqPy5r^n4#^Q!^VoWj=b zC`4R|j^pSXftig*zQ@T0U035O+u!n4U3qytIyGBtZf9w6I@xEm?v0GE3R5Z*?!z@2 z6qhQ&e_v1XWQAkB^uuz!LL%|(Mg6>4CH(zI2#topGTla?{(kj7m!++2N#OeDTBlb= zq>pobcU+adVxQ*j@-fbV{^s4l{!lT!m;Xz)+0q08Z~~D!#x#@u47*2sD5+`Q zBfQ^DAt`5Pgucal=&DPkH!_5j=&`KBD+Gx@9*63nzVS}wS5`j#ftgW6_*lPZ)P769) z>d?H}8P5o3Zh#0y;ssln_2ovUVQvzKh_V>o^v+hnq5}0AO_y5IP2PQRu0%XuP!DP3 zVsr>o6dGoUU-bDBOFKM?sCi>r)F1L|e-2eJsK2f^Y!+g<#fdhEeq)Kc1Go0zpH z3q@Bi%_R7(GVD)uE@!LLwwv@GpZCfgN86rNbse&zl10+_1_hr#Jv_MIAMB_|)gZ-# zFTI#lsK}!l#0_cG$Jy^vE>e2AJ2OIF7`_S5ZOul)Gg&a8C297jrm9wI{kbiv(V|PQ zrQPGBd-<-D_TZU5N2ywB0fTW6pv(vbIvUSU2u}Na=iyQYxZ3b>v49&NB$KT~iVtu@ zznzn)aPy{-_fZ=kYS14IA!(Cdvj0}k`SKtUfNItEL+ui^)OwE(gI1wG-MNAH%wsf} z=FV<;mhBXX5>;flpACUl2^R{QD?^W;VJ~3tw`b8#)f(c6QpN3>AHV>>&N%BZ$=gjv zv`?B$#>eowVz#MF2e992E%s)1x}59K;iz6;NMkJ#;bjT}Lc19NH~52G(;ZSPO5{?~ zrOlO>S&b0+ig_HOBnJe~H@H?MCAlx%-aLxUMW_j)i@XT5N%|76LUK#CoAST1xMC_J z9E7QCE@I*fH1G8bE)C$|tN47@?-kykG61i6a1~lzwA#eB?Qiy!L87C0lPc8_t#3WT z)cd2%{jgC`8e}+F!-c=H?p>WtxqohC9#F`RnY;I-iYuqDdvz(ji^=dLPMZ2q%bybw z&SiT+ySovNPm#nMy-uOP;25Xac(sQzeh!QQ?}Sb=^AFG)^yLtOD(HF}Jjq)osb_z{ zUKQwNl0!+&Zf(e=Ke6z5bl=;N}FwgbSX*;pM_d)8N|cXZJ>gp zKx`Zrv4an3A}r1t_fl~}rs|O=Pf#Q_3w08~v|JT%eDEv67KQ8s&T3dkH!#kHGd@6$ zwdOqz*=|;jZtLcm&&~z_N7O3=WrQ?c^09%oLjZ5K$esJ6eVbt!x4?H9nl{gO!RH)2 z>#?Avsf)92-!|@x4n%3Fih%a|^zPIvCcOJzSB3zjMr6%~cOcR%*P$i?7TKzij@ zWS6OZ3_}X_Dn;`^h4c4?#Y<%^>oGD}02q<)0G&k@KWF`~?}NWSJ>Emcq&{+{EPK5` z4huwJ5@u>PP`-y!<7`PEr0j?cJRKhops)wpQ=UE#etvfExkz^74XWv63^k5l0dI21mKs}k zT!f_kHqAW|Kaiv_o}h+f;P-wNs_NE13%qMI9aED@CD*EJbMmGcNJ`4Px!8QGZ_Sf{ zglI4_YnRvIKM9brL*0_s@}onAv?ZG~lUU&iIosC4=e)mIwFI&TxjhJzDk4+lxA-S( z+2g|UKWuim>_klRHMlnSAI3+)C%?IhJA}(9M;z)!QIa8@qo z>Ke{D7#!33>{~?9f}SM4AB#~Y==5XX2{w4v283}_6*L*h@Knv88{35djr0Ml95L0M z+&vkM#WNiIw1m<1fOP$9F-QJRgmbHZOaUHp`)se5gjE>G~# zBcbymV?wdH8)MeY7Gpd?256+_X*B^y4>P%Q#1E*;T!7J2bEAqbE9#*%fA&8ffk@MI zbC$D-#V%{-WO5mtBAt(uDR&RTp)*iW6!5sG^~Z}c^c*S!WU*$UGjpzep-B7lqS0Op ztOQ}7zhj`5O1q<&E_Ms*dalBZkzlFmNfAK^Z(>2v6MVwsUbPS&_0~41A7yAPP-Qx8 za_CGhHCbB}ham3tCD`|GW`Gg6O+-dHS>*eZDm9?10&{APLcQl`U_$|zuhtiW$+n{> z+>3W%J!2nUC3vHx8VV-f<=oXfjEe5_CW@>FclDgFjE=yCggiO z$q})6QMUTyWz#GuUaU6uBr zEcl81++GsfudrQdWwHCjBfB>k7YOooLF>e)j$0^|lB454bPZi_8TlL%PJp_d%zkM| zdUu{>@ayYhrw29+lPEf6Rq2gzC|b@;uW5tQPucAq3AEeaHd0x-gS4!bC2xi7831eM}CUV{CQ=wmVA28wDukdyAc>V4Vs5~Xq^QFtw$KqHcMnXd6ah~E178DAQ# z%sM}EBQsK&qh5fBpg;T@jasKH6q@C^?YtJ!sTrC>*=$PAvL z5dsQMqjmt#)rEt1Hlz`LqYzp*8jE#UbL;c#SyIDsI;W;_&r3_`Dqj`Z_&d!X@%!NY z?)@b=tgf$Pt(-LUKV*xEWINnm_|Mu!W$ssQ^yrrK3w^W1sVKN^L)=qU}D?YX^zV52B3h`PxnTV{3#0cu}0pb>n>=3*~n`nyoZlm2d&< zL6JdMu0ukBB{MCo?N-ApUdkKpLbSB_L+#ZhTi5&Z;*CVXeTJk?jGhZ1hQ&}OFzlo# z+X=3e9F@=|K4PiONN;sCz1Idnd9&fTBHhKN>=9_b5X*Do^WPwP4RJwQ5Y z5tQ>amj=MH{zjU8(&hB&;2j)u5KCyYvJ2?=J>`>Xz_c5sT9EFuH^0q`GF%31z9xTF zVa7!B!3)m7tdDVv_j<--7;k+9cK5ghXg8(o88$R7=w@IocC~oI<<0i79kCO@A(mnrz&x6LYYKer!2vh3A zeJu3ox)+jX>e_Cs`CLSM!7ndwYBo@SO|dI9e^&O^9DS@C2z!(1FqwqE(xj=IOE6n+ z^Wb{T5Z3quWMMj)yjC$$r_E};{F%Lm?c{|}%##)|z0~KX_@fsKUlFb&ri2-m`&5xG zwvC_#0{SR6=*1Unjq6U<8>pC8SH-}ID zwvC1`_daAqWK@{sZO*Kp+!>pnZEu|Km;{7|Y%ltIzq5Gh{!o4?Yw; zmp<$t>NJ!e>%%*}QL5~JxK=Q5R8z38(!_te_Td&e_@lQ7*u`l7?g8*G*9r!g@E<1j z|8@79g~+D%_O*DNuJWG5>*nWS1y-gx#gxib=U_asTw`nq$7+rTZEb z@tK8A|5FD>)5pje5kmYL+^Vxa&Z#xMm-X9ob3a=}sn*F;q57s&VbRYxHiiSV+Gyra z9>+$z)R$|xLmg+LB0QAM{7a+m)2f$IODKNdO9sBk0DZX^D%JI?v)ObzLtVbVHrC9t zk`O04G3NP=XRQ-&LFQPTlBJuf@XO+Wk|`Ahs(b#@dp;x(mMXM$s&WzRma7bZY}=)D zIM~(?UmURFqJShl04Xd`@)H~cDw*knuaGcl=ni2#N+O}& z%d7W5piv-6sIT}Q`xeNk%iH5n-`T~)l*z?#?z)+2re%Y}t)#WQjDS+9euwX~a7%J5 zq2{RSPcvlA-C`_o(QaKpH2$NIiVP#iJ&@4q}Ih zTowvS7aQDzxVztc@*d|%T|EwnW{SK4W|=7fNXRe%`1^u=l=)vUS$q1;-=@{KnTLWM zu)sA5KL8O6Sa%Zipmd>$e)DL=eR_ySe&4VejB19H1idZhkj$_dJlqL=fR!H@S_zGg z;UdL{iBBA8B^<1oeZWNsaB^AA_Q9WWTLQ?Y4OcPp1^f1jjnw9Admi^^eD&AeA{zC7 zzGk)A_0jNQ!Kyf@c+rC>Ngqali=RJ`8J&yBa--qG{?^L4=xO1_NLAt}r3$}qGh9|p zQiunH63Lz5o@_?d(_asBY#w{Wf2P+R1%xRQ^{9$=7X#@*%QpkTt{N(&s8(Cl$#gtX z?&Y8HIpX*OiqD)gvXnbDq4-cM_A1hiwv@y#l2CqrgOJW-^{OGtPDT%Vkjg~j5l&Pv zi>XpjLf#LRjhUKCfMs@EKCfCbN{SKZbvXlIOb%I0SjaaLPYe&&C#Je;kB{$LwmQZ+ zo@(Sz-YNz0KdYVsuAgEbsG>qcb8*=O>nM=NYV0-h1boAon46b7l&MfJQ`q76qVru^ zQ(!qgVPdrN{>F|R_wx|kTP>4y&?d)h(xI2lFA4&XX{2FMvV0N31SZ{Vn5$tpm_IAhj(^igB>1$W# zx4vhG{fU`a6oz0olQ0ekqmob6O~t4K5#Q&j(_nYfQd7mnqQ4Z7jjBu~TXT(-X%v^p zW~B!sxMtYzju4GT`}k1eKV63!^Uz*wA_Jj77{lly+PYL*3x&nh9O6ThPw##f^X5kB zi8nd4Mg1FGQ?z-6p0;ozCT`${c_iGUg+k8pyrs7|3edEg~| zu?_xiCi)fgrR=y=AsGQ>x*1@6hu11>xHsrd`K7+y`4(P&9q;g9D@l{tsfC2r?l;bT zU7jhyq^RLhkXoX@ka-0`Y*l-@tG|}<(^7xKUXpM~@B;_3C zoWE4I@puf7mA&)xGlx!BT+Ald)s}rWkth`kk&~zt!xf4o$*w1|A_|gEIm;g{7DkdN zrw`%+>P^jLx~$h^TO4)^kCbx~HEL!#$LN;CMMH=3P;unZ+z-L5gnv>X6~ zs@BKVAkgJ(gQ<^K{Gr#Ir<>Vc$hp)wc93iihZL9dn{1QqMlsy(=x|HvNGIxghHZVG zD$d-3-DMNLa!mCfA;Qo7k7jQ-vn96$HVL898Sx76<>JFpnl1wver--W>;jn~F}hCW zxMsZp#1l(G1SJSaCB-WSK9zH^x{z6-@<;cUikXzjW7I20Z04A+UVG`2ry6mgT{tB; z;<^2pW?n3xUgs<(%B*ThCq92u_>Fn2GVIfDyVgn;Y7B<|dYqb`pw>7p#8fQ%d$>+y zMfNkMi_YlK_;gU+H%?28w7c7;_afMYV)I9+tNjA?ne_$ne8Uu-n}wQf4R89VclSQZ zrS+?%a`QKTGL03#)tmE~EFIUXV5_ZX89v3a<}lfD{jdhn+Y;mD^~Kj4=dL{2M^Pkf zros{lG=r~lXIdK0o-a@%#L2!yov1(Ofg6E{e)7mAOPjc}!!k5FBNTO*ReX}TKHSDC z%m;_knfF98(f#VA=Y7nz4&TPve>lcPGUs~1E>kd1r@Gbbq)+y{y?c2$sos{3Fnfyg zsXOnQ9-B?H2ie@Z-=7FJSn|@%)KuSJZtZHMDa4?cgl!KEn*9*i%fG81qE<@!UP6N7JRNO{*tXK51ysWDf8Xh zi#HP01AG7LF7+qTcoI-+Yeq9_fpVw!+uJ&YTh#R>+^*S)S;%0W^)oFF^OzUM=Y(?- z1Q&~rhl+mvqZ^K!$KdK8qZy~A-fJ3+m15@t!Gqr>`82bjZ%&Cut)325ad@2l+lSnlW!`fWl^$pV8a^{^0*(_CQ zFg!9!`{Qqkj@CBRGPG)pXpJWlC7c!OY|uu}K7$6&xcDK1Bje{=Y@OV*QrWZesK^_E zN9{KdGTEFf9DSoDI%^w+QM#T|Fi7}!wZZoT@suEgoOK-KcArzf`rSkc}%Mn`_l&)l)olbWqSW?ve_t_7h*e3 z__{z6XRphivxqbYKjM9RZLZONN#|AT9McUZ#Fbd+$uYyx0_wgsxX!+|*H!j1Yrl6^ zAIVs2@v0;OUEc-b>!3BDhXFiF=fklouWqkz?$M)Q6M>uMVz!&B3_ zs~8|DbV2e{l;$vx0E?^KLUeCg{UH_ID6zvHU4Bwd)m(TC9;YGK zxUYy4GY^qRMB|F@;gRxH=GS+Qhgay7D)m2KkUT0E%Mp{TwA!?2_4};%cgZWM+x%+2 zf6Uz}Q_BTQ<1}`buk{(N{>;bo-U6sO)jP1$fXn>#t|0bNj8S380Y*G(y>TN;D{dJz z*KX<+8Xn}W#P62S%7x4*(XZ-FgCY<>oBl{1M>X~Xq2$QQEny?Z%k`LJZ__8oQnRCO zIDqwx^t_jkf3i2oXB2k#$|#}`>rbm+D2IvtpDURoM(2#N?8TByQnR{RFN(99<@}{^ z;Z*i<`8$#|%yJDLKSb;=+k513Y;rc~Y?k48P{V-bA~uMEj7b&h#ItW-H>wQTINh%5 zRh-VoekIb`evue#IAWQb*0wE{#Sx3aa7bM>R7V@lSPxZx|LvT2yJZM=hR4&|`Hfn6 z#zLlV@$h_`;vnlXA?wbj0m6Izhxd1{$@SM_jZ)=n>C8dkqfmApxlAN;sd=WIaoC}X z1_{2JvS43in`=N>azru3sHkQ7Y6@RgK2#0?3-l@(3-Z>?hgPgnQtExDW2I{#0Z5C{j+d6&dl`ytW925Fj5TpdwaU7#A#l7 zcQqjjDrT>WUT%I88V$G4g&g8enSAWlzB)VsEwrnBSJ8ymE0ldKM#nFll$O6;al?M> z^Ei=|wyCv#_%d(xTtp^YKHqpoSj>6KMtdubdE9JIPDl}$%!FgJ1X3zf)7AN`wI>C~ z;Or|YwfL*GxF1BBKOy2sv^k%HEQU^c%6wk0n1<23lSLt9niLm!0Zpm=P|%8XC35jz zd2(tvZ8*|yD=;5E6*^;0*~QUFWGwnQs>HA%4*9*8yt0d_dA^>{$$@H`*z*(m2+-b# zn?5I(0WYk{{E#U^xiw8t_;&}bQO-_XB*oh+onY*>=*wznqit8)rL04^-non#hL(1M z+GlryxNCXTntDf+>0(mGh*Lu2oRyoS9I+ZiM&HzK;As}k4l$pzLhBP0u%v9(FzH|w zly`V!g92?;%VVJCmLbVx5e#-~V}QvSqN8~hY4e&w81*nsVdPP`n<^HeGMe=+5#)sk zMq6}Rg(j7p!?mJ(r_0PG7}XubbtdqTh049iza-laeKIeCD&#vW=4bad8mEpLa1Szn zzEqNH>Eq0n%cwJQ-4O|#jSsvX&6P**5>>_{v30vli7~Mtu8!r7tdOU%^N{Q!x&=ot zGfWqXX2Of|5T#I~1(i!aqjX{WFSSVMyNf;$3mOFS?Vb11%}7EJ$(A<`Inq>`+tEOC zp|zlcqCfAbwCh1HiLB^n6lFwP`V2EoTEVk_%31wz+ zHIfK#_#u2@4Q{mA_;&v1jo#-D=ISkkz$cI4yq)fx=e1k!$FnBBaU7S+nS7HD*PKURcFH9D*n|CSkM z7i<8v+Vdmk6S2-lL1oajshO}<;gZMNVu!zU=6t9d@uXcmxoCP~D4K^SA!Mlck|Ozm zH)YC*q-_%=x#H$D!~zBtEC#3;ZN4Kk0yaCKkS^QDTz9yLDyXAKgHKmD ziTS_hr#(#joNQ}W46ipE?`|&=Fvxi=suZst^44jAb+gi-liR;^v9zirhg`VK z=4h?U^DLOT7^KdL0j{iMeSDn$o}Ig^%MlsKzm@Qmj0rfia*I@{B3&((;hLB#vwbhN zT*!iyp$BPfTPYDQAyYtCM>^d|)mp$VSa6`LFQ|r;`wg}3kH{2J8E2fz%4k~`vuY~oJl38JEZG9}~RKB?K z3!9P36=vXZ%U5Bzs>RmtitZ^!3gDA#nTddh3E?NHE}Gb zr}nOdtstjLRPw)X>w=L;=IzmJVscR`@e9XfCPxX)jE2a(UmKu87bO>;(eO^pzDu4r z^`(7I{efuSh5Z5v_wkeU`WF4JGfn5&44J*|#Yj^5jbxp3)zZ~c&f9ki!Txw2x;wSW z(4Vd*`KwOIxv#tAdr~8!w|_|Bb=85)E6(_>Y2JibbN7jZ{fDsl_uL}c!?0}T`ICjh znd`K3yx%F|Z*6vghnPo2%Lv5CJtz7xkd)@w5km27r=bpv;yA=FUr~NRZ^47|xtUGP ze$%tNZ}Z(F`o!*+^E=RJlcLR4$4Nb9P|D0ZEoFqws2bt#CZL0Q%N+Y~9x#g&N6SMe zpA;(hcNHwQ7nT(S{rf6b(BU#6Agq<4m~-x@3^ZyiqAVGjOug&?&86Mi1IjmtDY#9k!dk)3G+j! zfwhg8f!LYuq-(^MM6qBF@5Qu7pRQg)?c)40;QQy6Rpm0-S5P(DstrVlPlgVu^1qBc zZw-~&nq;b3RLWOH)(6V8duwYfyDujQ-DE&H@XfvufB;zeU~VLY8p2E9--VEsfm1<= zdbW0_Wg>~>QGG6!SF`H%m!q~yjqT9W?+-O3J6DW2f{|MNBXjV)q??=&n5aO606jv0 zfKCCl(>F^;43O}mWK)7JCtUef@qIjpq;@_m|!!m$S&;$=c}{Q`1^u4tufT zy|G^f_i&-G%#@Hs{lg)b(MuHWnU@6!PLc)Sd?5`Q1f9P$AM7;-+>jBw zqvYeYwAO6y;G9qh-FOr;_KXsc%R1zKY32&Y!I>DyWcRLjPgEsQ5P*)})?oK(jr@Ne*xG#d6+S_`8grS9$MU5BlC3ECF(bOF=>1wAvpSxNW@9I2A0j_Xqy&5dZk< z&bMflN*yr@xh$go9ud1hZa2L50{x99_2W?a-l-KrGeePzDOpfX^bGsz=R=|Qj`))Fo0U@TPPTixI$YQ#cIgxcR#*(1@j{~2qC77tE~{RT7KVfPj<#{7jF^4>J**ak3;d7SCR8wT+w20tqq3q z)bWGy$ND^R{gWN3;fG1s^J}AnED@Zp7Xuv&#;IU#l=thgx!Wwxs(brom$0dUT|Umdv$Ltm6QaS)&QA;fp_TiFsv&p;y=~3 zzA;k@T7%>TaylIwV%-7;VAEXy+A!i(044Ajw$ssQQq%m#A)b*wPbOCpykXSgs#{=XBw(N__|BAE^9 z8vA52O}6Q!To55_RVGp#KZuLQ_|KruwStJ%mHy2}t2F^3(f%JGPHkP=760^(<;8E~ zGXZHJ#AGWmL;`Vis#PS>++_{|0=WW1a`}_D07{8A=yIRT_326}m_x-f7FwH&8atH} zOJWU_iP_mvhe@S`o@0TRV>WLY0_luO<7dgtr`%8M zBW(I2gqa`bED35EL0%0PVQ4zG4C>x-qT#mkaws4`su{?)ACZe+#Nn%J68esq^ zAVq)sWUWWwTxFN$RwiBV+(~xFz#!VuuE9h%R}n9?0>cu16F_*{Axr?gtHL~heinA^ zN+V`oUvj-qP`HSjs#O0jW2o#TFwqt?BJE<}SW)iB<_PD2e!`pZs6R{x4;k19cZ znmt*n`;HF!%IZ(6g#o_cavpZe*{(w`8nXN6NRCfpsa9m>E~{-IK1>8&PC2 zOqC8co3*&kob_1&Y${aPS$1F^;5i(!350{V_3}h1=n_jnkA_JQ>(Sjg&qis>Vya9b zVV-Fr?`aIc^4lbeoeg7hW!g>l5A*#vbV_DoQSm0bGt-q}i#{@XKP<>%fTBU-{6G6Y zj-VeaO%ULNUe5SSFVA4&ZkemciPMKN^($VqxP43}=rne8)DN>(;U5gKjILE^iLnT= zbf$nO_}dc*8U$SZOwtWJK-Sxu_3LTUA^9-!3EeVtZ_(}(i5@&4mEHOhr;iu*V>ug6 zV;`^igD2XJ@t4}&VhQ#_mCoFYWdfxe_Hjh|(tMbxAFxDtCjB`45t(lNKhI(Ne{kJb zu_&h5oHC|uWb=XNr<&uj z)0_LP(@b<|0SZ}WgsXO^>*85%WwC!vg9{Qc873#;Kr-{PxIYAaT4YCx!B%8x{ODib zG0qyE{dTON+a^JAe8~``!E8KY8-x zWY5g*?Ck8Eop~n_%8F8maCmTFU|@(c(&DOMU=X0s8#I`=pqA`2x>7JO1UV})F=ZJs zF%o5G2Ma4(b1*RJhy*QYZM7k+3_Vp+NEmTp**yi6cr;;I7{-7rvT#{xh!8Y0QRV8~ zD7Xp(@v59sl1M_7Y7;H2{u5m+cslw+)9#8kSa85ktq!hLF87zm@vr`4JnlOyd|(rc z_o`M%C9uL36iQg=N8@-&z)><+2!sz11V6xiJA|3G#U(=DXun5 zvt!B<9lJO54i@aatDsRLcz`6=md{MQt0sQDT0@)S9ZeJ)~y|yw>woIH3ZbK&~l@3caCLl zwpb`N!|sA97|GB~?ZA}v8IEeTOf3q?C=AWx7GSpYli9mMJfiuj6X(YVVD7<9Q1C_5 zn1&)?P8(_Ev7u@0j9(_$oQRl_Oa;PA#V@*k_@$!P46(ksT#-+5;(2~@=_nhA&VS*O zaO0QCkF&Cj^mu+qHWRVXC+kxWe{<0fi;7|+Oh7swi+I>5Lp!)7iST0(gLPP&fg~}4 zqWgu;w~WI83uD@$lU+*?h0l#lZ8U0cKT_}tEa~wQz zxC9LxjCz0U7m3ez+L&>NGM7(g>Sj)SR*LGK0w>JFu$mVZC<8;6X3*bucDwtFrv{?( zJXM_Ngw8J*{5}AOiG7%1p!HF}w1vTK@RAW~0-EYeJK$G}y@J4q2Zi6FfQR{67>k=4 z#X%aHiGbgslc9b>j=elR#0>Nq^e610<2ffOY~c;KdJ)W*<@A7aVuE?Yb7nYMNP&Ar z0?r>8eMd}mZi3l`<7}*P^Xlyv@I2;7g1$0N^VZ`1Bs4=rU>}$%3~Ts@DEu|SCTt?4 zO1~=JP1_|ilGxLmkirno9`YVUQNHyt3a4z_@FX)4z8U0$aixX0`|k3r0{W9UZ!y=R zXm+PJYXPlYp4?5$X+JS*mi#&sbW9K@U-Te___O`^BGIAp5pwTTY(K`%R82b)s;lfg z3_KP2DBzEBxmQ{4JuMN}Fo)RvP?obrbpzuIOYdVcR?rqOHW{dXTL#5f(icpBBC{Ha zpUhY=o@rae4*2flUo$K}oNk@Qo8D3Ma3MZ@0ZfhO)8RFs8XFunb6Ud|>)Vilj3w6| zQyi-Rqv;eXnO{uZ>o|q$vArMr{z?dTy4l{|F4f_ZJple=7s&`VtkZ?l_RdP>&DxVm zplD*{hU0c9*eU^_>G3L%l?9rUg~)R4ZCd~_3}iM5T3;Xq3#wNp?0hqVJQRC3zcQq3 zmvhxyV6cKQeGx=!x1Ta{N|%fymOg}57osC}MF!Ft1R&UbjXj8jBIF|rifc9*Fm?TCfWC7T^VHx7g*<2HDS5OPV;PQxOrUl7w zzI|)brbvv=H)FHq)QnCrP0(hXgUP&nS4Mc)Be)@+7Fg>D-4rBt=Aj>;)NQ#bcjnv% zSJ|tyIe!-B!Sxa&Opb$g1e*a#WI{k1%#xriPD5!+O+c0w=v^Fq7AsA`7BMI8-h}-n zT&EAWkFpQ3PoNLIk8{J!6gfhCiu&i5Hko(|LE1QVab2ke30}n(*#i<^lG1pE!Lcn8 zXEq&CCW@rb?w{l0D?ew(3#oC?CSoYbQbagDeF`z-*F-5j+0uga9Dyv~3F8mk)@K|ccrF}t90wc~)@^xedx-!fU$XW9Ls=o= zPWjWRybroo&hPG1YTwawAls}=9Zi~kh?$C<8J^Y6saHD;nsc%H+>qdw)u8Mhc%yl& zwh)Jl)0@_94uf-vyNF|nL&z&mXhWExn5Y;rW}mK^Zf{^`fV~X4Y}JCb7gt3pp)VlxwCEZ-bIu50#U^%9YrB}q@}-Z_Nw-4 zy-u4>_D`bP#~pQ-2G5pz>r0DEdwBGyYAkj}YX-mCJnb4rcE)+#j9MQDbGw8O^%Es4 z2hH^v@5WoYTE0DGAb$TgZxN}G|J_wDhjEc}(JlBGlW%5hmT9`8=cGo!`qYBCVbyq* zGl-?fEabiTcDNqW0TMx&PZ(ZUSgibj;0{I`@NH!li>s3{m2vYedn&1 zv!#;~q%n9mct3b~;6mVe;C3K#&}a}_kabW?utBgTWF`!0NJwZIOmjc`2CT-jDR^(~YOi#Qx=&#t5xGF6s$%RkRZH73#MX74o*kT+T~nPD!5; zKKIEW4&`lyY#k2?Y`z( fWwNKpkky98Z_SfMk?b0jCTpYKsTP`u>5DGr(Gn@KM= zx{H63^;5!Qw)53(44~Jh_aMDOufTGPY?Gju7@umN)+!JhKO56dnEbk*s+01Qawl@6 zzp_TOhSR)#Ja%*?emV6^axHaIT55{7b`IlEVp@hRzvsdhXK{O-^nzf&%Ww+qat+H* zHy*M~5{JR*K%oalIQ)L4$gq3Cd(3;{0xEd{76qG>_qrp1*8QkLA$l0PJM*`KVl26y z1^c6(?8IXmqYG^KU(-2TJ!9|Fpj>!&-j0{2NTnwUoX(3D_9TQl>{5?8=o{A=p9BpE zLA|Q0<*886x71JAtQSb!k)7wv_2*(&>OGZfYx`9973bA$ji7aZjuMJ{Xg=Cq$={dL zOKN6ZY)Wg=uX);mTgB9%uh+yX^J%j_DruQ5o9!=Mt@v8EBU&uCUr;|&A6b8FzHW|q z$S}ufbeqp#`y?6a-=A^)@esSxzf+`X{Xnuaram>AGr{(uPN(huCUK3?H9<2WUoS%M zvQcn3vFdn<`N*iG5#N^i=ZkCDdns=X`PqHz+k=Djk9 zx0)lnC=D4_X;t6G`4&IgpCB);`ULo9-DGWdUx(p@MIL@?*>_#O{(60kD1&GhCWg$# z<@Jt;cf;eo)E6tYewF3ikyw>DM(#Q9wl$A&*!_r#FSyjiTuRm*-quUShlROHjTx|f zE-$tdKh<`*cVjbe1y=#xmp$uIM^V>FOH8x%O$`JOv)A)t<@V*SNz2S!`sYnkKR64H ze`u_hQddIh^LeMcKTpMk1ewlgGp8ab^@JaJkktbAYTWyI{6`)Vsagly|2UBw<4?D+S{eba%@PaPw z%mF4O9(K0&F1#KBWPefcg06oxGn0}0MFOx9Ak$V*CJ}RRHYed^Vqsz-6NDonA>ns^ zZ^5f7F8L2T=$8Q52LQm4mzmk!-JQvuoyo!3l9`oli)iZj(@oR_nrTfQ|AvS7dPjBIsbF#Kb*g&z^iKR;$Z9gONAQt zRscaZe&+wH`G0e1|6vnk<=|ju{fF(p?f;uc=l{d=-}e8_qvUJ_(xS;P@dW=J3dun>;cGs=|YgfHS>CQbzS8CNG61C zEHOMT+|2z;fWP`9@qwu#!xWrP(Hs8FdG{40tl!(=epc{*>DI*pFpJNc=ay9eZISO9 z2MK$@uFMn*n)2VRFvJil>(lE0kqe~+($vgMd{$RS)8Y1HIq^}0d?k zq;=IQ2}o8~S0`e0JibUhoNbOX#FaVQic}Qj2|8w%PA|9@2qRh zG8Wk0*}2bWU<&y?_?b}P!9hC)X8nBe+TftH^=t{Ig5ZVY!^Pq0;24|h6>z9-b#VP^ zewBUi(4nKS=EAwq8KN2WbEJBsy}@&VI5^R8a1|RR>zV(*l8MH4ZEG3qsuy+#JMRsT zFjv>B?njW5>8i-fBM|ybP~g?C!g!r0%v+srP%D3>a*e7}lbHRVgwB$os@m@O?t z<}t9eT5Mnxsb!?6cS&cFmU2H{z|CVnw@McNfD#^IrI60&o@3DJre7$913N8iJle*lT{*3SZZnF&y$G~oo*Z*WKu&IM44&WRF>;-IWo^GK zVH&%;AfsVT^pvU^EqN~dv5*CD?_g2H(`LSy0$lH7ngksmpB!gHLqXz8hM+;kSKr-*200p+0O_M)F_Dp8p=kajhZmPtH))<%k26BW1qG4?TCb!=nJev9 zJ3_BhrIqc)ZeN!D$OHR_FUR>soSdAl4h|irMs;5CXsd{kjlvBZ587wzOnN2H!&-nH zPX~JB?WLIf{Fz=CsO!8xBMrSb8BTTXW-&QQz zT^7B$zlXY7eI!;-&0DycU!C6n{@QMH#8sK*(NhiBS`V9iK*ZlWc@;D!$Z(#C2Q0Cw zMcdT}9oG5|xDAgRDP{WHK-sP6=OO)Mn*4Y<&J*=;bId68UR_jw(R@T}@FB2NN57sB zd0@8GrT@}|ic!01Fm2YYwffjugZep7bH4W=W1-#~yIj9nx4~@X3CauA*}!1nEp#1W z6BV|RTSB$eGo$T7U4(t-p`lr)XTH`r5#W%KOI5)R(Eu=%@Xe%^^JGzr{$-5*gN+lb z@AL6(gVBTAeGK|cxi)LhYHsCinc+)z7=bu7fj>e$I`Q}(T9CTNG3xE1h1czK+=um? zelO?dij$afy~ZiV#$|H?t;ZNbPI{r|3wq!87pvf#BmL|(!5$ej=3w)sO-&&y9*2aL zCkCn04L_EH-|kHCSf(>o5@&>l5qeeaUARZVM4o^+hiIFpVD&+Z} zfyv1vonWKPeHj8RYSz|~{OexF=3g^beilJq9I)jrli;y=pb);hcWin2rk4(+-4c5M zn9NS}+jnMsYeSMiMg9rIkb0hRI?^(&&~t8e<6yA_Q$Ue@@V9SO6HL?4Eu|zNChy}x zLqprcne;!EjSu3%+ZLM%7F5|{pYJ~4-#0k$+-S01L=7XBt$q2bFrrmfH!PXX=UTJ% zvsg`P@v^~YKC#91SQa{Z(P#zzR_HE#`rVWgU@Z?8FeI^y&&>XegCSMr^A!J@i*4wY z@RD}Z=$8z#2YKb&bLi;&Q~$e&6|YBu!ZtVj7`voW-u>OW7NUbDKY{9uxekFCe7=tb zFRU?!KKJhu!*|R-dN`3uY`@u45#$Z`r2XdIM{3Pmv1uh_ov4@fW#19 zc&-j>9WxTg^S3(Xh3;-I`20^*VtZ{aW44Z`Vz|Oziw3Zbe8q@;?jkgtOxl@wn$zpV z*S%iuE-RH(>t3HS6>V_TPQ_0$7@uwnzT8vKd9^1njHT2-i za44Du`dw2Yhe)B7KDRd7EmAQW?Qq-$)w|S$OxaMsHs8N( zIr}_fH*S-J{HUU(eMI6>biKbE^>BMgFC<$fU@R=;wNos$A6Z(FWOeoGh+yFfQ}K#s z;{1A9*_mID`U2m?)rG#jCeqkkB&}XP-$= zF#zB9y53S#6k{sct(f=TSs;r<%p|DJemSM4FUq&)&PjDLgTskmLsN6=b;Z*ty+`}y z^3*nkuQIzI4)*ATnt;#x0(EMk-pxRevmL8FrfC-%7K%>n$*!m6^XJd=q=OSBGro&dC$4;1p~I{)h17I zOZjc;y5-k$fi&7ZD^II@SL2;7ThP!9ci2WA8Bfxov$u__uUU+G4Z4`P4Ue%xHy>nW zWif7_e7uyjQG65P1n;AH0n%TP_No{EC4u(mmkv}sf~R21nCI)-(=I(sYO!0wEG zWyYkPWi%l`p@$~k^EfZ{6$?YK&yrr3fTdlk)1h?H-NDA-sG3^a>D(z9u{wIm-EKBH z(PCC990gwyHsUihmSsVMyy&S_l8sVQjLo$>Xj;Cg9q$B2VqkpiMHcAWTbY?QYjT*6 zMrb~a6CxZ=^&>c(eo0|6s@r)!X)w`fyZ?5$7YI%4npD^A1Q6T1R*?leczj}yiwZON zTvwzI=x!EW_Zp#nMVvRZvlT-X)hb5=Mi93cGx5I?G(UbjtaLgsRkf-XpQi^RP zYS5`Tv_0hbkSd@=CU8Znn=RxYtc_f2S2;QbKN8My0Q`HM`3z|^G$Uu=CZ7w9pf#Y~ z<(6FBm;B%jJkBvyzq%%^_$)1byA{0CrfOCL!iGZ4CA6M4%{J(*rmgCCEH^OUGGGX3 z-;gMKRdn1??K@|Uoo_024t8c+hHk_?VqrNrV9;I)DyfUj?OCBQqT)N94n-MlOBY^#OH~%wo-8oqWY@^=3kVOhp>IhsHos6` zGYd^Z6JNH>*r}J>tuS!A$7_9UM&l6mQg#-8_>R7khoNlGo|tpy96@d1xn7<4lk#2} zgToz*&vDGF%we8EV{7NZ)Y33+<13EUIb>43%{=bxz=w_~rgmBFZNhPa&45(QCSaEk zob2nT?l;SMH_whBt4BqR-+<>7ebKBm6g&H>+A|C!n{ z>Avy>4(uidM^OHx*WaUQV<+^9ZghSH#_;o<$iy?M>{P3kl1{opkJGH${r&FhdsUiL zkAPGOS~ACnmFC)&`<1k@MY}uWqaW2`7GjOih9xg(0Fj<`f}q2)PGBtek@6--iOs|h z6WvKhowK-e$&%21gdlqp|AQ(MRj?%MQC7q`@GtFwbmOq63F;c(r7p~WgZ*IQy|UW;pV|C`|63bcIS+ zU${c^V8WyTRvXayD1JO~{D97@)u8P?&+pbd6@Ef5Pf^*nil~0{EnUDEKcB%{p{Fup zXWg(+XxZf1am9GyaByv8Wg{BCy`A&I(bUcfnhK>%!*5=Nim`!&$~^}6XC!Yr#!5>| z%?$zL9^|=_v7d(ML0DFfaI4$C>*coB-u<=f9g&D*x@P6jEb@>mz*Wb<{m2F2&M`>l z&i`OJ}2!5{EGiAv<#i9~;NBIFJ zm7uDo!me)yN|!Wya>?unktdZRx3EPhL}=J6!@69E$+++14QnKU{w-8mqg#3P_!mrW z^itAS8gG?P5G7v^-|mV(jRu`CM5~W5I|A&I>orsE*_V62M-ar$1`wVwvM$gJ3{Kjf|` zdo4!&V3b`8hWJ_ITDq|99C3mSK&6C(R-@miI$`8S7BlS!3wwi{M)E`?iG#%nKz&d< zTFB4roj=S@3Uqy1PNV2i7A|WEta{x-k4q9NOEupvnFZ`F-+px;v0HLS7JR~4_8uox zjc7R*;^GNyt{UCyA2U6#>2V(B2X&Wc5%_>y^?%r+Ze+%&t>F2c~W)c z7UT>YhL~OmxWSVt+SJP}L3|vG>iewV~loC#qXX zsva@HwnH5#Vov=4Pmk~mP#1Q5s#p1qBn>OmMY8!FqE3K!W6uWV} zPK!ao64zB`YGsmQ{~a46En|Yt09+;*3{geJ!ok6h3<0F5Scbt3A#T{X1&6#VGrr3! zwLPQB_UxwyhR@#hr44SGOn-E>?Lr(=tI%3`$;(^4d*{6yYU}}p8oqd~;~L(h;1;OFM-b~<{!6Sy zAs>y!S0_k=w~*(as5878s%NcL?h{<`&JUg_txp6nM@Edc54Ir{enskJ<_**IC`H%B z3pAvqE?t(xbRP;e793Z?DtMv+!qMb_c@sz?f?!hRERs7ku~7;i1^E<@0D_H*7J{W~ z*Iv{G1`lHq8Q3jHjZ2>Ii#P(I!j7_8d)IpzjIGivJ#bXs++tn_43Y7?#t|Nz1B84M z9USLq68cmylDEyDFPYj#t+rB1>of;myjO#-(r~PxDX&lX94If<5i~uQj)SMlDqO76 zO~d&;9M}6Ni_N6mB?dPMrw9yEG5P2jrh5?`6&keGQEZJ| z3uC9xKF8h&Jlsv!w8{vD>2j?`S$7u7aclR6A(Fzg^f-6SQ65_1YVHHkw5xj`TJC$K zh2pqw%W9&%*o{Sml3HD(@%VP1qLwLLc#(G9XhQBxu2?1G6fl^m?oj##qLrC<)4j3U z@8|dw?|VGOd~w#q__@Y~<|MY+0^HTJ`X1DJ#w~-9Rap{fgtUZ?qQnqLU_SCIVHl{P zXoDgr{6)C~$=dFVK(GuH0(a~dFw(a($i4ZQJ`X&+&t;d4VSyu}se3|ggC>!kN5eLV zuh0&`eYF0}@6b^F&`|(--Oeb|fl%@iJYmQS_Z#3V+A8E+DvI3?h>}kE=H|`{EXsC6OyfvVK%Lu+J>T_+{I5>+}iiUNVX}Su>7!E}%Xp%8b=;xFCqN8C5If-^Hr@MzsA97=+EoMHJG6D)jcy3as%k;J;ZAtwz0SgM7R5O1k8lkUOq2k|pF>;Z zhf?pFYYlS{?wCm-p@3fU=9vUym=CQFh>b2dIg#J`_?%5r10IU0 zqwH_TOgX-~lT&=(9k?Qt1)A&HJ-Y1g3$)707o57*Y3i2Z=^7nQ*5+ z>Y)%L#@-|!SU*2JAS1XE`LL|rM|d~c>4mu(5yIbYvz;pjwN*QQK}9*Kkz)ep1}Kje+P7SP`eqc=m9}RpJ}+w4B7zc*8u<jmKTVwvGRbeGe4b3lJ37Gvl>TOoG7D^MiRYc^7$Xd*0Bs+0HXL2RcU*_>&5u_RVGg(pMNiUS&xB8>u~fgdH3X$1DQe zCwGITW?>Sz<%$o@P|8d zCU#wds{#Y8pQ+0g-lzW39Yt;B+=kMH>0W38PyV-4Ukfv>-}{S)Xv5TbIFFk?5Slv$ zFyjDewci2P-kc_;R&YT~_cS^^-Vh#C86^!vz*{7XT$2|+n5H!>5s^B_6JF5^-!W*>`%>>(d=m`eT!Ju*} zN2L>S-OQl}A6939$^{d8S+iSI>%o@Lk+nsiB@~_yUGX(hj1wBoH_c0LyhwnN0JC(- z7k+vwwG_K$%@0WzMs2-{v^hfJ`hg7J14{1=R{VGiT~Bxx=+uwiEq2nBHj=MWN_ zrIfi+^N0qAu|w30%q)?wT&&g|6bcr)GDu(9PHGgnmlK!(zD$!L3ktu+*2fRChwJoO zTCmT#+=lmef0)}<5qHFlcixqRyZPw^o9z%*EQELF?izaZZ?6WFJ_R;e5_{~acwJP7 zy`Sfyl7Bs2Zj{SMom1Q%59KsH8)YAF|6pG+V&{H~kO8eE^cckOW?hm>0f)KpbI+2O zL+5=-8Wh;*8EW>+&ACVbEKny6mV|!<+|(GI>gzXkK_eTre(pj*dnhh>i=`#3{|em0 z(@3QOwf)v)mTn%Nj@H;p2qa5$0UC|G=0z%}>Qw$a*?lc*D~;q?!30A_4ZO>Sg;Uew zkMyYt0`;qO^guBAm_QZfgKVpWu~|VtD9wOv+G7~8e}jTyYvtTca_O5AL~E;rn|(_o zAUUIxyn3(94Q$ls^sXZ$V&uCdeV?Bik}R5~S8)R89PO7YVTx~%0F-cJ^T|KvtS>Cv zk9TZBT(Z3{T2Bersn=X~A~yZa7W3zaO4{8XXI!hS!wiUywC?rutsKivbmvl-OA=Ak z4!eTPC@U5~>r0-ABDj7*U&&suH#y>zV5DSesAZ=icj;u?+G6QMfJGH8DIxCOk2hzQ zFP{CfC)jayVS}d~czBAqEA;WIhpge6g)PQj!l?snq*jmVHVLb8}X-L$^Q4G{SPVPM)j)r+#!f5Pe`gOYm=4+p6Z`P++3 z>7BQ=WZMoo`b2-wBW#E>2T>N2kO*8pi#mddnRf5Qv`y4Eus7-S381>U_%~;O z|1TiTDC0kX8;ayFAT2lQyTX5fG&z#IH_l${o3)MFWMpLR-+T7|0Ao~Z;v`!b#R{RR z#d;Q6k>Sx<=bOlmCAL|d4H$N?>XZ6Rzvnv<1RJ71Z)k5wgo#mxjCbM88aIA{Ngw1U zD2V!p$QdRijSQ-;xw%`Vz)kZguU{@v)$X_>(M6(}^0(x|6EL8zGOT%kv`_q)cWV0v zfog>>`&OEYe_%Wo@JyJHJc;4LL`SOMD;)p}`3s{Hc{^74M>V=gAZ_W6)o&&Ki^my5 zh){u`!cT#h`~RYXEP;u?pu9vE#{bIk38X>H_iH}9zemX0MlqHs+18h{hy6V%l=l!K zG35O&yHNKB7ys!o01c*zY!<_1*KVPXCu^d~@pmr)umQqdtv5je?nJ;MOnS|W*+1)% zEZhYPsUI&2AN0Sq&D*cFekx_*#Bq3Fh~l#So2rA0pM)Qo1OigTR1Aewz*^P;@Ac z&GLUsc7_k`v)3p`OeXY@q~y)LH>|GQa`Pk^1rLV@uATD(4wGZahwN|C4;0{SwPz=A z4Il;CZhYVJ*&8!6`DfsXG#HNl)+o&49Y7dlb%kvV9GR^k=HKeN3l&ytYXt$MBl(-6 zf0XY?0a_1kLsxtD-&$S6{srAakz@D#24F+Te?hnBB`&FdEVL7}9>dHy%_zT>OG5B# z)j$O1G1^j5K%CP~79Jr3DPp80V+oIH;s|ERO+-l6emaE{ z<2a{q)o8onrI2VY=HsnWf$v7T&&V|V_LLo!5LGh2V7h4zdC~jD46IV=Wfv=?>mm7^ zW4_Y;&yTxJ`R;>7v1|&3GuqS=)*Im*+0yyLW~cs{N_=#;EsRmEEO`NV}bUnslo^G(7m8DVrzB&ts449 zGp|EOriRH5JvX21YW%Yo{TC_h2z1s!7P2nE-!3VHDiHNq?SpV!!^Li~C~i?A0bg;H z+N2s)9-rOiThOA9fmH9j)2;VQr-4x7ifm1eL28h= zW1m~N#N8{V(t3U*2qbUWH(pi=y0m93&3QC5pi8oT&7DW&d}_b)wSI0H*qJWaShiN9 zGoR0xOl@&>z6&pY^I=4ZopZXiC%cu^`Rqg3w1>j6px04)!qrWC?t4C@l}d779#=E7 z$elL%tbVk!r^~W_vbB$(l7tB~7;&peIrm9I*GnGXbRbO~>RiIh^5TSV(ylfquHw<4 zrDo12P!2ZEfGgxES`F4oOLAGnd0uN!8H)bWeen2Zh;^pJAX1zioKG1i$bBjK^rBp~6WNbXhCez}YtD@dM;b(p>&oV_|W3at~>?)-Qy zS8z_o3`C{j-zEH_;NDRsj&(VaIzp>M!(vI8AR*97HSEjmpCT8k=RR~D<0=PW6a;)X z7EL08958Ve8-$s$dphF?QgyouVX8AcdX%gCsmHUvhCn{z?$5Jf=F48LOqanOuvvr; z|359X4h5nV-VFy1J|)CB-hcF`th@dXBRVyDS&PZ@1a;p*D&$)^3&r%kN}#@g#jt(lh}j!YMtM^M?VVyaGjC|mkh(3amT zPqny~G)mjimXkd-!1l|*PE|6OsHZx6J_X_e>4E}89ghmAv4>rs8b7!;AAJ)~BHJR! z2HxjLA2VaH4H}|ysD<(cWMZ@+W`o5NB@ageDf(Vn!7U+{>UT$je=W=haL6o#rN`l# zw~T?J94;!=)x^s_vR>A?v-bXe)!E|3n|iYD)6hZ~Mc?0!EN1G-V=r^*(HLJMQp!@6 zlvLy|A!0hCYtlQU&%1cd%wHlo5!H_BXv&rzw5(6`@7dks6o>hsuuPdxS`Tmn<q=r8&Y;bk)C#{BFC;&@Mk8&Waa~m@7ZsuuJ18v$ldP2AI&-D`c9wWdal5Jj5qtRyiuSj}?RVBR!5Pim4f~Cn+8Xw@L+v+-_P`Of3 zf;W>JZ)6fwD5upsz2_xl>1$vYbfE?)tUm(bfQc+fU z$Mt^2?GVGkY%I@NIbSF-CG6Ydf+-_&TQHy`dc@P&DH8gk8?2fdDQQd`a3Y&l)e72;*z>CjqN z_Xx>`CUN`NT59IuNu;qia)2J2^>y^a$0iWpqlNby=*U;5DOf*`X{u7+!gaD95tk4szUQ>UQEL^cO$kgZVt<@W^m|cVGR(6L+RMp z^Ecd@>+pF5->WTkR@}%DgOur-Uxxz~m#u!p1*BLKSRH>L$`+8xK1wzZ3cuVMb|`5n z5FF+$$Y&jqMIC_)ViJVhuKTPvb}VJ<0qgAoW?rSNJ<|dMb=efmCQYk! z7PpX6^5A@&lijDO*L%;5oIX zqB6^z7LZr7T8(r?k&Ohj=fGWV)4h@}f%MyaH_}3M0Q>`pP9{h&iCg>w|M28mBq4(d zjSsv2Q0AxHsJdXDll5E@^0z^&F+uP^vXJ*p+r^<*b;)ulyC0__z;f>PA&3hfjV>AZ z!5Ms#vEBx?kiHM0kGB%9a~J;*w#k1N#14-R;|?*V6zo{oeQXIKpCtp+b#ResiG>Ow zw}4na;3t0{6ux=#Amqs({5aTW6MEN^j>Vy^mhT?ZqjwSo-a9gGog<7m6 zj&Pic&45s-FA!n{kvtbOZH`qfSA)_d(MTc0GbaLb>u;`Vsxqh;m~oyPrL=>yeD;?E zcItNQ0JW~x#GvXRQnD7VpbCj-qOy{TYV|#3th7Fp_TW{_7ARKgOc}1r9bj4_Y#j|m ztxzXR(eZjkd)CIz7toPrEf%b$uplbl0fhGsd^cEegv@BYV6|fP>wsz5yv)}J{g2eV$B+`(Sfj{;;65&V$MItejgZIBf7|>}K#Q4L|%O3P}{5OQs z295qMkz^NSSieeV{~A)b7Rmopaz~byEenYgOgz(5cc64b7D6X~`}WcU@GiF z@^^Q%s>h3ks&1NClvI>n-)Tu%10SyT6+ktd`5L8~DmpsN^X4IHA7kh{vpESLYc=T7 zn0OoiN@+|)!*=0?{u1d|4(kT$F|Q+yxmJ(sU_~IcNW=F81n;WI$iOBfCQhC#Yiu;8 z-W(O@?Cs5A;N#0VZG=^H*41%XV`iIUNMLMXE8DLuJoE&$X@aVcx7fY>Tkf{x52h^P z=+#$pHwpe(cnS#REaQkEG!30Z;=J0qOsXx+V$E`0mD81W8iDp&mBRyp**YgPQcU{= zaSaWPZ+@)_bLDz!yJP7zxpLUnglea^YRXj^&MucnHBbP57v($%xB&Qnmudn6CIm1~ ztX>N8AO9NSUjwMd2bp>3u`VD%SYDWq zBzn)_IG~yI5f6uM@KqOwq%5#gMIXWRH2Oq63bf4yxmA$U*8dDxIw|EXZ?1IJ|M${F^Jw6OD$E7S6g~Y>X@v zHZlRQ_ahKxpZ^oYYf)X@%{SU0%+_IU(#k(6mhXwbmNGf7$y6#75)b5H9@@MEv(hp$ z6di5DY!@5S>F5Y{k@}jO{>eXqykD02uZ4v3h-#Q|-!*>^fKAqb%Y|qK$Z%DBFf`1l z9{V##|_vL`eOwmScbvPu*YXJS=(N>(Dt z)bpOxA9H;BU-@9@Ay{Q_fj>-e`txsclk?;wV;z*@RbVMvdq_7AXxM(Gp5x-MQ3UAW^zez)i-Q7_wkoJ{s^!V2SlEOQFDUpl-p=w(3_i? zkUmP%;{4vCYv6&L`;Th6o$UFlTO!Vj6v|y^a>t(hb_Op@cFbueshk+d;(yiTM`DVl zvq;EGCNcFe&~Wxu+ATKp@Xp49>T3s+V78K9%#Fvu4$@YBsua+;ZGIEgt+#%sh^_v! z-o{dSeD`>0V*~w9x|l>BCJ(tik{78hAjfp^zPz8N)b5){WUN9qVe0F3^OA9=k=Ps= zCgHKNR~=6@r8Ui zgsz7Ofrx+b%tTa+2*Sl}?~^3AMR<{?jt*`@ZdZc-A|vG`&m26sH*~z90`l;o zy?S}^i1f|Pp6bd~D^^AT z7go;?h&4{$wFHC(kyOI1VeLKb#Iw=S&4BM<_vOP;RxvEFU zc01-rX-~Q6>Ay}ax=i4A;@!>sKhOx7Ex6C8Ea`rn&VQhsueOv=(eSXW3v1i=-$$G#QZOhu zKRE?TZg+{vrB8(4vDqTkWo6;6Po_tj6wOWFuS8QL7L3EXiLud?r zzwLM51S|wC-lNec>AOKmNbpdNWZVp>>$Z7h`)La%BMX_bnVY*O%_+OCp8TwpqPf=F zFC^~34kqX1+vYh9ilPxT6u-Mxc8i)Us_eXR4xZUf^9HAkOnPI8@~ODV!7p>m-j*;3f2obRc7(@KJ>VYW%R14l}|Qb*KrW^3Qz#|7+CH3=s!i+nZZfVWfd zO-v7xA(nnFwA^X9a}x{Xh`8E`OlW% zagbPMLe<>wXP4LEfsU|>gyNZRa;3;8*m*|V-P@9YK>;%`E_(t`xf?R-tyspF$9 z{(sE9V`F4ZyEdH3#7-tQCP~M(ZQGvMw(U$jv8{>iOl;e>{q$UW-`Bn0fAD_lFWt4) zs;aJ4=b?g^;XN@s`R<`j4<#wFKap9luok%K^IpgdRq~$OC|ol>_#)B}vmyq~(4gEn z>pqpjW-WpzpCS*pvb-08+Ik29Kf)k7-_u)fH*L7m)-;GS2rL$$L`XN}>HSCqo~Dmy ziezw%ZugYriVw5g75gbyjn0&)hKDIERD5`_aSXu`2YyfTY#wu;uavp%){3c<&x$$RL z!lU4t46$`HiFluqAW_6_6dmSN0FpqG@BN8~CY5h8pEB(d+_A{m;L9atz*`J9Pe?Mg zhVZ8Mt#e>Xd3kHv=qzxIB*O(c3-8LDGhE+-!gqpslYUG*t(F4bJvi{_t%Xw|=AL#p z7DnkaW&5uz$-UH=%(l9F>Q%;qUwU3Ine9@pl2Wn|D+bT_RPEAisz3`13b3i|y~hJA z?Pe&7hhGOy)HOp9g7m64I*x&QJUd0*vB${g%SkkxckLS4(}bi<8S+f8^!-hrb~oPp zllfm&%_o{3mzkd|Pfs(W<|EF+)Q=)aZ!dBFtLAnGv=I?b+@4oZWhD^>wug;{&RTc` z*c*w_twDLjg+T1Nh~q;7_9s;$0H73yoy$#wB8i$vflh`b4(c|YX}3e6o4phDdx91J z;1AqBn2(!>pSpTU47UYLgSiqLc>JPi?Svnl!|yGFHC~$W_O=1*K#B@KqoL?W&s7Hp zi0L%b?9)ewbu@N^o$tBKQI08Nr@NgSt65o4BYz50^h~&$c*YOSTd%*7g}113xu>s* zyH?bQ3LU$U%e&|s%p~c!x_fcN*t9Fj^7KiB_dn(tT}e*pjFT2EK|`@R_WQiGvTNHGhshFirwEgVUMQL|_mHGcrEvEWzZF z8uf=03VVZaSCG4e&Ot*Iy@3*B{+I3IO&pcNES@@ZnTr+Cq;2zqu?lKzPAm5DY_`RG z>RNkyVrsFvcyt}6rv&AQ&nsk-<2ay&Jx1vI`MpVRkG0e9Uj0W}+Hw#^DT)*1-hQRR zubcedr4p^<+2U;Xl(j*3pSKULQ6rg#+w;#318<9Kk%;Lgm%JN)$H}aYlF+A8M4CMg z{WmaV1QQOl$mzC?KYFtts5%xcs2Dh6>z;S0`wvd7$u*6ByBW(5(}^nU*cpo=zwB(= zZ)R@mq&S$UwEBl|B-a_4qKR=AFigu6Im0k6$O(LNSTmDPvK&`Rt=&9rEj9K}S{p3Q zSL#c5NHIxIevzi$$1SKPA<%v9#_+}SzHRX|l=sYF=mNklLzLwBlr*F65fdTEr(AM6 zI$rPQAL81R9SEqrds~A+0G1g&^enex~gw4*i557^FN$U_g?T*zCN& zpj=|Jy}*5WE+*JBz(kJWcyP;~D3J?EZM5op@lXR(kyWB)_)<&faFlaCmm9r%>2-gA z`SL@St88U8f>H5tDm;ILqRN>DZ>lNaV2@N@rD3Y79chkYj*P>GQKU@nQny!GYcn`N zT>+|Mc!nEV+xZzBj1+38oDp2)>`Dl+fWY@-{gAP}(DlebY^v4Sa=&juXQR_Q6Ai09 z;~ryWjpO(JS1z6QM53#ACBug_##bpc4BNuqXdIOr2&r~JUOt|W7JIYTvf|0&CWC-k zm(N#VS>Z6B3=uu+QsSjftJNypc}3fDCb?`~p3w8TUrxuT_6wgTGFUF2632(J>rL9} z#M~66RX35p)V@%>^o_EETxyMgE0_+>_&8zU#`T&s1?PiHUVKWY-AL>mRy`@Q2evaq zY5(zHL)Cq*F3&L3{vsg2Yy0t*JbKMG@yt-ge2XM37WU~@L&E3;A^6ZN*UamBnOs$b zZHev2n0m3d6gpj=p6~PU5~SWRMz(KARm+8FpI}fdKo6B7Guj?BGRfyFu5b29oGt+% zOb>=&;+C#m{Y{6fwVBiD2-6`#S-b3(Nv>gFo{`az0DjmZDuJ##szA?_Bnj*cU;nd9uixPUEp_LMJJ z;tiMx6ij?mULs&mtAmUkogxEPud6uQzR|JY3%3S|9dOF%^CnDg2_3Ty9t+9pqvv}c zoYk&y+7}wje6uUSD|B1gvuMS6P+;W`D$;+Z3`dp3x3?R+LC*e0DIqS7s!I7ej#D(k zLWe<{aalk5^8!!|hi~KNXzQuCcjo(#c)PY~^*vxiGp7~b%$q zid>5;z^0MT_Qh$4=e73~Y!tZMhACF9HAt)F$&1prK3oy1@S@n+@$CG`KWekp@!j8p z9ZjOWLTkAQ`L!?J@#cKGXGR@GKl@H_cNeX(m=u~sr79k(*8xu=7L!-a>S0=FF73Ux z-*9s%h#$rJmC6=u0lPgB4a^dJ(xcih##R?c3m^M% zXEst%x8+PGIyN;hGFp2|G3%qp;Nr)|kyD!%L4cw+^C)!%z{OC_RqfHQwMcTC-C~5H zzB8wL#;|xI5)qm`o$3n)ORB)Rl2nw#Ks5vCCrw);jb?Ka$Bb(Sl zR4_(nrYb>C?uwdy%$;+k1{5Fb-;_nlblMt&j`ik*`%|mHbv&qP0{!Sll$8JqIXt_U zT>#T5LJmr})vu87==P(@qqz@DjVMkHZw&Wr>FmdZ#eJ9>Ap~9pS0Iz4qe(k0ynf&YjVY z%0t(NPF<(lAgrNdWA<5Q?)*m&YPidxw1Ph;Z^#RZT~f) zQ8)ULvdp!XsqBbfeGrW`NnQ@TGzDltUDbG?)e`0xDn4VHTIZR z23cX=7ZRIuOV`YvvmSNg)uUeYol_8_@cRWzVo7EmSGAiM>iit%Mamh1=aCbGLv^9J zJhft_me}l;z*h>&75mn*b(MOvYs2Ccb*V2S=Y-2FhgH9-DUtxr(Ob87(NH0w2D3;U z+ASAS>V>tMhKU3|^w)^k+`=)95>lsIcL6~x+o`)Twp*J;ZpSD2?ebL~rKx%^ zeFG&-?LmS9NCd-_R`Ulkoz5msXGd$n1&}RP(w=Qj!*(N`>jTCIosH1wa8x~Jb%=a! zizjhwkcHqr5~>MQt_Oc0m3r#2Skr?;^5@IveZe?J>NP%V{%UN+kVJ=? z%;M>)XzcW!gC%zogzSz4wv7tm@v>R3yrQkkCx6f$PC6%{UdcH7AfJ7=USCJQ@Y67w zxkRZ%q8p8(9SQ?VL*DyI+&Vh?w0B{o!@rv~BlygB^3qH( zcL(8lbuff~41 z&(lfe*6R{tEWI*4j7u~M;AZ9fR)lgkZ^wX8O|(^01X^Lp*HCP@s#srWbqXc+KnGF8 zWTTcg)gH=V3Ld1jnIuA(Mi^_qQri)-yFCZcb+(J~O} zpxgPi5;9y~G-MY#LAPCZ5PRmnd(bOIA@ws8f1m;+ZQCCrs8MumR!2rVeC*kZc(Z_; z?~HsY(GWQQoMMqwe}3qU4`hP#uwk(l9&lcZIWeRRV1CdK78simh9N9fTJ<;O47Min zE25q~3bDv9Gz^S~=_=(JMd`iX{*BwaQqj0kzrz+T`pn=v}JS@aX*wdl(C&*SfHDU8#?uQNF#{`7;1a9dKl z1VzFHXRk$GK3*@y`OqC*(_$cIjrGMF69lhKU_up1!ypT^az{o-v4MJA97LrFKu_SO zrP5o$Lhq2_$n;RzcgAirDfxmeu7K{ezL4lRr4~$hRI1-U#;4diG(+p43$b9xK^af- zUNeqgaegD{akfo6M^h}$wgda6Y9ufqz+43>Sm*PV|BT6({jH6YO;F_ScrjMr+L`qB zaH6m;HpA+>K*<+7u`6k)6Yu&WVFLogT5v_iRwvRYR{{EN{l39_+3OP|99aql@j$=Y zT(UOFWTn+8XkC?Zb$~<%Cr8L$1G-WlAyTnM-f2-(X_dL#SjIwoG_XDa3I@xN>@^R@ zGQ~=FLRP3nH)?_izUZV0o(f5XE2@1ZvDQDxcG~K(Pz&7e`kYA6Ydz_krq(<8s zI)*NK%b~nJ_F8*hCZl@HvwV2svEAwUEbpQRPc0x}7dI zyMrIBBCeLFU--JWi#Pxoce&o|Vm(t0n}wFTrGcUTxaDM1DExfmpObae-bAqHAgyE6e=)qn*D~)5(w1yO_BOl z8|zretiCWfYC50&jODe%-m#W_+(q1+HYJ{b=S8RhLp&acM4zFe>mtkyuAI@|z7c?4W8g93OR2c1S=a&Xr|`Me%0^-KlqRQU8_k}AuyErw>_^dejCl}iGR z#FA&Dl_HMPNgAi_e?|gwCy>2gM*1OQjxI(X3u!M#?uM@ah9cd3lpe=2g}P%ElIE_D zrzM<$-=V}xH`7Q)v{$+vH`w#3#;MJKE3=W93d5OC%oR7NO7{M33 z0L6_ze*x;prcs^|l(R=FDn)!9^iOh_hv0`s@QVKf2$TIo8Z1sPd?a0HW?*Vb@o=3N zVIr%+FyzyhO=4*9o%*ck9xe0#1OoYAFRU(L=_mUBg?xh`z5wV=EPZqK&Pdv;kjN-> zYiKu4y*wZ?R+UI4Cow9VAL3!q&3O_3m+|udA(>ovdBj((^`NCPNL-!JcT z{*P`Oi5P6*^Omqjjp82^JeL+I!+k;9dHGNF64Vz^PuCR1k2|ga!?XZWn8RKUAst{F z_f-A&|EGc7@%fzcAI##1s)9w z)r{Y~>76G8-T9~%2)^9d?f>T|L9AZ@{7(blP2>$j4Ny~7xJp~=)TQqeghI+Ohra;G=WIxf9R^3?;yeAlp-y9TKKl5T+7St zg}NFx82>VeNOphq3b+i}|0@>&Uf!$}C@N{rGSz6#$UOP@jlhWvx=G;TPvqKV~+am8&zU9&)o{uq~}kaqUf-&oInJQjF-D}x#Jxj zWHdAx&$2Qz;D(C%a8rZX^ntp1^v)ClXqu5=f*a|LwB5=f5|!HhhH_LxQpBto&j@2B zK-CAtK!8D8Bj`ZJD|W*Rm_bllYR*7&wn!J+>N4uIoCVa}w4SW|0OwMO>%M_lcshB4l9mQ|k9Crhz1RQvX2M|<> zJq7Ea6D${g67ZV-e08kWD>D!0tJt`(hj=v$cPHmHOMXI5PL{di=P)?m<$bD95cze& zN5*wzvVC82dq7l6fwkH%1nwvLl}_tlZkP)MLc{>YCm0n)(oR8*ctvKnVX!y3t$;{c zSH(Opj<3|BK*$+kAFkr_=%EmIujTrH3&26D@}s(BiHL7y`(gUG8o{$wHbsT&IWe+k(UJg!a-Fo zN-p710%c<8cLvZ(9f!KkUsv*e;1KJcCD|JKJ;zJ6OwOZYc?fu1Gs$_xnoYEF)NG>{ zbdDb0I2j(Wr)r)(uCI*_Bj4^R(e*jwJikGL!V@v^RaeLM@6nGfb;a zk2iWPqpWBs7$mLjcao43kc=vZPhFU1c@*@p0F!<&nckAY=QNqa>UF$sxDlYy{s z0i__VeP$1`qNZZ6s=P$Nrx9p0x!>Wuffz0+Z13h9;-+8UH(vmaRXhyq^$#!J zH-A9s#_!P1_XAkYiy);vTBmb?ZT~zYQu=#cmw^U&FN-aLKn2ZTtk%GgvG52{bC2ie&rSmlbo7?x&xwLb-ee<0L7sD&kLx_q0e6$vrfjt}h%CKaZ6(#WdR^5m=VBNH&A)-~?H;59`Kfi3-rLV8Ac`+hP7h>~54Nq+OUbP_@cQON9 z$7!#LREc@vD!~Z)M#IGteRL?}hf;_$ef3&5^L@PN8JmA3K{L3Mznl%zQj7*}0$ z)BA?x7Yu@qNJ^zf`;G2lIfOX)eRojK;l@|NytW@BJjsah!){29J&x6ua_%S2DeS>` z?oV0XK6!e51_oGajv5O91r-%bB7oiNG$K_ppAJ}DiK+*1&fHG&=3csJ@~KB*O3YFl zz4XMtM(0}h!ra})ZXUPs=<>afIhy~OLT)_nIRY+W=wy$|FZYK888dj_y&|^=^hrBB z9&>M*_s1#WA9|RpVpExm`?dm@f*qbFK6RN0ENb8j?-OTF(Dc6ZyKXF0PRQ=TGu|Ko zU#;m;AXz`LuwqOByi4?glP4Od65wi8>XJ-FpAx~nigW7M#z6!XSCR`D6-wm-I;dN5|#G#}%(^<-` zZkO=Gol?fHA0IfD`@!I=1d@s5G=2j>&7dwL zg|@KExdZnj_weZ?v&>8b*FCwV@s^7BAsPBI z#Qh)pBl`}XRZkuYBQT<-J-*dIjX-pppzvQC~HHXA!>0P8VUm|~sm}VT6alb5mGtqowv%8W{ zDLQHjYVlm28DQiIx!?2{>KF`Tt|w7pH}9o8ZqoBj;DdX`V_if307;uNDMZE92zx@* z38vQ(>fViB)GcUlXK}#!{F@yKf%8;+yk0E7;Uv(RqUW|Ek7RE%*CTu7%C6d0Rk9lR zxM}iMx&7red-Z|{P#sshO9o>)F?k-5Z&}qLGU%!REsvk5st1P7+g}K}7>e&b2rwK! zQMr52s>WVz2l^8EccC)8POt_y&tES)&=mb?bsFF%>Dsvxz22tVELe_4$!f*#fwEZL za1@B}-soV%xe3s8UT=u;G^W^vgG#118RC3mbD+q|pwc3t4B|Z?Xb1XQ@O*`3wnVe4 zh8|!U!-2H&CC^h1gWZ~>3q?Jb_x;J6gpV3v8?hDj<1|__c7FtIbng#hgKf=$UzoS| z%L0`~O&rCc8Gxl})1%{>$u&}7Tk)KqW4+bHz<`2E7%vee80_ih*>iuWjs42$ToqdmYI5d`d?ag&*s6ONS*5_`k0zV)xamGC zpI1XLaSzNYY>XGCj9dY5@A9ulC^pae02W&NI#(v8fd6H|K#(kVAbpaQ)DxQe5d|BK zy|TC?cpYEb3-mZ{CORXwij-Mvv6C($hU?ZjrCnv0xDv1aE>3qjTOtyLLz}(Y7BX?w z3pm<1rPjs9VYR9+9uWf-1>qGgTZJL_7mo!>BmWz>mKRIj0_V`pPQh= z#p*OT1RovX{owuHq_B`M5Gjn2ntzG}1DmlJkElw{BRegPd^Rl^*Xf$wIj12!AR{iG z7?XH?4J~^!bR630=dZ2Y?|v{@rNgM&hWGdwe| zi;0a*j-8$Bg-@w}%0;!nNw7zYfK)W-n9<@+9hweM7Kb1tSK%0;>nlbQ7fWIIq|ssOKpu`QIgH-%Vb_I zW1zmEzEHUP3}cudidm9}vJ<=}Q1SYt!NE8cE~DPdJRY2QLW%mWpj62xoDGtZ$f-sT z1g1`Cete*}9q-AWV$S6^ZUn$Boj;LZd;=6Y==1*JWvL)0eR?3S&mL+o2mzD_W0ud& zHrb~FNG1Y{idD z-Qs5Tmuvk>lAFtAXT9J9$Gn&$+26ojUj`aE*6T2FZss?>1X1WhHH^&6PJ#tG=L*IC z&AM;wr6hIqtv>fpOlBk%;mx{#<;l!EU!L6Xb=l;>eOG}5Icn``MxgCUpzT#H(1)5z zg-H8NhV;r(r8BqWQAv*53P+VR)fujpm^5zz^W5>!pi9h8k?xy1k$O1e6u7m?r~PgR zFNUZ>NfjGd;vBe+x2g}4s2jG^R-ot8TPR|^e z-5i3r(HF~eI@eKrh&cH2on`}N0&?i3#qlFI8fRg2wolTjG_1=c8CX+E5s>ZsLX@Ld z_#d>qIf=|_i@LjWm{@RKc0Ia~6HuJTiIrb=y%tGB>VX4f%Baw}w(nvHbGf7A!~h(~ z-=F|rg5cx{%-v!(>}JntCqwC}p0=MIPRAFUrEy9EpWIXf1Gg5wNF_#~VU{?0Xja`H zRu#8+ix+oV#j9vwoJE93M>Ej6G+brgi0BU(UT6Ak1cxfp%VC2Wru(LT2tg-q81&)! za2y!a^bLe@vFDs7q^5p z2_&^%o!2s&=WsT)67~?QkuDS_f(K1l3CH&Ug-J@M6etwKph}eBVsQQa&;Ojx`?)kI^lHdpEo?+eQ7U5;xdqG#Dxhp&N5tcDLHg1Af>DFTABu4A-+1SB;Pk?}5eZebB=MH8@;&?_ z5>P5)yV;o;(P))R%y2Ghea_1RTfK_ZE$_K*3(1iBW0~C%BWy{M?fsB8zktDr{7>$s zyylgl3Q21Yx1QJWJlHAt&i9^-sFK}_)(3g|jFot?f%t$lwc&_;DR^*+^V!VmYvRy+ zjv{J5es`|Z3|QqEKWYPrMU&qCz`Zb$!av)oRbB;+wwJ~#BO@0?ff*+zN2f}@p97_^ z@G&Qd+)rRVbTIiEcb3J6N~d8>g+n2NTS`~{g2iBZew?Q41+thneXHxf2=&5u>?wICZ=}L(Seb+%1uC#q2DD3X?^BPm^GK8Ir zZ)0}>R4Xxf=yeqq)*NMC5^jf@_L=~I4L%>AJRDhiSwlm#e6iZq$r+Q2T6OC37l|Ng zYM>i&kYJsi!w{WNhUfFmzF{YWrygQtUZ2C_7vh~}+S`M-av-Tk;?Ph7!;fb) zB`Vz;`K@-ICWW|AD&Sg}so2{ZdaSf%>I6*B88NDXF>$>lTFjN^y_)(tL!1P-@MWoA zEJd>Zs$-T4&_o=8mdeCm;3rThHAyNDy9I+yWlRZ#lzx*}+;U4N<2AmE_rFqL(s~~= zIay8p3QI(ez9)rzeXmI8?qR}8kf7zP;@>$vSu2n>!<;lZJ5-fPj7Wi*uB_5Q099(zSe?^rsYQVEGR~I?Ip1p7=vv z0wWuLxZ~qC{RCnivR(iVu0cJw>wR60=gIVI*T9|Wq*6J>b;2)~K){kP2TWPmJ_9V~ zs57G6f&Mn&BdeRs{3dbN%D3i)Ef`EEUXWz5Vi--Y!$cIwo=adbm;?A4Wm5LEq8jq$e&^kh0(Vw-`v8QJ)E^LTd!<7gr9pm>v*J^`)qaN+9OOO z{xOsQ@x^?JM17yGfon!_Y$B+jlkCJ`3f~Q`cD3Bbq=rpJ!cOLuag&>N~ zOae0}K>3N0FEvwPM)QtdA!toBAAJyrxWeVY65 z{`AfkL{Js1A&(d}DCBRNap5nkO)PN|} zajLpGdHQ#)%<}taGP`ezSteCZ=lgsc--ot5c~iVM%^uk*!@ZwSHD9Mu@m?#uef)?0 zus{hVGD~|G4stw(G|8XruKs&CK+v>j)pr)sUQNin;;%IOd@nlD@i2-D|bAc=ou!sCu~i*T+e0c1#Sx7#1M`&8K0Z-@lo;AA9u}tVx<1X~AbXVM<`R?X z_&(KNn2z?3P62c>Z&&jCc#=|5cYQLQF{fdKxo$PTiRbrH0;!M=z^=wnd=sKSwC>b6 zWSltyE=UToBU1WjOhzf#Y%A>$E(zOi=fZN}PuV2Fiv`tDx#Q;^Vr-BKbh-=z3sHiN zp9udh)JoCLO!=!xkRa4!>|)+qpsNTZ4$I^|@V9{;9sICVjZNMHn-E1pwVm!Ru?ybRH4sVX@KEZt}g zxjMc@jBj!N!{em0_>(n>KL_eYAAFCRcB@J(1+&)%R~v#7w58VjD4|N}0eh1G$w&M2 zT=dLnk=wwO}aZ=J2_N`Y$xk-~7!CIbsfIaHF6Y zW+-S^Dvs$DSm0F_1X??yEiXzDljHr>Qu(1!_{~72IY<6CTc(Fxev=&i&GGd->Sb@p zPJ3ula%N^F(l6uwnwHhtA;#7yDHLep|9gRdP6z3Z;g75lPfD@fE;gP;729B+@YVd&0lSk=ZCZB`q!bth80i>l5F< z_XPYWC-X-t7NABwl%B(rS`ai8t?jr)SaC%tGI`1$KEq>LMm@1raNUFfm{g;y=+e+Y%R4SlntaiQBt!HD5b{U95>hhoCUG`w?`m-Q`8miZp z_1F6p9yg_&{K=G5^&H`1t9OWkOYmQ^2k3oNC?F=L*D$vnr9wwTQ(ROQPH% zS1>vANjBHHK>bZ8nA=-ze1BN)er-wn^H$*Bhaqf-4yym_?4#^M{~p0{ja1v7BwwTr zT_JA*Ee2z$Os+P}&6&J%>J}k~BOL6QrGJ_z*3bT*cq;!Z5+vZUCqNkeWVMOQ`6%w- z8t4HS$*~R}QnD^*kG*Y{3Zw0+xJFd!8S^ZyGcIl0^UC-yx5NZWg!Q4n_h%bEvBbOA zx3sl&4rJe#Vf4+`?I`ds&MMR?hM1~a4kuHpF&bsmG;^a5oGW@se{SU&9ovdJY;Ab z(#FG_cO=J4{oN;CXQ4#x{UFC>v^oznp}~G>t|sw>`R}AgA_Gg8j*p0pOqy-(A7H~Z z!N9|l;ox{TNdY>7%KPhSSFyEY!b;pEC%Ef-d|bJ9G#6+3Kkg+_XPPYb1+|#a!W?aM z?<~}X`Kv1{3r~1FONxpHh5gxpJpo1L544X(pxfVFT_1-F4}4b?Yy%qlq|hhXCU4vn zX^Ww~L0=!j4HL6nfP(cn{z|6_78>oR zXd~Csyjen5O@F^IHmel?Sd9y&^a%I13UL^U!DA;1g^`#f7u-!x`Hi)$+YmJAwYXtI zi@8iXlOHk;aO}5aJ~lSf02JDS1No>FXf9?P0@I1Uyy5L!BKxLXfJrL1O$e1Zdr?v; zTDrOY=e@`_ixk<$NTRNUdgOPQL9TqWf^HRoX_f2p@s0-UW2UA2 zN)h|TW}Ce3{-Z*~8{`MVNj+*(FPNAN26G<44l658^gtS|?*X(9A%{ z#=uK6>F;Pu^|XGYF0~9Th5DVS7M`@Y9)r!oSjrr`DG-{O3ba8moRW&BC=+e9FqoZ; zb;0EQn%ICUQA*gr9_bO}BG_7_%80NRWnLQ%a2qVlHI+5bl+8o{bL28bqlgzIr)+4L z87!e5j83gB48&{_B~dja=&E*hK20wvx60W&FGz`C7y`(U2$9x0XbOW{<#Ve(AIjU> z+L}CK!WS``YL?$${br{zNfQYgA)35$5-n85Sj1;VckcTprQ3kA$Rv9&uYz=$< zSt+se#a`>;bVOLe5Z7tY{JGsjA!8 ziYV&JXtckV9CyC{@k!UQzPIU}p#kp2YLi_R`B>wOX6Sy z9@1gxh9Dph#x-B5gI3s7@$2G3&8)iRB{oXj>f6Caj^M z6V(hftzo?`l~SA23pYj5<0YzyP8aQ9j%G`0s>})wVx+XO4Q#GEmfyIK{`Z-;!})(( z0?Xh{0j>dTk7Mgu(!Ay6^->v4Z0q$#88^o2oTn%DW3e)!&xvLKMq~e&75wIMd#WFU`?4dA`q3E$WqyFyB~=L8NY)6I~FPJik}{2EeL?)R`*M-573{V9_ImrY``LIkw#X`Y*udvr%Q@)t-_iWvK_y1^ z_d_ZzE3-JZ`)!-O5wy)Crr206olrG0G9oH*V(}n<{X(!lBgrzNO>p%GxMYfOzzuQO z+o1n5CH`r|EUMdIXmvXL8)K>WuR-0X)BYDLShb|7Ri=gM2g5_AN1PPg45BYYihhC? z>F9Lv_@lD}3G@^c6f=R(8zUWHJN4$b=*1yNfPBE`C>b(E;&$m)#{U_gDNKJ=Xqw|* ziDlGP#t6!CY`KdFl-YeTcr&3kDhsof;)`WYHeM;aV6Z503QXYUOZLf~B&ls-dZK+2 zz+;-gw#+jT2=uc4f14b0fkwsnCSu8!JZr6l!6rFHMHPP0s*O{W{>0Ss&y%NDh>>)vv0g{CRjqMt2Bp1GaV7ke62ruWPrM zZaMUK67lOJACWOj#%iQ%O}@vvtEK*N-ry*n{dkQ|cH4E3FKQ2rBt zSa;qhPe0XyOfEt$dww`LSlKN4{MFD zUTpZBPSd71B)Mdj8I_K0N8`-yg~yZ!hv4q)C^^hld~gti~xJD z1ZP<33!#mw(!*Eh%yY$E<4k!vOuOG;Rfrdf*>A%nAXIl6jjjR zN$z6u=%Hln<9^Fm71bq0ZKPZo*sMY{y==kY+pK~eXFjBm6aCxoQHFbnuTVm`GlanW zk8q2ZUAN23CV6S;C~C78txKhS-Aml+QUmrS1{u$D8jr2`;`Xw&4~J?7_&{A z@6s*LmhB@15oz?_7o?Uj{OgYbK2FdLs5`x6ZdY)&g?O6P%5YK2FS)Sh%ht4{U{%qT zf|n@M=<5PA%Bo}H591VoC*Fs!`~GT^5gDctU-rvD?Te8TA-3L5h8bBUj z-g12UhP};GjRg4C;x@{5C5H6R$gl!U10}jqj)Qb3k(g21G4sQ0W%vou2dSGXwdRIL zAN(^;N=O9>Z!2c4Xn6i7g44I1K8}D1keQ&hT)$7bHr*I3Q4LYKD!!ehh1GZZ%)eE~ zNs29$=Yb3NGK63)B~f`MfjR?HjL@6oRiUmb5^g82T7&-c7Um0? zqHfP%S_RV4498CdKCAX9N(zd?6x}qNBx*q4Mcb?Du@X$u>*1z*z4>f%P6fHz$S0JW zWD#+^@HXw;s4Qze?`p)uOu`$=?!g)LI`Br-rmi~887mw^g-2+XXuKP-!ryAXx+2W8 zyat(`ai;&S4=Wo$SJc#{iOxpEpVq}Ua+8r*&a!BUTn-;OWsSNT4+hyW5=~c!Swe7B}Za0t02Vm=&zQHqbbvq zFi9cQSI>?ieL^yGOAn~F(auK_+WPRcNs9hb=DjH-7bJa7*SVz~po39RR+f(MZs_o5 zE|cnn0Bns^DPA(q&m(}428sGG_a^`g@R5|LGW|mUl@nS|Jg&X~lM-cx$QPzwDyBdc zsZb|C-as93g$M~Fm7tl*P9UfMgnKoTs?^DqxUfDZ9-FMg%NgCQkDj{Z8}Sn7cwH(- z>BPY5mY83-^3`U3T*-F7QB2NQlx$tq=R~I5XmT}NnnyPGF}sFZvw8DD$g10LYFxA9 zM|A-eBiitH7^a1}3To4h@!UcM;j+rB@I71NLO!&sI0VJ7uQbo!9%NdrQ6WIkdZuqV zRu=J6dKHS2x5!ie*&)tj7B!?@1U$^Gd zvDDVa)$y2iuXAE=^m?kDvNMAg%U08M$*o}XD01C=1XSw&mc_s269s`{CsvA=&hwL6 zor5@+UdA8llZg-~l#}F%@9yLSw`_MlUy`&4_HxFLtHLxGDggV9sskNzJ9kevLX-O* z6yL@;0-4)KCkFS$5a1A5Q>;nC9lSV)DAG##Yc~)UI3atS`2_1&+4Ou1x0zr%Q}wA# z(D#)nIa^8ZFBio`ZI^1|U6P(RLFTnFa1pV%w1B-ahwuKaIegz{ZSW z>{Bx_BtrH%@w3i6^RBN8w8hLrA7p0oPZS;IVcVXsc-bkLTLMLJLrKuX?FxJDn zEbrRDfmRL3&d0BDm!z&rNq`2oHufiPz^Yod?Q>DcBj()G#VB zai*}rA6bcnAI+7$bE;SxyUog&Dz8dgYbZ8|goJXb`yshZ>j*GD8F!p5S_Fv-B!9l) zN*QuFc6QiOxQ+;5;WS>v^Eqv`NaFJBJ2NE|i~`1<$e>e8qo30a@`6v)Lx66rd02sgwy*Zb#_-RW;?2*ep9gg6#wolsEJ?Z^7ZgUAH|LMM z35UO>`XQtIzJU>E@*hui$D;7QO%=c$#S2OWo7(8qcttQWi@DWivnakC;rxlw*gAy% zNXHGw4in-a4E;gk@&8DB%dj|_t!o%(a0|gb1h?Ssp5X58?(Xg`3GNacf;+(>5Zv9} z9lp+a&wX+~zrSB|T{F|w)m6K@tJYp??ItR)_<$&M8BXUr*s@WQ^AepZ%)lq;ByfCG zb3Y$zvk)g*(8g0 zq0Dsl!0o*X|0d7%?{-7ksA&_&dO>7+qW!*C3>9Shvg;sNZZmdb z2*TO?fh+URAsc(ybWTF+c1jh$59`jKR~x@7}3dp10Rb#Fj&vgbjfY^Q>xb%kbc zJf7!!OlLAI3Vo;^B=B-q6>TyruawrWcyB^?*IIW3)tz2BJe}Dw z=YCplT6nFGVJYZWcpdgnga762M+uLKT+! zv$eeHd~7$>-YWHz1Jg0ASB){84glI?Gp|1LK-*gPmY9fgTeoNEwHNU2?9^JQuQ-0K zhyW59N*XQYLwi@soL?$ISY4odRR4em_uBeCl^e?t4$4;TJ9}h0z0z1>}Eq`P7&JTPK`YaHR=7B zshnWt@pX;*W%(C}B9xb4o}G+t@|O7vCodW55J=Aq3AaoS4bj`3 z`&oGhrrF=N#GnQ-rZ^y%Z(iJ;nnU*sDs_>b=I#A;veOL?CrgfLL~*L<%w}`?vreVf z;KJ6ZV1j?RQrt4A66PQH2{i&FAbdN$R4!C=$XCj|B=GF2UbCk=2{K^CPLt) z@+<;XZ3DO@ULOAxI*E@Z2x_{bJzo65^Bong z@8(>?Q~w6^aB2W}td;)A3mA4iOW^+`Dxvs~7r`CNf!IID8AK=;i@g2C#XHQMulO5=3d-^y>Q!sr&3w{9Eqm`@&XL`` zfClDY_WrKZYJj?Ip>=8Jp`1qAd~UYz9Y(fLO}KT5Xp%Kck8wY-l%Hvb(-FD`_nC9! zV18BkszG1c#dGpCYne@wYQ1AQUMUCM-#Lb2hNx_1@7D6H#QXatBLuhz@M;9>-UCMN zpZOCoBkK~Ou0JE1%laEi5Mf{#rC)&$-{aMN6dcQT@{?ipOGE@Pm0Ede96a(`Fo0S#? z4Grp@-Cad=U zAS(Lv`YfXvaMtq&)GHJ<5jHqq+C6qAs`Z6S0hd_+zSv*?8aT8lfe8$%!5TpH~j zNMqj`{QyWbYAG4008J*2SPU5W$tx*IXhq1ouIm5q^86>ni3{cjfFI3YpWi6?eOYH_ zXQi$+MH=EN(Zyo$WlBp+bA83{;r}%rMyMbvQfMWnwnlwnl0W3!2$%Ob0u&!V{st(~ zrGQBg6#xIdoO?X~I5GwJIKcW&quvd!8@s)wY!S$LkUI_Ui{y*P766x5TG00ILGNM! z1<}SUm|3l~e8J7PU8q%tmbbE^y*XQpg+apaszgUratr-Cu3pgsgBVm`3IH@jqw>8V z7y(OBR5aLM-ebwBH1lwoGf@L%jro6&_zn?b+OQ;uf~F?5MH$TRb6Vsg;)*gdvK!R; z*bO#gmFVwO{?#G>A~IAJ5qLWZRe-mlO@3@)mmHUoAwm{Z9&~(sdQ6>r@CzyRKk0-2 z7Yz{p)np2Xl~Ss32*6)>#*_oF*NzrhBgFs{M|1OIYC-*MQLi!}uYc+u$2(tUuzn2Cz0b;#?Fwhd+w??_w!DWGklGUO-{mWZZ#`Hs*`_#QiS&tsU}8wT`4! zx06DX_T}pzCuW=WiBXO|=c}4Z>I-_I<|6lI6nuPu-)seoioKoEaY3SN@%HvR9A4LP zD~%scHTebjg#MtuzCMYi4N%*)pO%9f232s0L-Itfu;=i>LL%^xG*TLnA)w;r&Ahz4 zf~$K|%OH!ROxfbxo*)ZqU!d&qiS$75L7fF8bQ7I#&!WE1uhRLkU42^=fSaUtCe|tO zZM*Ag4q&l|+e4?*rXs$!s3>Ii`%r#zzz3^kHM5{2ZXiQas{7_IHt~z! z8;eQg(60s-XKtl&4eVk0go=T^=egbS)E!HqSSJ0Fh1=EYjx)T6o5iHFhUGP`mx`QR zxkJ${`+OA3hBD{O#7lCik=^E7oGdTKAN_{sSx0i&?dc6WzLrlMsb4ZLGUu_x;Yu-) zv5^tHZUob%JLPhd|L)jB=*DnOp;cm%5052=N%bN!#D;eK5fL&%GZbWdn?0xu_9=K z1@G*LrA0+Wr}M>8COKS^x`~xv9&ZX`2)HK7mU$-S*l6RvUtXk`&7a3RE#mCqZc7e8 zMSEyYI`Z$%W0>^~GF?9>6(93)ygZ?xFLwR#c;9%Jn2?A>I@5Rtc1S7_%#6chlonN4 zGB2!{<*tR!!|PqHQc>#Zg2Fqvc1s|XR2)67O)b_(;~OnhK-Yi@Y@`wCcX zvVffMa?ZDl`0>8i70(;g`M8NOnTtck6kI|# zvsRm9ah4BTG@+xP_B*YPb+Q5|q7*rgS><;3B_}AGwg;I&k&{(zvAVY`(KW9doC>X) zQEY;F+c!wK-fa^}j38}E^#%GGjX~s4elv*`OtVefmK&Quk=$cZ1S|>CA1-4S`8rQT zj4?7i2Q03U$(b-_;lFsEo^wd#OT0wP3$9z0wX}pBcgOSpyi!$Euq3n2NsbokVD(#V zRy=s!`%d%s?CK|24gyGm0G~?v@9t?7$1Djup}y1mFGvvZ+_5xO&GD!0NADjto(y-Z zdbZlE-9(ZDS)@FJ80Vk6VESq0Ah{E8bbW0^a!sL=UEaV0qdf%LUplWCib9E+MkGvE zspuCao11CIy8D?zHZ6Xhf2)GJHR^;vCcak-w7WfFm*aB;^@d&nddy;O+fIM$Ur>Z* zZQ0q6EIH;XIBZ@?)3+swn_Jt`oNmwhAw@_#d5v!yPiKR%x`53pf&H`y1gC<-^yI)$ zuA_4lT|FeM`47iXLYH^#5B)5>aA%>M5GyUFct&1FDPt@T2jWO4oQv9KER!%oA(5t! zM-2Q8!XFxRmLj|M`XnG0g>?tPVF`^;GdbU0zhwJ7cL-+5`MAX5w}?35POffnHvUdY zKLS5tyzKf81%c!|vr4@+pV7e?OO_%5Zshf0?z=io=#|IasquQuDrqDVIHRvNMsVm| zeCS!OLycd30(m6XZ(ZN<0-CB8{~VbRKg!%j|9+h_&T^hob8{CF`1W^gR#}6e^5^ukB6bZU%NGh>>R@R)CjBE@RZJKoF^L4xSd&CO?&yW@&Ki9L>7qf$eV3&hY z*a}UGp^)0>rd=L;0?RqJQ90J)nb^sDmxJHQ6Je(diZa|mNaL5r(#xM@L@6Mn9X)g1 zKTAmDWEzmdhLBE%X~KCFSqBl27F600VSaC12;F!^!RHXUcahHP>4DJ5%%(Z4EtW?k zzN|=0FyaVVX|w{$VB7nAuPTMw*wuHRmn&$fK|&y1Ng4Zg5|W{;Q%)C_gg#FTm_mvZ z44cxFTe5GtshXEE;+Q>y_jsQq#p@R=)p&CY8u~qX&ZCLrZOpqLJPd_I;~yh2eg2dE z{UfP4IKRMVaigTuxz3J9>CNH}T6xbHaDBKl?=vyj$E_dSmDA0p2%|OaB$zk$5tJ4L zwj@1Iv4PX$sY?1xM=klqI;~wt<2P#MX8TGEena+XgbZNf(mq#`#+o-KpgGZ?`NK>c z9nLy!hP%L&XT2*B>30zFZ244HKH!0s)be9^HWAv0pE7*fWpce9D`evlcA02@Js+%7 zA(Q!}fqXY~l4uV(_|pZ+{xbPUW!aQ&wuyM2(g!}HZ0|>ZdwZC?H|$DZ==eN!>u$vJ0_e6h?Re_^=vE2B4xixU4t9DXD6TGj}{d2)YEM z8xu3cKp{OkvoDLq@_Tenkqk*!HT^&f7fL5)Nb|3ApAw^H)Yo?&2TZgQPdm=g%$fb~ z`3!!bhZWXtbs>Jt6!FhdkH;*p%|)6X+I;k&`znQCeGC*~0NwhbnxRiFu_sDsYx=oZ zRi^Pm<9tV2*tmzi(D%#P`YoyjS#N!Gc+!&uBm1%XJ~g{_m{=h!``O_}U0PQ?5q7UTcOEX>aXXxQT;tCfrbc64J$On}$Q)0p7 z*RozJOh?>=+z*UsS}$@c|1qSH>}!3+&vl_|q~t$HF1!{X$A=EAM+f`l7H8&`MP&IO zs(X=9L0A&dENc5rdV_*k8L%#dl~BEIX=5(^>U%hnztDRpVtF01@f~=8HEXn;SuIaG zj!_m)guY_kGnrLU4FAPDGHm93rxTixM9fK{JR~6+uracN{9UbgYF+M($7+m5We6-= z#G+GcZp~$j`zIF$FP$Sn9DFX^eC~PGGySWN<>wd$X9-aJpr_}v; zo4DxjRe~d4H z;PyarM!gc4`%XN0ZC=1eZ9tpFGkz|G>KoU7kiF0KCm=kgB_j{yQq|wJJf+Av{AK2J3c<(i#_bWtQ zT^95u`++R%n%K1KU9U&n?9HN{d)FH&E;tW=T2tOO;Pxcn+OOige!kib9jTr(6C5t) zxj_iz7l@b_p&YqP2N)~Tl=zuZ_7s0nFD4NArjaau4cV|X-GOq{5(sbRcm;cdQt z(sioS8=NR=IJs*M1M%C<>bp%nUxOQPg@@`H{uU38TYb3-1U@&DPD&4+TPB`hu^wQL z9QKK?gD!YBPjLY8D{)2!^D2Zh)*-9?@5{J&~PbPM-b*96>{q}TDYNk zj%?drYqis>e+JYvmqA_zf^t5iLT9Gw!^Fts$)UDI^IzWAiKX)fPu7u<-b7=wO-F0n z6WmjIGO*Ngbhh5&+RFF_pSC@bY!PMw8eNwHd*E5x$8A&9z(jqhN73AoTA5eTHrN}c zf-^!&P_O3E9tw|?jIM={B}}e{CJ_EgD=6J0$-|wNQ2CS+AovRSq}Z5;20PrUoUroA zRIeH6L-}j&@@Kl4x1* zTplVuP*=fQ+cOU_+|5~86mbV9>7SXWKjbS?YhN-?`s6L-) zK^&!qS^3d2zQLNd%Ew}-a(%X@HaQ4uq>wir%o%BMzGYu=0y4GoPy#(7LZ zAHvPYSAunmRVu87y(JLv;?SAeu@lI=cuwAz*}1YPn+w%J)4iLWQG^f%N;=HKc?JuG z;zA~;H1;$qzWkOcdqcA7xU>3IplyA`?FTYF6{8AKd{yQ$K2Sy63sj=(RyYaqb=FhU0%C59$6Ys!t z7i1AHx(P+FMuUR3q-4njr?5Gvq67_#Jyi+W4C+595C>b_L+rhJ&Yrm_3z&*Dw+KLm zAUmTM_V7JzdviTZ*G08e=RU3kgyiS( zQJm|x?k3x#)B9W#VtH?myOgY+LKn$vi@G2ei5nYN_-_U7S9_6!?`NyZlK79w5baS5 zl-=dTOgEhIjmvhlzn2jxR*m6)a;hc>r>3V)LFUl+ok>E;oZ;+cwc3+e@|K&MQ@sTJ7t#5qTN4IN~$l#BqiC3Sr7`N~GXA?3xVoi_|0PYVU<6ld6SO zzH*p(U~YD15&B?}ikDPlYMZ#Ns6PeeN0f>Gmzal8mM-{>iF>xjuBIj07L`H#y<@dI z@tvr&b&m~R4LH6}s4K9T=W-g<$u{58E{YMn1l5N&MQ{5XINPmuzD-fDS%dEGt}OW2 ziD0oH3{iO0kOy*A+-^T2w0@*{vnrd#R{4d+mN<@2bW~}m=ev*4J<-_#*6gsc5m^f< zFSe!fTfD)~MKWqs68s_@i&uSSB-p~U5L+WKkgtvy(LP^M99}atC5ayY5Q&gQF6w5{ zV~~e-FaLkjB>l>fBx=+GXD8z_UyqMY1B}EXeTi?eI|2nDEBEFS zduqq^HE*W$fu3U;;=E(BS|2j+`NW7 z9DtIYpN)BNzQ=l>Z{-a`j9WPpr1;r5DQc@XmLtSYHyNNy!->bDnn^pg7Wr@H+p?vE z!t9QF5++Dr>3!UROI+3sQp%iKq6eyp|KIYOWldCai#MR(K9(nMCve1qkjWFw@78p_5H zkU{pz8qB)n?U~JC3Kzl|jsZtHfYFD9uG)Wuok_g1)9{4aedhkwf9#sG@}2q~v%5uC z4q9AXbg5m0n!R2)rl_l&rDHWfz|j5OJRBwG!!&ayGJ^pfb3<18u;J>e{nE|v)h>KO z>H#}3I4qDHvfwO!&_?>UcAUJ+} zl6-xy&g`3yMm8`=EP7~{6XO7;(&ioEQ z*5q^Becbb3?!CFy;uu)BFxO7bI$jn_D)Swpp#+<@TuFm1WzeYGiXzH4Aeug@HCQBL zJ5bpkmU48$`2)2L#60rGh7V2p)&p~Srf~glxYx$-6MWuoC>-tT@C^w*nnAzg^b><4 z;=HQXtyB6aAp@~x?uOU-Fxz@^n$9<-tBhG^sq$T|40-3hM)I7Fdlr4$y;Od;*j5=o z3N>U#>S3=X_41r1A_BfApu<(W*Lyr&s@kqu{DV+$GjVC0!`&DI@rAM>23#p%U!rpMxf$a{F>dT_hG@<_gPNS`7n_qUbC zKBFp?go$qQp}sBI-}%wrW}UiT`n8#KsdWy~QG!3V=5l$6>!Ii-I(0V@>cLEVbszmzdzTzm<8;0X6euyez8mfF0XTU&EqVPV`YTZ zs_74{?I>h7f})RH?Bi1RB7UD6V~^Eu<}eau4$yjsA)tUjLkOEL_# zPaNgWnP_l1UC1NjNPqkVbrDBz)6Dl^rnwoVFY0Z$Fmik7SX0&I+M%zb86Riyrum5{ z&i8k^7!q-R2~WWgrayl0{R^+pSGKXoDg7}kx|O6zLabM@>ON)qS6G_$j+R&1)8eK< zAM^6MqR*fNy&A_Iro6q? z_W@;IPG3Q&X~olwRrb5?EX3UN2COXxe&M4umd4NXm9H6nC+-i!q|A(~Kq z404(jhK6qnl|6ubrYREaV}2JRn1;f=vjcE5Eq;ujK5&e1%qN534^o>T^qKmuf-rHk zZ`16NC2;y=ZD#v?AL!+wO>E$i-uc2dRlMVGSs-N|@W~_Zl z=-ibah79AZ3C1rxJ_$9;qu{Xk+p46&>N$4j;n}Sa6a_6g6u){vEYRSn6sp^j3`Aea zU7;4~uMqW2AC~Fn)N#ge=8lCu$K36`=>L<)ZW9Fifyek;H6T|I`xYiLC)9V{9~N(> z`y9d529X0urJAWg35808gAcYRdq(Tl<@He*LSg%d34<}KY?KKME$l6}Qp#=k&l}7Z zIC%Q4`Y6sNA@;GJbK>~h33k~Ed-|H)e$E$*DY%DPGWdFKcWSk)3;TYgo${<>$8*?x zJj30C!oj>6C3y`d{lPZ^w z{h*cM zmMSS+PEBLz<~i*Ozd4zE=^%=JU;W|Z|1bOPOSbMxIzv-TVeDcvLAw#q;(SIuHy=1V zL<{PD^aOll>LR6VztLlns|b6$#C!cKB^)IHhI;-j`d#Huu{>O@0Ykcape$#p`tbOv zjP=x%`Be&C57`gvh8v|^|HJ8;{1q-QYLsD1z#YZuIrL|k`u}b3XX3uG3ilGm<^5&`709N0^h>6I78>@g1nlC6}3Y+DgsNFfo7e z@R#31+=F(G7Z2pP7)7x^0Ke)AWikxDtN%=_5fgGyZ6lK<(P_W+FX zrYEeutmjn!XCOd-h#?T%*-3xrs0SP%hHThjJ>dTRCowU=F@gsjdnx=w>Hr227T_lZ z_iArj{+(WbKY*V^OB^)@S5orEGjaLJn*XwPO3Ewpw3kw*iZFE* z-G@9H$B7PqMY7Kwzh|`hXb_rV1F>^t)O{L<@u5tCcIQ8>b_WWysa>yNruT@~{1R+r z^oP${dLQ@IPwRWeLz?s_OqpMit#ijmcs;mOx@5Q?cLXt@&1bmMe=pW!MmspAY2oO? zkfCaT^x|(f^9YnWJX5Dp2WA*bclN1s!VTz>$ec(i@PC121-C8y;%wiy^UzstH!1dW zLp#XInvVKLX#pHL3#2{o z=K`SvI5+`qbqq|fiHD>pKR9sNRpD8&^sdNtVb?5Z*WW?tLH{9U#C2u0>Nz^CD}ECtoZ*!Pvxxs9gZ^G|+y;{6OY z_|vmCOD)rXdPWRFGfSRGpwCG9QbU(tQd@Qra3?QMXEyD}R^OTzQsmvj1*+=0qGpP} z#AhDw{(F({K}J8MbD97PoYtBQn{O>m@)0`fl1^_skR_gC+I*7{+#>YY`^_L!ZrA1W(;zD=M3>?p@7p~@mACMJjYnUgQ z|EgoVm>^by#17)iVK_hg-MbRvZrOX;2;!`~^eBWr1TY1JD>1GnqgGA4gCm{e!vUI(IC)_q012fOwVlITue6L^9)2Y7r6q9hgBsy*Tz6()k=)tw9PO5gmF3?N z!DV&8Ha2!HDwwS>zdLnUthUFX1GY@7UVFmovc=FGVNmLATPa7BWcm4@FYXl;seErV zU`sjE&_MK1=QXXH^;tT~hYPNbrFNRZs_vP_QelxrPxN>K6K2nV&fEL-NX&GIGX@RB z@#iVvgV0k9ff36YP}z1YGzrF5;#rfO@>L4ht`*Md`lM90Umy>U=uYkD-Qh6iKps%Cw@@%z*T)3d>agOMLW#@ zz|0&No&*utC>Sd+aP4;Zn`E-w;|B(F?Xze>E!X1VG(UIYLfEuBMyouQ{c1w3#n(r{ zEY-AouBm&p6Z7MVAGPyC0Zl0DQr-LjAxb@fKu^`|j5q^&%FrWGAbV`cedSg75K$^wBPd!Rv_JdUUiP`* z8QI<_V;$g2v(r0WPN(iKo%yoG2oKc}H7O!L_qZPi@EA`am=ZY(*CT)N4*c}Qj zshi-TqN1iQVzd4|O=64VA1A0c^Z2RdzS}+e&~sTZ-Dy{z4e273|J_8RuZ>Mo2qZQ* z4U~tA`IkE#F27l8>SFF}T_H%%q6xaayFyGM!$ zg*?|VhHG@*wVv5x+b&Q9s1#awWZMz>dhhrne;a=sB!UPbS)nl;`_T)^*#eKjIs?M{ zf=Z}2=+P*Q>Y*d$e%|bGiZ@*hMIv?XNb;cz_D0GEb4&6^oCF^EC?}()?AU&wdniw3 zcDHE^N_eD$yyUDzGgw%@HrYg{t}Z7x3e{T{@4%;CQl`=354`Qsi>yCtYJR{#eyt(xnQT?8$dD^6l=zd&iZ+KTn`wdbU#b1ZF?qEM3xo}9a z*j@R-vZ^Jm(z~p@W9~#&9^^dhl-VhOI*7`I^;>KES6l^Vhx zu2rF&l$PZ9zGjNAHp#g?t;8CokH3E5xECOMOw~2TeTs1b>ch)2eEBAm?fnp){{f${ z2eiFygfaLI6kluv?;dxzgxcXFTh7;{O0Df^!XSNu0U8qQU6L;kGV{2sP|kXPqU;fu zjAer-1Gq52YKkzErO<}w7u#YB-L*9(&4LWgK|KWFeD*Nr3Fw-?dsUG>nB|W`K)4<^ zA(mlS?YE!7ALns5%I1Uym4k7Vu^pUfJg{7Rja`erCo9;5xU+^Nl)5O_VZ zqKu>Yrr=e!FL&wPb~;9TA9uM(!A*DAc3$LZV`zva>_b{$cn8Bpy3xS@kAP6zNGhH(uIfMX!Je_b8>TRjiM1ePL%tD1 zG{NtbTa0ZmBY2ppG&J^?BWH9?-&by3v;KGCJ;$xKCf0e$madc49p)@D-`{50=wxsw zvwgi>Tgq2eCkcMh#Y64Qz8y*1wad}W2DH8zFCEvxTZd!NT3_z71|p$1n0rFMJfEph zFKY-sAxRb62e1UJcXe0=g1$BAwc3}O63)yJ%QyGXBWbj3YR^FAJ8?<(HN1zSqvK3L z##{0CK{w`m?1z`a=-=7HU;486E;lEYU;PUQg^}Tl3gLOD-ya_HdL!{O4OkD*+q&pr`JuForM8V(_onzh`Eo%glfje_?{hd!W?77&%`?phUk z($_o$av8kIT+c?`2-RuvyA+~7x-FGz^CTzF$^Bf#t>GC$r^Y&J7QAFXE@JRql9)Op zqFeI&9)mQJ*hPt}KxaY`AffMuBzA9-&XUVqSlly-Oak*M%x_< ztZ&v^DfE@eMgjj$DiDh_3NNtDI~v(Hax@7C#TE7Rd|`PxxdR-%Sds9!(qgzaQ3J#L zKVznbiCGE?lg*Y0MEU`R0D4Aw>I9}(HRqk(nVrn&BV&7E!Ci-x3KA%n4`O=sa1}_j z$o4--!9@7d%q35bJ}m9)Z6Lt)n!eN}noIhWM%<3PUnCcYU`H-TaFs?vsaKg`bQd~? zxt3sy=$P8%xk|x8tN+s8@-cj4G{t4-j114;3WtE)I@?JIO0!s+s21q}hhjZ5P6(i& zORQ8*l+of_@!9=4Nx;wDWoZAD>6Gv2%zAQY`n=)R@5(<}_pAMTULRst_V(E-w{6kO z9Ul1z*G&Ni&qsyxAU@Yu-%q}6#LDNkGdgC?j7#SMSHIrF^oLG9U}^sh8WzZM)rv2b z_$XhErr;tJEK~pCt%5dQ1YUM(g3sKCLg7*I8>N^2P8hUVOw1KvB5Y#Am8W3?jAnNMtqo`a%N2r zTeXlMgpdK9#bC6}=}3@l(cVY?j|4iK%h|r1!mr;CFMg`7DP&FX%|x(1;Ez4F-gOTg zEHUt-?lctO>rWh&>ba}{z@$-XMFp|q9|a&jTaf+Ji9u;9ERp*#Jra=!8$`^Y(uYJ! z9yDPOb~D#GYZsp7`uZ#hViXqEF%pWXUj>FJqj4_c9b7~pIm=vQ1&D79st|9I5fZ$w zyHXyz{kZ`XKP5gv3x%#V8-P%Sr&Y}9{Cb6I6jQ-5W9aRtgB^hoZF zU0*y^Nq?D1lP8-lbsGU;gVF$*M9wkaBSH2anangyyl8CKunW*kAGX%-%(mLkMYW8vA8_A$TW22e1)JV7K24J3qAx)zX^GX z!iu5km(Oku_f9V2eR>bd2MfJlN?+aNLatqd4Y6BvU0oOq*>bs!9lov$0C$1ia%eT6 z4M}sp9FF`YS4J#~Ixn0aI`y6Yx}()L9^rldoyVa%mYn$keYw$ep<@xEI2S6hX+XnE zmd`VII@IbcL-VFb=ulz;ZU}xgArS(Z-hYIdS=QYr6883b!H_-F!J2;U%Fe%M1Wd;O zai&jNb)>@O+OR>xQ7Rn^m(;6Hy)bqQdlQk|#!B!AjA|ZL)^S454VYCW`j(~?7W{;R zJB{4*ABpBkkaS3CBVwZHK^@$fF-;@#t{opT4@7i(AasX}Rv@bAdN5V&2(+L43uaGY z*O$hXquJyVa^oDn&WlAF+AA&l1L%G^{f+)FF6IFHUW{GKvAMw4j=3a-~i1c#{|m=H4_3F#0gr4gT@eDPu1)a zN=ypBGK`(uR)_p0>|UXXf1|S-duZB_y0bN;dLTc2%DPC`g(7Cg&5i~%6@)C00|Vfd zYBFteaGC5h`Ic#jf5dH8z54DH$-=_Q1!m3b2~ykT;vvu9LNH$(skrnPk5pC11u~sZ zZ4?ahzI0*?zsmT$Fb**nL+4|W{Bku(;C{EKZR$YiXO6HK-U~#--4#{lj$&yBF4=zG zhy9o9qqDmGJO0;%54Jhjx7^opf#z>aWYM*&Z|91JYwFEnq=0UO6x%;FC~z>e5}(pr zvYVM5vGgrSSVj=BAATwJzrLkcGsgqZ@0w%JIjf zd8p}7{X~$qozM?En`Tk2A5h^!1eucYc5&&{8G1tN8IJwm$LhtJq~-Vu`CiQ-2|j3X zcD1@=HTTc}~5}3ML@!fCNRYj5Tpq4!mdI)*o4k$3$t-=|YypJmx$jSid(DaOX{ZZzO zr~{ir+FYh_mvXNQSZjkD0u9(qDS?xzK}_&y+~;3kYf2K)O?S#z04WJ64tQMZKyg)p z=C3mvIE)M#>VZTq`m0nd&yyMa)eedXV^uA=1Qp$2Jd9#o4YuMpNpSy1hTWsI1;(YvxsGQc} zs7#Bu#zs|ngiVEurHv>LRH9F>L=>_V1GSh&b+!j6Ng;9pRx-t^#sOukaZ}xuy0KiZ zL0E4s!+EU@J!IW}kx!hsC4#liXuL|N7=ACtlWFJs#jzjEjX1;xt~{N6YGu$5NnyJ| z)t|?m4R$jxQz|zF;t1Wnq5Wyop^dElCq%R_*LkR^8?tL)QTFUyT8xXY!dZ7eJv6za znK2oRx((P$Ud@u{jjI4D207icEC=l}g0B~S+ls&Grk)6R~VQx6eA?&{I*$-#i%ZqP5{kC0h3U_d{j&#QLZ`*Q(%7b<w>sbGlot+fR6K!1L`CJj zgaR~q_3os1lKzYd62yeahIgOmfz+_{?9_02to+b!@VhX5WYwE3w>MHh<~G)Bkie zbnoZXf4e#*anS4T`^+?Axh7+mfP;Y{tlerd*>Y1!1TPD|ejS4*kWYX`bjATb00f(W z9I0Qd;p*{TK&_2d>AJ9Ac52ZI#@x!cqU2xAe`5tm25A0C2Aovv0K@*jx%36Lgu`nf z$A2X}P=EY^j+Zn?u=@Xo`m0!%ZU63TWs}Y;-=Zmg5911+y(wE1`;G(Q-v|TgLiGel z?Ck6)X0Nt~YoJCG^41Qy(lD@h4jJ2l|10KS|3upA?wF<-;FMQDRn*quNGuN!OFc5P zng52Az&2o9hD)_fA4eqts1|e6(95V8pjM~SMcl#hP5-CwBz@;!O`_1`ORN|nC%XT# zJ@PL_t_h%k47vS^#=wX9_l9DGfC0c%M9P1QE3v_U0qflz9G#4R>2I;Y|G0I)yleXx zQXl1K3JlLBA_L&G^!HZx^B1TaUBvV30`G_8T?vo)Vb5!Yg6o=7ybyhTG>0|Oa&r`I z_%BH+;2u#5VnK*kFe)icwwB^tscV&Y8Zir~qWqVKpB|JK&@5^x0KHWm;Z7-h&s06r zt&`jdW4*7fZIJ^?@d46bcWt8a!GHHeC`UbP`gq|@&e}SYt5|%g#_*1URz!>9^6g=7 zjc{iMBbLZFj%Rdq6jh^iMrTeOSR?$665?7kJ;STPjyJEHztc4V^#^GI=NTXVd!G0| z66XJZ|7(-@g^P(P%IkTXmtrU1{U@vRpL2>3LyT>{5<}P{MM}rS%H~Y{;+bno>3n+( zbWp8`8wjt^m?UuJ6JV;TQBqYESES&V!DD|v%whTv)#Elm0b+rjwd4Qf)n|6N*Z^4e zPKW1dh)nhbUmXByxXU3{JCZ1Y5;8y60!bfaQEm-w~_Vx1-ZMHo2**z4v zuVH3Ff|RPRD>L~YGJj)BOGJ1Q0jU?NIS3JtFCqjPPf%UERbEIa?^w zC;2O_Bl~;V9mNZIWTzE++lGVH@zV{Ou2QnHsRfv8`3;sTQ@VLE9OA@3S-<*!C&=bD zL!(^Q>$KS@@~~byEQk8X3qWZ?C5>hm6N2J1R|6p45LEuM&+Dm-Hr@wqkAeK0O9U+m_#&gJ5lEU z$Jtv&)e)@gqG*^vaCdiicXxMp3j_%+!6mr6I|O%k2<}d>K=9yhw{y-}J8Qq*C&pm( z==x_{RsEm&9P7AA1P~XXxfNJTNrI~GTp-Zm=#Pee2D!$o$BA=!ra$Afxc zeGuMDQ<^P7CUr)|)CDLyJCWq}r1%?LuyDB@!^!Cg_$;LBuNQtHaRwesz%4B^lj9Alp>?JeDiN4}~5gp~X zX+pYhj_4kdfLHZoNycqJ(aGs@?xU!M$K~T_qr;i4XSfNwK_#U9MgRNnbsNWa z*J)1ag(Zeeo2&WQZ~IfW7JgqWpOLV|-}&B6J^A%N3S>m6+v?)E+KTY!6zmpc4?C&3 zDPj(I${O>Pf5m!x`Nh@#*zCP`K@lqY_2G{lt@E!=;$X2*#MGgJUz`fo*-L4m{7#!H zh4-lzM9g=_PupEw8XOs}X4%4cBUoMm z7nMfCGSi95!~adw7lLNPmv zYj5`rUBfzdT=89u7={_XwuDr5^ zR~IiXrf|0ZK`1cj3Wp&S#Q-nPG#bB#Q{jXCM~s%178FeegvDPO6{ z@VOonv>fAA++t5R-DH1)S#F?;P{&{Q5S9;lQ%zz$k)#g)Nrg#zb}GBkPOE&QWl;DA z^%*{EJ>ofs!-RG7aG|CuV2oqqLLEa=VA(k9mzZ_K98{37!hGc z6QUA$<_w{8BOsD0>Z9OpS%ia4v9s4LORX;RS4A?^kbc3(LjjpjvmfqHgoK6c|Gl3E zApsP_SIIt4m(MrnLSM@VB=y*drHH%(FHOs!n5zd{dBT%*E<}26uI!3swPS;LUt+hu zlI#f_C9y@7{Ux3~7!$b-&a!(=fJ<%wye_F_{jcx=6Er&Q=JB)0Zf7Y92k%=HAIep1 z7BCSu0HI?gV)WVH$i`D9-By3iYJEwnY#%SORAgcTCVAg>6{XX6#!h+U?&kWBWk*Kd z`_R1afpW0o%2>$t_gmhP00plMrlV<#mnMP{jXQ854O*ZJm>&8atTD|`-Wl6Bveet# z4?Xv9S@99pVG0D1**@&=^4<~I>5=1KR(gX-DgHz!bo;{0q#tBixihKbA7Aeu5Y3b;|g&{%wh zzZ7c11#2SOzu%IX>%flyKe2uWvI!Nr@UMiL&~Mv8%+68~iw-w%yrxwV5kBpgF$@^w zVrj0=%8YLMyf(oA*ljzWLjyaul-Esltbjwp45cRW4^y>bZ?{-Ua%CnoqR?x`)F8;x1%O%V5FSR@pdf{%0%dKQ@ zi#F4h=7=r!C({8?cyLRr#X*`xsx*yT$kxuxqBD}#yCPu8DLRtvk4Oz4l8sAplZ_i8 z2#k>X)J>N6V!orXT_t_QWBKOyd^;k!1zIttxrUVTs9=3*yTywK{7Ry+C2Lt0f%Vwu zD-Lm3R1SxY00l;?pSmCCA3`Iz+E`Ik{cW{pxP@=Cvl2{8>-xrBk8P~x!-zWViJe~} zO2f;m5d;Xth3%tKQN+}(!PMI%DXI9%Zv|Kuz%z1NSGaAWBIrjz3h9g?A<(8joC>jZ zPe}1_I66a~{2%fWH48opqiE^ti#sahC33CE={wF^++0PfeXmE82DGULOJ|jAxUj*6 zgsDcJ+2m$vD!*ifW%C$R5fJ9g4pHVCOp3}Yr&!i40cG+`8AGZr8+N4V4UVAo3l}>2 zkBbcry8WdWrRAa>KMhzeSc?v~QS;W%sc;M>{b&Ig7~bZPF~j;l$%4f)A7W=@X|~Kk zW+qU91mK-6j?jhV(>FPJXF;bGU#Zl2uQAWLd;`7g^R+t&>P*t_JjlQ!=>x*h^g+ikYwL{$4=mzi^j9F_c3~u;7Ue{uO1Fiwr~!4s9xf{rb8VC82K}#-L1A6cPpFT~*$9Od&ffQb ztfV-1T=s_!a#dzkU%xh4XQ9{e03>ya_%+JYWJ6ES3iucwus-qh0kr=mc z;*bv;3#HaA;o`3_g8x(UP(m6F0 zuHhH`B!A&D4Pt#9y&&rV>7#67jhI4)AEVG~aW7ItoP@mU`vG|bB%AIHd4FaqTCmpK z8<+old>5gEa$0O#2Y;5jj1il0a<^VWJq4x6P_gVU6btaq$Pu#wvBP-`+ar&v0q} zmN5kr=Exf%s%xG4r}fP1S7{>k;DDyobYk)%LSIVYmuYw)Z3Z2+uiIp*=j(d$x#e8r zQT)Yg0pLbFyWM>oD&QHQ#_L{WRkP_fTGC}+0~^#VMP;62{csAmggA2{c)0=@EsdUF ze5eK+exf&Tq!H!}Z;yRC!QAO@RG%pZ<`!}RPKHbjg@`$5Gv@hff)jcEeh)(HA;&qFLbY-JEFKS93h%E-9k! zWkt3aoB_uc$JgiZPZEICvNktZo`^P|7iUtQLUy+CwFzOuH`RisVwX#}SSl z%N$+%RKYYMsNDX*l`Qk2c5bH$9LTTlQP&V6qFPfpj_1i8FfNIM5K^j}=C6A_bLxd; zYjXEXNA%841dIpGcwn_4?ms-ylV}}HUdDvdGbiOCo!GCM`YKKCU$T%PpMti<{FZp$ zsVXC4U*$|gD>TC327JP$!a$7DSrPSE!IP+0+=*ndIo8}Di6^UE8|HlG1Mj0DD_C>5 zJ1I?E^5FM}fsbup5U%e2%r9GbgWbc;Ft?G0ovpbtS3vTqYXy=BG>PL>!=w35*nf8* zb?zI|ngPrOOgs&$rxq6;%1SVM0T!$lh+B6V_7B1r6#?#jIhmn!*Z`D2C0^RaEo=RU zPg5O4jpQoWC8`w;m7TwteYsU*?N(WJh0x8*hyQ3397^T_4uyqsltjHODBELQNn7-!lj3RB$}Olv6e)?$02%vbUY-U3+gO} zO{HjXQJ#Ipkv3PuBa8}OVI@bv8y^#)gWTGl8D}{DaLt+C^_Og(L1-N|zbt)6`W7`oFD0+gZ2k`7}qeBoI2XGBr_N1w)fOHB?2!%{W=n|Sy zTEtubfN}@35bhgele}v4br$RqzHcM@^$@bN_+nDK~n8n1pdT9ywgauw`KQ@dJD+ip2>8Bl88WN*- zhpx5q3>J^IteMI{QykKCQNA?x9^yPBxAH4D%g|;6pKo9%?TaT7i^YcS8gSW3#&a58 zh$}%rjk&)tM9{=NSD8b4r^01n{mqPmm@~~ah{zK3r1k|O{GhKwi_zC!;O?UUyWT!lu>0Fdy!tq#uO_#PR=kY@V}8CT?sP{ z%sR732Wd=+FpD@U6Ma{3oft&BJyi@tya`S#E*o!J-m)$A3JW;I(ApAi33si%=(vq} z7SGPci#p!-Z0}LTy8;uupb6on?)y%)QogfxIe;okA0=E%;x9w(=v?{I?Mt#z(Rwn0 z**%+-7i8hLwH;%zotMuF8~PLQt0_#t)3a^`^r6|vjhWgw5OQDIP?52V5pemd(qfIJ+1Iq%#hfF(1UXn=zpA@(EingXHmd<@9M_ zH}ZI}F%9@n8mdOxCuFRJJzks!y57kki*d|I7xs@``7wv9CJchs3Kyu}q=)&YYqhMj z90wsC;97R5{Wvs!nt^u16S(eBmHlRxg{-V$bx%RDD<3&4g9V_Yo-|@{_xoxRE8E*# z45e&pwU3Zz{Rdi!0=;2WKYAl9DAd63n!NV{q)ar3v{kPvVih1so0}?MzYPVV~lOv{vW zUgqfRraf?<&%>6{a3>J`T%Oni)r|D4ZbVnh#ZAAYs8~^yjZEJ9T@5R7>sN2&N$j~ZI(hhRSshKH2C&rS3=va(;{D#f$`@DKh9~)LS!{A z7y)djHsDobfRykI7)~TJqIRpaTiw@2Ldra<(SQ85>T?mki7qk_n3J!{S4jVJ3D$7N zpgd*qarWX%`Dfy)YBYpFzydEXforW`cCf$Kb~uIy92agvUu7WXw@2kKE<^8#>dq%g zF}!duokzz2`;gU|L=8^`*r3#XKwK5<(7w-Dcq!(oou`4dVYIzB!6>RU4SdO6NSG}r zv^(z6bgdeOwQJy`DqKlJxH}VPz{r@^aIFI;A#&x2zCKj*XuH+kOc7*R@#?0)rJHb9 zqm>i&Da0+H4toO2aIlG7pdM$1_~sC~d<(jcil#gD7m@E*ns-YjSe0l8PtOHN1?% zJePjn-LAHE=1KPQ^L?+bUMl-+--Qqlw^BMu&UT#V`)l;G$3eVT<2+j}LTg z%6;W?_{MhxboUbBjZ6Vow?Ccf-EUWH{cB&^4_#Rk5u9k{z&$;0^1VTBQf0A>j@Z19 z@2ee%57ZSk-Xz($#IO`33p3tYG=bl~5f3Rz&=f#miYqINoNCu97r|@41%`(c(^7vc z%Oh6sIuFK802uh>pX%?g;MuO9vR2c1T+V&(qlv7Nt4D;5FrQ^e z!wCx#GDCEGmsfAf(W=&1mwH6F2ES)Il?2={XM45x_J`-A*!_C&hYSoRohe2^yFrT5 z`lfLzgngeZLS*>S z5?|lT>OFqTzZ?qGZOpMGn>U46VmF-MC~j5sBINTpOGMrC$6V467o1z3{qpo5+Av{c zUovQTLR#gR(}LYC!pfqOPS`{*n;v09xfftR_Uij+544O(5IG&RE2lBf?Bj@xW}?!g zv0RmZzq)VLIwRECk|QC0YqXx9ZK6wr3AzelL`6I0`+%wW(Kut^6INQBqf7cvd~Wv# zxJQdn1pj6z@m^|Wk`n^5Ek76e>PGCDCG|38nY&2owiz%U)K^qm>_XCz3o8E#!oHi+ zCXVBMF7{H-xS|$AB8HAZE!>x;Z8~)KyT+e1lQF|(SF@I_4-mrz`A321xu{O9Q6-QX zoJ`FZNPWjQj)5ceq=PA}-j{nr+O0^E#6rmaZrBZ}aw)VD5wNgd_I{9bu$^xRNb*Or zh;*L`blc^1V@SN-_-AkTj9*D*KF&Xh!GK3 zBkG_a;t_G;3!%QnvubL4xg)k@g0F7_gG4KZM5MJQrqc*}U2rAh*wo!I9wc8`qvGB& zdBy?(4GwN?9_4g><-9?x81p01kAKQXf0yU?~niE9vZg{s*P1QB%6BW2?5I@Pkn7A&nzF2 zF1QFWpXNMQx6%*)k3{1K3B>pKF%n1p$!pLH1wLs$>G1b z;s4@xA(ayc{{@#3{`Fv%GTxW`2Z8ls{RINywbG~K|MMG-q4)y<7ENsLSoA-1(x2(? z7+BS;xn%z-55Vf70KkwiAQ|tU>IU2hAfqKQ>01a&{a4X{MP2+5bX@-hsdf7UV;HrL z`NaHJ(I~)=^MulL_%HF7&tLIZw`1}n{(lus_V>quzHdTraI@bmLSN5+LkYBqBf=GJjc@RcUG_VtM7BM>Q4uC+5$q1Tlg;(FgSxv`eSJ;Br+5>Ombz_tDWg0D7^0}11wiO>19)`bfe6Mv5^o;moR zNA|Bel93d6QY3m?x&Pf9W{AI{EjU=9yZc{v`>*Y|K2%iXKksQUvOM5%ERNg$|9e9G z)s6o>@`_}h!Mx+~Doq0Em}P8#ZoE@a^B=i_w(*#`w(I3jT&n)gY0?;Zkwaqt^9*<5 z1niQ$vDa$3!rd^*YN<6ac^EZXqu4Iy(HkhXDK>QT?M;^M-mIia^B`bg{nu;g4H6Fx zQ&tvM;dN$BmsDEKsj{v*Ot@K^M<~-R-d(+dvxPt_5A@pi*!a&y5Edj+E&|2p&M@K( zO#=ZlKJOF0zBp2kT;e-7UtWwHgCo@Y+BBgZion6a0m)ZXR1|)6mv$X;yE6ral&cC2 zIeD6@YW45dZYtUjA3h*owE78jjIE=+I%WQ!5j-FQDntu!HfJO`GbP_T-Pc;Pdfp!> zyzHM8GjBUt0NoRpVKM}N31H1Q_kP=+YP(P-TP&MWgvaHeJQo80Mwu=#$m2 zso7?GKAYX7^n}4Q4p!Se<_g2EZ#pR&0MG`@{`=Pb`y4(&a59}-p&_>7?eP-n*RSIY zsTmoPCtMCCmx(3&Y4n;knjwFBYWNmo%4sfXNd>{Dhp1)(g2IlTiBjgL47~9XqOX1N z0}_TH%KV~Lc|=V{`rwo3U-UN^-uxuWJ-b+;x`tPSE5Gci*LQSm-(iEdkSZ5RWX3?t zh5cTdpY9n(MVtC(b}DF0_!{qA=+MiI#0($xkX zl0Usx2@C7|ve#H{E+5?OO#|;76`c-tqczS5-P=wOaqlLKGtUZG!w)uU@Dr6f2%Jim zi5*{lfb*o74xK%x1Z&xy-=vL4>S!R?rnt3tc5gSo%An`&z3FI)fcq^p+oYWyzYM8A zeLnZ}Z6RE*F(@YQQ{m-c2y!EA->&o1w`ond;HprbV!cKfn4)fn-$FVtMAQ&ada^aAIYrO#Vrqe};b5%m!a-%xvaKbKu^sD>772 zK-#-bjPB}em*{YM@qGrc%ToQIwzUU)u5zSG(GW1-Zs9_Q>UuGQlJP$2ezTm>gzNO} z+jsHvXkQ9F1M(*X>=Xy@KW;4FN6|?b18})<{)L)OhTS!O8Ar}Arbw%H zm>6LJNtvL=jjWu{u?GC;)pyrASU=2^*s^)8gd!$CHhiK6C@W2iUNiOs-ftZi%>B;5S@4TUU zI*qKk(c#%7;xw)nl{zDiYcKCja0RqCA>FahMNtUib))Y4dpJ*6!Y= zH~x0lQOy3_(6+|n=H+@WtAt2MJP$OCHARi+qx^9oWKz{^Zc|)V>nqgh6*=fq0n~&I5MeNy?E-PfQ_hJ_H03qdslqb zXE!cAl=2U^C&(}1#MIB13p&n5uP~~OCi7pRsxbD-`(o$Hw1z7_wYMqADezst#tH#v zK!-TeZ98U?*>?1aWsZFPya{nCOJl%0F15E%&PL0#yxz>q_N(Ju&#vDwht1MgWE#m^ z_U`(tKnIURQC?q#c3tOpmz~|>Pvmeo#6bqMyTK`-q;CCDQ~p2bLYLrL^{qWosljQ|TKd*K z+O%8dQ*uP($oZm?Iz?AE+)~k1Vu=u7-z7m@Rsta0U1*7#a1gPH0=JN^ z(P-dxZF_dhU?0ku!27n!k1zOznc>}&;tZ?A-Uuaa&=&TcG!CC4T)Bm(lTtZZ!gEVgz0ddF!N-x|*6;FlTKaK$ zA6SYhQ0A=iP9xZ8z7XFf2NM>B)G1l>61EC5PlX2^1o%;V)Jd?pzU5-%)J|TZo{aK(*pUEyB=-oy&Z7~JiW0* zDn_WBs1-_bBumiw=@p-yxHB5Ii^E1>mZ}xTE=K9(+Px06jL9<(C`80BsDD=$u~7N+ zeaKv!uH=L3*5ROOihaiF;>2((L_;1qSc&` zC|dY~`eY_Y305wVEU{XghN##GOC`E_dL5m#g{&!12otSiwVUI3KC45~- zex!<<9nnLZ3f(8q76;jRF)#*&VmWxmXIWjYa{IHcN~4L~1Qr#PwX?IHOm6vR@(~*? z936x-+~DM1K;Pn|RlqLBQBFYH_(NiF1ZMWDH$9R4vMbAlV^5QVvLc&~L0g6*)vsz$ zgGsxiG8W~1EwX3#1(Vp?(F6Lb;9JmE9PV<+xD60*i2pjC3SW>mMiIhffl@vj`HfnV zN<35VJ{xOl-w$1_I9T%O4!=!WOS~hFju6C0g7^E~IoMwdl}691pnK4MpUhz1e3fp{ z)AJixKj}iX1qo(a+Xon%uHfW`vhQkYYPX}SchevtqD94@yiGEn87DNgQ!jqo6`IS_ zkej$=s*qu#I6R^b23-xIh*5~lYG5Jp2vuluWR&>6bc1r41G8A(HP8^RWDyAjE8H6F zV-KYU#Be|1tY{PN*m8@jDwOB8<$tx?n+QP20u-bwo3cM5gJLMWu$ zp^h9s@(}pYXcRt?U?t2KU0+u*&=V;z16es=hOR_HS0iYTIkPUJfmp>r2nI>~!RaS= zsik0ytj|8Gv>d3ELZB3pS+w$c(3U?P?E%Xy|B|nK&~RQz%G+U9K%?Y zo0AGM^Mh%f2N8s!&DynKnuj=#1Q;&rU`n9yuj`n;Bitj|=fqRuZ;zw%R?7OaQHhjE zeX;jcP_QAwLARS>iF@5|Jr~T8g?w`t%t15`3u!IpKBY{*8S@4Ky~#moopF|c%9O3NHx*6T;w z2nautz((QPtgsyMQSnP6{BkAug1jPmnS%+N3LnMh8OEwNrkJ-?%$j)WMa6bvSuE)M zKw-XM@1GbVAP9=X5$b~}BMR$G;u+?nb**ltnNXa`Ku1+0GD}6%jTzoLbbhFMYtKGB zzSxyDL%yWYX3YrISdTNJ$B~Triy<5Dp`kW3v zei4WSV`o*P>SCHSJ+v8}v$&f6u0>B0bO9^NW}*4P#w&Uv_o%13oIv1MlK@6DR&^nyjOib7rE? z(Z`F8Z-|6~1!wDPeW<+O#6{>hT!-;-w$+Tf&nBym_EU3GSGHE$(14M^{oc)*x4yys*q!Tk`Nn!i;n+IrX+x! z@H~D&fqtXh*{jaF5;?rUB9r%LmdHVQQx8+3oWGS3xUS&_HnC z*%Fy@H?&dH5KnFX*5%ga7?oR=e6o4wV4v%*FV$=P``Q(CA1<)k+DG4JS#!0dX`0vrl9` zGOnKf^%@ueW>*9^>`KdA7<^=R7X_HC>!@!LGn;MUeRhA5f|9Y>C<~yUFB9=?ORLcd zskdN=sk9x%X<(gsGseN$&jo`B^H8{ha)k(aR|~udsXv&8f`Ebjq3^L`nAve>Zqu9; z)T#4mt5In^>J327clKw811v8W^Gwa(WK6>^Az%b_8gv5KPD%5Y<@58HCa2gSKTz^f zfckCZk`g(tm_VhrO0s#(l_aO&P%X4C(Z;-L_Y89=BQipiMLcBIzuJkVK=cu3MwwM+ zay;vjr>k_qLWj*`-)2xisd>YYQtsS;Gcu9RT&zrwa zN|`0L#8sW9${-(RDQI5cEtBVn4 zTsun96oDkRjy=w*tUIhx84C`bn<)RqQP1Z7CR%A>4b(Ei=dSaTx?S}1@h;|xz70wA z>USkzq8_ZQ9LWFOo=bWHF<7k)b?^(X({2*K_(SkPuCJ_x%{ohetW12iJ)fJ+(MsQh zaNHPSe^Tif@oPA<7%dL4C7<-En5&g|Of~XSl;d@M`rbUv*CqxAbns-7M3vLa@?>n3 z$?W<=$B-Cs%6Kx!&N{<5RCldvV1LA@ARoXs9DRy-k{02!+(R~jOKL)%ar=j6Uxy*nOgP)a)~QH#oSXb)@=@~v<=kOrr(SJp8U@1cJx*i--k^+ z&2C{n_w!hsq>t5i+JR=SZPi7jOIU+m?nZvM(KBg}Xwq?TJ75ic z!Le4>x3z3%zmWEDJy&4bvIMW$PUjlabH|`F0+3Stb(lXRGCcaFFYNY(!RHft0b?cM zpu1X5)GrJP!UGa2D7Q!nYrQ2Vx<49n<__Gd14*G4+O(j#K(I7fMUYF%=3vPjfxU<% za_wABp3-2T=tjkHzYts?PM~W=N{iX z;7^^vqQZS7IY_A1abtaNf!b_DF0yw`6x?N^^3dg&f^iT7I^64dH$OwSg9?4J z(BbZ_LJ5>dhR+Iygl3=(@X03x?Ka8;CA4A^bc?klW0^JM=bw$RU%i@dHj!=;=3g~F zyfgw`tq$IaW(AoxTZy8#^>%|`?gtV0WdC%B2R1m+8rpOeaaXKnS9?>FDKo<{G}~>S z0Hg@iWgqvYRnk$ekK|>jBjQ*cp#|PjO{oTt3ulaE=S{^0q_;-GIOTfP-bMf$(`Qu;L&jn-dK!fd-h{hls~&IvQb z4^{{$b)AwHCrio)JzWP);>bB>rHT8WM9Bl?cc!V+y4(+go7Q`2STbvDizpljeqh)3 z5(Ng(7Fd3w>WRH4>Jjgfs+te2dlgPttYa~v)Ao0t_^JZ^5bSa284Kn^p`VNw%ImSh z&v662_Oit}UxJE?W-}OBgKD{AfyUpapK!Ww<@;2;0GIwqWAe#Sl;~!`WwoGS8f(0% zjA;OaG@(_cL_SvmzT1FQCXWTlmt>2cG8s50g-|KBd<@K)k-RC6P!cjbFJ1+8m_$I;8{wC;Re z6WUbgTRK~LGd#=z;5az%yqT1iw*AwOPAegiLVtGA^a`JIFwb_rqK)0apwlCwIWkS9 zIjcf|g*y#xeajh5LOd9yQ3H?5e)dO#&es|L9Xpf^Mm>n@Uz7H_u-8@?k6>FZ=U`Q@ z?m?ED?3H1>#1fX~GDd`N>dZ$XCruV7h@$-TDg9x+mt-(|G8kyO(%z_sRb5@5V)sS7 zgKzI0nTU0{CR86EodX`LfF6kfrcTmvHp^<6KpL5AGtCzUwdYmqW8_Z*iJvriS*NRv|QtHa0WAS-prCd)Ej!+`X zbrK6`rN+n~Wg1j!Kg$<&Ue#aZVT0F5^sYxFEkhjqg1lyrhv+0uoEAhEL$I~X z{jv@68@$h8|JnnDu&U@-U0-KNdsfA&r?XnHqq-WRVj? zFH_4{;%!%PxEQO&N{xBNrFc$Rj9{^9Lpluw>*5*A|G_=~qBS|9y(i)7;^I&kShy77 z4QtfUQ$xIs>I2A0v_*LViojC^o572uh>>NJ4Flc6|R|L7lB= z;5Ff&2r)2Zzyne+I-H!7>7-ERoXNbXT&&w^HNJ~eDO&Or8~`1$ip=;NM$+Nu$2pqo zHdYA3Ft9&jR{O)zA9tpvDvd(D(l*Tp)Cpx0j+>8oy4{` zi$Yob`+zRK0+pbuyn@N7{nQN=npt>a#w{X&f?AnBoRo|V7G*{UpUgkZP1&*bSD=0% z0B?7~fp-csW&PaOFx&0(V1ghff>~0y-30e~{BbpDLrpEs?GLY(nE3ig?87uer`2S9r7mr=*w4k7%*GyTtr zin%{< zfbaeJ@3so}NdS&JeO+$+&i^X=VFi#E_OGG0|NI*zZyUhEE4B^!2zmY$w8sYE-dB$h zj`#mYQFa8%(QvFGh|T(UtFLf?x*vVOTmLIKnYtAyhqiS&Mr!Im3SwpmK+cX6!@Y*xL%d~}1Ozv=(f0r&w|Bs#9HBq5RD z7k|z7CfV^{1d_ekASfs(WnEp}m<)Q|MrsU(W2xnugYSOvq!K@-r-eptUD&OuX!k#$ zc~2f-GI`q{u*XKIE5={Pd%Y6kNY83is2I@c1};mfbNk+0s}T7iU^eAHEPj5N0#mUvv2K zDBf{<$^YlebM{pm79pVsvD#=V(|nzo)M2bf&um>`n8JxvQjPHa>y}uF=kQ=|>btO1 zthvB>^rPj-WJXIt$)xTN_YYI>)4$kCm1euUI&6lRghtI8ykh3^oc?V7@~cp5A%up8 z9^a**(K=ixPrP}q5t{D{dM4o5ne_pvHz6(CT!?}GnT9e=#~cgQ8-PW0;#$)=^}SQ! z%iB7W=3^UA@4!x7fKo&aMFh!P^8b+v zIvySwXPY^VLj6Obn1;2c-ZLT9)!C{JqHw9zGlfah{Au2@NYBjoGRu- zhD~i3OH|A@i&oi6SIA+A6$f&>BW7|90Rjt&(Bbito$&R6ui|?1Tj_Mlb9{XA=)=cp zO=`CMKyD$eaP{eD!lFzE2dhQ=oS(_0g?mK992QqnNhuk&8pE?93YYQxhokvxzSUzv zWs7AfVjMZ&Q1&jho;+8PXz8W_g6S3hRsZ@0ZXet{K2g z**;sWq-ivMOT8L@*$si;9cuCyF@fTb>HUFal+S80KI+G4)Gf}}{JA*z!9|^|q}j)C zrwv*Z{ET*DQquGIXa_d}qWr;oGB+v9Cp~Wx{7CpUK#5=Myyu=WTS>mQ!cg<(`32sr zF?L;zN@*rXpo3aW8&X(3uUO($@RhJIDG7b8=X0#a>kKQV8W$=W+HTcV6iiH`>C@G{ z&`OwYbGrr7D|#zA1%_@W|JT=I)B0z6-O7)Z3lD&zS8w zZrK%!WirG%aWUDv^T~8thc!Z)YxdJ>=>WYdTH_NKgZqP_vyQk}wiwoS*l5xm~N*%dOF6vGbvL4-c=z@N^lj$Va3tze5zbadhJRF?& z0C}UIH85ZAPMq6YM&4D{-CD-j<9Nv8RT*)a#bUhg5vm*<+?bbsGw6;}&iom?JXZ;f zDXOCGh?0c6f>F@-G|{D3DIgE<=OshB`BQ0A!1>*XYBJ}^Yi1k4%d||s-5^a@>;17~ zLG@&OZ%7cWyi>R>?k0cCY6Ys zxh#}AEPDvD6k+mE7Un>Nk?-0j@rS`7XCdj!CsGv`_pI2et)uU8zh~t2eJa}EdJF4b z7&!7V33{J8dVvRNYz4u---Iju$odp5U| z{)0Gv!fSd{5b%8Ibo;QeI#|E{szf#N^dQcU7V8%RGcuFxdxUfWbt_(Ohi%iLQ0n;% z4G-%c^Id%oiWSXnzlF7g-oceR2*$CW{*yh&B*tm`F#Y{AzoW@rZ>o90!`x=4Q&)b< zNtg%CAYYR8shtK#cJzPeF-EJ^r>4p))g~OALPQI6q z^wHwwg9dyp^D_Aq-_WNKHoRN4ZhJ;M&X20U!R6*#;6|uML}E^rYHfLFCBSTa?(6H* zv^WM;p+QZP3q+{ietqzZzv!@K68d5{tlh{#i=-z}R1JD3b%*_9v!NBY75udpt5ky~=}k>}LRCAmg|`|!Qlqj)`dHSI>-XC;xyoL| zL!DRNXUq4wDW!C)Z@_dg(ri$ST3ilbjCNhYJFe|rUWt@iglFdu7|tN>Xw?E1aXWFV zdc1MAIHoXcmnBN+#4`SZKW7D{abI9`o4QvUsl)dGQgX3cNp~-SyIVXGDEV&bq|gRv z#h1ya*VD>4?99M^{aCn)_GV!*9x}@M0FlLJhbwS>8vf}3x^z;>N&(CKvP`3c8%*Vo zka670+*Aq;s_|0V{eJ0cczE6UP-J($Uo3yMufeXwHX@MD62>Abd@A_mgZmCX(l^mgzO~QVe81nSK?5`!46PrGp)v zk8M7qJkfF8)m5)!rmU#U0jHSabMi5Sqt1R|108I0jXH8wD=k|-$o{f5$9fS3pORaOLZL_6P&(B`IB&>h zn_#S_NCKsMr+ZU`^=^#M{Z@Z`82d$XGf^8~;@P}5;Nj@dERB9_@_jlQyK40rh)dXu z+gX)HAKSIN=zbF|MwqKp2V|?S3U{ zNoJUz1#ClNZG%S~Opq*g*ZR)IC*$VagRrK0sX~98R4N_#O7@0>2}%w}`Q>c-xkRzZ z@gW8+ajKcR5>d4(ExN!CLJ;L!)~oqsQJ0g4CmC*foKdX4ry5NxQR$tf((A|)8p$X& z%Z`Xd$a8(P{!D_6#C|@bjF-J^0Z#Sy{OjImKh1x<&E+?mpz)joA|=vn%ighXeJ$Y+PHP0l(nX${M!H2~P~&d*lDqD8Wn z??5kiTG$=YgGNlsK9ST0(DiBQpI-jDy4VJn>mF0nL&oZ4&o2&G9X7HKx@oWzCgYN+Z{XU*tTukwr!`wj@?nm?%4jHe&^oX@64Ky zv(|h)tJbNfT=nd|e;aPE02#wgjk|HsJ3mcNI0`%ujz!Vn%XXT>%OaJB-ofBtOJP5l z0puNve&=JiKL0mWq9=j=hI_#GuEn7;16X{8?WPx$U;J=o`I6dwjA*%uVqvHs#(Qk{LOh_-?$;ojV6 zQE|YGnad{aIFyF=wBz=R41^Q>}9$A_qstQAYy8Y?NH}c6Dnl zU35uUAn-FV(On8#62q_gv8s5y3Of+sRpBI$pjDB!`~ah~si02-SGVN7r7>p~O@Km@ z(kniSzFCtqDCk;cnx3x+TFJ{jjuc>;g=`3U5RUWWJMADau;HbQEL*TUHQ=cqYDzuy zgoq#mwQIPFBJ<8s@`87O&1P#^;u3Iz4F5oRBzcvubcE0c%4vAohdSE(nh=WDZ14bj z?)@~NF{ScFnX1%)CgDTowBOk4;Wt+1(_EJpEyj>;XO#>`jd4mP`X>vi|2Fk4aIBEw zme(uW`LO>PpR^7S+uU|)Yug&BQaJ)JhtrGk)C`P;2OZ}3u)PsWCeOkul_H`*-hd%t z!NMJZknJ3R*Q*M0JJ-W|c0sEpWNUKap`qyWYA%VaN_h8+C;@@&lPNU zz&IdKaCT^bC+mtzsn5#?O9O@R6`LTwl|TCKAZK+nn*V+PGR%Q@D+kGMM;RKZ1BXsn z_;`z{l7D_X?{%`?K9l(b{hA{XC4@CDv-YTKy~}L<2mP`$40o|6G>WyCR7?uK+3G@J6-8 z;vKQu`E$OUkUfSUp+S8+tfV>6GpQ_BrJ(NFNuUiIqZbsz`@Q60SFmr^e)R@t+zvU! z>B;&5Hb!&@bD=4XL0kIK`8+^`s=ZdW7!|wQ1q>)XHborASFX$L9PrB5>#epyrTrLD z=^sa)zV;(HRaMHhZ5AHE>w`@0HSSyHNQOiEj6q5sQ-ajCN&Sw}m?W zGH}E0oZ(xT8M*ky0R=u8mNGfVN*^~2L*fHlQ5Xj=cggP0In*w*aEKvKA@1nFEMV*} z=H=4Rw;JJ3yHsk`?Es)XKFjk4kvk(MSg;%tRo|qh-Uu`2$Vz_38eT%=y|4TJg31x~Jl|H5AC+NYy}4@wgepJ912PnlsP=a@n1@7uQo1vqz5k3ym=6!D z$s8{-?IS{nUG?lxO&77VaI4~v01mlK(zAqWdF4h)0>k$wqc|7ld6g(@G^-M1b9mf$L7|l-H9kkfUrL=*~Uc-ZeoUcF9TWse4wE1O@tx%Ed zenA<5))ap|P|jb?*n~)cC@~Zab8s6jIMG3*G`sIM{w6u_{&*ey=+qq@TP<+yQw7C^ ziNn7ZCLkc~3v2j5I7Xp^c%udQK4;qvY43B|ErBP%d(TuR1ixw#l11?%9nh`c9`Mha zrmU#27$IHQ<23kSPC{vDP#gEWF-$RV{4y#@YnShhAsfk=VqA)>ATuGKIf>nsYWZP5 zkd~7{C>o%574JwoYiK~-sK`je*ayavF$rowa^W-;3l9+|9RzpXC&}PFxd}W#I>z}&0Wr34_@l^EHdtv>( zS5S9T|E;-ATJihy@n{9b)3lztkI%11T~Nd~SJBNGgquk1((8nf+pRG81$`6c&czr0DIPch4qi5;U zb%Nq)-TBjf;x|3q)N8PMxW3Au^5}NmCtKYT!4Z_B3|W8ckqPOoUbAy@(mqYZ()79b zJRC#NN-5h~u2oj&Y3AtqN|W3X6o;%qxX5A$m}7Bl@m{#t?ps#YnpO<>bSvPQ%LkgD zBhWF37y| z-7VX(eq_>!j8G-=s+`rj3TBHEtqN+b>F1tAi?u9!=WDK)9LT5PE^Ht)pk;51L66du zTU$V+ITV%$(!l?xZ+J)93Vn^%bJZdH7nDkV?_f({HH2V2MZ<@NvK!uxmWqTM=D)Ya$sJGg|5`^D~(VmbP1Vy33BLCo}id6gR7}Xpm znD80XrK3LXIa)1owcuK2%cWV?g?(yOp2r}NL^mioO&?MFLxe>emE zmIx1#C~z6PLAFm-T>&!+NurZ&y+G74@@o7&N_LkveuMpRN{FzcG$qMQ6UFxUv)L>Z zwu}liA8_Z%IBGru_PtHtvCKZG{6T<{soO&irr6H|HSZq>)Q-fvX!gaY?bu2RGn3VZ zNMKDxcf(KIVy-e~iB=gAqUY7Wf%h%MenuFv?;@E|_q$H$SF$I_!8KpVcpatc59@e5Z|CzyyK=x>r(%V)Q$c+osmF zL9&upD7LSgd^X1ByS`(5_6|S?_Y(&aVt!>jAu|0u1Z9yOI*G%Y_R1if&)|LuquXU^i@_EyOY4(?C ze?dZpJ|*|i>2bxDh~fHdu`E2;06h1pt@|nP^asSOKqnh69?_Yt!pf$XQT1NgSfJ&)9n=UxHHRW zhNrU6Pv5Qk=B&ZE29A*03%r&&K|-%NBDf(H{a0N^{4>TxJmS;s&?kotYRPn)%P`D? z0K5!1tX)ArzjEeT@*Uq52DA`f^OY0gx9-EC{$)=>(q|}PZe6|;XuSiBKdrg(Ur0l z#Na5Y>WT{h;x+w+;C;-}Hqwk(#k#IFv3}HdTtxbhtNt%@vZw(NFopf70U3p2QK%^^ zOVOn0L$|w37`&i}d34OwnQtI(!+dBGVel6dO{)#Fof4|G!b_Da`KU;ppa!6mV>$S$ zUNj8H6CIs#Ud$rqXN^9Xr`Ut;*Sxh_EupMXJ<4zpltiE#IEA|0_pbNB}nO zmFWQeUt^K@6Eh~k$W%!Bt8Z<@`S-nM?W4oM0Apcc0p|RrPfkuk4w9dEF#~`j{PXe% zz(B#3<_f0)bKeLx!YQY&MM_Bb<>mU{0(i~vou?7U{-$xMxK7fQV^Ht5WaOt;slH{? z4vGGd%J;6plw4d&M%CxB;nx@Mr$Oo;mF;XN2oe#-O{D5ZJ#%)CfJ#=^lbS(*9^z^? zM3E|d{J8HGVOGWTWvI<<>Z$`qp>iY9l3WWShgRwqrJ`15m*q`6oU?#(ly6Y0 zRFCxake6H$?3MfG7=|DCDSW^OQt`2*rzw!@pYFx!H}q^O<@njjf3mpozC_QAYRjSr zAjcbIB;N%4Q(og+6v3~&pJp?*0$EI;k%IyH|Fi8H%++IAYK@kXMu#JOovO7pt<7qu z9F2OVv6SUzCs{}^>cYJBIVpvHY0KG1Npf;kYotB*-?Iad-6e{z6NP5^ss%;7*r!iG ztvAVprPXw3M?QU#GhsW`YJRi-CXVmKVRz|dEn-+Z=$mwNOs??*o*r!b+u zoYw&fak+Zjg?s{K6QESFmzT@2Tjd@&2>2wI-c3oiCX+g%?eCcc5H6tuycZ;eK-k=8 zjZ}KQgLwmTx?C52q*NV;KAFiN@1nHO`uPa}5?#attnLTW(C@vLXu~;CWq_E=HAN|O z)X8i5V4Teq_R`7pw43DAQc@7a+)uZWxelkJ=GOlk{W>7~k1P*OS~>H*hl+fp5Rcpa z3UMm;7K@D37>P`R0tFXW7>!x#kC8Tb{6f9c{yNd3Vh_<9uI zp+jIHlVhA*vF^<_xF2FfJ zKjG8#$!Ow!f*>$=vFT;v+SBQBJk4{NFDO(C_&WQ0EsjwEd(~1 zb3wt~5DExYqmr1koE*yer>Ng&PwF%U*&KqvyJ(6ice7HP+i%G*c)U_L9CiyAIi6k7 zzoYmDYE2klCR!;Ra&vcF^j_|4Zo!o;@Tntrw){ckonZ^9geunJUGSNNc@L6z}A?Gv^^x z<;rEP)({48e{wPga1gh0SsXCLtW{LW8| zB_$=AXg$7sy5_mPWz=&i6;eqfiQRD6ca%OiLgnQ1QNiZ^w#e+<&#b)N>*Z;hls8HSjdN5?mDkb_~=wU+a;$a|%CX zcuLLnIixyy`XypsvO7II2bk(rOc{pz<6amOQ!}ugia@17Po$wUkd&-np@RZlU^9){ zeY~(8r_;N@M`#-bJmEqx{+Fm%KzzRaWwGb@@v)b7+;YNWvwS-O8;4xsc<=)n`Igfl z6i=`8vszbTBCRf-bGty`xB-YbSjfZTV!io9;6;Wrg6DR=M!751dT%!*Dv@>-SdF{I zW?jCo`YFcqzFQr9AGAUVh>OE^gEV|uVX?*v0~#8-Fw9E;(8hFhd^~5wn>2%74nMEW zZYTY@a;8_QSX9}4kuI0vyc1~uARwGnHdESUw)eYrHs4nlo69>KauJ)JExkO?`yi5W ziN2`g7Gtd@YEqA{Q)v|5rbH8ii23Vhb$jW0>v?g6vgz8JPYgC!bftRTZvDH{5wiK@ z*(E1!8N*k_w-E^b<+#)33bBKsXvO#nfX2=3c*p5;e^0#D?h)17F7vwCwMpmO_NZun zGT*41effMVwQFR+&?Dg6nB8%z6r}UB46%R0b}Wd^$$6T_WRSJTIs|2It zej%qCqsv#Xc_WaQ@=C|37qTJI0AC+`#KWD|J3#l8b>fD)KEBksZNmq!un(wh&1^@~ zRhpHg0<6a`m5HTN7nlZgqj1$NQwTz_T1mjO>Ui(^61myQ6AB6nX@}o(Vco7*cEQw_ zTG;8WaK^PAL0~|0f#R#PiB*_fHp8G-vy~SLo85BoAGi0CF>Dx|6HuOTzHrC4N}XTV z+-0Wu!BJS6xx`9yXtYL^`aRCMNEJYvl}aXacJn2ynT^~2t5ioGTBGPl|DXfh5(#V5 zYTakJ8?FLQ`7H6+{vS91tfGx&w+;~m70S~9c9W#@wO_(*8yn&;LIKI%ZBJem8T~N* ziEc@>ZZDHqnLL+PSR6kx8U!cqCK&qWR$$P7(4~esklOR>zr7YHvH!WxYEQ0vIneUtF&d?v76ViuG}& zgJflMuW}E!O6>|<=%T11KGsPtLvV4B=qtx7G%hqOY+SJR z`Wi}$-?iSA#JGX+-uGcx-BFA;LG!xJV#IFe1nn7g5Ni-zrE*i}H@tW5%uMho&I8?c>7eUGoTf$%1 zYPLXE+q3);#M!QmzEM}gB|a|AxDNjjnjodK@hKPZ3Nl{?Ahs$~f8 zmdR>MX(dczN~$>Ke)Jx(HYzAPg)RRG440Z1vPIWItSA{q@)}jN6`#q8SOZ9Dst(X^`2`&AD|n=O6^z zfULPc%@VZeYN7C4z^b?JARGkna2W4&_LSKq10u!2w|M*oNh0yZM;X6-?4>Hj=I|pG z)ghZxhCuz;ysL(6sr!2lm2G~FEhEEHoowYT!>`oJ9y4zdll#|_0rVL3xw z+Q`kHA>SqQS;=veM4334NCVKzoQ^j-oaPBCeS19bu0(oTPL6LeyhS8pahIAwAJz`L zX+Z@OujWU#J`d@}e$1W|aaJN1EtiSMSW-u+8H*RMATztwKNtoQ4j`h5(6U6CPQK`z z5%j8>D)nfg(Rp0*TS+MS7{C71h#Id~gIx|5MO?+K$*tnq{H&|PUAblGHEgn!Lb@hM zOx)cNQLOV>n0fgAe2=WPCEwP%;N58L`U8s{DLkS=o=}-kv=;g_zm`F2Ppg3S_l_38 zHp2LY2tZfRNzCjX1T{99wxWaDn@^&=Lx_tHZxmuR5JjoP&p?A^UQix#4*wA&YLZHO zsBj5ylO7{VL;zZA^(vhyrLr`@PE8zK+P9Hi8R45!Dt=&;eKnKG-`OGkLrr{QY=f!Q zVDf0MTddy*o5}@S!}&=DY4|PS!^ecSY~8ji#n8ye;ypCRSzcBq4BXsbgBx7`(rs%g zBNmEfIsoKQpHage^MKIH8gy6X-7xC@)zkTs{1xm(i(HuD_m-VU1aafDKafw!Dgrrw zu+TQ9lIPtzKOY(r-uG0hL&^a8;9tJOg?58+|D4^$t4x&1cgMRfn&&-2`_ z=EBeFrjNmD!rcs^Sw9%0-knvVpptQQRsUPh>hSi@Ul2)+8E~o@+15-bNWR*L@5~Yp zYr>FVWE#~tI|#X$PvOh(H+tC5)vy7K66RHRe>$V#0iDs0!+=!lWYJCeY%~~{)*VQ? z&*MU-a`WSun59}9YzxL&Uq}j6V(`)2#nSQ8q=uML=|y}(y9A$F8loqWZo7N;eT2z_ zrnF@zyPkJ?9L{q3xA~xK?lfVVmAn!ZGv#Bzu_^B%j3MN_Vu(Vsu=?OBTk?6jpl(DU z{f*&kF*~2rmrl+|E#V`o2PHK7BN@7wM=PytOEhbbe@nz9*vX@>R<%R{>C~t3IQ}=v zD}~q=?XMtz2{xruRt`Hrz0lLGg2e|A(&=1Lmh)4{C*X@d>x83)KKH5s`>EVSmseH2 zPjv@5zSV7p-$$+0=k55F|1CZo&iGk)qt}X}=I!0hf_tdbi|^u`JUfq$sd_oeU8%25 zE2Rcb9*_otjQZN8Cbz1gG!OQo_H=(tR-J8<3JY1o7x172Wva(bW7o?biKq;HbNM2- z>K#cu_}v7*mtP;3X)#ii2t>46YsozG;rewxKpTDfz|Y?Q@^$vT5e>23O@J{^&ipsI zN;N`7v1XDu>;Cv?jU?)gJw9Z>)!^+6BC85*EzuX|7FpR;do`AWC{pNf{%1cn)~WH% zb128t*Grt~c>rdL)n-S?Q#*Y&x#Dy>i$ zVNgSw#ZFzrjYbSbr*Nt`wEUcXrvge73K3@rH~?a zQu^!6-=BemLDKg4mO7`rD)@G{7y-OQN*dno&oh0{`baR(0Y;Dh5-$;H+V!ODQE9YD z3yYsg)4viF6Iji+i8cQAR8m<}t;hd6S)!gc zk1js`9*2FQoXKuHT~&WlS1^LOpA0mUaWa%fk@$?L+HQ2!C!M@Z)>|JLe^Ik}Ujj*E z*%Q5>ru9y=(uF39>dW*~QmMCa&nsNvHGu+!$*-XfK_0Nd;azOt=|n1hGDX3rK>PI2 zVjY>XxFfR!$PCJlb+0?*_ZBXB{K!1wrMg_U3Xv3tNA$H4AtR3YCIah%{p2&XDU#^# z1t@7I*v)EBKV8MJ7ss$aX$lF7tk-fVTjV6eA{4hi;2Jpvo?p?X4qrj_%P6*1X-DB| zP-F%~2o=InzXkZsAL&n`kt0VTK<}~M5%BR5NGV)``7;jbAD7;W?!y&e$UZ5oUM$<$Y3C z@&YIpL@cKsM344)H;G}K%zg(u$(dGFu&_vl(5ru<`z2V$^hn zfixcHH4b;DS(kHu+HEpUzuv&2%0G=1kh0r|o_Y>V(Q#!H^TIXMq(xev`)pWW7Z_9@ z;oF`zPr3L2`QF=LN#SO2L{J{fh^2$6gNc45S)i0#XMEK}DM_^Dk-f$?#su;0y^Au$xht%YkdX%r6K8(ke|G{kcSl3QanBg-s~9Ua9353DVhPz z+^lpYd>{h&v z$99Smzn*WjWQq5@Rh~#%n$^}pObreMwJznkW5s%X7FpW_hoqpy9&H||I6axxyzL>Z zHJW5C`kT;9LUjm#DXr2Z_Akwx?>oG7aWu`T5m$go!V5=jrXW;qHLVYc8V5m4heR3~ zOeOSPNLQShc=&3%yPx5@(!}GvkGV6G+wUFv72F=a?xa|A?k9d>HVrc*+zQKgeP(nA zck9dUn3SFNIKpxb#tr=15l?UH82-IFeCdO)Ai-uRknzarEK{H?kK5nk-X=N^bOhsbJ>6I~=fuq$gZnU34;9ae zKG2($@wCNfA$QzTC<~{WP-#JLvLyqCs`cL6G`8raM_dOBhkafjN-Y-n8#-iRd-tuD ztEm!VFc`vQ45_jqd@Ccq-*!TP@Mn`#ajvD^WJ zpHxCm!mHXUnmwrbbIz*2(2SIPbqQbN1g@(sx@jfOZP&V0S=0;hyb2iwu{K0#xg-P? zN@pYMlFDmd8-2Z0X*5lhvI^D(%}tWOwPsR)4bY)Q3{G}w4gz^krMjPR7rx+;>~abz z?^pJ}gYv6i`3yc>b8vL71>-{O%I+YLRvJuwJzXwHj0TjiPhxu4+R@pt7fj&Uhj@$h z-*W`wghrBS)=M%0JB|!3qDHkXmyF_jiGn)4sn>h>VckN>?}!Dn5Eka|mgrO{fvw(B z?HK#spR(DY?ih}wF!dLvW^@ESsd8*>XmNjHfjDAM+&D}l^-p*{L`M|k7VaRh9k#gP zvbQ4u(R67>5?OX&C7do5RUN7u(})72qmBR%SZbn!RyCW*FCtjp1Ut-wMtn(oyvNU< znFqWf1T}H(7g8QYek1<|!*mT4=&lh5=eu0GJf+yB9jt)b+{iilb!Q!H^4h@=wKxoh zjusS@k!!V;AgY0$AdBP+v&(kBLBLXe_7E}JJ%wn!PQBx zt-HQ~aSs-esWKahvwJ3+O&fgQxs*4}0WRPqNgy9O14#Mt_of0vwD0!{a5b2Pt?(TY z(hML23pW`Yt=pMCE#3G)iC2MQJfk`NB0}z`|KdajtWc_E~ruzdEuysTR{2|z?>2DQ1J5=Mz6J^ai!%OPje5U9`5 zc)~eDt_(kGho}cdz&)9J3`Q842TU9;+Bcs=T=o`N9BfAo@8W}c=LnuC^5W$Qhm(QH z{b)iMp53oQIBu$tUrHnn_(y3KE1G_$31}--CFX zTWx_KP)08*z2VACc?5&fW@2?(0^}lTu_LbVi+=qJyoMD#uw1S~C`n-rNhj9}TVhl5 z9c^Q%yAEVP|E>?@&kxmu0gaiF;c=Jqm&daru(jqDI&YO}$QV>$(oSk>!XqH0q4?o< zNN)gxM5RYdwPq)$>v2AR^u=QI1&_D>gX7WaoZHZ+Cr@2t4CqIUr$IU?5TVAEjn`uh zlVdCHO+MQoEL#s?LS4AYOg`CHP;ykuDILhX%5U=N^&{*+3q>PUye5j{rh{m)-d7hX zaT@{vTA^)0%bfH@5D-+%m>BE7)*e_)d3gcM z7wRLm0vWltKl-RNiMwcG3|XB)oSTR&LS~ zhZpEgphB&#_}zj$Lj;pCw7&ubdy%QqN!i0GS2%_cfECB^#$B!lH;I}dJOlQg2kkJ< zl4Ku~k{DzbhzzwF+A)AY(^UB7D^2(UzFNHe12GAK(bO+@U*)h>$t$FhkgA!d0mP@G zCVbMH_5O=7Y1F#I_SJeQefyrFt5A%1`ejeC0QutgM#PmFDq=H5E|$ST5g2h1XsK8a z?D2}WpZQv8?-$d3pQbV4;}8Ol-3i1E4uS}=e0^VscGB#tYtQ?G1TBvi z5af`r@H}qkiht5C8=+suCLr{GmnaIa0}lr0CsAJ&_a;qs%^Y!7auxcxp-j|rB1az# z9aKTc?OWUY0i~qywMX!s$ZHse}RI5E0h?TFB=AczNv(6E z4D2aGkT3`W&g#u?3vCeR^XpEHzmy4i1wLFNJzXP{hXqS%gQfLlyh)*N?x*TTYmh%t z9oju31@rqcO8LG8^d%7gEGM>9L+jrD0^0Cc?y@HNt#^?C=e8vf%$-6%0@WU*A;3;W z{-9jL3Bix{IZRN#H(D_FJ}~V=Swug-O%&A;^qN&#*pN8J=ZNHX)upi3DzWE{7HQ(d z{kIerv(OZ~ijASQgCQ45I`s_XLZco)$C3x{3C^$?w(~n~()p#Z^2{wHh~3ZhFQg_m@dX)Hg3?_p@^AMV@9O(;w0)L zYQlhlEt#{fGArxf{&){e%x<~{k4^v5zdP(HG{8O{sHw|9DCrfaS8V1vDjAc? zk6>)m)qh>o@!DvSfw+TP+W#xC-k_8q%8mG|@#P1}P1=0hr;!?o4!-sC%Myia2X=|T zz7Gg+?YGqQ_?C@`0<1dDZerkc;lirn{bzSU*tPKTO~r&1NUh9sV$)3^vZJC~x~k?6gn3M;2B=M`y-};LJDPb+{tAx3K!Hy#>Y+I& z>0KcONGnjOwRd~tjetOD1by58O1}YTDdW0*H>2E3CF=bW%F*rL)^Q+l!nQvVdAdLy zK&Jk`m;!I~KZYc)ljoto67T=t%Y}6N0?I78l|$Z|pYH%!cwvBzhLMDCscK|8Xj}j^ z`+a^IQs?o0ZH452n6SVNX3ul1`C`SHT%>Lw?05Lk%p?2PX4>SX? z{@py_fB(cK3Ro3<|1eDOvwA$88DbOGdHd**%R^c&=!Y1Ii$3fv(N}`grdhFzI6Z`~=H^(dzjs6+%@NR{kMPjxNR)-am|U2y z(0+U^*L{t>aR;Q8@1Dz8T6n$gn}q=?A0x0wte~La7l41|pndDl#ULX$ z(@YF-HuhY3xUA7>w-WK95|&7(nG%}-d;f>^z)V3x@;y>=bG|i5t;n_qT&3FGp))a? zcH#HZKk^{JFa`zuABw_P=afoRWTj|(hCD8x$cOVyIU3(*Dg1RD$vyI^<6K+53g?rr z)JnzSv;+ixv8l9Lf?-1v<$P2CTE(X8sIE$vJYS^>RpQ$_2<8168@B^Z5rzR#W`jSHzaf*@#Nj*UyJqVE$TauRQh`uS{~eO+bX^Vfr@eZxNM{E(D=IDT)#1%n&SXP6RO!vldDe?xA2V(gj|Wp(9Ltl&rio6z zeQ6ZxTO2GLTYN_wP7q%oFZd|g>0=|KqRh`yr<%=oE}I<>n7a)5`9S2$a(&SOad9S# znj(xmzqK;Qfw6tOo^Q?6F3`X=!GiMgZrmS3NioZS9xCN~5_bIHXE6&4sFE_Xay@p| zMP)e`m-I)CP726o0Z@7VdplN(&!B8Q-2GCVBnaGeP`>A(BHI?(qii>#7+kjH5^ps% zcHNhmio21( zy``1a8?jOjkJ&t$x?IsvF=?443riOweEhV&??(Xt%Qjw_v%c*}G@gXn$2%|Z$PS@! z@!*bfJU=L00KKLr?^jr+)6d(PEs{vdo|im~lj6Qy@wqvsyJ53D_nakc25O8zf5KU6 z$n1}{CX2UVsY*IoS3v)*G{6p1d;zGVA4@Pw7Vou^=MZx(74WW;$&2NF;S3TzUu}}G zh;wwaF7thdn1!TA;MyHCqViM6e;?Pvt&;8fPzxj=D=sX|26SADhE$JZGuqeBe--Ki zOI(>P>zQ-@@`cS-N>oT?Rxr=^tylT_j=T+qmzIISN#-uT7tmpz?VXsMtn#uF(}p7o z;bN!JC*Lv$=tw(VXv>@LJfE?JJI=!!Z?b~SZ0-Bp;|0O!;w^9|7o|omm&pqBkAwVn z<@qv>#ebM;{b%bkAq7d8ZMWW4k{C<)*x!MuX=xcduS`a)Gau@-Q8Ru_Ur0+yjYs}I zhGmq&1N48tq?+>aC9&J+)Lj^eXVq_!a-T;xE%Cj{VZ1*>1Xx=D5zUcO+nLc%WnUAr zv9nhiKNZ0fFhx%Dd?LFD#LC5~5vME{pNof<<)+IIi-l0z$$aA4&k})0yqvG-9|Ib$ zoKM~QK0r?9C+d_)q1VXt!%?eYC_x^sT!DzkFWiW(&Tj^x(=bG8%X!Jw3UrCB&&% z8kE;Wx%aQN8}J<*+PYCeyEvxNYbGz$gehym&%iQ03AWm;Tb?1VWh_mDc(6k(IqzMF zFHKjb(3DqKFILd|fZTU|IH)(Bz=2?c{)EHfPjtQQZ%u)kdvURf7Lrf9cMXNcbr-R; zv`n4}X=6@*e=zVy@#tS2Zu$wZ<5BxT*&UGTA|ismiF_$#vC(_UoU$`T4#^ah^?h@I z$8&8Dq8&guJ<2=8j_LQ4OxvnA$Pp@Z4&Cz28SPaVrM~5Vs}*k)I7l4!J2l2;^CZ}N zN%0f7WbUQaZw+p>+bVraViYeaDN~kmXiy}lqnm1{r?c?2<=vQosVM;I@V?C9(6JmC zBr!j~^80d`GJxGe%s_hK9|X@fqAAO$@BKl={W&;M?pA2T>t<1mMgW;$DOOKXL&Yhm zZ$Eb+4v6f(3q%IXW;^F+N?}5I2MBG4nB_S?6J_0QdqO6aeRgdt8C}hu*b8P~kG)5h zpP0SC?%qH8WzPhSXr#F&lm$chADQt9*-tJyUJZoJ?SGG(ZyR|g^o<3%xq+FPrFI2f z3Jf^Bp;|#Sjdcxl^SkB&75kty$@sLO7CvrM((wgvr(uc-@lNJ+=cEs|5=n2aV;s5Y6;XH>!3& z?_=OXLSvCs*Y_&AUhh0Vw6Lr`9gjWmblHR^r*mzz*aP2lNHwt*@}RrSR69F0vYJSs(x1T9bvAApBfiT`Mn2-7?-B#sn;p51Pp$JH+JSOkrYT zBCgaFJLPWd1!RN!rgP-|nquQwjt`vxjdp|d^8%@xx>#mGz{Tp3iG}B=JL)(kEw70j z>+!?_s})cxvHg|rehmkbA5@F221b|-ZYq{X$Q=yU5kbJcO}i$ctMP?P<@btwSH`z> zHwt$N#9|6l{@<>%5it=ZRO&is!i8TcO!d;_GAhTu%A|^~-y;~`Mpi5=MiN+Yn|6=p zxkt{+*JyQYWYRtc3U-Naw>|e^idyzXKyV|W!O7y*u`i$`cX#KE1S5RT_Pi@|C``68 zS1`$-TTKzM5ekzh<#Ww&lLM?YPcb6v*68|bl_u;h0gl>qN$ra&66V-F;bhd*ku6V~ zDWQ;{vpML$HXypr6!<-7E*h?3jS^iQA&~Bdi`zYy99`w}WOy{bqub6iZE%ymL+OLE zMhwPv#2-RR<0L zz4HA4rfBNdya_LgWfOoNV*}STFD7K{6aH?7W)9pU5W*&R0T%EO`DFws8Ycb&1iaIH z;#%ibXy*kZ$pZc{7j!RY6~glTR8@Wz2^rjQd79J2ymP<~8`urZ4-~uV<98gW&`;EM z{B*LGiucGL&}jTSzaUI0%bxtQy@)nFM}3@EdJq;?k8}hvNkGUj%St!xafXMvMot;{ zKl2n+zen)nN}+NyU{mGs3y&8g`HO>SQ6R#--SXex_0fb$=EQ1{=LXsmm;R8kR$91e zYnpbzF5V6y2dEgavagW#5k*E+jO; zvE^N`TY2o2{dl0EeibzzxVppVwrN=Y`}%v|$#Pc=5IVWS&j%s!b5NG$QT(1Q!p!3Z zCO@u$vB<`O#LxOX&^Ka2fWy%F`;;5C9Ogy9O2BWkZ!Vl-nc;-9xk%}c6LHj`D83{l z;<2uC(iV9H(Lyks^htGrXg;%|BHNe74`9Rl2q-k+9G`@Ubck{L`=}{fX##`-7L= z$iOD(`Mm5lB)*g5(y1$^NwSDkyn?HtYT`PWbs8NG8jBAy%Gwqe#`dI94N4; zff+Nrj2RG6Z|+luHV_t!1_MyqQMm>uUi#A-Ib~q)O-|tYoz4l5Rw_@Nn(h8=9$T=-9DE^h=G?WlOI%lyHYabg2`*$P6T?TyD zw;EOfKMV#WSM!&AraKG*D<4M&$YwEsjp^m#tj?Dpybm-FckGEghHVVoo2CaUyL?9- zbbu6E%jq`KP!~Vbwpavb@&EMpRZ(#+O}l82Bsd|sdvJGm_u%gC4nYTZcXtbe1sF6) z2=4Cg?s6vI_wPUZT%MaVH?!8vdb_LZE$gc8dbog|%%xK!<{*7)ifF1Wsde!@x%k01 z&Nh)W%F5mPu~DxqaOZPMblEvftEowOlPPydEw($6we0$c6{P3Yxk+!*>o2idyQ>HOzy4VwXTJ8pSMIw;2 zs5zit%WsT;!bxs(^h>zO2M?`V#&SfC39_+8hO51IHqU(nTDi;bp=?nh(>ho;1jDf4 zSsCw3k-taM)S$`wGv>GLC(uTH-|VbyH{dCs7Q5b_#ev*YW9Qy!=a zq_Cv0?lIVOrwkhiRts>8RB^!uwm~$tA_NmPB`=JK*bftgwTdVKP|6ka2=Z-PuWAo0 znRaZQwt`R2tW#MZVE3K)WV?lKSh7a=B@_#vWH3V4@cc&ch|XvCWx36~m)S(Jw3X#w^S=F4;qBQNFu^DpR0p4SJv_?vGG8X6l3X99JSg-ROv9&h6`lL{}?^zRY@j*={}E$sRqu$iMqxu1A%;D7Fgr^lAHIPUV! zTHl9~n0!ET#+~)qJ!f$!Jf{fqOkP!uIRb16vM>EWuNs<7oSJp;b(o74@QqAiobKK>M}^t#{Xmt>d-W_Gp92iv%29QI zH776=_QC)~XY9+>-it+tn$k4tl=S;7c4UqdK*-*FBkwW{G(iFD)(fLxx5n1;6@%O1 z?ylVE_B6GU9ZY~*3`A4rWTcpZ-Qh&`X?aXuO@Yc_DA0!-hR~n`6Jp<#P!>72_@c&Cf!9IkOF(a$jMISnSfK zSSA|VRxqMenQ;sY0mE})I-XHfH`ybKUbcnX*|$&f*54@<_?1HpnP?bwpLgyPqj;S2 zl-+M|(tFQ)`ujLOcvI^l;=-WVBXmy>$IR`H8afXNBFNf>#Z}JClwkpDrsM@8HEO0& zp?or67gGqo9Nyu#N49D*GOqZp71AV}zaQf(4m9g2$EcKItPC=6^WYmO4J@RnskS;J z^iSJzZ8En5vekZ{fkpbz>eW=b1n7OnLn0<7frp1WMZI@@9djYG2CRD^b=zCMGTe$H z!faYmD1{lq34P$UiFO*y2UL0=5yr6sYcYL7>b{n0)bd+Z{Q$QUnx0h)qYVLZk2vP# zZParIo4b!F(XL(F;~OtPu*+=LC4$olTqk>gUo<`y27zthP~za_Zk5c&73h6OFgqBX zhc3@M6BZN#E4u3|7t4R^(MxCz!?SlZGIP;s*mp@D0Re>tbNlRbOF5JT2j_hZ9Wjo= zokMW`@(fgnK5ea>8$=1k0`Jn#MG)rb4NC%MzM!CdsQmWR;|ifJ<-#p?Uecj~RRVfo z-82U>AL$;7_u-zDev$Em&i#e92sKfQZh_^mi%$KlzNJpt!kiLLnXemWm>&W+K98dX z&Bfp^MPWA(e06<`e;rm~i7Fm`{E-Fw$0^i^+2vPbJKWN{+L!Vl}NZ0Xndqh8`!2RG-`u%e^i(?CV)L15a4M#%f zqY?WP^Ud~*M=wS?_m=$|k<-sn*2{G$`2%21&cU@TK%-0K=>Bo{=&jg;KwoIz;Fkl| zCIr$2Fem+B`}a<{UMW)WMD&q=FXLgB3wb+ASIt&!=VN__Yr1!+|0EIb+tankm9cB| zLTCyf@9*#EdJ<;5P1+v;JI(VhSU|qYJU@#>g3Q;vrJ2C7i_rcs9UHbQwhVRH0s<5; zT=nazaQ`?(7Ds-#*VT=N!x7o8JIp7y`lYC#0~}ALrzxYF_hZ8zUoU_uz0B6YL*2P> z&2C4))fV?<=OZKF*w>}s~uJ25raSTyu^m+(Ng!?5s#@=GC<%fXgP2aVZ?z@ z)iJfp>`ZW!W*`r2Yl=~58IVU$gISu1bws{+GN5lr0k?2uh%$GkyJ%EI!u@4@++;N| z&QK)MdovF0PMu(OT3PBf^5C#C&$_y}VKss~{Dkx*pLM*(L7WD%lyJqu+zokI>iO{; zNU_Aj9jQjO7=RWNxS-pHMsi9b9&sb_sVX%nh>U&Xcs`%>i8)D8PcP@Y$wDf7eoyEj zJ~7VmJEZ9VUJFuuoXF+o)4^x)g265IQ0x^-C(L`wb5rZNa4X8ufxLf@{&u(=+6eM07}C zNYPhw_+%5XellP%N?2z7Q|aQ9OrMH2k-{l_5j4;C7^e>`eTY@2@j!P{;HPj^`q8e9tj&r3}{4L5fKE@FkCn z4N}E?I`e#K5l^xs>(R-Q^TIVMmlk05-boS{oE9PiuNeHbjvc_RP}J(c*aHdu2y}L8 zphF{4FE1~b-bw3v!nR#(;4+fsY+@io1}l*uIGF(saPwwREUrWmae3M6w3xgUSZ6Ms z9wQ>8E2{U3uWVLj*3~pK3|u#D#q+W&Dyj-}A0C8D?rFo;Q*haBdt(}8&XhWOiFCnv4;E3=)Z2d2H(V+~5 ziZ(r(_ouH}rHxC^$X0JjxNVfia@!LGk2#jAD=b{N%G7`8X&17Ij;VaK3 zjq+xs3(;25jHgQIXbPNtMS=znQ61UhN5ZslcbI@=h<_yJe+0)sn8-wwCh{c?N~l2g zY_nzCBh%8-lGVxtkztKNJ^usZ!rCwV{6O|f=e<$+nJ#1*(f>-%e}%{%J~&F!_2)Z2 zp`;ik{BmbAb7>ic;=>$13yD+t7@ZvZV770cXaRQ-M{~8Ys4~*-rAfXue|A^@BZGn{ z=b?g|A(|*l z*W(Q2v5M4xXcFT`geMGMEKwVoE5iS>L=aajPc0l{Q}iP?Z*Zf?OF3=k42mV5;d>uc z6td$W4Rx(kCT}%Y%<8W{64WohN4nSF%A`&00NE>I*wjh>GL{J5LnLn|Ox4AO^&=sF zQmct+1tXmA8}BY_)N< zDwCgs>OA>i%VX9aZQe0fRx<+iKCMJr~R*1G=JHweX8YFQpA6vN>yGq)1Js)Uf zd+NG_sF|3$XKSTWC(M5aOWzuI@}_;9v!CzsQ>&+o>Q@~7%b9ijfIM_+n>S_yLH{K> zeS^iLSvG)rjaG3Czwe_W#* z|BKD{5rPi$QYuGZG3T1~^;0?Jc1MfBMo6Fi!q)t)R4nq7(m+i1eAHZ*5c8C!;M^-7 z9L)$NUD6Nv+}d=G08!i3_P#T|M;|*8=D&I&m?=h7CQ3t29wO&aJlG13z~ZU1@FTUb%J~!5`-Kc*C)+HH}7wT}8w;L;=6w zy?ALHor>K0GsAR5JIKtPV^(RQ2D8CvaHOhKLhyWQt+xGJ0MXJ$VK>f*EMM zY4Ndqht7Z<_@;I`s-u~|_s$`%3`dWS`cJ5tF9DI5F8;~~HjLinDnv?_T*kqIA+N^o zrH}=)jM2Dh(R35q25G@K^f*p~A5o?9Si6Y)??;2+Ycie`D-+A}P|M{fo{f$r?Xa$u zJAJ4|P1|4ILj@QS@?V5Iy&-fh5GJH02_ImmKa)l}8vmqMU_R6)pPu;PkoPCnZ2K<* z(O|_z(i*rc*}SZG(rR@2h>7Vq?d~J;ZaXeL4p4S_4*1ugZzQE=5m6k621CrT^D%5%r+LX9*SCf z%oc{)+;rJadzcXc7H;p;ftWW<$t2Dp?!2sqNaIXnutn#0`0Za$55&T)*{Y5xZTX9{ykshA7TQ7+%fE>ZIVMDy%y_TdBDx~l|G_V!^10SY0=yqFQ{a%z+QZzrp~X{ zZc<{(MOA=(FxoPrZj<@sdNz@5lpduCi$kq%RQvV!FVH_8=8vOU{WEq&Wo_ZT{003< zt#)U;+v)NF1`4`pXkfZ z0Qgv9sbsqR05)nX`F#mC>W@!^KKNJxmd``P?9RajR|k0hZNxq_%OPFYztK=1**cem|dMhwLV zrqw;Xbbddk!O@$1<$4<}^&Q-ebV=JASKyARToj`5W1qb}6v#9}fCyYK_bel2wGsh5maQPMCSI^a7hto?>EL zpZthHDpQR=)a(z&zp}B5tDhf(rM2RaX0gsO5nCX)_R8&~pk0^WoP&Ax!p{qr!-n;A zhlCk5Y%e)&hP}j4e~p5eIEO9GoA9!r_~dC(;XlE5pkNWnIDkzWS%+)L_AdT)(HH$i zULRPTW#?~}zT~u#hQdmM8N)#9i>MDH|8R7{`Va?Q?p~XNF+j_dOzok;Pp8)&Mc{p@ zSxd2q+6$O$s4P`e@Ea#(*`Qu7-5-OaL<76mcap;2{nbKBWm+^#K%F|{BA?RH>L7nG#evtRX*3?p6sU>YF5yl_@;4Tpm31^ zy|mS#ikGx(C2Dy$C=v6M>rI>G!s8?;fNb5g^?Rq%+-OX)JyDIrG7?q*@^m`KXrU7H z)c)>!z+}WnQC_ORR#98_VlqFV&2-Uz!J^ZXwg+87 zzH~UCvaxcSwJm7s?uVEY0IO{}FSfEIF?y`qFK(Y$?*{ZgY)%(?b9k-iXxsj7Zg@%i zEOE@7mW;YKyb>^P*&)r2KDd{YV;4vDr3r$5?d=>mDSn_<28YiXE(qnD{1r)uXKTaT zV#pK=G5iv0O|!5Pwz8o5papKjLMCBE=0<4wIOP~{$k$fXSHYjJ z@38&}K>_C0js`8~j06-hFPSxa8O(`L)xz(M>%n~Lgaqx9(XHE z)%VoZSSh#?80B6e;=c0J6?9*{suMy~x_Ct&n8I(?tG$dO`TSmGjHkFab-#HH3ulbJbK7SN2aC>DfUR+% z*#sOX$-6dhi)V6O$h$AU#G!`^gF1)xyM!$8ap><81Bkp5JF{;!f>>?W;$_Tp-Klr5 zFg$1}4g$Z8!Hc>dN@9=i7Y!&0>y*~b+p&c`nZoqnhD z#^(tn^xZZ|zTIYF7%v5O7R8f>V(+$bt-V=j+g&8=xC|=+DjW1Z^)R}*Tt&n;uRbVR zeyvL8WqzUdx*JKwG(75yIX1JjeB$$VVX0VZ@&!1qOh&@Wz7{N)-0zXheg4vVnvlR; z-yS3H79HOm^6Q1YwebvBTpv2L ziw6TV+@G&vM092Wt`3wuk+t*Vt*_$u5`12Y8O-4q#fj6??2|oeeX1kobb#ow-3y_$ z_*QsvI`f&{f^^Yq@@iKEUl0^ zPiQLgcaBqwKUSbixVc^EF2&|rrZ*SGRailR+g=={0{!8^d2D2cU$#OJ9kSzDqF13) zh2luSBK9@;jF#HgZhUr%o&wceR47|-Zl}qqOhk}N?C5@v-A@To(F_d>~Uh=s3Xu3E36{oud zmj_aF@K;o!#jNNTJ#C{@^7S!6btJq@DSX>a-2CsHZgIJs6)Z2`!MN%)paF_wgNaI^ zBles^Cu`ft2Ux*%uN^W*>_w5ICiS#L4C)L<-rgqtF6vDDp$)hj%(jsrj@kt zw1e+Dq41Ez%EV9|bZl+wv0_8A@0ek8vtj+853aqy0#TY|0=~a7(yhLcb`trGG0S0@ zNqjbU@5M@It3cuo&lTCJiFOT?j`+kGD4FjMPmEG_+vYaHyttOS_EbTg`gxaytP2@| zq6Lm1=fJ2*74~iuS^bUgb`aDqq`9flK%9zlYgO72L8NnJ0T#ZLIug4ZGjF+Qdcv@)JpNzrz#zoD zK5f!NhpL2ij~_)5gW+B@>k1^wPurr=Ch*A^)LnPT!sUZE9U?*oNC>quWu73CCBbJSi$>v__7VQ`w*`De(i2ApIagt(LR$8m-UA z+YU&2FUStMC+TQdBcIyXk9lN-e;wKd;@bbv?yK_JnQ1O7o4<&K&8X8<;NNUGiD&Q? z%(3HINXqGdCGau0DM$fdN}fEcLcl;kf+A7@cHZ|hUj48x1|?8|n|~I;2A=Q^lS%V! z3y|-)CjAx_lJTk+0T!GEIfl9&07BaK_xfPpg-@QaGAm8)@>&3@&C3$Y|&wGD4bsw?+_Ll@kwP;0k!C|Ui%yk@+9#9aQHO%G~81^u*NR7@XqoZbnB;| z4wGh}ht8K8LT}z&hvf;EMQX|l-g$4wLsyOkJM5sa<+v6Kmekho4~b@4x~cXExdw^Z zBjFv5xfzFPz6CK$XMS;ZZAXw=gGif!WHK|IhU=@60a`|;oh;|IGAU0q%hR0ECq-aCPwm$ClY=!#cQdc z5aaXffP?>`<#*^A?1}k=qmRaCd@OMEVtK^M38Ksb7@%rDleuSw8KLd$II6j#@xXWC}rhCq}sR z_RY&kRra)6yUrt_!2aLz($X^2ky|pBBT2dhyuG(HT7t5?;Q}WD%v(}w9DxptT#h1% zZdbN5Rnr$nwu9XNPMce9RL z*#Zb#GcBN7Nqa>)*;hjbvo|ujatfpTT-dEBzEv-GIaRHE!5QR9%n>aLy069iat5PQ zXPq8$2y#Z0?x1?qV59*-cE}!#ABivJ><&fep%f}b&8_5o?I;!{V;eIJ2Xev0-)0=S znV(~t9n??g*lP0T8c zh|I*=1IM!OmtI4oGYAYK`>@g;)}N04PN^lk8se`8Ij8F9G=G4s zG^+q5Qu&WhQ_%SjHISXncOOi5!ucR%N+G`;C;vg5zti%FVtPNE?gqCQNK_qwknjnm zDEAZQIF4HjAhA_baNMij?XZg}eW-gmi()Q5;G0De$(D0Om>!8Zs(Ou~>2iy&xQd=$ z2dWc<(g5Et2qe>QwmJ>^kizIb7cP;1QR$!&o zRgHp^mto6ibvrHyY2EZL#@2rIWgXpXqxfy{Q@5W_h6~AXpyW9!M7ma+TaZ;5D45d$ zU_}am?VPkzIgY`8@K#gA{^>Kx1|WC0{Ht8q=U_4W>H^#zJ+Hl7 z@01R;iRtLflE{>XPMaUSYcyP3;W6As^^I0yE~l+0;#*w8oEDG>+&e{E2S$3?X>sGv z$m^B%9mc?KL7(yckCm(%bLfrv6+oM4Tc37C=uQu34xH?;p@tEFp^q}~jq{9Dohr=ovKgSRjHw*^; z6FX!|%7v1y* zB8ZX{Tbs!q_ZfXi>~1R_g+O-H_lS;_kKg?orqE30Dvo;|J6Va1iq?&47ofT>A6H(D zN7ayItk%8Z^Epvb4(f_di$`Kz4lbaFM!=#cVm^RyV0HcA;Dy}w3>Af>@orv93KwP_ zUboLNyCDTOW>(+-2_z?9z%s_!2Os_I13aojE44>yqoS*8G3LSZyc*hr3{)#rnJ2 zeOZBp5ET38Qm-svpAxAOVky(UbL?06nhI$4^3Ta97|1xRDskw8Z$zUBT(b!^ZFwzj zwS^f$^IfrnnRyIhCNX)*jGaQQ=6#jDI!!58Kb^AO>U}lXJ{}wq**Y>QS-lB5be?_M zE-?JmDldD~jQQr`~-Cx>?E^ zdE@b5)6YGPaUwGAf`SVSuqrUCrkuXBZc3U0=O$QMzXvzNF|TP)MMt6f7`{bEtYanA z00;tp2)r7(Y>tV^tc+zn=j6AJS};lK`t5YW<5Db187iUby1&>4W4h6!eY?#yCoI8^ z9jjk)d*>U3{@9nQzlD~Jzd>>xb@{t?kJI(z&!bD)Qfd_wS6632k!%F5O1k#uHP}=g zaN&SqCU#~)1tgFC@NOcPxRvlw{1qPR6AbT*?D`haMz@@VDaGg+v?&+q`TMi~-9oRP z>ucD8213kY82BU~i~5A2%KBx=xAd~L#i8408qAmF_Qlb~)Wt_}VMck|*@j#6T>%@a zs>0$U7nCBgN*UEM=oi`C361+$Vk&bw`qX)oUxMoBgz1p&U4@=boZJJkwmgtK>{R>XXHy-9sq~wJ9LsGO2)eR7&LI=2 zXlYeocXiI6atWjmSsl_$g{O9<@+@(A%*epil8Mc}-xj3+%)qjNIWN9OYRe5kS4y@{hpfs&t-J3v$BNyE zg6)7syZ%G)fno?qf$v7BLY%ZO9{MeWT}5!{#KV3!A7c=rbp?jU#tHsFx?eSZ7}~Rc z?$(L^eRHp(=i<3L7Brt0!+NqzJfwi+d!=D83p0^@v1ld6{z7M;>fa5AwZMn8$U>|v z6g2DHCtSq4MOqF{nXg9)wxCn*tq$q75TV$RgxtZTw;xsouo`_kDuA}v@OlofaY;Ko0&w7rkMJMhCrF(jhM0{F- z;-o6WX{Mnk_utyO`SJjE#IvbIw3%v&H6HCYCCk{d)>h^!!~OAmXffAAQ7}51lEhaq z9v%3ik|VgOdPH<&VGKSfk@T6RyprDNMD2s?F~&e}g$S;Mgx**b1UQEe_EfNy<@rrL zStj1P`YO_64Ann9D>Y0Bk+%&T0HV-8)$AscoNMOmhc~^YjaQJJ2c55L}9t zbKPMg5U<+J6Y%~i$9y9~nT7YrT@7}>iG41?!(83QWK_ zF_9>Z%e>6*f6=l5o+IKMS+VtB=OOa{gpB)jsVV=Wr3dWUFgFPET=f4EEerrJZrqT8 s?q9S7lY-~y5fD7+_)GNv0|VcX9i-*03mED_5a5rLn7n9>utDJe0X*&-;{X5v literal 0 HcmV?d00001 From 089233f4bed50267c966302fc83335d2bc71f921 Mon Sep 17 00:00:00 2001 From: Matt Morley Date: Sat, 19 Apr 2025 16:35:24 -0700 Subject: [PATCH 06/42] Log message on robot mode changes (#1923) --- .../networktables/NTDriverStation.java | 148 ++++++++++++++++++ .../networktables/NetworkTablesManager.java | 4 + 2 files changed, 152 insertions(+) create mode 100644 photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDriverStation.java diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDriverStation.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDriverStation.java new file mode 100644 index 000000000..0e48008e8 --- /dev/null +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDriverStation.java @@ -0,0 +1,148 @@ +/* + * Copyright (C) Photon Vision. + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +package org.photonvision.common.dataflow.networktables; + +import edu.wpi.first.networktables.BooleanSubscriber; +import edu.wpi.first.networktables.IntegerSubscriber; +import edu.wpi.first.networktables.NetworkTable; +import edu.wpi.first.networktables.NetworkTableEvent.Kind; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.networktables.StringSubscriber; +import java.util.EnumSet; +import org.photonvision.common.logging.LogGroup; +import org.photonvision.common.logging.Logger; + +// Helper to print when the robot transitions modes +public class NTDriverStation { + private static final Logger logger = new Logger(NTDriverStation.class, LogGroup.NetworkTables); + + // Copy since stuff was private + public record NtControlWord( + boolean m_enabled, + boolean m_autonomous, + boolean m_test, + boolean m_emergencyStop, + boolean m_fmsAttached, + boolean m_dsAttached) { + public NtControlWord() { + this(false, false, false, false, false, false); + } + } + + private IntegerSubscriber ntControlWord; + + private StringSubscriber eventName; + private IntegerSubscriber matchNumber; + private IntegerSubscriber replayNumber; + private IntegerSubscriber matchType; + private BooleanSubscriber isRedAlliance; + private IntegerSubscriber stationNumber; + + NtControlWord lastControlWord = new NtControlWord(); + + public NTDriverStation(NetworkTableInstance inst) { + NetworkTable fmsTable = inst.getTable("FMSInfo"); + this.ntControlWord = fmsTable.getIntegerTopic("FMSControlData").subscribe(0); + this.eventName = fmsTable.getStringTopic("EventName").subscribe(""); + this.matchType = fmsTable.getIntegerTopic("MatchType").subscribe(0); + this.matchNumber = fmsTable.getIntegerTopic("MatchNumber").subscribe(0); + this.replayNumber = fmsTable.getIntegerTopic("ReplayNumber").subscribe(0); + + this.isRedAlliance = fmsTable.getBooleanTopic("isRedAlliance").subscribe(true); + this.stationNumber = fmsTable.getIntegerTopic("StationNumber").subscribe(0); + + fmsTable.addListener( + "FMSControlData", + EnumSet.of(Kind.kValueAll), + (table, key, event) -> { + if (event.is(Kind.kValueAll) && event.valueData.value.isInteger()) { + // Logger totally isnt thread safe but whatevs + var word = NTDriverStation.getControlWord(event.valueData.value.getInteger()); + + printTransition(this.lastControlWord, word); + printMatchData(); + this.lastControlWord = word; + } + }); + + // Slight data race here but whatever + NtControlWord word = NTDriverStation.getControlWord(this.ntControlWord.get()); + + printTransition(this.lastControlWord, word); + printMatchData(); + this.lastControlWord = word; + } + + private void printTransition(NtControlWord old, NtControlWord newWord) { + logger.info("ROBOT TRANSITIONED MODES! From " + old.toString() + " to " + newWord.toString()); + } + + private void printMatchData() { + // this information seems to be published at the same time + String event = eventName.get(); + if (event.isBlank()) { + // nothing to log + return; + } + String type = + switch ((int) matchType.get()) { + case 1 -> "P"; + case 2 -> "Q"; + case 3 -> "E"; + default -> ""; + }; + var match = String.valueOf(matchNumber.get()); + var replay = replayNumber.get(); + + var station = (isRedAlliance.get() ? "RED" : "BLUE") + stationNumber.get(); + + var message = + "Event: " + + event + + ", Match: " + + type + + match + + ", Replay: " + + replay + + ", Station: " + + station; + logger.info(message); + } + + // Copied from + // https://github.com/wpilibsuite/allwpilib/blob/07192285f65321a2f7363227a2216f09b715252d/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java#L123C1-L140C4 + // TODO: upstream! + /** + * Gets the current control word of the driver station. + * + *

The control work contains the robot state. + * + * @param controlWord the ControlWord to update + * @return + * @see "HAL_GetControlWord" + */ + private static NtControlWord getControlWord(long word) { + return new NtControlWord( + (word & 1) != 0, + ((word >> 1) & 1) != 0, + ((word >> 2) & 1) != 0, + ((word >> 3) & 1) != 0, + ((word >> 4) & 1) != 0, + ((word >> 5) & 1) != 0); + } +} diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java index 5765972f9..2ab20defb 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NetworkTablesManager.java @@ -58,6 +58,8 @@ public class NetworkTablesManager { private final TimeSyncManager m_timeSync = new TimeSyncManager(kRootTable); + NTDriverStation ntDriverStation; + private NetworkTablesManager() { ntInstance.addLogger( LogMessage.kInfo, LogMessage.kCritical, this::logNtMessage); // to hide error messages @@ -66,6 +68,8 @@ public class NetworkTablesManager { ntInstance.addListener( m_fieldLayoutSubscriber, EnumSet.of(Kind.kValueAll), this::onFieldLayoutChanged); + ntDriverStation = new NTDriverStation(this.getNTInst()); + // Get the UI state in sync with the backend. NT should fire a callback when it first connects // to the robot broadcastConnectedStatus(); From e754f5944ea1e1a7729334ffcc7ef39dda756828 Mon Sep 17 00:00:00 2001 From: Alan <40917647+alaninnovates@users.noreply.github.com> Date: Sat, 19 Apr 2025 17:11:32 -0700 Subject: [PATCH 07/42] [docs] Reorganize camera configuration pages and add camera matching documentation (#1917) --- .../arducam-cameras.md | 0 .../images/bootConfigTxt.png | Bin .../images/setArducamModel.png | Bin .../camera-specific-configuration/index.md | 8 ++++ .../picamconfig.md | 1 + docs/source/docs/hardware/index.md | 1 - .../docs/quick-start/camera-matching.md | 41 ++++++++++++++++++ docs/source/docs/quick-start/common-setups.md | 2 +- .../camera-matching/activated-camera.png | Bin 0 -> 293488 bytes .../camera-mismatch-details.png | Bin 0 -> 121930 bytes .../camera-matching/deactivated-camera.png | Bin 0 -> 216740 bytes .../camera-matching/unassigned-camera.png | Bin 0 -> 85280 bytes docs/source/docs/quick-start/index.md | 2 +- .../troubleshooting/camera-troubleshooting.md | 6 +-- docs/source/index.md | 1 + 15 files changed, 56 insertions(+), 6 deletions(-) rename docs/source/docs/{quick-start => camera-specific-configuration}/arducam-cameras.md (100%) rename docs/source/docs/{hardware => camera-specific-configuration}/images/bootConfigTxt.png (100%) rename docs/source/docs/{quick-start => camera-specific-configuration}/images/setArducamModel.png (100%) create mode 100644 docs/source/docs/camera-specific-configuration/index.md rename docs/source/docs/{hardware => camera-specific-configuration}/picamconfig.md (99%) create mode 100644 docs/source/docs/quick-start/camera-matching.md create mode 100644 docs/source/docs/quick-start/images/camera-matching/activated-camera.png create mode 100644 docs/source/docs/quick-start/images/camera-matching/camera-mismatch-details.png create mode 100644 docs/source/docs/quick-start/images/camera-matching/deactivated-camera.png create mode 100644 docs/source/docs/quick-start/images/camera-matching/unassigned-camera.png diff --git a/docs/source/docs/quick-start/arducam-cameras.md b/docs/source/docs/camera-specific-configuration/arducam-cameras.md similarity index 100% rename from docs/source/docs/quick-start/arducam-cameras.md rename to docs/source/docs/camera-specific-configuration/arducam-cameras.md diff --git a/docs/source/docs/hardware/images/bootConfigTxt.png b/docs/source/docs/camera-specific-configuration/images/bootConfigTxt.png similarity index 100% rename from docs/source/docs/hardware/images/bootConfigTxt.png rename to docs/source/docs/camera-specific-configuration/images/bootConfigTxt.png diff --git a/docs/source/docs/quick-start/images/setArducamModel.png b/docs/source/docs/camera-specific-configuration/images/setArducamModel.png similarity index 100% rename from docs/source/docs/quick-start/images/setArducamModel.png rename to docs/source/docs/camera-specific-configuration/images/setArducamModel.png diff --git a/docs/source/docs/camera-specific-configuration/index.md b/docs/source/docs/camera-specific-configuration/index.md new file mode 100644 index 000000000..4881a5720 --- /dev/null +++ b/docs/source/docs/camera-specific-configuration/index.md @@ -0,0 +1,8 @@ +# Camera-Specifc Configuration + +```{toctree} +:maxdepth: 2 + +arducam-cameras +picamconfig +``` diff --git a/docs/source/docs/hardware/picamconfig.md b/docs/source/docs/camera-specific-configuration/picamconfig.md similarity index 99% rename from docs/source/docs/hardware/picamconfig.md rename to docs/source/docs/camera-specific-configuration/picamconfig.md index 1177887fc..1ae2b7d5d 100644 --- a/docs/source/docs/hardware/picamconfig.md +++ b/docs/source/docs/camera-specific-configuration/picamconfig.md @@ -23,6 +23,7 @@ Windows may report "There is a problem with this drive". This should be ignored. Locate `config.txt` in the folder, and open it with your favorite text editor. ```{image} images/bootConfigTxt.png + ``` Within the file, find this block of text: diff --git a/docs/source/docs/hardware/index.md b/docs/source/docs/hardware/index.md index bb4a1a99f..8e71484cd 100644 --- a/docs/source/docs/hardware/index.md +++ b/docs/source/docs/hardware/index.md @@ -4,6 +4,5 @@ :maxdepth: 2 selecting-hardware -picamconfig customhardware ``` diff --git a/docs/source/docs/quick-start/camera-matching.md b/docs/source/docs/quick-start/camera-matching.md new file mode 100644 index 000000000..1a5b6797f --- /dev/null +++ b/docs/source/docs/quick-start/camera-matching.md @@ -0,0 +1,41 @@ +# Camera Matching + +## Activating and Deactivating Cameras + +When you first plug in a camera, it will be detected and added to the list of cameras with the "Unassigned" status, as shown below. You can press the "Activate" button to enable PhotonVision to use the camera. + +```{image} images/camera-matching/unassigned-camera.png +:scale: 50% +``` + +If a camera has been activated in the past, it will be listed as "Deactivated" in the camera list. You can press the "Activate" button to enable PhotonVision to use the camera. + +```{image} images/camera-matching/deactivated-camera.png +:scale: 50% +``` + +Once a camera is activated, it will be listed as "Active" in the camera list. You can press the "Deactivate" button to stop PhotonVision from using the camera. + +```{image} images/camera-matching/activated-camera.png +:scale: 50% +``` + +## Deleting Cameras + +If you want to remove a camera from the list, you can press the delete button. This will clear all settings for that particular camera, including the calibration data and any other settings you have configured. It is recommended to make a backup of the camera's settings before deleting it, as this action cannot be undone. + +## Matching Cameras + +When you plug in a camera, PhotonVision will attempt to match it to a previously configured camera based on the physical USB port it is connected to. If you plug another camera into that port, the cameras will have a "Camera Mismatch" status, indicating that the camera is not recognized as the one that was previously configured. + +Additionally, pressing on the Details button will show you the details of the camera mismatch, allowing you to compare the current camera with the previously configured camera. + +```{image} images/camera-matching/camera-mismatch-details.png +:scale: 50% +``` + +```{note} +Camera matching is based on the USB ports on the device. If you unplug a camera and plug it into a different port, PhotonVision will attempt to use settings from the camera that was previously configured in that port, causing unexpected behavior. +``` + +To resolve the camera mismatch, you should ensure each camera is plugged into the same port that you configured it in. diff --git a/docs/source/docs/quick-start/common-setups.md b/docs/source/docs/quick-start/common-setups.md index 590a0c749..7d6ffaf60 100644 --- a/docs/source/docs/quick-start/common-setups.md +++ b/docs/source/docs/quick-start/common-setups.md @@ -34,7 +34,7 @@ Innomaker and Arducam are common manufacturers of hardware designed specifically - Driver Camera - OV9281 - OV9782 - - Pi Camera Module V1 {ref}`(More setup info)` + - Pi Camera Module V1 {ref}`(More setup info)` Feel free to get started with any color webcam you have sitting around. diff --git a/docs/source/docs/quick-start/images/camera-matching/activated-camera.png b/docs/source/docs/quick-start/images/camera-matching/activated-camera.png new file mode 100644 index 0000000000000000000000000000000000000000..c490eb22dafd6d99f0eeed8e85239c81a7213762 GIT binary patch literal 293488 zcmaI819T-#^FJPL?2V0$Z95y=-q^M`wr$(C&6|yGoQ>^daMPus_CvzcTeAN1vzm9SR7ao5D)}O2~i~w5HMj75O5;sProUEGlYE*5O`?|5fKGR z5fLH|ssYZDL#D@j>P=XAe&@y6E`44Qp9%rZ1NRDmBdT&LQuptN;~lAwn{s! z=sk00Xqbb+k1!y{F8ul_px?i8>}fs)z?X@H{s5y0SD^J@Ml#G@Umq6^I~2ACxA~dn zT+GjN4wW6%Yf*w=dGmxFsDUo6PYe~dKZo~z_rZey(Ybd(`RSl8M3qk&1GO*;``}#i z*B;{+wa~{vGCC4eLmLnU9on--bwkq<5;8rL*j4B~oivudAonOcrRYuHvTr6@!#ET8?WRns1J~QDQ%@BDs`#Bl z%#~NXIM%`}!u{fgI>ZpZ7tHI@|alG=V(QgjhJj zFfmG4XqDlZM6rZN4fNPk$=g>W6(a{83ptfuz6*v47_}Qy>-F4M9*VoHY1`?`_SMJ#d@lo&g|)V}hTMK|_5_zlj>^ z$3o~C34uPMk)XsO#oS(=qWgP~`QZ;xb6pdac5r{cd*?5fVt0pipoa$My3+emN``$$ z1j_3l^+-r?ZGhf~<@inY*N2zy_qQ2)BD75aukU8XAhou?`@hl*n0OVI=pZcrwN@y-(y+mBf zqF5Zje}3=m^Wbb_$XY>fSoiHs)-*u)@vaRaz?<*O6M+U<3}5)DXdM!>P&aRnucCPH zJo;MZEsHzF;Z|pM^tw*izz}4!tRQWT;tIkOnmt7SO;&^No55)Prz%LEilIQ73(2hr z+%&opK(2Kei}SR%U&DmVM7CuXcXm(N^Nr~IO;Tn&k0!S+`OMgqk;6|+k)a()h!|3h z8M&Dn5XxSG3gBAiQO_mpfc4YN^ano33gni0m^2Q7?Li zVipwrNaQcUi5f^oTrTm6MCkLFj4{7bK$Yl3Je>qv0}@wMmMA@u%^3b3@mzSIv#UiV8zyVeEkWnrvQ^=q4)E`YX8AYTL$w8nT)FFfm+v>*mA-Q9 zf~_5t-vwTUx^uio3zA}?p26fm5E$SQ2Qnrrh*EyBrobb~^7kqayo!+^V-8;ub!)>+ z4AUIK9{MtbFvK^6HpISTWQY_lI!CdR*d-ZH#!nTiBB~|6D#k6>A$3CJLsS_rJ2taN zq!X+ z_R3t&6`5;UII=xuG_ujKB3W(Do&7L0kDiNIm{`;*XjVQASaPySXi0X>Yf

|D|@W zyc&y*HJH_J0*!Txy@q9mh0iUDZ-t*Dmm(KFW1Fp(ZL4dei@5=@VbOu!A?~u4jx`@K zZgjwy%Jjfu$1H%rf-{0mj??0O z+M9FO03CfDBhNVq(<4CB2-)Ik7wrPNHTE^vz;kq-g_%YA`I>=?20qJ6Q-+qUZ(HmE zi~~kN#-jUS+K4BJc%j~*IH932GNbmR!lRy}sibsY$zyexZq~=_t}|eVu!pCG7KMRd0oWUi&&iS9kz*!>lQ!xhry9WEn&}$-jr9#<+h*JB z3yh2Mi_;CedY5IzvoB}21Q1Amv0MbQ1cZDWytlj$Uhn(+KarBf2$QeTai%7EKAY0&SDx6IqRnH6e%NdX+G`t z;Rbe-Za~b`X8cBGVp=0bYF1{3mqr2IcuH1|HLu6&9(#Frlf)|ju+u~a)kXv3iYpgM zE|J~XyuZLR9W3s!d_?FI{}cKXVF|emAET^QhOyS9bLVknsQ?W$^`prrei6n(kCNjl z4;I3iovBr3-1KbrPLG(UEJ!ErgHM3!4Dsw#zDuBR=|FO@-66${ozAzWZx;ch0+1gn z%0-G~G#$;eR@)_Fk0jRxOT&ejwc4-M8XDg9L*+$Hdy}aB36TP^&+TW2o5jb{+Ntey zYi(I=It{M}uv_S=G|g%lRo-2eXB8cbRg1%wTQ%uT2g2pj$0f}R%@NJ#Cfgs=aQ_JT&x|gecQ^v zky3ZQ&Tyt*(TZ!$u=4H_YAo)hDzkWO`EYWQ9m12kn8y~8F{4Y>S#yTCyrFQa&}o9? zBtNcKr(XXM>r?(>dx5mJ<^A0!?^oV_|9vP{XvAq;$Fa-Cefs@5f+T`Xs0b1VhbJ2W z_l~=4A~ppfhrDHvm*sl-X=$N+YYq&L)4TQT zit-`nVNC7=|CV$A?Z9^AS>%1{I{jjETMORv;yqBL+P2yyb%TLJ=elifnZ4wES#_(D zq83tz$1B_IZ7wenp~mz&;O%E#Jar_&|M1^O1SOaHm=N@)MG zrT5ap%}U^z@u$IL;j*|JAsj)kJBi;-u~EPB>inD;IiMn!N5Jj`{-o<>^ihCYPeR}O zg8Etc6mZXAqet*Md0Crs;jn>UYh3H8&)`w`VLGav+B(gr$cMDK-}Ca?^BDLZS`m8| zd&vLA*YlUh3FcgCLv4#bZf~$pCopqujb?xH(We&-OM$><4%EFH97GEh1m4}YC`LUS z=>@icd;S;kRc_r0{EGTINLld5-4ETX%L5D$uU61+koU(_Afi7&!frv1j(!BX{GJZGe2etMTx%$D@K@-l}@s-XX7{=&eTABe~n|IPgO=)&DZL()`M7KHkD z8X5!=6cq&gcMA0P4+Ink1oB^L5D+O)+`rOFpp^e90|o*TY5@ZApE6p%uYV4S-{)`c z|6IZH!2VkTOgInxziDuy-z7j;&oxVaUtsJdG@U>|;L!e@pdcApSic8AkQOQ$&Kj~Z z+(vdb^ajRuh9>mxHuitGKzQA`eh(zohO^Dd(8R;2G_+g2Nh1<*8wh$! zE$?Vy@>}6QYVkAi{!76B(Ee7B_fIX{3Ks4r)*7M~HYT=Ce|R{V7?HN7jE>c^Uo~>K}&tw^#l}{p}WhSYC#|T+9!PPc$9}0wM?^DJrDm4tmxN zm6Z*2+32**-h^Ta+{BdxIqMEX{h~RYP;J;g7H-`>=HW{puCqf~ufM*NI^@Bi_<1sg zZZhRFMT)A7iy{eCgzPs8kOJiHnQx5U>p36XTRI@3AQ=>%L z0sQ5QsXD64v?%^zf}%tu$S7gZq7Zt)&_(*eRx#2szi&vu{+ov!CQA8E{13`ig%}ZP zzWTX5Atu4U82??CO!(UFzg7LAsMCSPLw8&HJ-1!`LkI~9lx6n8~Oo(O`DfHsxYp?1F)#QrtZXCDD@}{isl*2T-x2kM9PAJlUDgH;Anb1!i zDtKjo?JTm-PNJlcNK6dd(c-2AzHwczbW}Z#FHZNmwGUGOCsbk~TP3P7c_Oa+?R9tC z1o$LVS|HOGsSrN4Y%@f(Ua`NmKt?GewYP0R4VyWRofc8DN0o@459caXH z(U;(&K)F#!*ZOjtUsF?^&rZkx@8geO= zRDTq}dc6M)a82YI^VB1mP@9<0HeTUh?SWc~ zR)EQ0-Y&N*{*O9qQ6XfUrdZEFcWcuR+Z#J zx5P%Tu-LDFR4HhTYr|yC*5LZjd-g}n$2=o2JiAjCeK?sQp_ zow_p6yV>oYD%r|7fZ^NTAy>Z!-9P08B7dhQi%<{_3P>8f30U4SQ*%w=n4ZE=!6H=h ze6&cGhGa8wQfe=AHm%vgqs6dE_?A<2h#9cdh(@fVZ!pM<2D^56+zZc=No`itqK81M zUF&RBD^(uSH`7)0zlP(*1w-uQ>L$x64H{YqxCxYpJ*EIgp)RbHtC%&$oUfH1r#rB1 z$5*Jzgq$_QcA(%5Q7g{c9;g(|d-?r3bwVRfr0clH@Hj+OY8IAJAmB)oRERyG>y^MB zn^j?}q`s)9b*UIagq%LnG4dQSqkY#=9el&o`q1R@@<%!~dYRvU$$mI~z;YIeR}()Xs7;hw_K{9%av;8^-IS_-(25psn*Z0 zhAXRj)2W&3t-V%v<`tK_TTW>={nCtI;P!>Zs`qXy=hD6AP)T3ETlbB{<9T2UaP|=V za5dNDUgN?GyltG`d1~?Kx#tZz?O5;&-CJY%_)x#R)Nwhrk^87>E#Km~^?LJtyKT<_ zp7Q;+sZW;go3)LcpPHT1!EeplFMzqZ=Z%{O)&RW-FSB2M2M;WxzvY=N39Pw2Y~NV> zu}DVmb@Lw_6Ay3a*j<%k=;+(WvQ8C7j0`raP?sLeJY|R{?|QXXDrFHdLfNU7onB=t z^NgR&OMde5y*&KvaB?jnNh0>@NZSx4%$jMbVzs4YviicRI!>85PL)Xy^{~>IKm<6H z$;+{dVQ6}Hx_=PP0gnDMdwYIr5$N`P>v(_iel7!6`*q0vN$b2VoIW-B>e}5}Z=C{8 za_`x<0EZ82;=ipkZu!0~93EP_J-^MraK1g?aRXd+|7FhU|9^8jwD``r0?tn#z{eSF znC7p+=TXq|s+77a7Bi@M9cdNQ5j4>jyD~a3%L?6m+j0kZRD+?zfe#|SyoTLb$|#PI zW>JX!KM0~EF)Sg-*qUj8{IOX1yl8tK)kV$@8Cdz=%Nl;nBjxOs`Ik$MHQBomvamCpLC3r4WQBkiw*~hL@qD(jay5j zAFNXW!a)i477uBn(A%h$b@EmDipL`u$!Q89j2AfcjkLMRf*A?eWRo5(2D^>_2t0b- z&{^Z3QJ)QyM-3HMDA%W0>)D0rt)#d1#CGZUXcq^*IHOz@+M632Lrf2b;?lpgU z8<~EOpraftqRwu|Ma^WIO}>HZXl$or_dsdrdn`JE=oMb-0f2XE_3x zQ}_P-kDx00b3eGx2{}I%XuNCvKmBu860|7Eol*hzOT^!{{fQndNG4ocmP;eY{*T@- z71jSxHb@vtAqvuysy^1|A2IF<4?3%WKyv-2d~E;F{E?SXz>Z{Z?CgKLv{ykC#JC#B-#?KH?7xu95fWx8{@+IKixmHjXE0+8&WQhEGj+;8@I~0K zjr07U!g&8s-QkUp{)u6P|6myO=fPo%e_)uaoj=rJBP_2!;Oaki_=z6TH<>H-hR^0 zlEE+KI1kE;3LGA4cFOs(s{1PRO>&_gZ8>Yj$va+J#R{XlD(RVrxrQ@b2is3TC8}g4 z1RalT^b5=ZZ|XZunf>J2>6@T?YVqE2-T`l`^zY&tgb$Sy%7EM2o80>AFiV z^;$@oXzl2GTu4(bBe?~6Y|N$O7J5*WRaL8YMlYb`(q*ab@%xkR0#@=GC68R4U5+iy1VHacj# zwm7W7SQrFgK1AUp8b3HOY_%@X$3rhaRbi3t#K$YixGRX{(N`(4l955}(4ozOTQPXK zT|TiK-lsz~`wWr<{MvzM9(<8ke?l|DG3`nGO^O`&Pf=7EaY${sGMC)ryPl;5ks)~^1c+Z}RMpc`;g zuK5W>*l!%`n(wbS@es}*t_a#dsy-8DyevO1iK(tsCDpMb{$A_4UNiW!DpSD%(!{3< zv01VJp`2h1LHYoxgyLY;NJGXR_DSCZy$#MmEOI$D7c7L0;=a}bY6}{6$@&ZfNK#_R zB|ctBKQsCxgdLqek%u_U!tRul*dg@Ao$y``)vHM)cG(CdT z^_C;vG*iGdRV%fHu8x8RN*-+42F6PJ5rQw&ys}GL`8~;mAGSIAPS|3Rr&LSvhP0S8 zUL|%GJ!VfnIxA9ferA_9@QKx3_fLo*s zF^tryX(v|OJAyHkQzJww3E5AJlu)~sX+)~{XnQ@VZpFE(KDj9-&{jlI+Z=Vm!`5@( zCh*(~V|L3MC~e7AqR`1t9TGLaR7$BORFSsFT>jM?KMIl9`-dqQ%GekOG98eXQDA9y zIF) zMn{H>HzYj6%fwnj8oMBV;5=#H#BJTVyllGw7_a6A-Vf9)LliBUs!Vg}Yd)OxRN(|U!Bm=kVY-rRLCsQ|3H0Z zexJq)-PEW=C$CXB*J4)P@9UE2USagj%ieao$&CMX>D)jjusvRTP4Yh-k8n_3ay}U$ zIoA?}g8dw}4yBlluP2g>$=8YIlY%eODwEqi1IT7^GD>mSi8;()n;`>r(r|tZiiehE z0vr5`EvG4@!o!ojWOa0!3NN)BlpZchE-jufbo1}wFsOCY6=@uVp<LHg zm};q|5=v7o5^yp+KItH6(wWbc_m)c!Q%8s|P9Uy|H$$_PALWaL7Bf8qTCMKq#KObn zGuzUdkb{-8e*B8xotrAFxwM))#Q-Q9iOBK9${h6!l2RAnYR$7C4L}SBR;dyTV2>qA zMik~%#F5bOBCJ%En0~!mST0*lTSAERbUE!Jke$Z3AM+RDb9DZyJ8h#i`$Nbp%nT9| zVJCUF0~(uY$s$a@ow>6ASP}sVA9xbdM6bJ9+tZ_mAd7J~4Nl6{;p zWWbSQ6rC2T8#qg*wq;#JoXiRMJ|j15$yR-!B4mUXxaztG&GCfL>FMksPoaapV{{+J zo`1FWJMwvDdz_}D@3j8ay1U4rb&yF^a@(VI^YGYn;&82a(cwSb_-`_`W)~~+j|+Sc zNn5QRu3^{=+N#Zq7za#L5=_JT3dKwBx7X+wx8BF-GQ|8JCqEo&`8_TRwSX%nU_NWQ zMhS+y-iEGfwYvQBxle=oD&WQzFIQ2UH&Cso+!E71FNi00e&?mm)BBaI;PG`t#yday zAgb*c%j9H|T-?o7pqNfF3B6?eZjXqokI$7bxF&FlYy{?6B3-^1IsPI9{b;ANY|csW}HF=x&*ufQT4-%A)V1 zkn3w->WPEn9{Q6{4o?4tsLal&;?24bh z;P>*v<9t|Cn6WkR%P*1I97z`vXn^i$*{a7K3#*b5M3(+3c`<#`{B}F=d4t1lA+~!L zNaQ-V8%lA<JPQ^)G~Z8`%d*B0MhefG@9v z2_6tI_+W&_GGRofo+kxg_banzy^QDm5ZF}S2?uURYT>BV4;hrt%Uy8FUcFEZ_p$;` zuIuB_`~K?cDtIqgF16Xek134kf+QP#{4A?}S|A24w70_V9Y80~GU3`JEyAM3JX@*i zvypZclx5Hw=y9-XTwbF;b&HVUy%z0x%NKhLc;B|g54zf8K3it)|9QMB_NKM4S)-`M zc1X;L9IUr)Cms@eqThAS-TiRhT3%b(T@%b}1YhfRooP2WBE57x_;K90>gFA^ATh&d zyiZllTa*t<(sa5^>~qDIdIa41pucx*nw@aJ`Dt8kzTIV8t=p>8%HJj5do$`+oMP&_ zv!7`%YocH|K|LjRk^wpWyomH#MX%Qg;+TBrNdBfFC4js1*2Mqoxb}3*_laM^lw)WV z^i=Z5nQr=(IXc6i^PtTZ!Dgcc?cq=ls$1`#pF(dvZ;gV93_tefCG9q1 zZSJW9)bC+mz&CsCyzl@Srx^TY2Q8{Cr`+Z(Q)24gvfEdOn49MR(>P4EfR2n}ZK1;C z%|>e>et17=$!p6#o7)THNY?MsL6@5`Z(xu0p2(tD)6-u^Xf=RjcnHtW*?r4l!+B8k zBot!%`~0uM##NuaAo8yv4(Y{BHN7IZOZ2cn+|;RgySLX&ms7j9cJ}*2)^HMtHKLo6 zB9X$;`^j3((yhm*hqC5&G0tu0pjJAsnA4%3#B3bw<{NXtT3o%+nkx4xlMa~gmHM+U zz8`>vwb>#ma$LiJ96W3wV7)<3y-F8(soSWiD0@`S-1?|YDVVCcx#hUwo~8-8fbDz1 zJ;3*s{anCa!msr$=zybjwmRPKMwa)OO#_a3@lh0ABFJD|9by|@V zCt|pfBd-!f5-N?P4guODDZtAd zFnsb4rM>KrLkhiGLZ3Hu%P$8ftI@aj44WQ-?@tuH~TT z0tM<8C&36UZEbWa``u0oRGhL`5o_RrNz8d+!jr5buXTnrd41%67xR-(-E_K_;$vd1!E>Nc3(|=g zTBy?HCwxdmLm=<0>@Z+Xt*;(uF6`L7`fMC- zMAAhXp^g}Mp7X{F?>|~zNL(CDrzwGaO^X~+U1;KS#BjN=<#Ro$LP8(b!J*p&kBJ)r zJun9!eZJ#VKc`5(yaGC>TwIYte+s1Nc?|P?Y<*Yq^L$X7p22XI?8&Q))2`8+t$3mo zBYdCiyxVx`f%+l+tk(^1Vv)5FDpQr%Y_sX5(ffvGHx$i*M4=-qkB18cymbOjX?SAH zO=>DC4_Z%dW?T(pweIBKA6cHy&fQSv6GIWD?0nwXIt+c0KzGIJDlHA50?thH>~9@(c)=Zd8CqU?ToCUb~Xwh~lr`pc^5UGU< zFG63fz(TYI8k4gSYWd21-tr3_StL6TB|hGswo;z6 z)r|gXR{sH)tmfjh%nqDpt1aXh@=N5w;-#PfHaq?rGM#{Z&FT|7;E0PA_+o}}Q0@A4 zUCSA7!K9ZqxNBov;))??vzS(^cmDgJ+2z77k->%9GR%NG(pKG4ir8r8!w7E8$xYHh zZqFkuh;nUwW7$1cwk7{H6gGN3C*f4*eTUHV`LQvH267$!R$6W7_zY7DeJPf@UevvE z1yC4YfWvyS`orhD$xAODOT9){xk9}+AOOw%9NnMNxG^GPC}0353$ed*1rD7?GG1YV#47}qMN7BqIZ9;Q?su%F*@PTo+D*2T%Bw}{ffPc1o6 zqdPyHclW<0;+M1pxvUbtC%TMjEl(X!((SumTAhO#7t%G9>6~5eCIE}X?Jv}VA+20# z_e@J|PKgMtOV>g^pW<8i8`@DvIbhV`~+lBGSyv%F4G)r$;92G zS&whMj*+g*Rz~Z4E;5fQZ!a0bQ%E;yEeW2@(9%=WX!H*sWr@j^jomU&H3bx~qG3RW z@6GqG^2ZD!bA@RmH+?;EYf$xlcw~B;VR$dXpx4L~T6zTLc1!bIuFRmy(3Zol&&GW-G#ST zpO<^6+$~xGr7hIS5p{Ur3-+fgy}~wkgHMl_3z1c%*eiAVqq+<%uV|{ zaCQ0~G(2@ISqc#EyT__HAh_L8bGB~-+=fLBV=aP~OV zq1rm=wvz~c+~M;Ka`YO^{^Zc$lYdo1A1@L9yyxJ+r)vHBbr$5zw!3O5BWclohh1%6b(|rK8QPJ!yv9Sg8qFLKIq`MN z2pEP?!ESWM2U|n0hnzg(W}m80V8UTb@tv2gf)=i>>~)+ZbbyZ;?8 zHW7%4!-AeZg>euY1KC?5vND>;GK6?y;pM8 z8ubfieW#nDEhoGB?edtr2O@p>tO@`FfTpW~KMsepMUrBG_ZPcE&TU_ z(B#|ep}e1Jq!;&ce@F?qZ}gt{gi1fB`Ye?1$;OGf#ghNHrq6FQS$YOx0V+f9VM1g^ zztk%=1xOkj;&^&%M|_ZpPBdKqC&B^)HU18#D1-KT(}_Szj(n;<_-&Op?+JP${O0w3fX?t^T^k1yk-%Fltlj}h$gaAkd2K53Q$Se!gfk@tz3b`B31v=Lj; zCF8OR?O1HmIXSdJN0dc1%$QZ{-(295r|6sPOSIA=CBxlzHM7ghvx)NPL`Ls6lWm^& zbA8o0?am;wKQ=Hg=HFhRnqg?+kcrW{)ap9@KJ<~zK{ zy%(r(5^$-7;(_9*~D5J z)s|`s_PGI`M;-Z79j?gxUcDq=^UF6458QeIyN+j6RgTN0FIK6RdeUfz2Gd8{nQrD^ zcnVUko_{^GSfX;wf;7wwLwrhQTyNFsrh+)l;I;PhREdp6he7_O_!-NoB(7nQmSr%E zT=>fcz_ClbQ;qIu_pHG~i#_*|L=XJ!b^!sVq0x47Hi`dfKlF~_{S>pQ9y9PF&&u

B!&HSMKR^e z&sCEIjeL}t#VhuwA$(I*QLhtj*V624tITn&w-mPS=fSPVZxU+98pRCj-C}-^u@9$8 zs8T6?qn*bYih&p6(Ju@F_gWjCyNgZagg?-{?lN<`L{d>ERSeH8v1N#5IR|*Xh23QY zK{wMNYl$8b;djTk0uOh4dcnJRlqY^IRYgu9UkgVU9%U9DVzZyTaf#4SK zHdoT-{C+>tEWJ1`!=U|R9K*?Cm^lG#&f2^nkAc5E@wSs2yuRJ&RL{q}p^P0Y6^N!x zhN#*7nxML!MQ`@a*K!R*)l5M{VnM@Sa2ay+ow`8|jdS`M$u(+vz=&YkSH&wfrVx7j zhM7sEziej8+|e`&(=6PW=x)5x|~WG%ZyMtzs2ORm9*wle;p5!JoVZT zzH9uor7_*pO&Y;+uYB%vGT}VWmNSiJ^E@|*-Q#?$pIGkmjGPL2OrhYoq@gS4a?)d= zWJ{^nMhRPFM>_9)cK0ehMXa%k?$$LAMx;y-h6wVllc+gt0w=rfcj$((J}^nbzUPKA zgYK0E0vx<02EB#qt@lO00?_r)rPUtKE!VfH-VZO`o;+QaI4l|qgtjB{k^wl@Ql*(AaDK!=^R)p zaOd0ob`M1RHdSu{|Nh}~cKf^x{5>TyEQihrK3?yr^yw2C<_$u;?3$DFNFjZ|01Q|F z5!d%I_jLDd_FGrKgVRD<*Bq=LFPJstlB^yfWo-Pu0lLmCs|yJ*+K<(EPpnUy){^oU zE9JR9=ZnwTNbg0@D>esvAY1PCp}se<0&v?#K&+FPmwV!J3mrY45!mNtFJB#9-EKh@ z6~fM|_g}Fenw*XB?BE1dsUF4Q*_I(`p0BFle9wEmFNfPiD}{*`zXuRcPUoDwMI|YS zbwSQrC$N6lKgSj{7OCv*3gPBde}%+I5AnJsEUKSRcg=ckipwQe7|7OvzBAW)AQtgxE*hCF@D=U zG^Jx-3wVk4a>j zo*hWH%md!&(qu;dp3}Sy`?DgT7ymJBH(`X(cjEtGwUTTY3cC(kKmyNrsC5(*>Si%N z5*f}!Ro}cO3Cks54Yb|x`X-afEm0A+-;A;`n>43?i8Ti}6DZ5%s3P4ikd#Rl+- zI13w^X$%NQ___vHYtS~SX&4m8M15c6mjgFKNRF{U^$+iEqFfNnL9_= zd#d)fF5ttkBO|qm|7+Mzp#0%ulcL$#0aMf@1B=quv?P4LygX244bQ0ZtBx++kmlR) zgDbK>0!Ee-#&T@9v<82lal6}Vn(tWyXv@#7&y49=)F%%;cbxnk2F0ALuCln|^}@{f zWS704II7XMpSQl6V{QHQ)slSczEKvq^D&&Um8tlz7c^F5Vhkc8!(#gQUgqa>p7givebB)z{a2KjT%jCHoPR1%LH*1f*WiQ7QhSl%y^!7xJPH5 zjXGCXVJK_C1HhWY+Yd4&zNK5iK83-jj^1Fs>kEhH4LQ9nW{v>I4L$!>SE7xugEZ$0KtBnk+aZ=1_F-YwnqZuY&g;efi?KR=C0 zVTx|hV>|U#aDN|FCtRrY*&%dM6qiFou5^LxxXbkW<-sNlYuE1Btz~f)lUX~PSxa); zl1LMvP7SEXXq&j=J-#yjO88Xiw?NwYV975@Ej^?xi$Tss=_+{Xx7E1_?NRk}U_w}_ zh74vuneZLN>FQZV?$wc)Jo4KmHGOOK%cpx9zdN91pO^-9qn>4`k<@ySYj_Q~rTu!i zBdiYBJOZkTl!?qhyJ;5N4weh%rLYr-EA;w-7nvYv$|J^q7A*ycAoMmxp^>wk4m8+m zr{!&d#mK~?U`X=vM}%V(&MO7K+l4hpQY3;6A?#2o;aau+7cWOMX^~~!UmKyVREwgh z!+96qDu|IJ5AZ4lo9_Kf@dOOOc5^J{bR^>Bg`wMwOvdBKl7g_FG_%RtAUikWYUhyS zU=MRwj-0q@ogSWy3}RDn@Z%V5)rs();(EEQ1)Zj66TKW_$0=D4S3NZ|H1buNfUD8 z%2Do6mEadET%no#RnKwEiG?a%xSSvrzKNXZlVc zbrl;VIVgb3Ek}}sGN?V1Lu>nF%*>gsb72*ix=h((<6)s58CjQ=s<0PAwD$4yHR}va zi}znqw$>5?HDTu=id%Y+`}#;d+-2BpK%l}VIJ<0_%4ndZl8Bg$E{DOK!HeXxHOZ$A z4a%cqrWOsZx|VjaQ*JGVFJU0C{fo%NRUSM@8fk1e6IM)kG~L;?hNB znZeNQww#A>3bI)^mXP?lS#$Xo5~#+Oit3H4_SnS^q${FO3Bf-eR2gr{L7n7fkiiq{ zGNaFLw8fXb5e-<&HRP2B_Cgarl}2*2hs&T@^9$r)nzjg9D>!!W@zoP(U?M%T@)-D5 zPixLVS;0Deb%k9ik>!-ZSY599y^E=G1MSS)$vf%I{=%rF%r&4$y|sQn*W+d3tkv*Bb7us*U|45w02d_I8dhodxS814f;<0JL(?Y0GB4gY=InM_3E2D?i0oS!;Q$Gi!z0 zq#zX3z4I`{weHwCDhP$q8e{?SpKggdg9kW!%v{m_A7$SZo#_&^n|yIHv2EK!u=3V*34^uVL z?R1M1g~l!#{O-uS#A+z3o|QKt-j1}YD;j*S`~AU?-P%rBYM{;ap888OZ-eLm-ds@N`cI;x)(Bdq%vG$T;M@B6R}iRroH^a* zBHxq`X(d5YxUlZ+p+sW#5p%n>gWHAqR+6sDI?ZXd z@qRI3On2h2@q0_1LkZ{Gj~_Yb>}`mr_OX4BsA({dRkK76;9v-S(7E3SN2$>gKeo*0 zm(lyFt}N`bW;1S4wo%MRSw~KS=E~CI$YvCeWQjJ>XZT#WN^P%VdP31>3{fmp zi3k>puRX2}1wJs6uv%`slybweX?ROf$>t8J(pxr^mzLVff>IsW44t4`;n>@*PjP8y z`r)%GzFy(x5|E!5h0wX6RY?pj7dS^E2Os_qk>d)@{5{9;6?*IVEE8 zhFG1FF>R2(X|1XtXhGkHAO(4DK4Ed!E3d@mZzjS7N1hrW8NKke(fl+GNPq($Zc0dq z!Zn+KPfR;(7f_!sd}n69^{rxz>nGDuJT(b6nJOwfMS{+ESSiR>_QouzpkhYme!S`oELn(WW3-Mz!&?)%|Tp^F5=VRl+EM204lga+79A z7qceQgyE-^yb^3I(*p&ox`BKGeogk`oN*e@EK8gpQ$39G3EOOGkzN`m1Kk^QSA9^w znQMDXf$KqEi8Jg<8_YtSEPqM7noDWS{Q#BNexXgH<{Lu z9e!&C7A+0Oo!=c~i*s6j!ubbGygw7+MuLGctqg@8+-9)a=s!_X@T@4TrG}r3qAEQd z^(h4JF?~I@#yrx+PX?N%)jGQuWXR-83z2L82OqHOMRXHEBpi<1lKh}{M-K{?IALpZ zIflaE{k>)}`ZQgf1Bpx{r_#P&%o|HE!&CQqdXR(|Q{C%~K9B!luVEAg#S{Pn3I~<} zB*R~Z`2s%>_qZGrf6FGkgG4v-O6D!{^(Tcb01Fm9Fh?Z&jee!Nmbv`!nLFS}hGu!> zZbc>79kPzEc}%$gja+otx-KAbl2WT>EO*P9V5YXnVcs=B`ecLC?TU9#%k92pfti;* z(hdEeU^2MyURposwFF3O9DAOr!;ot!uSsfX+xg>*_wr2LwG-ZDDsUl6dXcVnA=jQ| z@1F$0u^u)twCy{IL+(NHEXcTSf-N4R4j>%fasjPp2D6)LBx&DoB6a}BA{p`)w za5Fys$GQ3mC&~H?L~-=%e6a05pcQ-lzj{0Sae4oV0|$O0WuiW@FO0_ql+*tL1(5yk zBR+eN(YIIK|1$~b$VHZ$nR5RbH`fmCZoP9in(@j;Fmt5P1j*Ch zqk_pj(Jx@X-%Gx|;JRTmpr@G;D&n{n2&Luj5qPaK$Soii$Z@(-)SQkiV_sR4EsUrd z8S#7ps;tnLdSO{h!zZKsPUTLGI&Q+NwZW3W+f$NBwV0vw4*GEaIUuL9cVwLlrmn(0 zvFV7;p5m@j-(JkjKmz|M1f@OY3qk%G>FyggN_1@^D0*RSvV7F%U zX(JPox_WnUn>NQL%|VceaxlX(UN7?$#{S~yD3CUT5@>G^>zQ)Q@Tinv{j7RD)i~Zz z$INM1nQk?yrxJN>DJeAMY@s}~-r+J-M2xp%XKQZfQiJpcuNpnkcHixWhhXOHDJiLy zNRu>SCH)xu0pVYvykcJ0=Yaw+A(8Oi8}t}e9`;@_pib<>+qvJAhR$7q2o6kSN_&?= zZ=EayNL7?*A&Qm)(6E`9v00g&uLTO};2l+2J*vPRe@<)unEyJVr>(@;M^VL%#P-KX zzh#G5bn)@A{C@KV=RX<>7yvT}dTlj5!Gw8s88qPbpu%R~?{-R~gq@YWfIOSN{jK2j z?4n(B;iwTI8uM|r&zL5O#%fxGSHYi!H+boLaKfsT0RNEd?NuK*yY`Kyu-8pWsvb4(7JfUT$}ySKJ&*;9~F z!UTDS45ksSYFR)GnS?PYef1jW=h3uM9x9n?f2{60JH4KpRX^p;-95)}EUTCL11nilxpbPlhf*95oUH+rho9huYDz*d>QmZW_jhoP%(mr{`XnI+2k z_f(-amwkM<>qsNyvq_Rn)4~dxb)VQU$eI-lW*Us9`p^ZNNeS^}aYA-**3|Fq#fI}* zS=@7Dea(vbVZ86-CFYvXY|s35WWpaq|9HLcLwg~}g`G`D!TYVGyVVulU37bHYFaGd z$ttd))~Au6QE@kVr^@6UDdOn8MJC~i_9AbYO*k8udPw*{jdvPuGY`Ld=GWHM&(^Zc%{+#?N0{L z9Iz*FRN=5w!brgmv*uVOr>Ks#VD|&1o(BJ$Dn(>LfEDU+v3s{o zfAVC04NJa;kT_o?nc2v#;t~t9c(#J&0y@0a=;P__yJG+F$p|x_SeTSMkUyKVtmj)X z&xVV&uO%c)L?I$(mXh4?*PJM9@dJ`Lkq-V>@9GCKYZ44-$5clfG}k180|;dJ9@HJB z%mfb~tpA)3gaFJa=yVQnZx9&^u#?pU;U9T&GLVgCL&|b;3g@+-A?uGv*~Vvj@!$o6bR8{a(7w2=Tb*~!$DCV)Ke+&h8)N; z=If6NAg!EF6RN?9>+A->K84q@P|KWH~gIg{;6;OdQne zH);CTh=wKxssDX_X9@lV<8q90zIpObo7q zR3NfI?hN$HaNIskS|-}Y!ir>hP%1=}E4F}h?QK1FI7o^#omxKv!yGlO9#1O*GNpYF z$u?*jr#ld-%UD;^s<$HgFm-eioqE_=5{Rvc1KE@#oqXpCD(vY>#3~9fn_%V9rYi3# z){90e0{T^Lf|H2q#_74l#Wk+M+SNM-=?8d&i2eA#J?DdJ(FMs zt%h1{*xq)^s&26YBAw%BUk-yy=_Mgg(bW5J6NN8w1rCj}50)*>z#Hq?luP||vq@L$ z6`nnRBDRRuM48Mzv3Z#S_8&cR=3pr=mxFmsFKAcBNXsxFjj$oPMfe^ zcd^|7YsWa{f3&JJ1cskkdlUK`oUjO z1Da3xJS9`H{N<&H@D&{ma({ky)h?0Cyx)T0f5xb6y(Jp>AV#PP8MK`Xz!M4p#A~*uNvjt)c+MQ;y?}S=qy1ZwIw+igg>eL2vdk=x_ z7a3sM-7fyxyqH2K+77Ph?7R(Pp#%mcwumm)OT%03`|D!kEi+V^*o*A7xGT{b)l2#G z*tYIjA9tZnmyZX(IPRM+dCBp&$sZAloTh9KkkUH|y7Bv0z9xr0fTUwD=54LpFSNdS zGS26Fwl{s_JS;QpvGRUCDY3>`>aq{V$@H{WC}HRBRuJKZTX%eR3^+O#`q>#d#idCS z`5z}L6zIE&&kY3F@gH40BRqWST!wj| zK`g?w2Q7~a!P5A~iVn_wyW1sAwN{&~`(i;?qKd}=I_4?;wOa>9tsZ9cpKC!kAn7Kd zX0x_6r+&C2#OYX*levFGx3eESFH-#ns&%2#rce%l>=ndEB!a{R<_z-lys#)TsW=JI@;=42g%f$ob(E{ zJ6`b9HXgvio1cT!^|tfK&tLSh5f4(rYR8|iW<#vs*nOp9BZ9HzN7ltJSK_+@X;(ml!2Z{^cDcnDCF|;#1)Z>V;4assdkA%mf&| z97`((XJ|i;ZS+KIE6pC^u0WA?ISh!~Zgd$S3UuosUh$QAeNPRcn0UJx`4I1Uk2!~~ z>ee*a`IYu@=U>{0wj%uon*Y#MUWIl8`tS2xk5mrZPR$jA z@6|r<*FA;d3cgy`-R_C{t`m>zPbUn&D`&RzBYC@~@N!mX%c*tEhfu5}h^Sz~E49Z0 zY>FHb)tK&F^p=P$r_CEZURi#*xo`Pg54`>9apbINYX&;K>8vkqv**<`3q+&IyxqCB zRQwJH<8dqS1Atk=Ffbe0_70B*nMCA(c@G4xnzDb!JepbErv0SXFS;G!ar$**xcLnp zXNy^(kTQfVH?4dcv>qFbE(ZI(N*~;OyB{h)YbP{<6$*&ZNOS4}i zpX~5eJiqy`791Da>wD!OH zHLTQR;<*MtdeyL8*#0rKpzU}RRgi!r5oDuo{%a0Tj9XieTTPjMJ|@M>c} zSpD6!e#7)M?6@=QM}rv0$5JgQDjU89rBv$;|CY!1a*`d1!DO$kE$G{#)>R8_`WO$^ zZgkMrxh82Y^VckWh)XeO#6xIRSJ>2;1yi_Msd%#Upy&?&dTPa8%g+lH2&+npxiDD; zHonkVqUa#mEotve&pQ2b8OI00K_;4|u^>mIs=c_Zzf?mXt=&~#l=8}MtGiGQ#*0wi z=2?qTr5h?^4}@yjd!subIj6P!C`iT;;K^6;eXl&LsDC8DEWGEs#Lbx7<$O8;tK3*> zFiFQitb6nY*LA~qG3+Jl{>OT=Tl{&AA`#=h>^A>6r>Ghs;Nkc>Alex@s&lI0imc*j zqq_5JGW9Ve7{C2(KGOLz8P{oI30Ep-wJg@>QYaw%{vu2`UWkJV8EZ4v5!nKrtc>To z?sbP{VNLs!c9=4p3B)%A2W<^K*DmQ`t$;jY*flzDlcfs~i!wQgm9#`ageH0E!#xA5 zdFGS4r-iigMS&5ND#E;q(TYk8&~hH)2WnM;779PZ#PQ=U=|-c)nByH$^-3+hRvD^D z;ClNb_2p^<;mS_*QO1swA@8xnDtL(7S&<@hUe1QW>-2Hs-7 zS|q#DdUbz5cKhMu1@}O-YC5$Q&F>`Ga!~rVB8gb9QZ@RxD1W;+{|h;}B`1sA#>u`> z@?!}{1j12#DFR%sZnEHZ7249p(X1->z|G%Td-i5Zr=u8X|t>Ha7Pk)0i8~Uxq3wO_!)HJriPr;cMLi zMj{MFkg#B>aZ|m^bp_%4THg=(-x$w6hb56sR;MJK(Y@#$5%0{}VL|7;d z{#AQtMuA-7I0b_#-)J@L!3De+G_|S)z~D&^J-6qQg&)V_K|MEavAqvfa#!FrbWxN+ zA5c3Unv3DsIRr{N2)%?2UapL-EKNhvFNHCz6OogM9OVkTk#;XW&rPU0%D z>|vzSu;ow0V&ZAoU|8iu&|b7#iETqO)5$+eonkSjI?+;l;tlI+FhP@=K&}C9%L{;U z7yhZ(`p3(Gc6WJ6j+&TrHF3|}S+P|W!wRa-Fu+i`oSRCH-BHk?Hv=-|Id47Qay(hUcmcCD zFMIjXpgrSrn7i8vMB11Hn93x5RLSJ(T93c zDcj%c&40=SZZD_K#`iP&@gIvN2o`K7n$ICX5zW+_sIC& zxw~I!wXKiOBjhm8>oa{McUE~T`)>?mI?`a?)8#u5MhABu5`pm+fo}^FIv}piin1w*Hl?P&>8#S14SkYDlaaU zCF17xYi_dq;B#aV%DK=_6c2m#Cu5dmh}Jf79F_Iz)|{*9?Tj7zH1``tD9im)r;@_! z&8UY>7KsK}qaa&6*r&$WFJ-w4 zfd1sB#uho>CeuiaD$SI*LPv#B&?IWvGE*1LQ0Q+`h1*r+N_W;Z?MX!XNd%5yT91}u zW7wJ1_HLG9{I>4U!%DW9SnA*Yz&6!;+FE#V41!f_&sP6TH}-IxiAMr<=DZZPYwM3^!_i=bm1*LsWcR)t1SCHW8h&}RQER#0$hXa;bROF`Q0}&F!k9Uq2lH$`$=!5{ zU+?hz#6H=<>D=NIqR-yUp_U2DvuX+5)|;`&M@@~htDK$c<=@>>Y`q@^(o8v_Y^W?c zCI14pzKRo3Rjw#l-bNI>rAkF&PFbCAXT{j+lzmv!XnS5VScR9;bX$!^u@O&2WfxKO&a9^foqG+b)DSbU7QX@~e}DgkZEbGI1@MfeU0iTB<0& z6~JHPD1xx2Z1hp-&>qEW{BEs=DsqSvAlPSZpHDwe)v*Mru5k9Yg1@Nue0?~YL~tiy zI(8k@QE#XYW{WgMVz`+Vt{$7>vGk{h4e)ous$+P6IN>0ab&*+S@kP+l7>yqZtb82h zGT*wSH1yruVhGnOweD_Jr9{()FBg^<2vMLB5+82*Mw*c`h4UEa#@|ED8&i^aKeHy6 z@BBG>u86x{EZlfLE5F=e<8xCzSErx*_GeMY8A*A5cCiZL9*Qj%PfYEXJvDS{xF+SZ zYXP3z!p^=J+@q)9`$0xXm<>Nyjqk5*V-JfFeLa^`NO~aHOMa27wh5QFk-PjExHO^e(D^kbs#k6*}5qgnfHNgf;4MjjQFR!8} z(f6%a1WA}%AQi{K2sFtKd!bq-Zljl03j!h4x&LP+f-PB#qoFR3g^r@i7+Fh46lCgi zJsUl%8U1OydgN$fzS7WR%YDU44@?uM*QG6O(Yv7#=}H3cyofuINyTEgX9LVLBq_|x zl|eo63<$wooDXc42hlQY zbw=7MBjE-ajkt~32TC|npD`7b*MV%8M(_OYiFDHc1#|=hOG>}(UFURsw?^(G33VO0 zOv?OOZo0kC%^R&l`)kIz6}tBOv&-377Ky0$H3rXwzs>jSQ;UV(PJMbTthfVf zo2txp9;chpx^AI_fm;4wXc9JTdn^;ylsX3+&}Dk{_P|KYhtRgmPe{WjOtG{rb0lM|*t;+0Adfw6Hthqf@W1DIPAv-Pw>utZcl$zze zgM+u}n%`Eya-4(ChV5)BLGPM>{NN$KR40+Q z7J1R|GH@DYIj^Cgt7cuSq(GUmx!|z`oR0?8NN2?$(j5h4>$9^bw>P>8gd*sZ(vYF)G`z0f&I54mYL;Y4{nmbwt9!vblJ1!y_2dmE+9+-ArlP-mSn& z3v?3sUWLHgh;MidX>ju=!4?%@rP+o`o+S59#38JkI}13w;%u7@Z*SjA+yh- z%wn!!n`cPEBRMr+Szc2*DIarpJgpwdHOOU;s~&B$E=z9r(g(}q=G>b-yMF39@iX8K zf{Z+;b>^Lrskr5!=0%euW_n^)3U}9gR!w3&TZT#Sl9iSQW-B1&pxC9w&q={6OxGFH zmFAS_uI`y4MVM}~AvJ=s@VOS$f00je^1=y*c~&+|`7)Meup}dhZ+pqZ!IO_qNwGNm zl1;@;{6Qx1<%{uq-Xfr5>`fbYaciM4z8u9t07pA;yxBk);byfTn3Y}1HnzIZI*HR%R!Td_2CsnO{KZv2{Iz+GK%fMM5I#Vg zCD&LeOkNtP4hKy>Lt)mzOELHb&%sQC**j{-AKxAvyOcIsG4k+B1CG*;J6eIGE#2U~ zTTb!1gIPa^dp(=|eX8`*#X{F(MA$Q#@Ju!SBhJZ$}Bq%^1*TtX2m8 z?kHbAJ$DCfiY=SnM9mkRn2VbkN|fB0B}(H+%WS;cW9c>zL;Zp8NlO3Ve>4~Y&2vA$ zn89Qh8)mybR0bt-i7)@r4&nT&<5iWSa!=+$YPqLAQ>u$a5+p?a27zJTMLn05Fjg1{ zZWkmJoEBtzOBZ#(#r%NfJu;j2>d@ZVAl0D?t#KX|>pmS$F`;g{2E0Yx3b&PU;fb4})xG@G!D zRU+oXb~L9+peUivCW&kWt9g|-9}f{xBu)d5#T1U?T5Db#OSv^HN6H0iWLt+nzQs=W zh>ZC!OwK{|JC1P)?0iwhPBjQ~`*s87>j8T%U!2}^9003sTB;3kmprZDUkbx~objV! zlA$loG?U;T%jxG1q@hRb%pf8=Dvm=?aolobeZfzQT~oNL5W>;*!tsV&K`d1_EYe#k zLFNJC@PoGeY<**pcKB%=-QH&B3Pflt%UQxtHbXXJV%x6*r-P#NK+Z=NE#v!c#Btp55{tGmKC2lTLLZ(%MN}7SCQVEEI_+mvwyhwd;CS^qi z-ZvgO7A{x3<=9td%(VcHkg61zh0Fto?LZ=m$rak+ax^=MhS7kr};XhDqBjoANAPW(++cpY&RH$WtTGw3Um{~$$k-`Cz@hn6D-OfB{6Bk7iv z@6!Uu?}Du6@A_j2^tg-WMc<#d8%k^Vt*2P6mnWe$rCP`i3@y_e1?9_?6^`=92>QTF zeF0fx%bMn1<#_8fWfG$520MY4IXKIZ!HJlenQc+XB9e^4@ z+D@US>6gSXk3cOk)Do7spExNIFAlJk$BrY}N`*3396*+La1VWw1fd|7%bNd;>e1WR z&r@!4$(sfxuuNSgi%+)9QB(v($2UqyWou!u^S~>^z^8yoN@IXeX95Rk+wW+I<%EY6_VCa^H_>J@EWpHqmVw2V;6 z(2P`xj@k&x20btM)OTe_KXP-59#J&y1?9BbS_lrQs(dPXp5*SnjwyIs;wS>Y42snE zQkGWd)A`}ln&vkbX*l{RxNvLt6?bOQK;cx_bhDA~zfp7S7tATan3i45rUB6&l`{%L z#w$ssvs~oJmAP+H#U)f+0OHbGkF#r50PS%-VA-JsJ#--9J1=!oZ$bm{zLcTqT9W!U zhz2Od(#&NJJrb2%3NTZ;%(V{!7W{t*PZSmpgXoYA#cBP_oJIH|f_TsxnKd|d$uu^fsO`iJs7qh)vV*nm>m=9M9=SnDt5 z^XegAqjvz}K%i(6W)ML{Es_OK=N(-cI=3fsB+JK6YlSO9^e0Gx#6*6zY&33gqEryY z)JO#$ypj}kqS_JHS$=?)jOK*s*avm;ORd93iVXGpuOxkoDQ78%hi(!gC6ifC;=94+ ztOkxQnE{Em9T=rt^FdE{BH72M*0dS?-){J&J zuaF3FFrCx{?ie6aQfE16ic3zJ>fHGrjO1vZb4btrB*G$sV zE6waizvvn5{Nf)s*_}N4*a{jELp5`F210cHnAd0qUx8oyc~7O$3@qR49FD8m4%`H) za!4@MukF!hcZT-xGI|Ygh_e zYstC5%hrr|zZTGQYv3FvFo&?@$j<*dD*d+Gf9v&|ShMm@UON3t>W2Pw) znyzuE)zgiMd5C9||o^BN?(>&lm)GL$+1QCYvFC!lN zdn^C?76t-9q4Du|sFPR}iTe~_SsT_q_0zordd z5JL7}7BL8a$#e25RUH5C8U+GBr;Pwm5=rZhdLYidEDuVDirQ~z>P+ATo@qjdCey=|L8hCF>_R4#3sm(vDJ|_plX*J+h1veKJ6Tj zZg`k#pG=}EmP76?A6GMeXmL1xIB{$gA9DBbKx1EccNVQH{G&C6o_H-Ae^=ov6>@S3JZ|uXUf#zBzq>*0r-hVCcT{mCw@j)e zC$sDaK*4dGF+3~23b_sm{Kiq_^+c<)rqYM{j2N?cG}WnoD9AJ-!NC$&KD9b6phaz` z-b5ee54gKo}&%Y*u?`~kg^3<=Q1pZ$uUgwcMetIwyH!)IA8TXb$AK{p50Zgo@P z#V@yr0N%`Z`O9_AHIU_v0ALtV$fGRK1Vy{_YJL}%Wi!OvdJqHntd5Xx6`8(^mnJiL zj4k)ODJaDgYQXI4o2ry>@DChWnvl6wi6~Z@x(bANX2Uege z9qnzE^QpU(AbV)a?k}6<7jD(^pgSx95~K&Iv{qOI6inI$lv0VzvosbKfZN)S;6uc46M^@9YQWGDWSa*;;9ry= zvBG~O%7a*Z*&C4T*;gAu3DLKZvXMOG-iuJZMH&i(0gVev^wMW)zo79wER=m%xko*f zVrnxV513V3Bzq;o$Lo=VD^LAqBAmvyB3dM)n<9Bxh6VKBtP|&_$5D3%|i!2a8vf+~l ziOQ?G5F_E1H^!$U}-JsBj-PzKQ(b|SuN#@UJaoS{g8T*nBwy8SH9BKdL9Ox;ejS3 z>5m_gPQ~`;(Sj0losvvNN1U0+#5fh10$L?mMbq)vL7l=AOz`6pUJ^*Lk&LzLp|sJI z?=&tupZHJNq+v^W&fY=WlXA|e-KSh{KqO3WwocaC&(Pt1SkH2+;HH5Yad+R*D?+s+kU5RLyfjdW} zb;tiw@@CVVd+2HvkRq6elQ#d2PIVp=yZ&uQ;0D9f`_)vc5h_E4-~I}98DOZ?6EfN407 z+zLkxt+0b}_ziEhX-D0h})(O}coed-LPh zGdjl$1S}pJZ0|z+h1-cP`(rY&Fdmy>cFwFijk?hNq|}yGtXMvY$=zmmkZc#!0qJ(P z9#+tkzSirekaW6qF@4?}P&Ds{ngn&jo?UiVM9RRelOfG>6Wih%?+xn(hDd=b@`5Y@ z2xN)KWsm+D)#k3C{368*T0=BN;(u=`_i9lG@n>RKqBlH7o2Wk(vo)`EkPOXI$}y=L zc5QBH=i7NGEXR+Mb)3o@r4Rs(xhdp>E!a z`5PlZ4`rmH^_SBfNM(3|b`Ut|B9zq9Bd(+BxU6Ljd+>hKjcih*tP&jGc)Jqn@YSiE zs;X@{!@J*QQdox(8Kk3G;yXKI11JM4f|&d!EU8hXjZE7j%K8m_OriKX1tGzh(x8M; z0Lp%}8PZU`0}o6j1ZbGPFmzq0o-}gN`g-uslq`e`=`dALApp7rCg|jOXmEYi@rkf`R^x5vH6P41wVq-gA2=V7uy|ImWtXOl zlId598#BqgHp;&fITQ)3@rQ0TbJ=E3D}GzSLi!cS>$e6>EAdsBF>EL3i)v$)CX#cT zvr6u>(7A93<48)TB>iGb4l+Arn=S%;dnEx;k3&7n!PgYhC-TF)wt$7~0!x=F+~>8b zZ>~CEE=kQ2VzCEvPc*tIw!{(C(%%#7R~G&VU!kTqjoQ_a3pSlg`vU*8dWw2}Io|Bh zTvBK;V|U*0W~05;d0?rwI0g-cr)FM+b(Ba~KIOFfRFg`_-?=59%VKiO2?(geKEs(_ zlj+d0Su5el6tu$;wQK~umVjoFQ~*_zga>|}kdKd1NY{Ots&_j#iiB( zwOP6Mq524Xx87SI=&v$ohXV$oVPm1!RpmV7@lj|xmJqIdO1o)b!d8PQnDQrcCrfjm zHzrug-S6h|@1eg3pcq;pN+(;SP>0uE+Oy!%LTop#7<8JAvbSCiN^QSO^q6A9Twb03 z0A-V~ZHmS)wYJ0rD~j^K96QF62cQ$92BI=2pw?YM&P&f1=*?S53SN_qel=yLyWWHX z_KH(Sy|VR-h*j4ai9wa<^1P5 z<<~(YgojH4AQZ_BX`z1(^7fZfEwwov$BPdPIs_}?NE^7H6Z~0?*B@eif?4_0&BQ^? zy{Zu4^-(0pQh6@^yb{s=z`NgJsk-EF~g#>MKKy z`pO|%E~%hQG0g@Kp$#s8kQBGx1qQmMreL7kR-Di3QNsEb=t<6HQ_kfi%}Qc94C#7Q_!VM@W)n1-iw^Uq!PpB?+$a7PBq8~`?^jZBmon~e5yARA|BwDa#p`=lhv0er^y|Dsq&*hD|1oB06Kt1=W$+Sbi zQ6aZ$j)Ci3G}Bo)TFw$evBbK%u*am*^~(kvW6|Ysu3Zae2MR}9{`4J$ptFYfM#`dO zWiO&TRR=}OIs$fhI%|D6;oST~?xe8ryP7(by6s zQ$8-%1V3zXjYY}}ouqP^lL~e?54}JinY(SteNhI5g`CHlCaGCbJZ1=ou^JlVW`g3) zmTAX4dlH<@d{~EL3n-YM>?p}OrUrVp8zTc7))C8GI;|fiG_Y(DB+gLSVdFmPSZvs_ zhbUl!ncXo;?UAbo_2TYR$gZKW(P(*axp_ab#+Y-}aHNyEW&$$rIg|G7v8m~4^t<&X zHJkV;n~b92EE|mtCyywkBySP&m-O4*To434x+#VDUn)^|Y#b`sWOb3yx-gVbW=KT< zavUKHty2;a;c#UUk>b13Q3dw!h)pm%@T_{(a*)-z`4694F%y#c3?ai29?ybK17kOW)~AmskcYDKo( zIgMk_#}2x(|@W$}+8G;QWz>Ru3Voh#=sJ|o+hTQfH3`VGo! zDom>K2L#wJtwLhkXd(-fMA??;-*awTnH+NUBXhfBYujavJf%ip$wmC&;`P!@q)UXO z&3SY>>&M1)=A8L4V?}e%?*G=)Or3JnB7k3U2o5#<4$)ThFkZTlPsSE429^c$ zV@f~`x4IvBgsihxtenlZ31)8B@EdI8Ws2!2S;>@Y&6g!<5o@_xOAvLFby-vA^}Gn# zaS(O(sj}k70`7Ak+cZ9sB`F-iZZUQi)nFMbD^)XiJD?;?zHO3GMs?jdLr%+3iEKsF zh`vqT2#1=Et#hp!{5+&4{z~NJ^t^xtQ)rV~=p-WlU)m2D2r*d!0>8dooWFys>t*wE z4(H7F7wEHb%*)#DC$NsaTYBioBsnOis0nhLHy9OLnQz+^YQ?rX20ePdj}RO_^KR!a z>$XpYri^R-6_B{Xz0h%ok}3fU)V82BYjlt+CfO@iFwx);X;{o^#AGTN@8Uo-q|Wp& z6Gn!w#QT!bH751kC8f~0LdjVoX=H7b4)ZCu1f-J{czbhnhRCOlq98?8XGGQ-i(QEYJO5T`_d+N|QiYMEav zu?>5(iu>6mC8XpR%$vAUkr&Tasyt-DY-0=oDj5}>dI34-Sz-iuX1%1+CG+*&F1oy7 z1ub+C>iNc^g(Y>Yk}hi^p?8M)57HMgFA{hK@syEO1Ri*5L&qESkkl9n)(a^zeWGut z8WDEDc+q3xNL0YQAz0zb+M1onI91B6H7uQ+8*{W)Ns+i=zhaWo=f`zyqwM7y*Y-0kW9o}q3#Uh7+3HazN%-(&F08#~tF z>pwtPNC2ZIB8e%N2)ArZG9+IbUhOuPA6tJ9HOaY5Z7?+HiO5_`dp57R`aZ>7UYXok zGFj4}67w3{&28UbnPmzV4|m`E2w#3&()aXILEp`XWUa8W1`bPSE>yCZ<D5`8$nF4Zvw89@uDk5QAAd5|`Fgmqn!$)H&n)Vv)Gs4*O69OD$4Ik} zsxc72Dr$iyluUQLxW$R|RAiw}|RN&#&=!yO;xBi#*)`ae{? zWmFqo`0kCnl;U0rl;R#-ihBzbch^9%;MStWp}4y{1Pa9|?oNUfw_q&<337P;=e+Bj zcjeoB$ey{^-m_<}d#>Nb`IpnF;R9r&b-hkB7@QkCM1#1$;Rl_>d>grPgd18mWM1yY z-GUwFlFVA~;mA-Zc&b-TO!k&hyr}F`BNOI#25Q|d{J7li% zs8NTywwrBSiQQF9uU0mStVV^;tzz8ygy6(tP%owz8GCifbm13LcsQpQKz{-XF6GxHdqH1$}W>dMnV8Nc$ZoU-iCAfOu!H z_u|xHeAa>Hyi+j6g1tsD`r6`OunD;FUS+)=WIo>u3{&)S))53?d=lsa*sTu?z&*X` zll2i*NP|_5jrsOXRmT|ANLWkS_5Cvizz>Q0v$t2OU*1Y{q&5;ex$9!yjxx~rVPZNj zn$MOk>imlp&FhFMY0TA9Gn*BD>A<|mu}H{3P1Ob)O~yZ3rIo}2J<3RdU*oih=WgXX zYr4wm3$(0iCvC<2{c7x90g(%sawjdMO@LM>hJRWOZ+QrNZlGspCLx&^*#teF@KbA~ zdAn}|_S}CW#pe}tR^K^QRw|0AF}FajbP$y4L0-D>6)E&+BkSz{Hbqw zhrMfH);(M&-nf{S(=j7zvH9HnEW#3uGdK&Nn4|sq7-4SU;2kL_Kk}x|zkRyS^w;c$ z->BCT?PN>vlSR+tQJj(U+z(dWIF47F=kMydrDhzaJ)N6+9`su|GqYL~%=jla5N+8t zlF03{vT5g=vHRGk`a9Sw@AyY#(`;t;?TJVGwywdUl?`bSTPNGZRxk6~)QC27_g)e` zzm!(*9`jD5;uPv(S=n6;w-lhl6!=ZPW6C7B)t?iv|3fMP6m_45{44I7Gm1q(OID=1 zAMDW3G6uMQlU>EaNN?m!@l6%TJNiINFaO2%y)Ei+7(bPeWa9Nm?!1@rKoS8Db zYE;&`@=?#Z)uXIUUn+yql0+9%b|0D1gGFF<_-WVB$|m}eoZDN{ zBIaG|imQoVl1|^B=P&bwKu0Kr|8fmB05oUqfBaJr?5kH_dwkp?^l@aBh0E0PpGKa8 z)lht+Np2u~7uN{}M&vcct(zm2AgCG{)D&H01?&;Y4!D=OodW+e^19?Sm3|w*9%yQl?&pO-NbA>TM!piJ%%LKHz zO$lGEo@&1H&?s|f_IF(LL)44Wx2RWi86o?Bi=EMMR$H;-5`*qfO7>+T8wH}u!uyx# z5O<8+5LKrou?v9rJxS;Hzf$l)cj(6I_|;cD8ltJhRiFd+1&Q&?!%2ZO3MYXqvH%wZ z6}Q%w=+w@VMI6_@a8iiy8X88Ku+mwVVIKY@ikKJ6Yn;wmwRbhlX{98N0e7<45OUSG z1$VXOFWT}S6%a4|FtnlXcJBSVxC8TOs|6G0UFDd#`xQ@0B2PMZjOH2Y0eb>!=FfbB zdTjv`=9LBXy~xxshQs1fkWpwr$33S= zbtSb`n?y>B)Z@lH*cxIzq%{}MTQP<&vpAxWZEV$}A5@fkRXgl_Y{#-PcW2{|=r0NU zw@M(^V^iF9x=ql#Yv~+yTua}XZP?=C(-z(`C)Hfy4 z72lDXnEeqNN576{nhBILNoyJwx`M1Z5U#qKeaWgd?V3M(*yD$9sbT_0e*v-qb)y&* zu@a3hfT|w5X5fj)B9(S6;IqD!tKoeSr}(9S|Cw^LVjlA7!ZLCUg6NqRP#9Eh;(Lc= z?(p>yIvqjrrrZ4acC;C|Es(YdRWNF5Uw-O#hy|Xwwiunk3f1CT=mBYHyWxH77Uuf{ zIeRZ_tfVIO)h8>Ezn8sdxQdsbN!R-0E)_yOtalWM55L}gN&mTsY=az}8DpagLZj7z z6+O*hN8zUN@?86L6HsF-ZPsXK*YGNIZ6fo0WC}&K(5b!&QT44SNA132ph~YzF5XQKCw2##&FXhEZtWL z;5w(7A;Gp4S$17$e!wj;X!Y)&vz>R}{d-w3mj(Hx>88c}AS==W7dDy6?wsA_A z@CIsQH`zEoo#E6x;?X~`npRf}KHEU;@_Hk^^y)663iJIu-ig^)R+4lS2 ztBjQLl~l9t#WY*Y)4`6fkBjsHYeNi3-uzL=Cx@*a_hBZYuHf93LlVRqd5_IU$(tXK z=hFd$8%;h%flkh~k3GS@)wuvyadS;Y@{u6yFZ=I3GmP9up4v-7LfR2o!nXe(3jn4h zFsFH=Q=h6f%Ie}+`C~ub0`ry(f-AWVf3C6u@j=f@!tOCcyp;F8#6d5&E;dA7NLV>DYE&>$5Z^ z{Lfv?iw-Uweo)g0>^AYdRKuVIf}Qtp!H(#KxJHg=ad5GbK-7#$nf)Y{2C*cGfo3pi2?bv>^wEAK z5#A3;G&)6_SG5T(`VkW}L2g&=EU(w|c(>f`8hkbC4f$0`e0me~Yz11?F**gj~43a377NJ63U2^C!coqnc$yJFH z9e!#BblVh78u)cR{@EvoJq>?{e?GTG+!|1yc6d+8RL@zGORm@wN{ZM6y?W#NMav?f zu;g(`b8qoA;B(M0#>p9V%W7OFtd=|-CNxFwlpnOox};sxC+r(;GDbvMX^-j4Px7{h zBrET=wj3lGJl#Q7%b7b@2iaCt3u zHt8zN!Ehp8L<;y|-Q1@E!$pXsITHgEn~|ODxAp%LLW;e0}^3`Q2!6C`(JriA-OKn}6K54LA5|J&6dKT=P^ zPB7P}Cj!Kw;5FE@Pq_0Wj}wFllxoA85n<3)H^kzHRkjq!U*Wv8w?b^c$MY((lVQnV z2{VeFE!JUX*1HY?4#<(RZXULJRyH@D8fqcyP98|8&zqRsZRY`(ZKuSl5Ljkyw&w5s z)8~yxjyKGfr=hF3CvA{PZwdSA<@!bp=V0p`a)vKsSRI{dwP26U=Vf^2`I^%+j=5h} zW#h>v+%_8z>mF`0e)=!}zV6X^)dN1VKM7AM2SZxZH_dx|F5I%k+-kZGwwr->QyN08 zaPA)m^)B6;`^^)3DKSH$-iXV<@l%M@ zLw8q$n^=F)NYHJJ;wn?}>}w-rpAm!1HJW*uIWivua&2|&#YiAW7O9^ITb&w9c5 zcT}RiTI%}!NHctVSZ`%#;olIZ9wa@e1rPCUB#R0HqbB@iz8th?+xc&G5>QDdtFUmz zrDruklUrAwXi!H{%=wH zw1YbxR%hnYRA!uR;z~XoQ|X^H%qYCm@i6z^*w)nU_1zw66V{gRz@sMjGCQ6@1C8xMm z6aC`Eyq!_@0)y5Iy4qc$O8@O@J2tpVB{d=PDO>8!k_8Lm=KAV?Ten`zm#?&S=YqL6 zc%0Y8GW=kUjrAMBO$qCF>th zJeBGh0h%d`;Z?=TP)c9dcKio&>`!G>PJPlJg`HSu!X+VozpW;G zQ5}ZV8#vZ}zt^lDZef1nfewDOceYs2Zh5{wf3|u)*;hP`N#|(U{PiU?_xt(`eZa%x zlHRpy=aJ^Z1QH?V$Jz*9NR@fpC~+;<@G)mu8AaAl9rHj6K=6~)d8>%_upuf`$BwsY zBQ(GsIBW4WB)$)X7(18-v6H=yCBvMnk?wRB?I-KrdrU@8nRqHSKdJJE(M$Qnn*@x8 zFA3Ym5=U@wG)_Ol_sFh64%K{4mDK}>38b8;SgLR;OOx-XD;W4k;P-*+iB$M(Qhv9vDpgIw<{6LIhF!25$uS>~Q4mq5$x z$CsVZnXjKQI>dTDFk5ThypjqH-@$1|D4H%>ODlN+_baLjnzu0P8%{KBJ{mA2;axwi ziwbwXr()HO7>`9IFNHMWYC_(+Bko7@trov&Ti__bpMQQv!aksdI{q&JWS~)SH)_B5 z+Q9%>EXxx00q2dy=p9n$yZqkIAbf@88p2|Z3r(vbD(dE?e8ub!<)#YKcui1uBBa#5 z4MhaALmWn`n_(WPtfnrDe~D}&&vt@t^(N>(Lp^f^r5EW~n3M9uI#ME^MH}i{rW?~1 zab*GPR&aIoWCucsXQoht)5gC^y8z{9^rKl>qOCj!JNVY2e2;Ide1T*p=;ZyXu5NZ= zsKa52vnMUy7+O#Ze;~4-)3QC_?FC<`gg=iS22)dV&F5*CWs3M^m_pGm#R!puOcre| z1Nn3Ew}B->iqVuO6$~%4pFP7GMuXCEsjbXo0aI7MByNp|bnB*|;@i1ARs*6cs%QD;l5ZaNZy(ua-( zU+-3NX(scv??j^v)4fVIcf(&b!kulREiN&?dRvX%l3ht*7vzy@^bWzY*|XX04mE-I zZU#;4HwQd%+D(F~U4rN4h+DhW92}IzsY*YDS)(4i#1aUa&N&jrNgo>kU)!`CkDZ71 z;f^wstulWx4M0tHU5O>t{EpENFh6(1?~@ zSO8j}&O{udnEV&~A@=x3R%A{$$ChhBZ(%vo>5P~0MNtd+97)~&E!OyfLRtB}!BJ)4$PaCW zJ@fmjUP)Qjv^aK7&Od0$GnINiWI;=5v{CrFWy~|TXHC<_jWcBl^mbB4KgZ8ZyC}1J zM6HR%kM&ccM&98+tz8nA9C_g_$CX7mp;M=I=vyucg^~rWV(t7 zgeH`cIa-d6XD$d{V3o|-{3o6T3;IUkOZuI;r3RGc?vBWc7-A(B8%xD^%3q8XDIo{? zf{`try`PYHWdNxRE|gjONP42$z>0<6H%W96t}jV6jpVYYMGn2*y}bN>OfR|9%UJ#L>D0JP9RgcovOI|j-?p7>ws_9M;bPT&( z>P^4B!!5q=es3%Xu*X{#J5y~*Q;av6!fEPCO2$?I;_ zRZjEl^}7iLr=sptSc62JX|B9r%Nyh%E>7?I&Oa#V1cK-bdC1gt2Z|rDFJ{W395e3^ zrmifn^6eb;ZHMN5?XGIQ9k2Us^O;u5-dY{`;y7+A_FKSHF)O#xff1RdCozzZP z^dhU#+*r4WIga|fd)tXuAk4bx zWS8raM*aEm?^gLLMY4|dRNnA6_MXck%M?N>{I6q3WcX=oZn8*82z^dK@Q3`a>l_Qj z!k#iBGIDvf(h9m(%-}6LyiasQFvSK4eMOuu?(T z9B0cP7$Dnf^Os{ydZ3Q=7Nx0)7c~x4-*%K@tCg>NVudq{QL^Wtu)*+rMR%7Y?@{mZ zb{uIrPg0tb^`u~h@2*TgQ!KQ_GXQ|yOvxk{IwiOw;DwadBHOx;+bSQOo?c}3Wf&Jd zM_4$G?L>pKOolHNgX#+lqv-lUZRyWNfaeWl2}CkRGgU#bUe$ocaRvR+IO!)7^R?;4 zYV#U1g6-!~<5HO+^uf5zYwF{Q@LZC4a+X1{5WtrOlTgi?pK0F@BwKExWJqr1eQ_X! z6Bb3Bjvm+~TXY6Il*MbfzzF{yC2SY`K~c`e{9>27RxG@-d_vWx{OJGqt$h*5JMBkM7R>~Cd%dXNQ>l|{R(0SUS? zRLJUuSdbeFr@`jzW?P)fPvaAl7>L_Fo6e&~3x9hFZ4S>STkh2&a3`#Z-HynvOyY(H z@b0u0&=@ZKC{|nN@J(lW#W6u#AlHFBqjV=7E_80>Fkjw7$y35tHDB8bmLUZwb|NWy zu5ozVWjpy>%g!DUga4oQEI;eEtZP&KK zp<5Tt(prQ^OMLk|AM!@a&~X--m9#NSZ9cO1+x$D0(-UuN;AoDiZl)~{wt2V_DCKb; zmFQELrlwolqE0JxZB3} zI!{EvsP+mja48FVkv)*u4Xipt1$B4#9=TAy3}s%80p*iE#B{K`suFCTAa2;?Hm|Kl zuC?LLSX4vC|E(zSDeD@3)bnj0f2TmKsbfb3(Qm^J?E8ui9(cDBh(}S2?s1Ad>IJ9E z8f&9o116l8!5#wv9*5Y7KZ0{U;9I`~%m-ewR_ui+QPP^rGwC`be$@+mhd$<;7}W&sh*sC-JF8Cl zNqOx3GuQATx0us~wMn9Zl4eUDm@d$KJ}cT0hWErWqmR?PEB?gCL^BZ8l9RqwqWc?V z7widX?eUM}%oSTtle$1+(IaeEOq zpElQAV)g-r;IuBH9hYA77w^rB5d#I+q1DajecZYltsy0u>i{`KGjq!Mm5~H2=ry)* zr?H*78skkrI(nJ33Z(#fB>}bVGXSmK58Sc{5Wd!cG5_ zYdlXQ;Nv^7^P1+^QcYrAY&Sw||~S!csO;J)lm`Y>#Yx*1V(Js zQ#I50-Y6)7NRWZ}6gZrlt4?N!866ju(<4&u)tzbQ*3xFjKgt4Z_JKGfnBEu}A+NL* zG^8RPRC#hsj$~^Is4eG*%3#Xyn@vkz`9*Ot8`GhuLv3Q%v5HugN&(YOT7ZL3VtT@|V`u&Ul)w}iqHVCQGlAb|4R7+&Kg zY%x9G3isVpLapJ`c}-e%quUM+=>G1!rK&^qRO;;Giuz4W!;!W|i(>i>)YUYv5tj^a zg_GWY4qW3mqvb{H{IosJ8-M-`NO8^HPYJ#bTpZN$0BYc4Vew3~71LMZz$GslSdN7B|) z(!#C&@nlqbJ6?uOok|DR0QWF7c?ru;c&$c?zDHaV-HW2}TKX7AnkP6y11MjmEkW$L zyTibCmmHmE>*@TaGDPSMD`vBlW*hF$j-8K5=^XraUnStT?n4>;uiB|=L*w2>GTX1) zYhS3+engT@?2UGtSDq|=Z1d?$#A_GE|WMwfujB!p~tQmwI|k5gQg zC0+=Eoh!^0vwC)wxnxm}M3Awh(u_=Rmppn_>fbQgeK$~kN=puaU~V8-ebV-}7c}oA zz)iE=S0AbM&o(TsVIXla-i_|7$6ELup%uCC!CRv-*Qj7rz<9U+4prx2Y&gIMt_8|5 z-5UF0Is1DW&~y*$PB!t?Ofm7@BONI);4rrbyNdg^O}fhKju1o~QI{WCENOtbC7hc? z&r1wIa}KIA$64#}UMeSA!X778Tntaqd&beL>?Ms+W+Y9Q-hR*27Rx!jQW5RykR`E5 zJcISrR>H??1;m6{)yyA(A~%uT(!H4IN_9-9+T7Cf8;O)w=#yRT<3CjBN_2j)GLz9t zxt(oUU-$J6t?oQz+`u{p_N}KmN}npMbtPCz+&sbKYzWHz^DCd1fwynD`sCtD797y| zukIQ&>8cKnnWi1iOdxOaxYj~+(m!|3b2)h}e{U6A{Q+m~y#M|a1V0ibPNp50?R1?M zf=>3pnm4=LA}8$z#;A}EC)wu!H<%|dNHzINYI^s01XtJ4UcGE{kK6nXXnpY<{P{5; zWSwt}$G*HF0n!%S6xa9CSm^#z7`VL?jDA{XFs&{D`ZvazBZ7Te0@N#iwdN)tI#_e3 zYPQ#m5R^fAZCU%4`UigNL?f@qG$_J-u0x5l=;*x*ThD;1)UvX+DQD?5bVBTX7$lYR zi1Nb}<)$-BtZM@sK-1Zt&MNTn5wOtsTek-4a#Obo#2sF6oGD|qI~gqdQ_>g*f>i!n zbuIcW+6HX3%d_&}QgABQpjV6|hTnFW!jSc8LvhMtyFO^Wc#52S1^Asn>9Az&w6g-BPz#jM+I7A{k&OGIg6_C>bcHu8C6&1d-rAZQ2vN zhcT9a1k-jRfQw69Vd@YKlteWbb!d#yy)%$yT(Z%ZifPl0f_^H0V=!4KZKuv60slC0 zD3Mpz*RJunwy<#{Z>3lBO`r)lDV0iFe;ov`0XW%wccD?V_w+t%x)u{X^`Aa%s1)>a zAxtwt{n2KZAHVujAAKGQoA7P0b^2a zO8%R9n!R%UGy6j?Q?^*970sW}RG7JVZ=O&VmulnJ7W!_Z5#-XH>?~)K1DE(w0~_LO z@QSyTn7Pj6dBaUWP-N|fsZBa}uaciu+;tOHk^fBrr$0`uHa(;QBLrjKm@>A&TVBH6 zZw|h{styR(@FSm}VqYdbJxI8Qy5?xdL@-%V1HeYE+*TjU4z%#JbQ@C;2y*ah*yu_Z z50&p_X-QX$4NLh+gJrCMAa!{-PSk4*BSWhpiio|_a`mA+EFO>Pj-V;zn%`U)?IC4~ z+DCJ@?W|63ne}T+D|vHC%xqf?o7TRjh3NoGh#OlZRVkZb>{r%$d2z(muwCM+hG5H& z`D#<3n|ID9b+PN0GU?sX#PtBMJ|7fAsdsV; zCut%z&Cz8r-tf0#{AQi#agVZ~65aI0>cV1ROk$21i!G~tMNwi7d->ET!xDP9T)3_1 z=WMYV@rhzQ(_H=(f!t7G(~@jS+>9@Qy42T_lJa>)Kn?TNBGK7T0#K=~2oP7%N=|Lm z%L8u&Fh!lM8I$%t@)MKEX`iOpFWenYp^Q^(t4j?Th6|YgLrR5U7<|f|SEbIae>t z17RAHL@gHlX@_TO;C}htQD0sxa3JI+%nvl)_a}pY6SzLZb3*tRK*w1Pi?qK;qZ=~M zvYPfTv{?oGXiV9v?ZBJgTVy{4OBL>5ULxI;F$k3rT%-@pSX{qDE#p+o)ae$2A zM-@y-<*_GB$+($6QJbkJ8UmlyX;yi2Q_GA#wSk*ikD@~gb3iI`_T-ctHa5-keFoN1 zF`#}8ORFA**f89YgtyazH5ik<-%zAwGZlOY2FyfHt|@R5n4bozU@o4fnf$o@Bh;B& zy55dcdC#nEh6I6a0P%%_a8h?eQsyqNF!AU_LhM7mgtID-cKd9R3P82V>8!wuD4_Eu zSG(#FM=W==;;TJw2p?Qu_98e{l-?R@2q-!|I3(a)%TT-Lq)4yUI6=~HuGFs7@JHYo z#5XM3#{%4WU>ds7g>~RYd+#b-=qcktU6a)9BmZfz?vK;^`UQsZ2w@qtpHY_{yxPN` z&7)J!y$S@p{)nj-3nArZRd{ftj+xpoqTW_pkU}!3oU0sToD;|S`3vR?{d=72qx58d z8noC|BU;gsPB9RZnUffiQwI@B@D^XDFa(loby)1 zp|iky)@=p*QJM@bN$YBxRzs@nkWo*qKz_0GW7r$y*p{$2Tgg0MGE4KB%NE|^V6Bu5ZHhvq`-O;(_)4(Z=_|Vr(@&HaBPk*LX6d5ftgccsi=yM9$u@Qd&Gl2 z`y=D{kf`l&D@v8}zZuIx@@l$|kP^}fZv8aw>|lOxFkX4oZo`;@@@ry{d$ig4Q%kHE z>bGLo(Dbn-G&6xkbH$OlTP9r06&t*$J|aGQ@kj%lJT))Kn(n(6ks5yFKMwPEX1~S< z{F6E3Q;El7ZZh&$#vxx)A0%TQ*^FT;tXf##64Nn|LKY-J`U8 z^(+!5lF(wl<=>jXzQm*vp;M{Pzkl326TDF`h<<$_Rv;Guq^VAUrIuj$@^!Jj-PE#= zYkAAvNAjQs=Z$H3t*3;|^BFC~CL`W#MdqgexEZ-+19GfY-G~v*A3<7CYse#GNLhCB z>C;X|nstA|7NeW+HI}sgFvA@7+?-4R=ciFs4CLbil+E~iq!kRx#-(K>(N>%2T@L0& z6@Iw7oI*2C{)gNULa_+paw|XPo{tK+b>S=!x{_XU?hoTAW^(R^W`gZIFTQ)4SFck> zl#!G^`C>+eD(C!8d@zM4P>WlKtd`z_|#rVZLN{cQ~_bCQ6j%xm$Da2A=g4(2MjpxmXh=x*nL_1QHk_tg@grSM9 zoCFE4dGwqbkY8PUvP<9{(SaSa2mdUf)+Y0YOy74z-OK6b5X}%@sNpO3dgd1dwvnIf5YVaS9%=Um1y-Jy%oK(!Qf@!_2M;`|xONl{T`VD~D;OP*zZ zHTH&e*F&_;7#5K;4(Fl=TobCu$oSnFCF!Cy# zDPS>^1?-#&T8epI4{2@c8QhFRJ?Rj5&qGZFjW3d~2>Ld>x-wtS!;d}A+0gK9rQjh} z1)UfzeLb79`7oNw((EB%mmFFC#KMTIeYbSl@iI?vzsN8%FQfT78gL(5r zaMiW>?zBFWWf2SQp==~!D2*smQFK@WUmvbJ;W=;UyCuZvXKjpIX5TKrzdrt%&a*f# zV1w&fLFOFNW+Xqjo<^47lRqw`+jEo8Z%BpryiiPVUZ@@SIu+#G|4}<=m`S9oQD4+3 z&A~OV*PWzCVL7x!^8lN)sq_^OrHC=ycg>e?F;mG}EoJ71!xqdQQ%nj(&y(WyY26Qh zF!WP{x3T^_uSdPQ?kV8mOs-A&NxL zIqFqi*MhaZS4nb|c12(=r&t%<*QJTWBR|yifQ(l&Z#eq<$|}<=`TP?I0}A_IyXbhv z!AmQJk{DQQ5bhI-g7^=Of_S5Hf%8H}5r)4nsN~`F_>#?I`DUDftY#w_nXB`oReR20 zFCg1eTPwDD-Bi4(N@2CQ%eN%*%Nwj;jE@QPuYdYGL|thGfAxPP>D@I#)Vp<44$lyq z%%?kVBKO4@GL*5Z(yjGXO_gZ^Or~J>*LI|qXgILQ|E@Wbr%&vK_3~$>2nq2XCCJ*X zXj0ms{z%k7H=@aKBv-UfJ))Pt#@{lWSd=c5`pN0;-k#B1h_Xy?4hg)trF*m?fg zxz#w9dHt%zIkw8=5BhhXG+m_=s2K>UbPP=SS0^CBXF;1dorPS~{;O%(3Uy~_+Dy-n zrG<1%Dbe=fT*F?Hvb0f_^}3Z6JB#d6^hb!W*1LuO#_IT=v0{=La{p(nEEMKgXLQpR z7L5oEJ!%|B<}MIo7A{M$aRI}37vwBsrC3E~jqRkiA>Mt=SyDP@v-stDi@1MZQ0t1E zH}y^xO8gRc!BPRzc9*&_`BAlugYMoVi4!?fukk{HG0m0S0={5zdU>Uh&GBEJc!J+D z+PC1%aWQ35%{ObsYM>%YV(MdtQ>Cnz2rX=T>9k~=U8U1? zQx6T7?tfEg>PwI$oEi9~F|&8nSWnd^=6t<(!_D!ZnS!ioPGOqDSrOIqWLxJf{fW}Y zrR)6Z>FCLC#~hmWZ9blpKGD5Ge@%ck%41mluf?HA7w!PjYFTcS5milcMOj+lT5-_* zarD0APdo?CufH+3+&#6YFx8N`iwK2%uzWIDc~IgBJU+<4F_n<77f__#<)`ZA4bmn)AR5E| zN$@?>5J@Xh@O?F3%vso28$2tjkSyF!Qf~ZI_5UJ&Bv{`}>}b#^HiiOPtDB(_kv2PC zyPb?ESiU6DC<0~;Q}OY|U%x0mmE$x2Uo?@hCrRQ{(V&1WTPghVyxF*sm-x$|*P3?dcZbK~WiaVtqcEH%8md{Xb@KRnyK z<`fDMHVwFLeAo=Uiwo+hM+i@CEO!kIo!`Kv5)Xu4dwb?Qt`GYTpWk%99P^GFIC(ro zJce(kKOg#Zq{sAZ9eO`aQa``6uvL!q)Pv0&x^=P5IH#&p4;D9QmGXGi&DfnEg3Ru^ z((*TkU4rjU+2e%c>n;(qdUxmSUBa<12hD;mJ8!8XqwD`lB_d|G;N(Fsr)j#}{@^BV zvZsJZ2wHmFu-GN<4D6!LebHh1ho9WmW|srI5IPSEJMDq zXWaRW1J6+?GI>lc>eAt&hEr@Z$K;)}H-G(W4}>?m>->k;#U}nwxuPH8@$^#X=a2T! zvp2=_v5z|^-5bB}enABPtCyMEHjjUgf7jFZo_b-#U#OWW0;iL^r)%f@k!E-m(b4n8 zA3;CjkpmA6iyMfIZ|*_7lx}O==^-e1d3H--^PKyk`{5>D=-&70v3tAQwC8^SPuFGT z7p_ckkH1&*pQ$HV>ZYqpsUu(htzNk2yIIat_gvKG5miq@eet70BsBk}(EgDL`8zz9 zUgs_F11Zt9(6Cjpp4rQr?#<vmwxxM1?%F(!s@RLe^b=r``0#L zK0gvw5K);NF~+<^-jSXC|8QABI5b;Sg~j>3g&6-Y8H*P^{+B`C&MU0Ay!lwE*t%k1 ziUNXO`3Av`NcueVDeb?7_QD-AoFuj$tB2R3JQCytWo?P@+4;s_R5qfrT;?$>3g0*v zybVtBa8|+2<=;(*|4it=@BVBV)$D|m)(;RPPzAH>>t`BQrM3CqD(Fn^l^LeBa=4GHANEFjs71GNhZZNtQvDg zpZil;HMawEczqFXX|T!`m8Wpdf%OVwTY)*yZ?$yu(?d^ zs*IuQ#`|%1CmlTH-cF&{hI#$cWi=TzFf2uD!r1sXdYFN-u6%Y_mH)TUIGJc|bedk7 zfnP^X)JE3uf@|NKUe$df68=Ezw(TFLHt{2}u+Z8vlcMI9A$Wa!y4)<kFNrnFjZQsu<~4`DIU4G~J*&mot+b1sWHo?Az*lok2Mk@{eNlLlQd2 z6>S?w{_iJ=4xn-6;g*i2DUj$hFY;wyrihQ5>Gr!oB7@rVQg}Ki{?8`4Xqs83`a3<5 z1);tq2GL=z(Hr+GFHcPyFI%e33Ytq=zOYCtarV!H-V4o;P_g~rsV;H^!$9W}llTSR zpfarqiEG0)vGtKm^QdD?F8G)vxAr(C`&DCc4_8O4eTK1TX8}Ma zPa1wCsRbl->0R>65{xK)_t@=>goq<8Cbd$7OIW4>K8G!lpb77f{;}!bZ@&glcdCfi zZFSz@OeP=^`LiCC*!)%#Gn-lq)g&Hm*%LwMOWlq8SdrXB_v2mqqj0`qIN1+ITU7c; zmTfja7`LC2&#j%AcDlf|u2On&b;1TZ`TH+E?+d1eT6Jv99Ll;E??J~@Rj#%5n$nxO zDqK-4J84p{vFR@h5WZ%YvA9Oq=ONOic#N0ZV(Cp<^$#@S7auLlzO(c95_u@b^ZI^> z)S=2{;YFiZlOm7s`_5uEwX7}Y&~7+r140gX#}@il3CwCJN9X^yqrS(qJ%!DJ~ zSi}SvAj-HoeQ;#Swy8p~F5|S@(r#uV$1_g`Xc=B7Pm7j{hPkuad#=kv|Dkt1a%Fx!QnUBxe zP2;&Qsj-c&iW8H?JgJzMEp zkpt@T2SL9XZccLy;!?(z&u2Mg$Dtt{42f0z%Bo~5wfw1#778A2kK+F-f9(GLM)i=V zasHXjj4b>kpUV6qsnPkG(qQB~{4jpe_~$SC3pH+A_%;f2YD|xvqTnGz^{RVps}bnJ-s`VR*S$q$XS%)19>vp?49t~M3&#`s?bdw#h!salYZjiX-{ zr(hb>roUAjOSahdCO6_Pq5YSYn^C_bTIC#nu48Fm=Gkoj^)(CyHilFYJ@X~;y#t94 zx5!?kwftB~hpp|rqiot+uwdL|X8UE~s;&AVWWIb`VQ zI6v6FJ%?$%bup$(zZeg`(*1e+V0mtgmRpeYcd5_EzV?YO&KPeoTowR~zTa6t7}7#Y&T0;rxpn*+4}I7nM;8 zxkZJsI|T!yW@rf7?T^6`9@FpMzp*e9XWT1)lCa+}$-XsR(R)oI8-=ZyDw`>CS?As! z`_oOHbn#c>g2l9)*Vlo_>#P?2uCu>o9HwtrbN~CeO9Fj?)~})vaMntFjB@1x{L$$d zUHQ&Om$uVK_SgG^)z5^cV%y^D^p~;1CLu%rYEVw5E*p2m@;jcs2gbOV_s6LkNv7ue zV0CkU&t%eTFQZJXu@S2Y`^DUP$D}L_4na_*t8)1h< zfIpZs6i%QgVy|en$MJI4&@+q&{7N#A9^(a=ewPkkP$s`qKEp<`l>YO;7)mECC#kGh z_sf^%uE3$72A@qcXS@1g&Lv7_mr1lUHynNYB4v${mOSkh0n-Z-0+p4Rm5#>m{@B1> zy(uak4=a$)&s|dYNA6dT?ww`5SBq;QQ}}7bbH%^=eeWs^Tojn z(S_GYiNx=^SoBL4{^v!1PBdY<>a`N~-L*Qa`A#w|=_OlN6sxH5OHc3qW=C#dDu#$-F=ZBt?;%su z95-9mVZ4zOj_YOG9Z@`JC&?{%U+PeCA|?T=&OJ-ewJ zKc`XzXrp$NS^dd3j|_b8kAhhkbpS!8fc83S$om|utOlypcYGIPOf#S5eC_oc+#COt zz3|%B4$1>O%lY0{1s9p3$li*wb#C7h78v2bl{W|+#<^Z=m3yQSu0lei*YF~x4bV3e zTrAyYBBnk3BVq9)zu#YYOI17i=~tXTi{vp4g!`Rb80p}|uLL5z%I6EBvikb*jI7XGR|evWW-5*RH1(poYI>|L z#h|b>U@La*u>Rh>*&u_lI!p;_vo^b-+OipBsAMH&7p(F!Ca$~k^__7EK`3CO5;{Kz zB9TATOC7TaDvg=y;l2#_5wb}BdRBe(l^mb~a5@tM(vTm2oUHeBR~@|^^m;9oK@fwo zIj7X(A7vq~(vXi*)0gnyP4V=s0#sxi<#f}K@^nw;*p#ixw1p>#8i2K6JOuT0cuJ%dSmYRiBv+uCPi8mnz=RSoL&yfx%^ z+Ukye>!cx$&9vDVO^YjK()UmSCW1i(7xWY0kS&jEo1l5e_B8Mkwh3b1Brha1BvQqG z5&kZ=1g(GuBfl&|*%#XT?Cqydv=4vey|!v+pZ(sSecf7Xa<;3h8&xQ3RPwK_YjOgS z1e_+Rq!EHDF6N_v%F}@!)m|!g{3UaEaDqdER{}!yP*~B60&vv`gt}mNA-<9UcLLgZ zb+_uSw3P+v@=oOsE>PgGP(YofI(2v^qWxDfn5ZdsTE3&*&Yv{KK7IO0Hf7pWczxKm z?CP-pdUCg|Z11#bwb;0*4XYy)PspjAyBqJ}J6kj#q@Qv?15F55b$E_fU0C&V>Ws0s zVF0CfWu?ixh=j!>aw*9LG$|Q)NB6^Mcd`B;p68w<{8LnL?$d;X+0U?C^?s z)YsLIG~KsRT_i`D7J_ai@+(pHGykjcVIwq`4+NLN)b-eOv>5WU+F80J|wEI zBl#^efF!GeC6y&dlTPSK&Pk$5#(TNv>ZWvXx-XZR%A_Buhemz*UR&PNVV_ts!v>P| z_SA-*HXsZRuuL$(RUOoRSf^*j;XWJRP-B;!a*A!(HE8#5$NrQ2)6};(++z=J++?45 z(?a|I**gzFyQ(VvfA5ypdrvQo<@J8=d;j0J&wB)&CNqCDCif)wzI)F-XPci;Ee*eJa4B)Y`CC+hc{y3was_*bg%bbWKB(M8ab;lJBOu z!D1Lcj8S*U_a5$r&z=JYK8Fu`*xPOhgu>(G&G^>?86gD#S=-U6YE1x+>EeR|_ z3oCw6Q+*63ySMDh@&Gij=&?{pU`c`*tif8FGlP2|2LH8zl7&bRUw7hYV}hQArOSdW4v=z|Ne}%Cz{fOT ze*#xpH;fUZA6ztI0AJ4nBrqsKz|4ctH$bzH?V%5jO$rpG&!KJKpCFZV+GNQo#kAQktBdR0inE~6N3zOn^^|jraA8>IL(JG2CWN;%x|mTq@3acJ@~ax z=-|D_YT>3fedVfKRA1MG0j-o%E$;z)zLBnW4a$${dtdsPM$}a4srl=4^Huk0YCNr$ zj%MvYZj`S7&ZkseQ>k3~pP%pyCe7w`$_JbEo4cOV4a2yT1vYkv~Raxx3!m^R)816ISJr1 zXyRWG9KMc)CHF7-Y|D}T(g^}5Gh2oNe+vpk)>S7EWHU*p_1czgy6r0;)9iz1sG+M{ z56oMkg{w9yk)6Y&Q>?wG3{h?_T0AqEEuMA?nJ<}Y1K-6RSOmXVd-i@_K6^%3#jL%KkO2MQ@f~V5N(b)13vVCaFJSG4_h&7Bk-j7pg>av zlS7}F?7i8_VSwcJ)A2l9NA!p`JtD4t}C5nvGHn`vxHn{Ea>CTW;_k)gfx zH4S}3=x=Y51Q9|5=tD1)bhky9@5P`FkQqyNA*ZFUo_Dggr*n0~@1Ig*V*_9ZJD?Rw z$59!?0Ei$ta@Uq6XvhU)Jl7uNrRA-uYo!!?!7-MdJQuE&h0Jsej$x(&qT4VqL;BGs z*AHOA{qY@GDrOPK)1}U~MjgNJ1byTaAJq8Ta@5uoVHSp{oXIm70CHA<3wY2kY^&G( z-?&J753AuA;)EEF2D;g}!#1`wYuwn;$|)?<(+f7~`GxD$v}20~0gg{OVjt~0ev~da zYqmCQ+N_0Z>Uhk!;L561RaB@!H5CA7k3Ekw#Y=zAO*jpILFjE%;IPKUV_AlPlu4BJ+E&kU={I3O|B-o=eu6w`m z0nL5?zWUgShv~-GuS2L+=qo?HACQ!%N9M2AxRPSE_91i;N__}NYf{#rY=+&AKffME z8lIP@T(rz?Gz<&R6bxXE)d9{~2!k9r(*tuycUtQixMj&c4K2u5HfizQDUf^;Zs(k= z0E`&aF!{Wy?V$$e@9K8t4J~KZ|laIiNp=C5+A*%;m zAu3c`P^@Bvhk=>}dS=T|;IB;qyNV1(vKfCp9c`Ms*HG=Z_xLb*Uv=Hx`rdUok8bTFBWD$HjB%~Dq{7FCW5 zpaR}E*f1Yw0eTuyc9u2)7no$nXxZ1mW;5Az^m_*?0eH65wfIRE85zX&k@7(3xd_T6Iqk% zc5yu!G#q)r6xDSlb>~B`X?thAl7)pqk@T}n0hS7|tQcrEV>zmat|=6?;e^=aBj=l; zofWtkXu-12f%T4$GH@_(E#NH)xNPScSwS@T2~ZR|{ke=wa35XtY1GgPU3|$o);@Lf zeNXAbN6qBf0fTyRQ>9t~Ajop!z6xU9dSQLNzIWzPI%vO%TD7rGqp<4O0_MgIti}`< z>6HbGbn8>EY01(RfcH{>UXEhjO}gpkoAvP3U)PMiCo{&!=(goMG`y@tzj$b&7S#3V z#RbbXsouQg^3*?#;pZVxUr)PXJ?iM0l-Tcqg{+^k1dZg10sVU1JnqR^TQst z?RG%OK*xhB1S~WA`*8>VwAC&KKJ22roE$V50@T_8LCGQno3v*8dfofbQ#$m0`)d5? za!o3RIhgz(cyYek8AMY?RG~F>s<^L18_;};va?i+M)1Ps?V1cT&Zwpkr)ivss z^>x~(x&+~7tqTyrwQVvki1p}=jhi%vc%K6Xm1=fgj<&V7>)ti%R7uRwkm5pslciNQ z1G!&2VYFsp(J6${dRm(FuQ%SIal}7VSZH)+V>CmB-I;6Bn z8|s_%B>kIGJvdl*+z(raN&q%%w`~SQrL`aZID$aDW~9_h8&_&ccb2AA*B~g(CTM5~ zmaRL8yXb7!A;ZhCNEIL`QrfU%yPjOxs*yE=h@G_NlR-m!nC$qQ-)@?0n?9^14#aI? z_?4Cy5*HCyYfGn=t=z2fQ%0(wpbQ|?q5N_*VE1|b+(SGK_(;$IahjcQ=>|mY)6!qGU?McwalV4 zb1nmQL!1p@E00*l1~SRE!J{)vP?|6zY;5gNI!W+1mX#i?5=-jqHK!(DgN70>f=y<5 zQ=eW~zE)F)R|R?KN#F56t=w-tmZG7##2R+C=%r;FrHauSMj&|~fzd}y8lj_(I!ts= zw>pnALRB4FV8BzhwL z8*Ls#JG%NbvwVn_ZD`VscifNlah=YXb3g#DzkiFCmiE3<(RT~ZlT`X+^oXvZ0$F3G_pO0vRkN%M7frBcWTMX71{?NR6S@2 z=(SsAD97zPHtEV67HIUy5r9C35C9h_tWC^2V|a?&u$r|%nZE;N~ zE82Ni+>9+jdnyR>BiikNkO!=XYZ$UHZ9xA1X3Z>&N^k}NcS*DdigxgsAq!)aqwLsp zXmfHr8x0QO)6=|3_hH7&E-u%<-TbKLzqw3dL7`)1+n*jGWWgsg(q3e*dF$^}c;ZX;4*#@(KVTO%3`S z!0Gyj-_#ASuGYSoS4Hq$bQcO~l!LOm)YQ_dvk#b{Yfd^^FDzW6t8aZ!9UbjD>(G64 z%1Lwd;3LmyW8G$b@T8+O72u< z;nP)9Ri^T?GIh3hXv^l!diaIq`r4h(Y5JflXqHk_Bc|V}gLLKx=4i;ET9x1nPa}vL z8+Yi<)ph#O9WSb`u`LMX{~8Ou6C{Nv*#wW_{t zAp)7;`$$OnuP3w;CiiF7uhQp^JU}NNdx%=G_}p~+ld5appkm5wY;M@9y@%B5I~N?U ziK7Oo0#M=%q|G}T^~Rz#`tFSnh4`KVl%E&ZZPc$mf2Jmk8>f5jc~J9TeO0%8>l4bU zs?nRPh^@NnT7CZ1lTmE4^z4%Dy5!miG<8r3fFO;vshz&rm52q0Pe}mh41is03KwEL zUj?|sR@QAqMorR*#~h$hSTiciD+w6x(}u0}dgg^U^p!iG)RgjaCfzJ8X=&4qmz)|D zt6%*52AzAsY%CpPHMqJOD_oy0+O$=7Kl+Mpe(p`cOrFj?dOv;W$m#SA0Eb26OBa7Y z7hxHDYq`=>;rrt#8)6=U>-V#D5ktP7=gP zE#2OxA6|5lMh_pPYp%OZLkg4n>iKh(S6Z$=zP?`fJo=o?*b#~4zk_?e_~WMrci1m(yh|+&J3>ni z*T5bKje&$%#`5tf7!)@WP~D2Ps6CO=(j84WEb=sZ;yzGW+JFl-7CQo&f%LNo&|AJCw3?yzD zljXe4b?R%we3Ff6lEJHujXM9R8L9$SFW%az?al2fLv@)sc{FC#Y*nH8tm!RKC8r-S zelUY5Pb0s0p-M&$)p9bJnQdt*ftn&V2<(BFe6j?)BQIhdd?z3T-{E0(5JC3X45A5}Rq z0k3WD)Vx>MDGyLLk$%j0-*i$Tac?)*EZ_K`CChXajDuL$I(;nL3%+ z4lEN`9n#%(nl!prM@}83Y2!vJ@2cPG*9*6ym^E-ujuS*&!8)ZVR!g>S(mzZesxK28 zlVoE4<%0|L(&{ZL%`edoEFT{jou_~N(kE3^QlJ%Ed-UcTYsfr}Y0B6k`uOZws;#Ql zaX-9W2hmqym6|?gXpm7I2auh1>d_iKY!FnW%0SCf%p*HAe$41_{l!b)#7ESvf|8Vo z8dMvW3A?eFz~-Arq5t!_{gp$p}J z1dFVYp~f6x_gjPwA~^>Z)Ha?$DK4!X7sBlB2vR$QBO|!e$mo1Z5WKbG4gL0?KZ&Pd zn11*45?%SLdHVdhvzU(zeSHCd5DIgs^xfU2<^(j!OQ|Z?f$V9Gnpmc}vrpCZ@gw!x zhDP1>^c&inVE@6(ZS~@glNLd)y6=xi;yoxfl^u+bz(#8SVbub;QY z^~K*jjA^_<|9Z;%bs!+HNft+ilTYgtw%vF3nccHV!nQK-XeYE-|kjbV9-u|>!iuF zd4`TYY?cmt;E!6peXBmQ_fXB9J3IK$Fa6hBbn}As+&}jRsQS=^N?rNI({#t{9h^HxD*5K7#UzOjjbM{f4b#Gwc)z`(Ao}l9ooT|$%I#o-*aida9 zQj?M?ee|r86a!d%`&xMa_b;fBROlp=#<)bces=ih@3s&P#;fiF0VOr8{-#A+zntiZNICi#v^2W`~=MKJ(^l-=Ut>3&{=j}5@U-uFz#4?hhnSO9UG@6ZhtE?5An2NVU)Gn9H8IldoiWr&?BA1@o}?qDPu7j+ z9Hw)wxUQKm!9*(oNAvW<@=bjw9YwmF2`r-Uw(F%e)8C2+)M>Z_O$50@+|%I zvh#J?smEv~p<3UeuNcN8zzZfU#Vc#{wIAJ~8y{b)%AB;e_tfjnn7}6EEuVC!f(De)M_OwRPwp|K$cfvxfBjin#Vg_H74{oc+;HDh>$x!Oc(W@>?G# zh&W#{=uiU~`t_I3(lLik)|E{yy7V{qD=*QaUaa6&&88o6pq_nYx$gPtomx(&S2F-` zI5m5^5VRo!FFX|sG+RnMtMpHsfHDkJSaXbJ3??GQ)gZQ)xF(X^wQ$Q8ee3KKHRtd{ z^a3E}itGQNkyCJ2_A7~wLMn|@%MKuvX6%(Qk1SZaQD6D|QTq7YBLZ0R^Ki!A0)Wps zm;XXdUD+Cm<&WSWCWE#h|2v4q>gHJ)iFM%?Gq|l7RH?fkdqL;__kEH)IrN>$1+Pd{e#J^`6tP4D-u_IEM>}`FcaMYJYIERYSY;k|j=~fX zE<9XkML3(mZm|(nrMlpPGxYHbKdf^vI$sx_k3c&9Py(vsy77V6^vj1{CUCfvLFlY5 z4}2>Ies|sj`xxk85#53IdBv^IXez$>DdjnuOgzD_@vGl*&r@Oi9JTK_rStMth4pCK z_z__+U;VS&^wx`uRnSqda?GDY0cc-4?^ex!@nwSFa&_FaQ3%WJXdd=5^T$XXL~g!u z+>n{VwMgvhv$@Cu$z%1E#hdk!Z~eQb6YxB`IEP6A-}swLF`YN7yfCKfqJ-8qHfz>C z6I7F*)F1ABLN{OWkcM^dP<7`HjmT=(?Z0?M_uY0E42&fRU$lcaH`kMr%=g-w5`FfF z2^x}aP+7WNn~5b_R@Y4C9YN#t%ck-u@DKQg5NCGctexARe%rY}^C?4t|1AZA$sQ2o zzs`VaXEK^rnXhmB{w00*pMRrY-203cuW!)g(SvlsImhWoUphx4h_UHn%!W)!EE=BD zmg3&{(ogOnkhE7bDvLEGpUEF9^4u%$)P}n48dqDUbB>s(g@0VFlV*+8P~6w^7q8Y8 z=iQ>gOz0gH#>*oP=*2fz>bmRi4sE_~?_q&Q^N9=Gv~7#Vl;`SKmw#Nh-uz`<|HF&* z*;5YCAOARypjB!3@KP)Qh~l1T5(+#{fb1EyDSi1LKB`i{$t{ns(52Tsh=n%~gK=DK z9UTORkI?9`W3`H!HDCJFZ#B4^egHf=iT%-z9lGd>Uxcz5`-~f|X+vuz;#53qS{Zy9 zi}Wd<`IVj^dv;wXF0X8g^)VTD10qcmhiyB8*fERFqD!VbxGuD2g15!M{A{`87^Rgv z>U7l1F&YfOd-bK)^^=SLRgbxR{#QUs>wO&toQCp$?7r%Qw?!$Vm*|LLdv(`Z8EP~1#*KNSM*BG)7owuXPT)nw`lOB9& zksf_+zMgt*nU+#du7+`V^*^4Yy=#gX@1B9^V$_XbnQL*DFwe*{pP%u(mzV4O%WnoK zmSV9Nb)a&g#Y)ojDb`yO*C^0vr?qP4z3}3kP^{B)3!CRsE8}~@<}trpZA1((C~beB z77oJ9pa_>YmK3ZkfD2F1Tbnv{-%HEXh;<_$(_>d_gX%EtE&{PXu%uqY05mydb;NDu zV4!;_1UCbSrD=Bl~>-7BlNPdDs_YAomOu_wP^7QHBx7zn4suMgNLebV~=Vp zYlHB(;H;zdu~QC32oUT@23jvDzU>P=8cJ}VuQPu9cxnB8K}cBSBpH)-@mVvoWyo6& zLZrB_MfKiIJrHk=jhz}=lEhj=eGDdrP^Scz=ptsKpsZNEq{BPPvS!H8pamZ|bG+_< z;vb1KV5p-FxaLR8KV>sfa2(qZ3el;sNRKbA)BR7st~rNJ*FSyobbac~WAzGgM~}U} zTDQEik>E$NR=DppesG(}Eg!-%2BDRKH;V<|U1rNr;Qt>5VyW+$G8*Gt>2CKnTbP3L{bx-npsC z(n^irs|pwVT3vVA{yP2S6XCxc()y7r@XFi+##*Hcaf`X6z2%y5oB|$VMwkl$M&JJW zr5ZVSu&#S#71am{1d@OL5EQQ2E zjjYWhIb}28OKPF%9c_K8s-$8v6L2p;%mK^Y{Xik#bRiLhhm6skQUz8JW6rk2?L;3) zFClP!2k}ug#C7sqD2RLa3m4-y>*aUkAhOVpIh#62{=KNAT+@e+&};Ka7C~N_8cP9B z8d5=gPL8s=x_Ac8qH^suq!uza3SbA}xG$U$t*^jW0w>ihN(=>b9k>ZW z8z&tz6d_}5xHy$a6-~uRWe*w?pd#79z-q^uWIwV&ikHv85`{4Fz|X6wV!-7_%!B%1 zjUov{u0sP^vaVI@x0A1dF!2h+*1UQEZruPd_rinItQNj|)MAr$Fkl#}IfdHLmxEtB z67THxFpM5Z~Od|&AkOTMCVZ4r8vPECL`W9^`4#IH>){>l}?=93G3ZF7>84A2d z6rj*3gBKpoqm~S7VZl{-jM*-LkxTZ>9AB>9wq{-Nn@5;SJ9XKGr)k`%S~4AnYT>dq zoNM(PwqVScqO=$YxTs93JHbQ_e-R63j`LBj^`%6`+q|F0q**a+B;%aad-EuhzIole z_~OPUE!v37f-JAI$JXk^4zO35(KFt_igK{xLv&IfXv7wd@0M0VT z+Pt^+WC zY=tKqdb{E?fjLM~Pf!LvxDx#Loh$8yQz0kKf790n)J0a!8_1m?Q z467>Q7}xYLfv0h=(cNzDwH=zf0#R7FvBEOlmgRKLgVz*`o_s|YF zlL+Xhu95?ZvykCsgKC2ONg~%=x6KxOXYJ14KrN)rO?Z@i?|>=GE6z!Cu50-i0L2Is zNC6h&D8lX$#G(K02^%yGveqB^pLO)t7BZATTZj1TZ|lh_JnPW?G-m9G;HEnI=z|H& zKX{;-Ff()`|M!_Niq}Qd7m{B1+Ap!Z@jSTRa4cGR!#rQP&QFqz-gUbDp_epm>fRbV zwnk$H4b__)>*=&=BD4-#zbmtQi=^0q9XU zLv#;e6f>sX57)?xMs;X%w|(3FfRM*1qcxcL2m(tYpu)m>W?Tlo#f&Sw&MM7Q3%qYe zjrZm8umK1RqIL#`P0t?s!B^_`*bGW6U1A6W&>{k#_lytKfV3|-7s$>8Vp$|_^(|!EuR2Rr{s4cV8+-N zPv#18C-l|*FiMY7{|5v^98HQxM-X8Vu@MvNAb?c~LZu0le-B#PUp)0z z2*NvNO0_5LPoj}qYn767F_e-#vMnGfCm?|}5LFz5&pkgr- z3cTFiQl}ApO&Uw#J5R9dcJMwaM+=Dena%gDbu8m?(2q3pl)dzW+2PGAXV@AegpL3$eyr@{S!1yz zeC=Z&(CJtFhPkv|`w%G3-33~-(*7%(HfSb^9z&^Qyu1dN*wPI;0${g(?Rw2V>00eI zXN0ffsh7!@8bZ`t>f!n1=9H-xxtxV1J5ud=Tl6Pcq^X&rpEf9e3q0{hjv}C zHjg=>oRAL3jTvC3d03sH>-2;%zmB_%)A8m;X6M@~C#Fr*Hw~Oa((C+14 zTt6tmI0^F{b6yl}8uig&&a}32>oN|z`?mW5p)k}uFkMNL$H$v3IIJ#)R>2@=m$idr z3g;FM`YcjV9p&O79Aqlzd1&<-P++;SsProcCX;XZQ8Y;9_2)Q@j{jRUwC z!OQ0zGegJDKAc~r=U6W&zhx_$ORrv7vPS#Pnyw2!c9J%?{<|J|asiDXl?;5ycB!6> zAHNdK$Uy^^R%nCn6)tf6>`{J!cZ7Wajc(j(=yfo5WCqP5INW{cV}Hmv!+HfP@IB-u z_>RazNa(ditEpj<(ve3Vq))GD(9eixBDex=F;3zfG@;U-8yfTChlFP+ZSxqNt?(ZV=07h{P-k& z{f2v`?e%CzXjP4HC+@2w#+CyZu)C1vy#q^!EhV{pR-%)B(LS=p>HO!Oa(J+$I%FwG z8Ya2{tFMcrQny1N`quTjoj~6?Gso$MFMdGBeg964?`bFQxls45*b$N#reRgO;mZWq z{^}0(E~PI8SOQv*TG?GXXzB#+)77NmNhZ*2W=T(+2_{5e)j_>1%n>XsrKDs(OBLxG zZ+%#w`}Bu&{6XXO`1d}kJMMc-Pc7a+W*8+FaitwWy8bbHzfWg<=t!;JK&9mG->4^E zeN*SuAFi1bN9r42ou#i+ZiFI291mR@h)t?4)=`s2YBM0P6Eje*1sihNuKxmLRSN5z zC2s&e$SMaQM=%wdx|0ta>K{KmM^&o`^FD4OX0`Xu! zyy6&r{`!Y_9==5^SS`pxisHU+65t4h5BnI`b}|irczFR-qN)K9WT7F$EXqNLD9Khf zEpd4T%Lr#McVq)7tXMix#c?z)yy&Xc1{jVJ0%DLjlh9l1>hnZp?L?FnD4`L9d;d-I|;KDpXjpt&ivAccLThG@f0A31v6CG_D%A;XEYxc z>euz}3j{DoWG>uOHqYm~)n@ag$8i_hj#=KHT{px<-zgvw?zIjTuZI8opJ%m?(DlV%WK)I@e1frn(m6jzmN390v&{pt^DqEOrT zQB(8}=Nzq1&OMOZZzXuTRmDF(Q&Y!}4FdkHMT>|{fE7a@VJn1#g-K@1P~g3$fHhdJ zD^-*zBpQbNe^#`g{ z=W8#nb;Z?p=|^Avn9d}->agjgpx4tEvZ``Py)UBXSAD!x-}@~!#+EGx7$I!Tt8BSO zAYCmeS}0Bw;d3}aH$llWX!8e8%*RWXjiPs)4%>UQW={GfsqI^^E_H@DoouQ;=TuS; zh<2WNh17ORXDn?^=$hX>sV`r6qWm9^#F1h*R9!(WjHXe~-pe zr>z64d^fHeSGLXv2=$Pqm&ICf(Rzp|etE$$MGPee03PDRK5hW)E?r-zgC-Q}%V!;- zvk#p}rTrZJ==P_ymc>ZFd*kD}oH|M8pLK#xe!t}!Y48+bEOho7u}KYN+J5fJd$8C6 z%!o1S!+PR-$hAd?rG;XIBXlt)j0Zfn){xm7AsZjX%V+{1#o!4*c7jV1F!pR&a`D47 zR=Zwm6uFYL%eQ2cSv;Mko5I-u6f2`n`QH$$WDHQqmzG@HZP<`(4a@J=Jc6cw`PmaR zW86r6YyBFE*tU`7N053^nTl%$YcMt6RsnFY``xqJn}ir!8MB?X#%9Y-c36!7%NDft zQ?^ymnSOa($+elXP^g{Rmcsq#snF}gIV>cLI3zE<5x7`j1 z8T>>+#nD4FxG^-!0bOtH$)nBVC=G6KMx~V@TSM-Yu&~j`pAdoXaYspa)%Blivy-aLq=9<$2(PDJdQ*E1 ztiV?2rAv=I{)+B;@+FoCA#^eX7Q#RXa&M+Nm+jwzDB!c7iC>v5 zLxKN01+35F^axeZ_o681b8oOL!H6L`XvS!QeW^%{v?n&1v7gdQ8ya*snMpr=;#JM4 zDA#KQtlE9-?G-X<9woj0qEDWp!ISo3B7yhOp69LIp=)n`QonooElsSfR5KYiBLOjg z#HIDQul|^H@sl-u$}pAGR%tNSfNuB?HA-ujz&|8p6yREp14_R8)8FdCk9<($CJZH; zlM40l`&KLgH~jQAiXzBIvpU=|> zTq-Ai@JM~}Mgqaf1l_!&MHgRoH30BL?Z59>3=4x)LqE)Mu1K_EEy@d3oiSPR`FToZh5q@@m$ZP)vJ)sNa^TFpl+P;j`6y?0vvT9!F4lZLMnD5d?wDfNY$ie@>f05kgYi`^b_F8_IQ8Rs{(&acv{O`<1l~j3MI5P)HN( zYwSs|F53=mZvj+>_)kJDkhxB+cVM~eE+tWBHzJoeb|kb6S-u5X-pVmfe;+|H$0uJ} zsHTCXl&9YQaZlhXS3EUjkF*@`tkE8Ac?sjV$6 z(oN8`=LC7pNNC_%dg){#?Ig5rdlN&=Nj1zpD9~YDJNjjBM_3S;u^dTiW;vt6Jz&ck zJ7v~?bEo#(f-oV5C;k+E#?Epk#7PH6en=jW2e}tN+*KyI;Il;#xIbXu5MN`)bMUdV zOV(`1UJ7!bNUC}tKI625$N1eq$b%p|xS_aLfRKICD{S`W{s)y;z(A}D-&Lo3fA$3> zN=o##?_aN<-S;A9*IEsySXMdKpZTk{DBiI{lc?>{Nqr&*7^aCk@&b8A*vqKYjA}(K zky0HrVpyQv{7qZbieRikAXdWAju#+gK@@w1VM{bQzYS%si~1Tdt!I#9p3*q#ikP3% zSfy6%Xd@1?FqDcX12>neV_)A&8yQ#jZzVT zl$$oK(F%YQYKkW0TSIWA?H;W}Sa_=f%uT5-*P7-ItwtLW8ptFnvf6~|B{qV4%)&B^ zr~oa)d4@$hH4L*@X3J3E{|5!I+A@J;;b!T>wc@2;)_JUwKrjf)#+1r3g8!xGJ(;o` zLjkcZS%48gMwBz|L?oosy? zR$Yi(!9~OVJb*(p;Aw^X0+;PoRjBdA0&T()Gk+5ixF|{EE3gTm^w}ElCX+NXd03jF z0-)AOAg$dwNdm(O6Ap6F_gX-_P+cn^%JqbZvl&ajhmsz@vZ-C`wqOruaxXx3c&QG{ z2^$}5f8PLz^Ri?te5eUjcdo^{n_xS*+I**dG&R`>Z`xCn`-8bOM@3teU* zym|qly=3k6HP>-1I>rK|WlHv`E%vOy@zBDN;K;$z-cE zsfnvfiu4+~TEea&l%kV%2A5@%{6btD&9}0Q%m(JI8mf4^D5v9$y2!M%wL$E)CIrCRZ5+y9rGUwi>4=nh0{Qf zOg%apd4&AT-d(46J0OI?74YLsD<`p9V`RvH@?E*pS!7<64`V5e7-d{|6?X^p*^1PK z@80Q|ahS>zyGzFx;+u}y-Gr9VN}EOL7X9I>FOY{>perZ>cJ*`1Sks0zbzq1NgkmD6 z7=dFmFG2-Jx5vF5TD@3k+OZH7aGh*^>t@)oPAffhYAK`5?mGC*LEcHO5wbG?X@abOBEhzyQszMDEW z4)D!34--7yK~|-ewjx~O^VV+Bzh86=KxmHs{h3ud|EIU(`l5&)%3eD~>IyOY=D-W> zA#Q}I5+*1wfawCPzD^2R5Ef8&f(3kQ-l%pK7rfXGr068R&_TcnT-eUkOftc@p}AYZ z%0UJtaF>S+DR{(I>mK^WUI1N^pjhTgCa7Kjl)($qL_O5`Da3`8Pi$i=SyEO$van#p zdRqz7E(tF3Jm}C(|C_1tl(h8Zgm@JfO2d z_JzKB;Bnz)K zRt``I77=RybTFB_u&w1pDp3TbkTU>ByO(m(STB6P0NX804LpMztIJTExeW;3x=w?6bja5)t*F}Gz` zGOy$YPzJ%cCx=})h6td@*z_~)W~?~iIR%L9BU3H70)r>(UssicT%mIla)u? zalnI>;dc6y-`B=HF*Pt=J^y6`h&=~dV*9nL$m?h(@%wuNgd#u2|6L~SGA%gr-*E$e zjBskOPT0I?Msx8&#}KAqT3aXr;)M}h8^Z(479^iz%Zb7|d&`y61%G`f` zMo>gUz{h7)onv%mP4wntvtz4+?%1|%+g8U;I_}uEZQHhO-Pp;EChvdN%$oUj*1G3b z)v2m=>g>Ir{o9T^e%+!nk0)NtJIv@WJIci4VJz|mFDM zAtzCK6r<>9j@{O##PD3RN;aKgpoxD#pj@d}wPMvL^UJbTEa6E|1QayF@x`2sL}8+X zb8M;@`Hy=kUt2>B!+Xz<=Pj7}_@;_FT@%#{XYsd{8P2QR0zzEjSz$_M)$0&%_+&nad~AON#jVt~OqS=h-2;A{LFix9d&R z>!B^74{h_6;$KHUe}@V?sSidK1 z&M}PQB2LgCOV0OAV3SbjknL&zoRho|s8_WaPxRBRy{2n3o7;C$Vo??(ji2<~9S|Ca z&%7p^H$X{{69S^@rp+*8E-(nC2@?rRx3~F{eYQyrQ3!~-nL&6Zco-0f>utA9?(9$8 zwLOd&iXyBzb7un57~#3aOk$W@KoFa`g4L#K`S=(_SBLzKSG8uJ>|F)_F=?>{>AHlRp{*76BtOMUSi-*)0Ota20FZ2ulqG3zw zYuM*aWd-vNGkvcHhsuVbA~=hEVJ$t89e&mKF64SHW5Y*$T z8Obj}k-u<2_uh+}PV9e)3G(|PErUx9omq_8Xk=4rF?Z8EBgh?Ncy?y=Cvu?2&_Ek% zwmXCU=FUSfjbS0!{zk1<>{a`xSAT~oq&I4!*J;z(se=W*OzVXccd=@2Ilt3X zEqxfS>kYrgM8B#9ye7_}gZs8!&JNjK2ZiXn8-c`=rjc9z$C?llH1#dB{|$gl^y?t*rKWBOoaD z*Qabde-}>}zJ?VeS&bjUrtKhi=jrW)we$9FoQ3o`bHCseE4ndah`v~B@66gE6~>dg z_#>gOk!wKSIGVq>4>*A6SraL|X5V4yS+CbaPZa!SB;B$7(&%OV#(Fs~Mg4){_+As8 zO`(aupxYl`&7!i9bT=5EE0@e=bN!FL5ds!T@e30f!Rx<; zX~N%!K!rlD4vyZkD*inhWO-2TewI}vxM?^gZW#P{?VbM7nh9NeUhhu&f310-&Sw4} z764tge*-l>!i5$hX0lIVc+jqaNF{YRmrERqPj7721kNuYokRvFi*UemDi{?#NG{6t z#U$S9f;a91Rs-$MR9$tgwchmVpPhq|I7>d^0Nt?v87^VS!uhQ?4z+$+Pzo7nZO}OG{xXH|`=}=7L1iSkcN< zS&G#OU+2G0=KXi`4WW`juHLj>Q$#j#%%tlBg};IfQ^+BSP+um5#TkG5_(0e2Xb4?iz9Q>C|yw z8xdXJLHL5&H`)FkFgz6sN15MM1bTQt0+cI~_s-+z6{$d}J`0I|XR;Io15}u)Av$bv z0I%P9Ph2+k5TxkP;g&gl0+uZ|{Mq&UL(7%ZF%Spt;tZW3MJzp>9|zE>JpZB%6W7d3 z^&Mo6&Fk$b7GRMVXKbXx&~sX7$S-kNrT#|8Y#r;L1nEM+wE5#ibdzg#GNeFWd@GT$ znZOAA2;$$L)n6BUMMr?3U+QmPZ_7+QX8$#%9|-n^t9s~E>K#K1v$|5gVAhRH!H^#l^8-RNJ;OKhrY)jm-p1fuk3IgBipwa`M>#(%@YU# z`yTZkIt+0s(KmFYNON|B(W8S4;ZAA1W7LdU%UnGL(7gNsjnH_W;D|+HRE+ok{O>)A zYWHPTPfc55u%QkLm3g9bdxdD735ENO9kA}_wWbRNBia?IV=~=(XI2o)&pAP6O!^n% ze{bCX*7bXr>n4IN+96laaxAY5N9mapF@$?T?IgA6eminmyV0OTQK&q3l3>%$z7tUX zZ^vFtkof!iP3$|-07OH&@4>DI>lkxG&&bW9p)xDDp3J1l|KEH6yQn=^^gnyEMLFEQ z9RI9!Q?MsKcq8a=Es7CKzS^&jp>iWHHwDK3@2U82PI~n-z~b0X=-U9*tR>g`0;3RH zO)yU>Jo}T3|6jW|If}hbz-rc-F9MLfugKUmpa1{oXYl}Cc!)IL@0SWYuBcxd?5+J` z-=rxs`YPG48-B;*uZK56$;L@pbE+FGguXp)0E!l$xR(WtCvqi87m8hwVakjPQEk)tQqAjgxsOZD+zy?Lhde{sA# z&e)!YmQZIFdh3!I$GVZKCq|3AENuR$?V84D-@_Pl-(?on7-Fa z>5t1sjc0H7JF$F%XI@b3jRrpC*0pm<-vHv?yetM}cH}`{A5i z%V5(OKY);ms~hx9FE(+<#=6`j+}z^2=!xS(wOTSkzt=8e$P^k9Bp+RrZ4-S^m=uwZkDae2+WVSC=!Ha2p$_;dDhNCV7CF8t=KB%$c%Zu7!hHkkawASyEM zk9WF6Q+6*La_|R`1>H$EWw?8|#~7^Oq#TjElb_R;yZ!We8&`HLL`3C5w&gSIiT1L^ zRvze4OO1AVr)NV?f%wA#R{`1wfW6$>=gVoYAE$nsAN(et7qI9zVPVh?dv%BQgfJ?l z(AYzJCyAgCx$AFJnvzcwaG~PL`hzpaUl+s-`-Yk6G41tt`OKS0O#MRh2Dx}3i7`^^?0+G}BlKekNoeMCBcIKo^) zcJGedy!E#64QsbrUr_?BA&13NOGvXBPDFhEnFMp9a+(HL=9v3@IG|eWf0~)PK)0nj ze65-99(n30;(VbatTnn^ZB>8XYX-s)pQdqGcHkpHAcx;kcDm)xHu(JiZTxX^?Dp zg-jc2t?lq8N2-C|7c7BRpnsLlPSl^0l}z9l z-O3`JE&u+VmM2soFn~KedaU#M6P+Q)b8}$rCgwF@ufN-X#E6CxlyQ3pJdDxrsF3?5 zLkRYkBZA^jjInm0mzOQ*ln~TmIdgL8!)d?P2JC7bje$*{8vzxQ?y>GF0}{*~)q@4A zM6Jsp$Ry99>tv2vP`$;5IIf7sbdZxp4YGpC_S3P~jmI`Awe;Y^F~2X|$g32nwS&xy zjPy1bGL*lm9!7HcUxzA?@%}W_7LjXz{%F=O;1N{d{sCX;)2p4o1h?Q_tNbj=zhLV} z0lep=4%ijMyF~&M<{KtIXif_x)~Ww;8~rHJSHI<_IJ1)+Am}t=7gFJxrhx-f!%)&) zFf7b}egv2)JLF)62x~k!*2loq5QA_|8U6h*bF~h!E6_){U0ePM&%yEwMBZM$Z8tqiK=dFBZtPllOK4&=gCa#-LvgI>F@u~0zC@@_t~B={%JEFQtt(2IRZYa-m5%ao_7dvaO-~+#Mt=MR6 zc4zk5A!)ReNO!60;n=r*X|lOQv6sx%;6eOg-HX)sA@%tLCN{UT_uO@D)%F-Q!{Gfj zl|@RL%dmD(!`PeRjY~Dv>bT*RC&%%W+PM#_Yux;0iAFCO1H^K!V%Fyx7ZTgn?Ht%b- zmib|d(!{YVbDNF4O+0X5RMcW<*zKPY_!m&c?|f{0kC3#8vfA|tXVQ@%kbnr?B=(ws z>m~jjo~~{dI*{iJb4=20*j6l=>}8X(HRr$2j2<+&3s(WEmw8ke?gQ<~eHeo8x>Kys zyi+zY3_$@2zoR&xClub=# zdKp?BER~(<*Mmfb4X8|<5HPnbCFH565yrgh%j@~Hvb4DBiq-DXQ|FkQFpNQ#KP6BO zHY1u^`GRav0x{KKOsx|I8E_SDwlcCDG3U3vSLVz>u{0wQ3XS%7zWO~n`@3GqN`mh> zXI5^jA%Y~K(?xd30+4L~E`_}9Nyy{#ZJ%h51EuCtK6SGlK=@pV($kAoiEuqyt82!( zv<{wX_Siv^AnP+CvIS83_#$|(3R+4-!QBX4O}C!};M`T*MQ#8@&rn0n-KjZFicCu0 z?E33c=)>^4yihM=d(SqLO;7}VToCrFO_!Jn8q)I@@;LanEAIUD7eKe&9|vnrT~(Bs zgO9eb^-4x(AUAtJM)W+60}eqv*l%vDc6$p!aHQ{SDJ}mT$MM#;Kx!A6&#A30Xb6KCVz*GLc=!@_jorc=Bqv(G>OL;X^#r#slNlb{S3~k>x52B4{wF;IHO0~MYT(-0oo7;f)h_r(7mXuO8pJ}s% zc^K-RbEP+eM*6mr=n+< zz245%^lPiiu}y#gxVW@Xp74xQyiP*)@Su&?=&PI+pSq2RTRDU@h&Jf3HROW^^9z24 z#o*#{>N%v-!`vQ$;jbxmm~uo}7zh$LJ2q^8liz%8>OZn0@YOx`2#-Mg9cz8AA{YNQ zt5a0@Lt-dsh!$<3O)?$X7zm*{qJD?~qV{poeCjq?{W+DGE9!qk{|3!l#iL;w5dC~a z7PXZ@xKM?Urar=}QJc6O5_>MuoA;)@-OVk$rtGXK5?mqJ^_z6lYG3-Q)3!8>e0x->*Z2Y7&AG#g~}G)7{e8Xk}{6 zJaQl>B&Z~q_wOE#r88{TT0jVw!GwJ{pVsSX7 zwCAI*YtL|!RMjuN_ILhAG)1F; zdE}t?Axx+q8kIl1MaD^*OS8EL6iCaaZ?X%ma|0^6sz^O*b$KIvWL8YW9nx z8XZr+&KGV2tsndEY+*KZXwPgGSj8_!9MM$2&M6IWPpgEeo zhMGbeW*9exZr&4w= zu>~lTCzX*g%ZS6qkbXtEora|iGAl$GnaeI}HI$Hn z<{IgY&=w82&~_JGyUJ@c$T?kBf)s|u{Q=Ls{?KIGa;kv^2A)k$L-5z1zR#LH;GE4E zU)m@1Wa0!l5{n(%#^m{XZ1SvTP${q^hZ7JhsXkNBImfCas!(ztfjs_AHXo~ zwbjaHMN|KFJKvZP@EE3sAmLTAZ7$hYu2qkmbmhHaRV#Wh9`GnIwLvtG-&V$IrLTm$OF?O&Vv11PXZ#v?;4G4D8DcWU*dnK_pPB9v-IX>UQoT z^!Ciw)9X+@QXN=Ib?v#tjWjBVtl7pnXdFQpoQ(S1QZ{G-7g9usS8>#RZ{XTqWul1z~nbQ@!SYRN~K(L%JS@=Cz9*l&sQ1$NB7h$?uZc{nl~v zc-fINq(-Q&$Ai&}RxgzW#r4qVPkWp@c~xz|`40raV3>F)8E2ARGAO1>Z<|K!a$Y*V zYB>r8Y2;wOer>}N=vokrA`4-KEW{q#+@KUD4b%#1qHL*EnxdTo{2blL+i1JhtFp6L z7Co7qYojEn2cA$a>p2^?{avqrtBHAp0^MoVt8p#2c#jOYpY;CxHSwj?`NpSVn=bPq!XXhf- zSrj*G<_!jm3{O4K0YQO`tkO^~U|XzOK%NHXPQUNY;VLCol&IOQV8qZYHkwEUO8d7E?A!COFA~Qr1>}N2rawPxIr{;{>31l@Li{|7WlB9{Mdf`KH&1cxkhNa z-rPiP5+t|k*ZRb5QH-=|pULNUbd64p4MBXWYS*rK_6^8+Y9N{;x!zeBK%0Q=9NSql zF8o09>Dm4ov<4osx>5dfJ6| zJnWJvl2%I5il&k)atDKao#OtpdUkLizfqkgQKPqlu)Sf1fBErBO_;;ECF&}CLc4v| zzBQlgKUs+_2)#YpFzNNmZ69r=exl)O>E_1ID-rxT{Pg@Hc{_uar&;b6P3=H!?eb4} zzp#P8{{q2ww02A_^#UQ-N}bHI$jAyDOC8(Fpk;OpN~Hw2Xm6;@QQ7Xy1>x{jH)UP= z(ALsL`)O)#t?9}rIz82KMO%i^Xn4R`KAR_wh&dw>4_6_Ak7JO!Qb~` zA9wPAkU%7TG#s?sQy5c@=&jv{Xj6Z_ugt$u$1WEcBx9)Um#_7C9mbeYimQ#_zC(u) zlz%L!x`0@xc{6Vy7}N|QUVyN}k^A4TZFatj=j)yrt_v_De8}K{Jj0=U*BgnWB#bjX z8uE&is-^X)so%fC&ThadE$Egrl;ycZkm9InLe|~7)037%L0}~f0z~R&T@Gup|6}Y zds9UvO&KS&+!APl_-Q=+^ek}r-1+$q39(PrjIPlt{y(ynS5dDWR1i;wSaRSlZXo+* z@~xWxnfqGtRQvIM0ys=Lxc#R0j5M%B{}a^ZpYflxMOvqu2(RUAZu_M13F$e{@g)&f zMs07PCvIbH+>SP==Hy@^-W=bMhX%*plAuFjAPe5;?=xWz52troW=)fUZ?(+PIg!E; z!Axmck!aw3{NT4ROtLNzc1?aEV(#gwnT!3oiS`Re4u%=_0o#!Fs)^op6mF@Z5?7mbJ3UyLclZ1b+4UO)U zv$wA~>KTt?ewzo|axd>Jf$& zsSD>Kl_1PWZT;HsrrJ8qt*Hkh;=>h&AP>-87!R1Q(d5{Nb^ajy4qRB*HhRwdxchAK98=` zWnj8e)@;c%haPjWY|52>u6i6E79odXC{brk`sq@Qo!@tw@Yu(1LRBGT<@V#^5$B_# zEa2iVXvawvg1f=<_4QTk&H1StYrcc-LSn2HH`HG@g?9xaM+MG>9a>Ff!9qbp75*H> zmkhm0F`f7?BXzQ*6A^(oWA@7SWK}rh@kn58e-m1ES@<%{?6L8(FW{IGNM(p5U zMQ3B|OAg@&aE~AGnDd!X994FdEq;21wNhGGDNe)(@JXNahyZ-&aVE6@^2~Q21d^@c z|Lj6P_f(E_KN%8m8fWtT8@epE->&=`+4cfiRZTkInaMosGK)`p*p?)NIMXexAXXPZ z9||!N6jcPp=z97~>Tp?_OPotg@GCDQRzQLz;DIfHYwW@Gc=GvsXA6gfJp-Ocyo6V| z)102xyq4T*9;?l}Y|YVo+4s1&Q;R%oV@*VD*m?3^$clTroMLGg+c$*1$kq~NnF4~as0`Yus?9Hu3elKvKuQ-FKavR992c4<6iZVq5M9P*CJNS6OOgJTt>dyPZCkPnF^j* zMNhAq>mo!&C(@QN12)>szw`I1^I<=pO^dR2{*&1NK@dY}OHgAmmV(paLmD>G$@y3c zJK&t1zibUUW(2ARl`cr7v0ftQb4uTNysv=ek3*Ckw|gU>*8o~NSEWR#T-NAuq2$DJ zrTBOtuq`(;77yFG<;nytsQ?^W6+EQAsc_ov16H=?x9W87KjMH#sQg$4{3u9SuD8U3 zRJ?iHm??ETaiyZ0?{xy{&AQ|=7^OPK&R{v#sMBiv)?7qofT4^}<;lM?G!AoRd9QYq z33?um1-IMZvJrUpx;GJ9;xZEFd2qMKqVQI7-u%Nk2stek47O>lhp}Qv$+l@Wq9Hv;MCJLEYZhJIV*6`&3>_ZnNC10PH%NBUq92SQjXKC+3w}&+GWg3ZV?ok z0Np|_-0DJR5zL&{Loufn$cD|*EC(`h1~M$~a~Oyl;PV%evC7W6;9_C=a;eIVr`-PC zuzEQ02*nMyUrT-%^^s}Hd!XpWxTnNlyxCUyLUOI(7E-g_dYg2qiOsq<7WcTcs1);w zNvzeLI}>7l*5;?Mt$zT`unIkDqITS{2?J)t@AAJ>Q{Rvo5@IXb-;K~9XZHNJFtQn3 zGSJagvk4O`v1Q5$@bT%q=3LwQ^TP7K*IcEOrkLx(>qu>&^f2$Q^3i-wl^bs$zCcDn!=8p$2&|jNb_E;thTE+CNq^ zdSDxxU0r12sdZF1-&nXeJ-yGc<(^c}Flvh-{V$seCpIN`V(NKmS?VZFt)V)2gR?h@ zzI{^*x@mW7w;(-@{j6Lh)#a4SY5>_ovgU#FUPts&JCLB=XHF`Kw4bfjflrtmn&Sdg zA&K~j5XS#E0-z}IcK}uGL2gvXO=rU5=315bN!4P0QpP~_Lt`3iI$yq+{>x2=fsx=T5<=}^!2a&^$;xgp2f?cS8_>x;;y{Og-+P|ze1d0b=Jn}NOYGnHLIp=gy#bx%tt z@fs5Hwnf!wY^!~5JO*$Yh&(UdvHrMgJY)Sh9)-(Osx&f#TQxu#JuhGL;!pRwO>5EZ z88*K$fyAkNw2I$#{oVk>kXF<-Q@xyUm?j|+&=8YTIZ(1t?Z$Ry+~c7zfL4k%?Hg(q zRlf8dg$SHbrY}p%a+8!SI+nphjofCWkIF`MW^IUy4qNx(->+eZg|y)|7l-lEG`*{? z0gY_vTUzpLHpFY7uGfKO6UyEhovWf7 z4okMi|>E=X5Wtd<-9EwHsUwJM(npqso{>|}ie4u@_>GYd6i z(z**))Jdna=EHZJ;6_Y%)8EYg$wqJ&CFy>UUufC7j2@;(EUgaU{Na<)*|lhF03a?+yIGgO zz0QQH{GXS6aj!3Q(1jEn`d?56)xa>est!2_`d{=}X<1W-(2K#?n;pdlCJ4ri5Dr#& zY9|IUWEV#5pkl0|uk9aYrtQG_jG{7su+Gs+`xVi9mw_$)rB_OV60~Rz5&j`rH-$Ji zt7N5GJj9x724S z5YQG@j=Tsx&7RQ#|v21Od_Bl0Lh)Z2}05ECw+VujVk1d^)OZfZ- zd^{iccWTIrBNtDmxkb(Wp56R;H}B6HH#&-GmG$3HeLAmyMWt#KTdx$>Caf3F^uLVA zrI*8!%S$IJYpaq`)$s2;viqEqUbM*Jmj^&(yaVZr1i>d*zG?cFLXg(Z3*uHyf!#i@v?HSr(yn6jl(nwV4x`l2ZFG#$;uN^Kt zP^;{^&hh1NPOPT;7F%^j4cqqx9jvgbS^7i9*~eJLxDc=Qdg^ux)-#!WY8mSZKmw(m zG4KwBt%LVD*{x1w2$&%C-}9EeThRnAT#fC}XHVRJefDy${1oo>bP8|3tC$2qrGXS7 zT|Dbq>{Opkatr6pT0T?a-3;SjivE?GaJ29*gKY1g$*nUiHb#XEg*`Sy_)9G5-AO`K z`vpp(k&P48L=nKxq&R?~)2yxC)kyZulJ|NT%zoR_m#ai&{(LD#%3{MtX9hxhLZt{$oj?M#*_goznda@?Y^~2 zQv&B~6D};Z#p@JkzwuP7jKBth2Wo(+d|J%X@U@qg%H(XaNF&#tq-m-t<6(KuyBBLD zuRDbLr9;#!KO%}~28nQj6kq#+o?9O`37+r*7Egt^HlhDidm88@3g7XsJT3Tqyfs7d zy+O8(Y_-@C6k0sMj~W_8E|VwjH6op_+8(uCm_B^IG%5G4bShaZ)X%$5*h|Uz^ZHhq zSZ}$&y$XtU&e0KfPbEW#hluP+;chm&>T1)|{IYMed)g!@X~?DM=Rco#oI3C1er6PL zalj!X3CRsB45n4u5B6|f^9IJ)i@g&*sXGevio>~wDv_|MWz ztxL(JjiHXu(Xcv&uX)c+OjD2-UstxO%8sz#TZ|tn;gSw8aJSDOu}=~0Z9<_L%)DY{ zlCTV^CA9I;O7m^a!{F88mBY3SD!PFS84m^Yy18!Icg@66**#@~Df(_bVn-mmqxRv^ zJN{c<$}rzpou(_+&#^9FuUex(b2O&-Ag z5;}n>^(t*5-O8HJJyZe><=`xRXvSGCSTe92Qm{|-LZdFkDge2XFLF7{zMQa_nYO0j zja?D>V6NyV}_lKkCwY^0}kYN~f5B9VGM^lPz1Ia@1SA{d`9QPWE7`&pUD1!A)OI`|) zHLi;DsB?Ji76kYG^ zVPu>j_ikZr5L^$2M&oFHxj+W}da&9s|39#CRYL zRR#Wg0zA*yl4Y+>0gqDX7w1CdS4O>(t;dpOCzs5u;>r;)OE(!ig(`OWH9>+gXV4bq zv+ubTUz-nlAe?)9+%%+ExqlD~zZY&YWhzoUZ2ojs1Svv>flk*Prr;86Sh2flE&FL0T z`E59kOSEquoEereIyTZKU{V}SQok89uNjWmV|3u#91Jk@F_0p1)x<`u zR<`!H&6k^bIyzS$|9(gZ(6}{-jOwuP8NqeNQSEwk=o9FfAlmRSc6psEC+^`SRfvj+ zZAC*bihzZ5`AoahYPRStt#v*u#^VHnstCY7Tnt_O)mqnT%oGTma5U$CYYk+DL}~OE z&!Bs`(sy|%>Y2~1_$*!E`!e2oddXKX?sw!dfZTBUUB=EYK-{tDwvW3LY(uq57uRoe zxm@XOJF+myFsbm1y+&gS1j44+&|&-XRx6@fO;)lI#Tj*2CfyYw?N!7UgYgOJr%r37 zyLEVky%1iQ&Rcd1Vfior+#+qfhh}Q~MeXWVVdm;q*-)KN>8-axu<;=iw1G<sd0%;xzHT} z0T+!CchY~Y^0%t5yE^~+Gs)uU7&cZE#Jz|?v_pi=32t7jkvmNUY{!>2ODP<%vXeVQ zS@lQs+;jUx5diCDqh@^(0DWkWS;$#`_dM`Wu-@P?k-_!wCV-|Xx3^}60*#Kh-tt6G zq!SHYaK8)HF-?a535p=arzCN=oZaj}0)Z#|(RDWpTMv^zx}LRL&UynNsL5sB*yeFI zmr53q6d->rsX2E<=;;-NyBqzE*n)6+-t7x~pmGi2ZnlRnFXS{9ugf@_7rTJ)!FRop zu^r-`VjNLQ8~id<7TpxfFLt$BjvVWYJ~efhw5I%Rv3bNS(ExRD^ejuel2$^9p)z0q zpXEELlEq^g+e}==s9(>w`f(3MfmX9HRP`%Ms&}wYIOKFr)Y|3i4)OOe5^S{C&f0iy z!td2ynk~JOFKpdHd%rUyo@FbSw@#Pucuu}=c&7eN9jPya+8&|Pli>UHkXAC zxvT%`$zGN|$Z5F%ev{`48v&~!!w&%Jss_a)4`YhhKHtui$Ag`?bg*}8!)+!)VHp25 z%C}u7W*vLg3xyCQlxXRyfb??GtM8|^lIsOqbS>xivWfOMhE@!4bT!<-yPfYPBwlOQ zCFo$Y;43e*#7Jx3uVTK<+6tiRBo1r91F)Ts=}#{yw(b%AJsAa4(UR78XXLSvrW!=D zwNVG({rO`N&)lRzc%1SnW@j1WC(SC9=>}gIzqIx)GuP#+CazAhXzY-f%bw)?R7d=A zjb?>Ybaq}nDC>GVw`47wjt4S+8I2Jx4xGyZ<;{;Hj#grfzFcWIP(pm^Wc%fRC;H3U zH~+lgw`r`ufT?Qqx|mlk1`7Xfg=0s5);8V7Wrb3O?h{=)~O^f+AcbrKF&JP7yR>968C$NZU>6@5H~8-M00xo z8&;_gq+nA9QC{_apr|$KeWNTNii(P1M}y?qsfvd+2y;Z2ge5x*7i?Z)Q(HmbU2AgP zm}ocfZtH$si%<#v_fkB9b>2B)w{ZFwodmbJtiUB=9S;x)@K!da%t*kzGqt?P1=Wfc z7Lr#(Wj(T3vJ+BK!KlC{`y|Z7062Eh|F&O9n4uN#TC6H-P4?Sw)YPiABAZ57oou{b z?i`vqU3Z(ByU7!7YHJg3;crkSv-*t^WE3h9yOOt-1>7gcLLI0O;qUnX-2%3VrYkTD zr06@l?!v!(Ll-ogR~&<05f&%z-r(dpWVp}vd1shivcEd&K{LjF866@LlWYT>mhRl*f|R+OlmpzY-*WA?v2(|BQE zhJjyDR@eMy|W_in1 zx>H^-@T?}Y5>dDw@ko?n)5XbPx*qqu3<(5+e-tBp0jmqvsy!aGpy138YtKYw@Y9^+ zGH;`Fc)^)izWbN%G2_FCx!}11h=&#ncAC#fYt#GKx%I%txMJL6Qj zOlY__fGMXwN-4hYB3<_v32VRNBk$TTS%r5;wmQA%&qiX(mQhwHTELt|-zpoO zHYzb2aIMj0zKY+nmm|T4&rWd)9!Kc2D(t^jY{$V~UY9`B{eU_IU&{kc(O~uhQ3}#m zT#NRK*0%JbUTZ$S=kRuQH2c@B8;TZym=1)ovljc)6c(it0RMB433wJW}WS0yUk?*3P)Jz6<0k7zgk zGIuGbwZ96S&nagX()7CnnpOJd-RFJ@Sj-)}w7;)P;xbw#9^YOyEcd8=u-2~BbnNVG07#A{Jd&VlX+(!?b+{WSwIxOvM zKDQpDB>p*0?E_w&&@D!CXU{VIGy)e-Jg3a@2}K%ub0+KG#mCe&04nk)PK||)^$dQeO;6u_$C3+}I~J5q z*~#Z;(QBAzRu(5UY9H;Jx~1shQB}Riir28iq|7{mxRg`ff$;pwg^_&UP5SqP^+(9I zc;1eP>}*36wn0P-^M(l(T9P^zpb%ZL!0R5~0t5P*nptRlD@u-FgQ(>xpl#-?7o6h! z>Abo(1j-&`^MX1o`P{*-$1jM3yQfP%loZzE?q~{-Pne?Ye~Em(2eNsi$CSDbp%?jb z{+7LvT6VyScl+qW-y?&_-Hf8wBZOF5lkV<^9Vb1iUfCYW6h){|#!tUpegJT_*0N0_ zd>=Zoly1IC?a(3WyyGH=4-=6E+N2Vw<(9%nJkS{3&-i{J1BXXuW^u%coB56E*A)Ve zc8zinYd1zI9?c=*-&h^v%?yxLRyI-cCB0%XG#Y2B7hG1Sg&@+IQ&~X2OOE5g^m7>O z3J|b)Wzundp?9il)y)Y#s)yfFnr?oKN^QDvvl7PO_EZmCMyN!GJ#$9HuoFS{|Cszs zXzNC5nyTNso}i4Gd;*~~{|6yTy~X+L<0KnL0EMEvwIXIdProCUkDRjJ!hR_a~gKatFIGc_1W4Kq5V`yi;=J^LVD*u=+~o$nq|X z5jbprO(G{B6U}K9&F8y32b|RuSMvP%x;cdM@d!Tg_?nTu=v>$oUQN+ClMz1qj`|%g z{CB0hQS9~+sUg_JYGs6W8&34D*wYCR=6a<~aJe)+Ik#rtEK29;Y~Lkn^3L%EDrWPw zf8}{N=VhHs7?hF0v#QTu3l378bw2m-`x8(2nn&W5?)ZLy8*T^5BCTwCNhk8X1m{>7 zQkoX@e{MFhpJfpFwU|ZY=GXY{Ul{=@2IJ z{c(2hK=K*(>jo-Uz|8bL}uT0IZ{_NccRgx7|oPA{n*Iefus7 zc(>#RhzZ&znxJN}`Er^`i0HQ_dzY)#Ei`vW`7SnYL#wS`%K4 z1zX&l1^Hels@>QG8xlnB0&DsHnJxJ{St zZJ-%cy0n3JtMAZlaY?!Iz0uqXYUM?iuQpe=S-eYGF2yf6z-l(C)l@IhizIS$1vSA< zf7tvnzE!WQdbA``CVRFvbPn^-3@eFs)dOLs-O?4#S7~6L9tdjA?jvQnH7!PaXuG`f z`APBt3_oGX>xatF_|;nkJ$t=1dkrd}t~?-@uZ0Fq9;bpD0`O=BP{266zL$G;-SkWM ziJf*sKKf@S;&N;K>JaDV^72@jL;5({BM08v%3Gn7ju*@y)U&S=9f4O~gddm_L@j-7 zpkl9l_K1U;wUDEfiWQ6wKT-S)L40z8EVZc*M{9g2;-WPK-xK&p7UtFvcM71dtXR-0 z?4$eYR z-3cVT+-%R%(Bw4m{@FPh4&kC7I9`S0;!5dc0DX0Q-pp!smOj<~nLP54)sZu|XcV&y z@yr}fs$Y3#qk}*9q0as#i>TdFhTZZg^s>#$l< zX?eSjH2d<|dJkWTAcTLD0mp>nc@x{?%Q`Wg^L=d4mVP>(>$1u2-tw4P19~3+@1)u550LTI5js8_Ngk?@*jY0;B8r z#h2M5!*WYEZ+z8HLnHzWG**LolGUx+7bs$gU4Kat*_Rc(n;Mp<97*fAO3?;RkWlph zMb%q|wcP}d+5w7dDNb>UySuwP#i2M9EACLVI23mYTHM{;3GVI^B)Gji=UnHU|NAkM z>}G#gW;Q!JGxs2WTzrBXYVrj$JsiB49XO_Xb1{`8vH-c!uKifOH-T}pjb?+`(1_@n z4%b`yQS>*C)FE)di5~m?5U-se()}LnNNv?Vq8nY$NS9Khp!!_Tt2x!(@zE0@^bu8M6@Vb&aBynH74I`VpuL* zT-J$(ljPLNl!oPzPYYGC(??I)Tgf!2q|z(enrw&^2u&&RXz0o}*3Waj*4e%e` z!&ymo6=S?|r}cireZqA&x8^s{=}PFlgdU+S_$~nu$r8v(0R(E5Zq`2N37kD36t@DvAq2Oe6IJ|zGyB{iH+4>$^FaevFZEq5PG)OfwLanui+`(y7pE#KY}@UVz$V$aLi;Wdowtq!_Utb2M+ zFbTk|aG32FCqYT50r2IuFrEN%EA`gjuBY=8sjm29K5ZCe!<>(Ay4t4cp*)Y6hU3Cb zopM&y{^QR;S-tCNtZp&&<9x(*PHY)cv^P$Z@vgW&fF@s7LnYMtYS^64wh1X0%WD2f zNN#9IM|32)B|)}L6te0o#2WX~=((};d6}Lpek||;u0U1d-AeY){Cpg@kRdLT1jT4h z8r|teX{hAA2{4vmEhzKqq$PbI0NF<8Ag1b-e&{1Q1I-ppyZ4*GPBQ zmy%f30KmgO$$)eF|dtT1WkiwIQ64Dy|~;5S4=ndi6Cq9T&`8o zPI5d9(E^j-ELx*7WGfER(TNg_NoK|P8#^)a&O*fYu!)<|DD5y(7Weu?=SRSD`z1Ft zF2TZ%fX=A=EwKz(ac47%FeI8HqO7?rO09U@NVF%dUW2BFzcg{Q0&8p~n;TRH5C=g0 zv2pdeg#z!98IA%+q|hz7;!cJ986K1|%Rbim7=&;y{`Wp5YkPlN5vodZY>x%8DO*Z2 zrD7I~yY!Wk%k|>#Sv;^PdscWQaw#Hyx9^Eld*Uw<+uxS6Yo_Ak!}rWE&6~2mf-D9S zfEgCc&yhQb_?HK5lJBESv9p~$v|C5|7Euxircig}nG;e0#=oP8{#D9d{*dS<*nm$a z?bIgAF5nIDuR0eTA7c25gQ-=+mfhNHpW@8CLDXJLj;L}u_Sd;J!}E(2aXWN&&x1UH z4=cC6HfC6$;elP8$_GiH*M#gZX_;iHLDT@lps!yXmTRv+-hqsBdMa-4IlwWE{^JDT z7)R5`9;xl0tGhBYZ~$ZNN_-Qejb0FO5)5P9ui)G9(`|*d-EGb*D6XTZnJaOS-!rPS9m-Aj3sO1eT0Y- zBa?lZ9SVJ;;<4h|kKe^u?lOe*A0n*OPK)718gDv(3*X}B${vN@9?8fnhLy;bUd#(V z1Ea)DcJTli*gXL_G5ak1gl{gYJ;0r&Rm=|i-WGhiN?eS?uiNIedlSJ|{8{LmhyycC zGCR`55>GMur#P+iLaX9^G`Jz5orF=%RK=J6O?>S}(a*_K(=?;*5kh>9$@bD7?>f2e z5|Jg6GrsO)0o1_-T!LcHG@IN$mqfR;Pib#1il6sE+B;xwbl7~SgEudfVAj*eL6NKG ztC!ogYkJar)jbYky-5rydl|w(vSR_d*UnxR&0a9e&M@KrolhMu-Itie9^Z!_7y^~MO7x`MN(^k& zM|c^tJ2T2zRa9yc`tO#u5-Z#yNBCV(1OdPQ&9mK0OiTnXCQzQ|Atu?xFU0mU`%MQ+ z+H=C=V)h@jhnnyBOqgQp&Ql5tj}rvrR^xE_JD~krR#?J?6i-pWFrVlqXnUM1h`Jm-kUWov%l%e0JgG0y*uR$yP z472~QFgfUl(|?Q%#AM<|OrwY{=(4_c%Kt#;;YZfIT1LdU=Y8jpCPY)+$1UANx+iP$ zGuj$(`rmWj=&21CtjpP0sR8;NVzEvFxRyh+M2o4V?IvcYVAY{$?T5fBs9$0W5MS!E ze-whs`OtUc2_>POzqUDvTU0y9oFUtfCUKu5PBYqMY}kC)7njOA*m|KP>?N#Pxv}6x z$)bhxAMtOg*XfJTPqAq8J@H=A%tMQAq3|xk6jSwfViK5vc`?8#-#>0?%pJY#SvbU) zS9FuU!9FvktM$cqkcJ2Tk2{zk=-0z{!h(VKF1<%S1$F0eZK5jiv?@CA=A$XN@xJQR zzm4R5_4XEQ>qD%*wW%2BZ{pLZeh0h|mVVB8Z(Ge^>Ou#G!u~+&$9lL|A%zorCvF`q9K;Hz#ZV{x-|spAkorZAP%qlO8f)s-PGxdL8+zv&9 z0h7nwEgq49_dn$?-v7z{(G7OhOg~ole;33JfW3SB*H22mG<5E|y40+yllkkJ^U-`O_kTVh z07(LT5A#4eXJuofW_chB_MWqgR-dAuTxcKzU$ct~?cHh0# zKatv(IjhS*?PJjOQ_8&X=EmW1?NhO`(JFt%Y`d0$QcmZ+?q+8W(?9>Ww?m~H-67k3 z`C|Fa)o1tj)8iY6JKwqRlN%q2_bi2P$9qRdRpF_Of7tK4Cz(Upl&*VlM?zPG{p$^I zD$5Vdc30^S-t=CKXX-QW)Y3VI9P`~XRrzPX-9P0NkI5`1y=5`6zw-O~gHPYpb-as} zQ&J{V-rjO5@4LV^9b@N4F;l(}<+^*{%~O9yGmmK7swAqch0QA0uJ?wHsVwSsrp=r9 zH=@@S^#kG7_gK(tK`rR``M$+}`S`}=ZSg6~-t^tuJ0)Wh40dVlxVe4L5(4LJ918hN znM0I!Pv2*+st%4fCtWrm_wO1h;P-<1*D>D;mo;?eOA8`pQf#@~VC1|(e+{$d7IdF8 zb&-;~fAZ%GCid@cX6tPLy=cA8UZF=4~!~>i?NaH(?I6;i{1x^o{>= z@%I~uzwB%C#sAaS%cA`5PU@}j!08Mdz+hJNf0j$4zIFR!dgJ(lzir)rZPWKLCP&ic z#od8Orua|SCJmNH$HCI+>gGovxzK2_#+~Ej$Q^7LNFX?p|0mhPuxg+ibpOT+<8dlG zTL|oW7H(W@y_?$D{OdlIcGHSW+r|{Sab`mP-_LW?;o2JSY$)+Xz1*Ks=st%C3dG?& z+PTulx#`Y-m)astOJ3F0>2_OyK4Qe1$zArrLx%WzicKiRzc~~5g{&UC%(%NSW>xw# zKNWxMYNN}~&Qt6z*)BR&O7l5xN;QY!e&;RkCtmA?alI+x@4bkJ)?U((*vcYdL^cAF zs{8E~d_JkozXqM3y%RO0VL}T>$^AkuXgN((Jq1ColU!DUy`C;EN}2bYS@SwM z&I`Pms12(0l6%>C43wUpHvM-!v9cwVt)$r~=pi=fS+q1l8v$5L-U1i=21`SB!Edf& zA;;mzUd&(E@u{dU9{SlYUD=a}@nnkcS zExYq)-&FoE?LmNZvNS=&lXXY>a2)4(NQ-Gi9{NoQX%e5pjt?PjVng<2V=8R%B&k^= z@dKRdYm6r&!)W(?m|ygfX~yi%PpyobeIAO_YIMjD#f(76q2Q;OSi@pe-`Lcqz7(l@ z18CPf`qe2u;NeJHur`R5$?#DzL*EVZl^6N^ms}I2F3lYSL!R|E1tmpvER9_~0Eio6 zWg;7!rXo%=WuAtD524V-6QmlE6lQCQcVzv#j>tSn+#s9HTEi`)S7dsS4EgF`2skuMYRPDv|d z0_}a;m>%~{?tSX%^^7x_@R~+W`kq{yW6Zo=33cU8%hXDuKNF5;6PIEjbh zhzv#{NKD^?W)W5j)(Pa^zR&;>^nZ`NUk@#rE@7$@GPZty}nvopj;tJJ1qyM4nUG zS50&ByJz8F%q4p(P5?Ku2G7$IakjLP1+xMZw~cbWf+TN24Z%FY{QkfqvR281CU&Q% zf2x*eDKNsD4?hxa3r>>Z>=Wx14(Wc)aMO_5Z|A-s7I2;i-s*Oq)XgTchq6@6%Hz%7 z%epbmFQ)4NN@Rd>z?S936*LW!X?MUN203+N4kC+eNu+Z(41l~08NpUX^!aY?{4ou7 z6Kd;e>YU6sE-{Xd;7k4Qzr@qkr{j6C_&>Swc~gdXb-n;BLC-8Izb5Sir0}Nl98BDT z1-u7+nnl5D(uW~TdBR07!Yy{XX>cax@B!x2SV`sq_)iMe?Zj5+hH3tAJg_pdB(g`C z`8_iZO_N&;mtvFRUIB4Eou`pyuCk%e0)>Dr6c8XV^I3_@Zk$qi&S5IZ>H>Hg`Ee?I z=~6T9f)UFu$sRT2YyVQ$Kg54-m>T150`=gCgJzMFR`L#uv-f8tigWiG>$cxng+^J8 z!~)|OR#1*aaqFm3*mpjSoKyrMqLyRCZZ!&~|0 zJHM$q>hiQm6EUYs^1LZud_TER|7Vodl;f`p>YHWjqo0=(*F^gnPeU5RW*)7o5WDz0 zmpsb1VDIDFEc&bsZfJAy(*h$Vb}un9J(+V9q2q#k`uk@!34QLYgjQd{GJb)+PN4@K z>9Eyzx$C1Ac#G4>4l>K9#vF%MB2|+6J^7rLcctCT8FH+3&q5*%3tfrF4vDASHI?eI zLnh=lZ`_9Nidae#RoN@cT#?)qZnh#dtz6Ad`LC<;zL2S=f4BFD+&K(6Dli2(WbpFuyM(9MIa0*c}dIt z;o`k?sT&K!h$*<@1>sAeG25e}keyLN+nV%xMck#{-YTvI^Hq#)YuDSFZrm~+1=b&= zDm+{w?ut&2RatpP7Uh8@@B5-|%Tcw-0T_&?+aUVVe50Ae?9!iZsZ7*aGgs;FvE&bI~>}L@n$M`-6;g%4cFG zTzQmRg=Z>3f+zn3*8!tSpQK3EWf#}qSKTw$##a=$p0IuI*N;;K%4R%!E0dyBD|~N5 z6EX#$MGYGT;Cer=VBKmmyj*6WPV>-;z z69$HiMDpB+j!-~PZ-smf2t4~X?mtx(MXVtRl!Y8PPbHA6^{Lm&IP{;eeZjwkne>bW zAQcEyN{|kNkV*2iE^eV!GABR7P$i5=5Ky=UN zfTK=M=Jm(15lXQEV3m&NJ2ik=6Gt7);Pwb~3j8l*>YCr}2N!H?40Xmb0uzMvGe$NEd27TJvnVmA zyD?@jbh!|KAOeqvCB9_RAwN0eR zBM|-m=IE<>ve;@%l_q4EwRtN=ZWdXT#Vv=Q3L|V_|Nd1~@VM6S)LZ$4!`Ata#Y~HZ z1RQ0cl+qz+JnDgcc2`@M4J*A@&?s70+0-yEP}yibAx>ztU-8;;wWVNSfYI^k5||Hu zGj|#oOCQ+#Ja*7aFFn_Jl-IIBW1vBt#ido=t0j9@(X`+7TNu&KD zhx|B;$!&D2w#9!@(UmocEGwn#jrX^MS29paKPFZPi8Aimg4!;_bft!e;&Eb9ECkbP z_y|>vQ=Txj!Xz{9bM72Wx8swD!=Q$tRw&XJ!*HE?C>&Wh88-6_qTSZmXtGR>@Pn*M#nY2sPsS$w##iAjO&1`AE{I|x$m9efdi4B=tTqvx}Tee8S70be8uu1DLg{ zLq-CE#Aekpr|&x(U0^qkTF?UWl$yTHDW@gFeQP-ovdoJ(Lo25$6l+j-qf+Dehi0d2 z{((c!Cywkr4x;^{$^y;55sU*MX0P!+ouFiXJugCChq{bUuuN1mz}8uZP|8op&W3cc zNK+t%TJA*rmqcbFED~hhINruYezyN>keyKQ0XJT^-x!l0u(7uN zCPqFO{KPnJ{-dwNOLo`cAn!1zMb224whEZp#|e#xfF0j0wi@orYnNI}mR0OH8nuMN z%W@7;i0Mw5y%yH^Y>txTWFv*aS_F{L5BqZ0(D&SP8M}wr1b?xgX${wJZPnG)5fP>< zZZJm}v5(|A4ryn2V4-khR%Zb+M3M9J>CPuW&`|#bTO(#&*Rn88Olg^Ll~)wYXPKDf zfmOdiTYH%Vt42dMUIQ$ORIIA#e|bL=1wu`(kuu>YN^vL`b5Z~$^P&Zi4|ms?A?&U` zQ{Q0U#+&dRN~m9>GO13=>q7Wmh~Dz^#fY1}(XE6?+sRrYa60kM5tWR29-((QQIWU^ z2{3(`4RMy(nz4TNYbyl08-eWZ9ylh}?Q5*egNf>La&sh`0FzSOQnvE>*_M=84 zg%#1J=m%}6+`btw+JJweIrlpj5Xpw|1|B*Q->kttCUfuY0G3?;k&{#?n(Rc5q1KY@-aq#+s51o$1;@yZ-UT&uE^ zx19V?df>%FI=IYaV7Ilko7oA~dIC%{jBBaN1`ej+Kv6QX%9Z^q&{1YIqSs8aI@uzV z5u>oy+M_X+PLWZRnce+QRi*yR1(7r~He}&>!VyaX|PyZqrbof0221NS< z?~l_HARKF)8BfJ4(A5wI{t&f2y6YGK8!}U^G@B0!168%-ATNgnk%7JcTY=Il`DLy=KkI7ox`L0ux^O*yA;&N%P9ADuCK5Q}{e zr$@MZMTInQ5phy4qlOO;iLo&Y!&eR&e5c~v(l|4+D{}%xW?x>`xtl0-wK7))N2>!F z7GHfjoExLzo7HG%r{Iq}Ox^rzS#=)Q!lu+GrU?vO*X_J6_M_=0EO`-$A``kwh5NqW zIEPKjOopZ$T3hiNf5I?!Ri9yB}p8Nr2qS$0J0!#H5qtXWY`#7S*trD&Uz|;g)H~8dw3Vru0Zv z$c>ZOGHXewV!4s9doHFv#1qhbRn%8jN;+>IOpR}wq$8Nl(kSK03m~Las^o^(qa}>= zrig<^aTT5A)FW)DE0lzfA8o0sv4iF|DxgPR#auXS996hEl!{_hcd}* z0is4aqcyn%_*cTEAcztXALWWK!vD)BFjPW8^!fC)KX}p-X|cv5hpSV>=((TwWSkBu zGFj7n;|lhQ`EN%Ub}6yc!}&k|(g9oUf7Q(i24rmn`aG}{!=I*u&C%gZw-TV7Q9#Ik zmUV3kwFpwTb#b0h_0PPE`LOA*3&`|c9jBw?KT`HX;`|Nwd<7$ajlZ`-X;$`{6MA?$ zO|T9Bp7FREmq^@{*Fyo4k9_Kq#f|bG*$wFd!Mw9a44XkA9QxMF_O8{H2zNXqGYs6; zbg!5<;Wj;J;XU+^LK{2<&T^U=x2%{*T(a+nUhB@U&s0vV>fYY89UO;xjxD2VmrdA_ zMn|ix=VN&?Tp@ty@Tvp9!$r+!ou2o6>3=N>vk!YlQyqztMm=tg6Z^K*(PqcQj4=gB zcrs|rsW~=HmxlK}2z1T}89af`hT`}Y4`=8{oM#6WJTvSFnTZJL2GD&Wc*ZaMo{DJ# z6^>I>B6Pw5Ky*17bJ*JLj9dI@oSU72iyx%%UI*#vULsxI0=YO6q9pu8$r9De6xNUO z!g{jJO&Rz-mODM1{wunCQXR_d)MfK|cy2L}`!(%&(XYu;gIO88eojG#+8Qe*@apnN^iJa77$V3p&( zMYDAa_ul$POh-*^5CH=`ORejwh41!w!R_R1jH;4o%dbcjeBk+3j3sUd-of)u(yHtJ zbIj}?=?See*jVNVB=s1}(eGwI-EP(=J(io>6my>MCRXO>WQ50c@Csapy9*q0VL1(0 zoqr7^N4H+AHJylqy*~B~hlNE4ukYYgl~QJd2Q+M)WEe3#y(oTpd%?FFx*q~XbE&Gp z%}riy?UyT|i87+#rx<=<4c~Zf2?DsT;+%-j$FZ{Wvd6uwtX#q%N`7j{#{o-_X#)45 z1LhKPZfieNMf|-?kNG(>6pbjVo<{rwDGYr>0s7V!PYyF}?{C%V2k9o)#DWe@Z?ZO1 zt*U(Q_vWy8`HqdfpRa2waFcR!HgmYqC2#a}Ow{W9=oSqlLF{sw$Jc?SY3i+}{d(@H zSXzRko?vO5jqEDGtqA!DEnM=c{^wE~Qnx>OLO(OJU;e;2QH4QE@A&=_Lh=VTPqZ@j)E5q9}+Bz zQ}2$AvDvOt@>Tay&@s0F@H_sQ zUmbu#)BG`fq3(7k9nRIg@N!G06pKkqOTUEm3;c0}Q-Q|aSl5x>y>Ky1S=pTE>h~Zk zdjb@^?lf6)sV0v8c^AS@q92U{P)7l<7X^V)CeiL!h^hYwXa7cxvQtBpxWnuUzLEE| zg|?1YGrAt5LWKLd`cc-flZC-v6g{z(={?Zht1PZ&iqcVt&O3E8bAJB{!)B(snZJSanP|e zNv>^NzR!_m(`jzHXw+Y{Ir}!3`QpjhQflHdt--;Ufm2BDwdM(_(L`=wPiRSBwk7sA z-L4KrX8WIN+5mGn`6yQIjygpc( z3dO^y3Xpa2*HT7>Rg#yJ&+~S6vu;2(c`o;o=4MU1tSIWD6uY0l5@h`2;-U%IQA$xW z2v%37nb32L@g^B=@W%T~R<`oLU}%bD=3nRgjE>IN*}B8YDpwv-oU@K?Vaa;Qp`K3@ z(5kzd*U$ktBDu~$$&>cjY;HYKWpoqMqySLy#=ToK9@__BY>S!C)3K`ac0bnkthz^c zajg_S9`f_wX6af2k|MEYMZ9U5>Sr8KXjZG`qm<&~`FZQkjkR? zYcbW^OYEO^>QbSrkYVrmNwHK1qCS1!mK{%P*nq<*=YBZ>$x${*`@MAmsUXj1CnBP2 z)YQ3sM;7DVYW;g5Cer&M6#)k7*@ajPhD0m|>?Pz0ch%Fb^^(Zg!%*0mtU|TdbK~SV z8s-c(T;h)PpV={Ch#u0@+gQef9}}^0N+Jp2zFkT+ux}IcuWE+I2#z6lHpMXPWWOZy zdFbf`bOH$jK&Yk{ln#DqZg4LRATIexl) z>=WAPLDEp>q z+qv2GO0iL{p=mm=j22L#6PbHjsFBfICI z(s&;`K$#x^w9;4g`kbr1*x+;3<18sOM-Ti|VrSq}&coJcW<+&is!@{2y}(5q3qsSQ zrl`IQqdgaZr`4i95twUQc)}V6%zEfyD>s!t0r7dJDJuY{O8yk#)dW{E&l5)y83$So zoLg+Xhtvz8ox^F51-bM9FRx7ynko^TIGp(f|L#~BVM*7Qwn!|Szxs1Vu#kqZ5V{mD zJ++yMo6#blgdu4XSOG)NBO8-)1p+<|qn1;A-~GjVmP>&&I}ZKsK2!U5*A~B*XJ<}4 zQpoi0dEFM*6btlHP^|y6_WISHnDTTtyj-5^ZWYM_H}eKix%1s+g4Z}$N-LRNDPd)9 zE#G;QO|=;2H<$75uX$$hOb)SUb`r@m;Q{#*OEmpIqz!}JFcgq^lMvPGnNoWEP*4$( ziD~eX)&9q8Tkv#AJoTyUO0C5q6OoGPA8ATnxS>z;oPGFyGyi_9)Vtg$`GQ}XO3SLh z-!rV_u9D~#!3@PtuW7Ej-t2c-8iV}Y@o$q=picIayzX_vPWX+UfsGedpeC@7m^zdV z(bA0$5}E|M$nYex1^tEsFx7MenuC2X_NCVqq%_KAz-HA&2%{W?LBL-h0Z@Vs5YAL; zem(SlEBYtIr_G0-MCtsczJz|my8Kqqux)uPO1IuUbo3J z%vd*ZET#-9o2^}!T}0JVQ^nyzt7)Q^~p!PmtRCA3pU{EgVFza+VgcG4$hv=`|#v!WdLr z7t_HdTJtHeNWM2UxZ9e*Nac0deNZERzis5&Pkk=+Gwzat`3h%$r!fLEF(D?{7@d81 z2*6|;-FjVrnyk8*YYB_iM2#HCWQDn1Jp4fKW2r387c5Ki>JHd@EViy=(lw6kJKBs+ zKn=V0NaR#H%mt?-p_UFKpBscBZHF|ha+EfT!2;UcX3>vjkyum_RK72Q%CcCNKR7%k zjU_74;Wyf*xz#}f#y+TUnJv6fM|q{wFGK)NFRmw3Ns@ zlY$CmuD%rBIFaFXyXTOz7AYmJ(Vz_aA+cwu7Ak02a7nN% zK>e6ijc|{aCff{xzaEkYSY<&kQpT}@Z;4bNOELLkvlNkHJr#B}DHlNTZx7cVxMyGFSH);O8E>iIuq}M-62jiO;pd zIkcJ2uC(xC$gK3q5&GA>AOuE3MJ)u1KB~DzmXOO~x?rku zx{1U`b(fy59x67Wt_XFZ!LnU*EQM+2_Ymk7R<;E?|tj0SY=2%0#}gd{(-6@hGY(8z^cz2=htaqfbPQ-|gq(&A)|{ zbnj&Hh7&bSzm)9tdbLd+m$DeXH<~0=;_~0MZ06AUT=w4!_({AqHvP&`u?^F%6WSUY zT13I=JQ9}KK2f2uUyCw#ez=-kwfy~+!emrsw04#1R?lr?k#D&9cJ^5B9x+NUAO8d? zbGm2hsBcti+Td1>ty%$!a^YD@XNCkGJ1_|-sZ*OE_ppyjC)RtPqE+bJ*7`ZlZfY!A zJABiq0$e1F6AN}ZB~^N@_V8T~Q)saJV8L~!*%ZAoo-Uqryqjx>MIdxgZ1d5i-tf=eI zF;j(nbB_{+nZ!JpXx|@$^xdFo^Qy((wteuSxdot!f32m8rt_LN8?M#s3Af)k&0Cy< z$bJT6%pP$kmc}S4!VO!PgV4?n`J7m+EE$$_=qXwZM#`Z(s@v3seTO(SlX1yK4f5dQ zswYeOKMVGcI4S$2>aZe5hi*wn#vSPkwP`hQ!qnTihuIr6>VAnUs)x5G?=Jd_umtA^ zS;E}r8$4C*Lvo#iIMsKlyR$7yV`=9dG>j%qkiATvuzF8ei2wUa#~32&wR=QktzZrW zb(FNRCB-IkrP){>I17HsAlFTm&Jc+Q1`WkEu0L7CFpZvxW}PpBvB)+y=0OUcKMDeL ziM$z*E2QSp=05nl3k~-_z6!b+Uy89?)<{>)@5+u^!OJKSeUxDd)hHZht>&xBEKcSK zN%-qGtNl&A&r0rmY8i6wHj9m2{PUm5*PeXaB6j1~iqbjw+~S}|{s|_)@tX(FoQu7x ztUIy-8Z$bTraO*8^l=BQqYGu__K+e;g`MN@MQmn8K@1PZh)OaSOC8wf2do!_ZG!KF zW=llwlsIKq;MFwh!J{4F6jT9Sy^L**AJk^_jAuK{PE+h1-zZXx)Bty}0#4vfL07zeja~ zJ~TIVbvfoL!!Uk2oA&qyhCS($UrRE+m)_j44b$v;1g@)+#V176S-Dv(MFY(9r5Rb~ zv~GfbEn~EO-8(BgcX?4wxe3nbk6Q4nL}RV7dmnV7cSQ%ujd#c3q9lw42`S;NQJNBM zmMV~A@v6>#`^=Ml_D9?e@v-8tJV8j(M4fA5<}r{a7Ey*qej$!0;34r9} zbgHNiM$f}F?_%nkN9qhy#S-V$#gLTr?1rAmZ$1f@g>zx6-7O5l8TdR<`W~1bT8oGV zYH>lVjw4Tvw}=SXe41l~-Y^7Pi{#s~eUu`(9OhjQbIOq?1z@dG@&^7j75w>Lk@qbm zo!zvIikKx0_C(a+eOgSB?r1*n?1%8pG4iDkJ!niXquy(P4(BflDzR#TxRQX3zu(XJ z?6qdYCja{%ikSkE|Bi+u=3PgPYf39CL7C#kMh}WI3?i&3{*V*f3a_es0{ke;-&#cVZftN^@F1Vk`@uk@CdECqe`6y zVwhPmBCmeYbT-c@xpt9<$Lgg=BcHRpfWtDD!K}>xs9N$-@F2Uk$``3JI)39o`HS6Vedn&0m~k0_(PYzywD2Wbi!074!(!;ysxcp315!UN~Fe@KB_76IZfdj(V4wM3=&` z8{N$@g~AsR6V<%speuhbC_Kbh!u1!S33Tw!WbmlHH9N72M>a4jsR8&+H z&RsM;3RnYq|5M-!k)U!wKBJ<)^o?#i=b4u%$2$YR5O_hj+RU{L?j2L77>$$bR6M6RER1ZnL5U2QRaMQ_2|tw- znbdo(oNc%IUO-1P+07L*J?2Wm{I>VBsMzpc@1RrUEM@&t!!dr69NVs0JegJw_J7Ip zT1@dPoauwhGa|utGckHUr+Au~h?Ohx45nTp6PK&jrkyGIT*xAwnwnNchJiAZKvvgf z|KJGMh}y9)(zAVVbVCz5N)M1C))VN~34&Xd&b12(9Yx@TGk>I8-DfL1F5 zVK7U`Elw_|wNKw#rfe2t_*@%yR#s6zb}i%gAu?|U_$#+AX-T_P-4_dy^l9?)$! zqD>r^gylQfXZ26n(CXfp2i*Eci4H`xCvLt{S)puB`x5U3^t@SSm$7(C1%v_f_#~G> zi8?R-oSD&n{e8~3U+X-CtmiC+4(Hf-ig)y#{a4fiAVT=1WA%0z`QP%jMOhTA>tuMK z&DrqWr*@}7o%-WLvd3`ln`_S3MdyR|rX78{##!%-1>CXhWgE%0?Djqg#f$r`2m zI2dN|M4g03x}w}oxaAPm_jN&9rJ){He61UQYH#ro&+<4msh)3u;E0nG1BY|}( z&@>iEL0b^J^YyY%c&OYdw+D8W57MV@X-jiQJ5{-wm$TL;QWvIe&3&lA)Qk z8P%cGFi4_Xc-BsC@N42+=K0bsIEQkZB2C85n|(}G-2t>Xm713q6n1o+blZB|Gmy^S ztidP~O^#s}u=7W{?+J~#4GtQmtjsnw57gLt8|6Et5{iXMEM2a&T!1Z$L;-VaoDowx zzS!fC7OLAS?Jm$L);CIn-jFOBJ8$Tw>!>^aI1(#{Qfl^ZEHFhSYE*T91JXD3LkKY5 zzqN8Q(71uQ?lL4`;C0i17lV$L5wf)|%i9Ns1_~4AAQZO^!28<7!>le%;u$W5&M>pX zSmE_^83(loxD~m$Rz5b#uO$7IM-wb)9kby#ry+Q?_Ujej?>Q1S!^JqnlyRA?8VMr8|L^oG@t!ssBIckGbMbAQ$k4P)vHmt9sv4BR zCD`H`jUj$!8FIG32 zmV_S>_2IcdDS9myj@92(3IDd9I~pG8`SuGcx z6C{r1M=Z51)<_*S&4=A(BZEzYv_hqDPTdQ0q4*m{YxR9!D8OtPXbN*`oZ>7DCe_Hg z6(ny5P>Q74DjnLGKUmY0*PZUwTaW1d=fg)}5~n6T9xL4poc8b(iG@){q%%4Z75Oo8 zVteT;=vDKn&PqCcZY$E=ZU^`R1`gWArH`)B-wm~e{Yv4WeiQ4~t7-dynG`b+D2hV$ zQPR`{rX(X%OjrL-yEPvsj+k-=klJ;OL%s6vgGM+`ahUsn+W6_G0mOeYVWFLMJlEYyswvhzJZXKIyY>M zXo{tUF^V^8RZ`W;%>d@$7#L;VWB6Z4?S5W>LKfF5T3uIXaM^0xtD){DAII-Go_lOL zoj_(C&MTPfcSCKrb+Nu^RoMc9^&SO6&*xo$P7f-;xc!qGI3k+BgeXD;OQ_FR1 z$pB#2PBx3px%}<4*4g!}{Il2Q)vW7)qOuK6Sq_><3^%SUkcabeY2&Mq;AQ$M*gNzo z{7U?pXrIpnJ8{;l9Kw$h^$Sl|l1H<7;@qQ870+LR{h*YBjT*p!X7fEt7i#}H>137^&slF0gzJOpx+TZqt32Ng=(w|yhxa9K^yaRZ>q+;GGW!;p zM*W)jXm94z!XR2%QjQ>T9j=iu1~L0f3CHe%O{(SXnBsk`sN(IyuHtCHz0hgdaJbr-b{|q9;W>|7*AvO&+4Gm zi9*m`_i6e$CQfiGQvyFgv{EpnBR<{&G~$XrEkJmhyve@byEbk81d_pwB~l$6b6C}Q z+j%8n)LtvartMg0yU(-Re{}Hk_dI8>q!)ggV;|Ki&QZy}*>fHXQ5I;*ya`lJ%<+Fe z9OZ>4DoNs)rx^3{8fXrQ)xmnmkD55}QNaKUmxeb(ufK7izjPCO%qa#p=grC<)R!_h zV$e+7tDNEf*d_m)oxvrjpM9lAGF&w<_vm_}qYxLfTPm(>JZk+xd+`+MH+neX9%Fr4 zF$>Wm8RQJNUwbk3eC0hIBQ(4L)kMwW_4=ex)mx{?9yu>k!A?w7lDseRQfrcT9(B_k2bw1g+4TE?K427r|i8}1FGs9 z;}Chd%`nPq3B4n;s<&J-3%beV`pINa1N;hH^r1e@da|r)X=p#()lLqAEQ4c@)VGQa zJ)~Mxs~m-1AL%u+ZO4Y}7enoR&#$Yg_?~cNQ$i&tA4L~3{pRJ|LUCQ|jP3j~P+k)! zkyi4UO?e0{+qkectHk#&=BTUvf3<9^+xn~cAP(v<*4{vM@INn^FD6lEI+aXn>*{LR zNdD2RR*w}{%BfdANt#~Y2mNzkQs#R_IJaFXWZt0Sl+{zS->fcO^H|N=?-fU5utnpS zkl%(+=|j^ae0y0yZ90z0{n9niC7+Qpzs%jf0SqIDfP15~TjDqL-fRkbEj(dUs7+r&VQgTWN8=GVi3< zdIx8hyb!84nY_aHkFa6XbyO5S>GWbXZxM#@7U>e<++a4sq8yaX zWyumAE6oVrV=MDFy!6@{>igYkGShI|dpLOB7gtT=Mne!fM(0^EyB=_Jm=3d@s#|ZM zPKf{R_i6u|@Hwg5PfBSo$#k3xoUu#|ziL>|*py!aSp~;g5zVA}V^eFvhh*pS zeBh&`{q~#5*qU8Cl8(l&4O-8!7`>PgPi*Mn3S=II!(BXnB3zZp(ee_#Cl7s3aoe}= z;O9|J!X(wU1q-R<*wN1fi!p|U6k42IP}3Rgo;8W|RV|VvZa)`(M^m}2FxQKs3uIih zwY`AHsurc;(Noyb_%*y^AlM6yNmrWAM0PrvKXy;sh>BG7zk>B4Q?cetbO` zswB;t%$JR$BL4{6s^Fnb@;YiR7x@h?YJORv9C0{1+q2e#K~+xts#t|S1nKuT{-7Vb zt+rN9%Rjmy#+nf4ji+23Gu5-@J0;OMFPqz7n#KV}cpQO00 z{>Wt2hBR3E9hk~}sj6U*9%H-I%?14}^}7_$DVwxX>#pro2%i{9w@#9+`2W~@3!gfo zuU!}lMT$dl*MqyeyA^jSP@GcS-QC^o;10!Iio3fUIJmog{O%Rp=V;&#B;Fa&ZuAzLtl0rh2W4Np*}I<%cl}VDwN4HFMWGvb6l6EQ%u$$W zD^F6VevO;dd>rQY*Q)RW^Y40DG06r^BOY1denq-NNZ0eWhMJ4e_uOd55Ok%ZM7h)> z88!1@Fo0}%K&BH8ClJVA_F%iJSC)wm{OPFXCrCK+Z9GfyeiQdSqmVIX#(Z$s#4H9r z(M551!rugoN9)gDDjRt$_n|GCcAyreD);sD0?02=+rnHF2$_+Y^~D^^8L zXyEA!Ma1m;Kd44N4?aWTKSqH>u6?f0g_^~>V`I5b{5fKyQeF0~R5{NhpQOYzunNbP zOj-2Z;_v3_do~MSYtkd`JLQj@uRiX&l#(JRc_a+!v$ZC9L1EW+XZfucK8r%mL@OmP zjhSw`>4I+If^o{(M|A)8=Izcq4y#LnPP&4GePLl5R%3+qPe? zUvgVi3W}qY?#yl+&XQHhyx`NAJhbC?=|s$QEr=fT-M4>mp=B&a!1x0NsMxL~0(d8r zs{c5Xbwy}Z%gi(iR%E9w*e0Nf3V37J=sfO=)DYuPq_5M@rBa*lH4mjTo(e4sG^++~ zMmX%pTaQh&1-{L^2-WO8UeFH{chq~mmHbZr`+B{V>e+SYn_4EeXeqzL=Dg97E-Yj2 zq^HnUL}{eTzj3)=*n>vChnK|77aBOFVa0e4>+Po58De`xgP0UL4efLem zK$!!)cof$w(D9DlejhX9Dugs|H%Mlf6Lt-wqT5=$AemSfQZ-pUu=#H+0E7D%;w5uZ z*yLOx@2btQT%8>EUfc{s0V%_(_55N_1+4u-7KQgmebQ>4Dm6=ZiB%pPWzOq)dNyS3 z>Ltf#o&XvK)r(zAHBbiXMy1omkWxm=xCQHXhk>zH>c`v>qQjlD0ZmRAzK}+Ztc(^+ZFvumG{cK&||M8-LY~2p_BT2N@BES`UV0Pc{gCbj9ddlf) za^UL_>?n)Jnd<;;HcJuyP{;kBfp7jkQ9>k@;GD6?>1#UED@qIsf7ydVj^D0G(zuWyuj1{uK1w6Nn02N{0=meRtj=bk@T(RNksvDj-b$m(mP}Ip$-qI}z#h$2c zEH8j>bh0sfE)WngoELwTSlx4`7TW3kWmY9yt-_Zx2Q~hg71I>Y(91=-H8t$N(+vxg zH59JzAd9-Vb#*6&F6JHjy>-W=7~8w}4JzX67>ju+ne&a+OOe%B{=S^a+AQ|Q-2PLS z55mDngD4}sX=zj)la(7HrUh8sUGc2m3?&`y<<3|eR|Q==67kI&Xd#7$)*<<5OlU)5 zd1hsFYwyih`b^n{8o17EJvF&y_fR_A8AJm*LJH3&%5obbf^*&7NL!QM;!iYF_wJ0` zgJLF($Oa84d{p*D6!x``+B9CEoJY-gG&3*UTz35JJBP;C8U?m>xwcATX(#DI3EEhF zP-0}(=v_v;Fg=o$wyiZ&@`luqC6!0X9CiM8cJIP@E_&~Zt2uj65g{t?d4YNo<7aJP za@1ipFBZ%Fx)3q!CAp|K6^1cz|Nf?IWG)mC&+xOr*lmQ7zn|dG8<}%)b~r<#w;pOv zdg*>UbNKkNs#&CJ>wChLQ?2BXiXGjFH;ALqq^;uwtzpk@C5s2O90bE8&|Qz7*W>qB zE|FcJEm(n18y=OvYiv3v)p!2o9>3|&B@HlFYx9oSQ0@KZlln=|wcP+{VZT%Y3$LX! z$@6aXrnpmH|HJ%*e(vIH=T#O5=wR)f#@G7=3*Mvl^@^#paQ!aBJo#qItAUfKhCY_> zxb`|Y^Y`NBS8oO~1-4agp2AE>0BrOa6ASl=B`1t<*>e6!>|#B8*~})i+VRh?K_lp) z)pg$nSRnWXhOia!D&tscWTq=&n%EjMZo1^Ue=t791C9}a&Y;eZ_h1mH`x$xh1q47! z;#E4*|NUH6uTeA5RjrAe+qRohzn@+)Cgr@n;eIHX&wsVfHuk&g-V)T^v8PJEH$rkX zQj#k8^5rZwV;0-cHKn4aU7;(NN$CC5Joyt5<%3UfR8v$(!?3F6v=QB@bn;5OW}z$5w|&wj34Yg^I>GO)If`+*Q|N zh1n(Bm4Y{ghm@`7xxdK^zL(}8d4(WkZVLq-2|D|w(W%c?7h6yPAXoGK9Q0BCdVTR` z_5`fpz&$w1c!1-LyBKdE0^U3{wlTMN$P>CaJ*5ev32J)w=J=c+fx5fjaY0DD+%b!J zAVdXl4DH9!;k)f?4#qIQ{U+v%#O`@v>DTkn43cu+3GuB-j4t4O$nUP5=j+AXR~bUT zj!G|y8lIY`V_V)stK!N0+0-yEh&-jqSU&rL$^{-F-#_WcIk+r`JJYZWnwwr%JfLw^ zBJ4xt4PecuQ@Xrv>9*)=Iz1hEOx{+nfi-P;ucw(?B}?fU;zs~J#x5{>Hqz~S-baKF ziXtGV+@o=}K;{g@wV}Ux-B9z3w8ZPmnk%Ws(EBf^CUL=nMU(qoESwXbI=#shvqe4m zYp0HO*GU(wmN|`7HD3S{+p&p9%dDyY7Kd&D3h()ry@~ruw_s;h(H=Epx0%Tkn|G0Y zwftIDgX^-?zZ3|K$utOe6igG-)4?CU2GtKiCO0TUCu=ea6Gsj5y9Z6*M)GrSGN|k7 zGMXB3rrAkncGcMjvpcqy(pu!OyQylT-q}X2Fx3h-syB2;r?NeYRxir01@9U>cgI+t zw9QH0{>i|mB24inmu34n+9bvZ#wG89M1*r&tr9(Rt{N3;7EI!P@y8=G@+fH{Oh5?{ zpzt44i4qhIp~DDKin#8~t-^y)rl}irUpU<`Sqg!<`d*azM=(q^zmArVTPh9d7v?4_ zVbV6*%Gh!yEJgcy#IhQ_{Br&Y0>yf}-0rGCUk|I9x*u0`k!xiL6WUn4<{XgHUzt{B5uTc7m*8KZ*m(IXh59ttYlNN?tjS+vRjwc3x zQ&6A~f^8Le_X$S7l`8bSkW0hlwwMlr2N3<>1Pi>zRO#IRBCq1SW?Z1!dU$^``}{67 z&~T9_R5N(HK1^O%jl0$%gn7v8D$jTU$&H4u%1^u(=$^OLcs(w*f9^hsLf#sDB}>d~ zctI{;*KjQs6R9t2nFm0p<#dCq@nacxgJA@FYWxb}47LI0BJ=Jni&4d{pDQKmO&fD# zPQN0k;yXrX!WUJq3ndwmR(I!qO>OxOhmQF^uSAYH<~n#h?XGQUozFqWKYB+a2kH5) z&wzAMz+B<)uVNtGzgzl~^C+5KZ;plwGq0hksoj@HAm^I5@auhGjyk8M5ajSvL%P=; z3m_Rq|GDbA%=)9b<0jXR8t{H*K2~9Pe|!DWakQ1}>o|hs5t%Qu8RK5XKVd!F(B^el z{dAp~;QP=V4FXI(E`b0(yF4H>rY@OK{o^F-38N*V%Myo(F7b9vpT}e8rPRVDLIa;? z=Nd-r6SjBHi*`e$$BqaueS&*Q-8Rtu+E^2QvxOMg7^M0BS_t}QLZs;Yk=>fzf;kpsdN8t>$PZaEW&s5fQ#m_;_x7QR~lvHA& zha`u^ufWvyCfcWAUr%kGqf*c_uN=VbCX-tyd9AcxDK{VK=3~d4k+G(IZ}B>gY7f83 z+*;+u7Fv*D8%9~kNTh_G~YN|U`?xwQRo0x_}mW=PD?{TiZ~B*)lQn&o^v15(Vs z>c>t3`Fc_GErnmH5U04M zB@t$X4WBUYTgYz@*dU>?2!d}^6zXxr)MMh1-dZ%~n}ElYRiN&VzClp-mt| z1V^E!>8UrbieVyQjgMpEGkEL7Trp;`f*UbM{V69OMSRgR8El97+P21J{iRgr*PYHw z`p-N0=D*YYm;Kj0g?40(kpPmM+n#c>xCHchpB{>ODsCxPoYey*g_YUpm8>(Xt7Bg)N}%$ z`?mJ6+zzRW+w}D#mgGPRcO5f{C;?gd>4U~Y3zftn+lD#bVJUo{vwN6 zvV+Ive5&uRT=DhqdD`q0DS^JA4@e&rHoT>hAOx|$#eo$SW_bkCJI%*5h;*tu?nKV=+q?Dbudjk**`7KXn(tT$ymUhy zeNM>@X?<_5hfb7$3Muq`p`q zr17SVlBHkg8u@Th-SxL)FEE$J@a6uDH_gS8{@x&eVNJ+uXT@wGA{kWi{Cusi`AI73 z1V?F(B-1{WRcp$WV_kaSe=z}N0?2ZCHwe)%V5noqn}XG8S=M$T@N&@h9K|s4i_QHx zJ;Aa0*}AsrIsCpU{~}m+G(evpbAo`raq51Fw=`e`^l`P&@chwirR}95WNsg%!BEmz zRLxY&k-mMS*10+}5XLwZi)J??Q->m7xd=SKgWC^GlPxP`E89h_<72OL&q^te6>!o| zU-3|S`d8(lUJPl}aT}ZB2gf?eSxZ^?on)e4fumuyo--WMri>^N5N; zgm`2~zbfl=7CotQX~IS0V(_np(e&>COJ~^3pasG6Y>xDO{ z9M*j7$8+6Upr!>|>AlhAcfOh$g%Y*!zm|i)8t%Ufs3*o3I?G;Son<~=pFJF>HkgmH zJR6S$-uBnFtN(sI{pY-@QY%NN48v7KmBr+TS;K&5wbmS!FRW;>pk{c|Glkn(vm)v#sv z;-gBoOQ&O^Pbd;G3ot*Z{b0a6b0~e%NZR$|t&dz1vg1B0d9L zW?LuI5qt|#)18i}U@0`7q(OP0&cx>oW&YK*fynLG9e<++z~KY}VZ(3X(5396qO*Q? z4CWo5Xjvsjt7L0xwq&#L);TdFK~ZE=?R?fazjB|bs*~Sir_jj zTHCthF8yt)pBZEc~u=;IRf%q+}i+3a*f zIxI?R?Ha}>OsAOYeUoy%^l_JP?L|2H6sx(Z>~kvgVa)Tek1WXX;2OpVOC@ zmV3yutMaLnyUu&%I_y|@GHfAGog8Qz;h&lAIo*R|<$Rqk-JZCQ&uo=NE>`aL)X3Ic zeehjAVPeJYbZymo(;cLObZS!I5&>?veYZlla<|A~q_-_XW`kymv(D8@F`y(_N1#*G zq<3lSwcO$Q2$-_95c=)6$BWb$uGBI2mz91VdlO!hQs=;6ovA|Xl(&Fx-hKt*9h>LX z;l@t?rJY+$+mr200!K8eSNIo$j;qguff4LupA2~m`1G#^*X!G^M|u$~3>Vjbya+l< z7E)<8xXl;pTrK_ltYrxafJ3Iz?wraA=8i_E+2NSqc?`Qz24fTLmK2=#&chupwGE0$LXDJcX0#knJZ(o_XPee`?U^8v1!f+FWKS$)R|GaRl?-48ApkKhW`{?DRn5fa2 zHLlLDpoZ&aqLe&360&2v$~-BUS6shCLMS1e?SQW4B}u=t%sEN3Q{I4k_Ox8m>)Z}= zldN+WIrXS6^-5yrC0psAnE_;Uu@Zgu%L&QXrqOi|*d)Xd*FZ=oDUS&{gf*_?_Hk5b zo+vY@&Gp#P!!Zb|cjyn_$a=Z)p|b1<0k!xguL1|KndNDL&U407!!EW5 z2O$dHjA-T5qdUttVss+YJJoWM>>dKKXozgAA0T~5- zsKZK1mp^((JT~rMy5D)L^p5F<{&uu?h;@(pgc#6GSSQrUp|~#tA~_)U)Eiebh6sn4 zd|nubkT|Z>;8?oKHZD|z(lpj|$jk*w-}};d7=$igOuY7cAfqbdOva+T2E{GHsnlNC z5i7JSoR@czH6l1@jMpGA_zfbjga=U~<*g~xa91>lLVF1H3bApF-t<#h3Mvq z-Btu!O(mi@=25)&Wo`LCiVsidOLE)AQJB`o8nzw*W|(UT;HBk(M+W?|6D%S=qJKWU zTbyXm{#MzRl8WDxjOHJG0+!=?QxQ_~{?P7UdC-AWw1;Tn1)w-b1Xx5cIfDf_T+$@b zTYZekiz8WpBGpQ4wZh@trO_gaqTkLPuC!WukZK1Zx6h1z6Bk3N(bx?_$?q;N-XQ&vimU z%|AJeMcSj*(ohB!rz6} ziWbX615s;1KQAhb)$o$Ymc`OjgFeyw*PGS{GH&G*_IXj?DM9vqh02(3(@Ka{(=@Aw z9j|mCWWuJaD>)8$onq%g98-NoDq)tdgx@U64*ZFyp<>g+r%}Mbp-ukjPpJhHZHGZn zp%9?9t7V3NjPVH-khA@|qb&AWl`zbnv?$1q)zP8Ej0O@#+JRB>P+!a&mF$ya$XgB; zJ?~70eajq&Qc~DZbPF{Xlfv(Q%9f-iyjbG;LOif9N?ZzO!Z8FSW=0(N|3@x{p(;~q z0pVO1UTO9*K9axWYm{BVNuKwdSL8)HuJaUOn6&p7UP3zeEV184oI+7-fzDdT?!YP) zotN5OIUxfP-hjV{UwAFTByk_^jPch1M_fuL*hpR*H!v?OVR5}tj zeJe^Pp%Qt*?J~e0e4$)a&=Oeb?#qj!r6IOFoz+Z`kJdukgNnYOHtBh&Vdb=zT7x<> zJF!?&YN-C4Z=2=J->x3Rb7FT*Q6X|!Z=8s~%W%A==_h4ajn0FdA-&ZnJ=iY8Qu?nz$~ zDN2ytX&Q)As@b$bMo_$oe1c0w@^!lsD==mQXnm^hSQ)TBVMG=+Lq1`XHU$}zrtKPqbDroG9!l z{2Bs1PJr&D-6m`)77x6hc}Rla5%(A2y`pACT{m)dKDZAT^(xg^l2cH&Wb7W!v-DO( z7M}u#;+D`uvsXu4$`=$`#VWk4pQuW%5h;FFocuQGo3U$YsB8lPRP#)VKZ*nTzBuAO zRD6Qu;I7@n2^^GnV7C0nC%#t@-I+KTIm;y9=g1cQ*?Ej8!x{qF1tKDo(G~FS`@bd% zj7d-I!`Q3H2M{5d711+9Rl}}EOoJB{8Y=&n6V4&;zk>e$-1rtpB>+t&TA7UKd+E`w z_bsBn_E4rfuk?D~x{K!xi*#p3ZHQX=g{_{*0wX`ZD&v>djqrb@>rqx{zdHRBZ0ns5 z-a$JAK|6MnwXKqYNC2f#)1*)nFj4Sd!TDdK#PxqdHlZ*xh)c)UQ{EsOuh_onB8pEf_c-qP=|JU_@X>mRm5k3uGkZCCWeAxdM zqj>&lD$&S&a7oGk)_vOY_CMPHS#SpI|5*6{4~zc^iT_T#|JOr8J|;!xrg;3Myg!ZA zFAQEb*7=ACMC9~Ku7uPR(6_B~3UMILV3OC>P#oL90L4qk+9Ue%XOKHiyZ3n?>a!gP zx=Zl^*GgMa%%t5a&Hbf?*AU16oI{}CjFU`FM)s@SMa^*Vr8}H`{K%th9 zW1acZ+f8T-NczEq`_5xlbtj~vja5)K2IE7jkI-wSjZoZ8oD;n7#Z;?fp8alM>c!Of zG0W?dcHNy>c@gqq@LG?0*4_9T>~xM4B4GBRZN6fTkze=3(rQ^f9;1-7!m541-mcx? zDW=WR&2Y2F8ZBaKz>a~j@MzfzC1xR}AfP96F5>D`aY~a`u>&Q{)zQB@{Oa2jtbsGJ; zH!UQB-~-9c9n}yEdqzRWsiopWjRQvJ%#hT4rcQO7Z2+P?>=QmB_il;7@re_^*2ns4 zkBO0D$?%0|pywHuklrzyZ9&zYiP@CMv-P<8$YB@#T2Hy-obL|J+Ln<%-2Im}TtBkp z7WQT7NL&}_{}Xu>r?1EP6^hu|3l(Mm3&xJH`E36ZCk@4P;6@}&&F?uT@k*m!fIZzvayWcC;}wKjH^azn*eHqzDAWskV8Z zz-YTfF)-i*mQq-d`1eNVUWS7Ax~4jF;_xI*>Kmu1M6ac}=?Tb&<;&3zUHO%p*S!^J zRO!Y}AHP4GvkG!0X8%wuA(gjK3Bs3|D!*oHk(_OUR85ePlb75MHs{Yq{;fyoI+z@- zV^8fbCY6?24ffL434>&WYZD4oB;9bF!%XXu_DPsN<|J-oS&t0C*nO6x5^xR4(32n1G|iom@ZF;tO_bXWj!r!}L^IIx zh)LECqKWo1`BYRA|IQ;q#+6}X_ji=Qwc-4|b!X5aVHQlLaG2iniNd{ALd&9jRI!yU zJUxZ%cNw;B%XT89{b$8Pszgp^XrgY2F~WTZ^E$uGX=+A$DB^IqVW11q|3N6?w*E6w z0pjZ^2-*0`NUikyG%cZ${&a)!VkU=jZ=3FycnOyYx4&Ju47E|v8~#m{){g3sjXRK% z+Dt+&3gnu_jOxOCZu7~x-5vSxZva!vrRJZChVWevRd+Zk3;n|ZV|pj0)x#^c-Rn-1 zj@{D`vWiOyTup(3QX5N6-hGN)b zdbSWVcBBlYU>@_2CBt2eN4~s|--(%so!BuX|E{ZH>q^~gr;qT}jX>Vy9Y;0#yMCiS z$eO5d0^e3u*gEs%dCrZ$c1+4jZl`~ADg|<4o&J4_^ZX^^D#n)h&O&0Dw-(YqDb+JF zHMG- zvz2SJQJ|^Lo7eo;j4GsRZ{qtAaSI=LC?X_d`39*$_DpzMm;0T1+Z%l|t3m&3!V=36 znhelQ`zQ_MhhiY|L9=Y4e~*1G;;+EW3wU=R*9Yk97cv33Bb&wR-vu5 zuv+aONnR+b*)fdH^|Gw~RS*U@K_RN;G2fTF1|UQ0mn1@tSBxUUPBNwMypSv_4D#Z| z?G3Cyn_^H;KTG|lu;-`2SWhev{)wbSUIBkAx>q*Z3!@|2@Z*d5`{SNT7#N zG1WnKNGF-vff~G-CxrS5%ngV=3J^4!jzcCUlYXn{mtde)*nH1f>7=tsn=YrTr3ct* zaPBx(1`tO=eKy+*T*7PZKA*O#KfFA!Rq?l|`C->NK3If2vCSM-0mTzsF& zGE(hj-+UVB5-w>K3xSsMmT~QylQhEB6Li2Scvho5<`gc+PiER*RUTw~*`H6?j;wb* zn`qoScKnW*J2`nCb8TY&9jghgjT6v$uBvT#t@QZKLu+>UkIA8N#62*xY%Kmw%41)% zH5~TCpXmpbr&^-v&NuPBzB0?`wZ!ESoFq`zN-KF7u!KgJrajqw9WHw((*J7rXtfml zS-JBH?sew#^H8+?`t$>NCC+S)8$fP>ky8sN!5~gTh=Kp8wwYJB@$dd>gxp1tM z(Nrb6(s29fp1(9_XH82|m=8!21*dUy!R&cZ5=BDbL6$hl+#gu)wT25)s*xk=Q8)V8 z(}rf$CgAl)CwKeTZB|YWb)r>vT}5tCI-UtGA%(=p;bBt0VcX5WInuR*(-SR;HEa>Z zq)*g_R>>jI_z0_Niu`!W5eo+iL2*vWC(cmr*S`dfkp{(RrFrhfhr^UI9D~9#!CzbP zoK&dMN$`@4#wAUd(OeO+dMFGc$WZ9{(7E0Slp7jInZ(M8XJOS?sTJT5`~%1$EwV%s zN!t*N17~T69!(W33U-{m95W~+;gS7tKioH93UXvl^NF`JG)I- zyp=pS>U5y-nVyRs&u_5bPb^#c9ej(Mh_r^qdL(@7!Yk`)lB|G8l&4DULCMSi zg%S23Uv*lHrB2<$bScf_FFUOK@^%nWt2RLEo0k@q7xukuI&67MzU;3{BW!^z5^c1y z4L>$Rh;|2D!5(M(xge#TGnbU7|nQAQZTfa@9d{_#Cp|I7>41)DRn|dvsHOXls}WguyU*iKN=Q`Kk6z z!z)5+=^59Ieh&&bF`O>Tg1#Y1WbcCiFoJcNX@=7mbOs=MTrW!Gh!~EMq0RXuV(LOb zVaKx0|KJaz4zbd+O%0`YqiR7rHjJXtB9ImP@kq9+3@fiDHMbI|XfwhxGA@j{jWOva zye?f}U}l&kBZyE<-EPX36FwyvBU2sKtiL=pfYaJ*4&6s6&!qP#Q*UxtS{ThKr^6aY z>_ScK{bPF?_kE7G*^9f(2RfSlq+Tf8!(@${%u5=4?N1rB7pyHQ12u& zKiJRbGH~o3#dqs{1P7Vz{V#%-^tYB~b8X?A%tnAx1uE%U(VPjcLjob6dWfQ=B5FfT ziLaXCDHe;Z71@4&)}HEc3Ml%|SAl65<2+!h2?EtW2aDS&+lALQZ<>MJu<1crPKWKt zYo~!mw7+F;7V(#Hc(ivt<*!bFXjYicp;-c%213$U7Mf#>)lz!3Iaig#9?ksJ<}zOK zzpo-a?MY23!8llKi{PJ-7FK5t(Pr)Q8Yy5!Wcs5)3I$m@p(*dbbRKYGi5ZW7jz>pg+2QwtZrj33KjVh#cJ$)bh5Kh#{0d^8$ko>6w~wHE zBIK7TdGPhs&4CCk9+~P>kXRyUgh7f&fL-w- zA19;SqhYZ8GwiZM!KXs|SFx(z7aV=10F+Bus{jAW)UYi80nSB_0Kf{?U;c_P@E z1p@`eUA2^}wm8Lzy!~XCdiF4Xe+IY}QID>fq>D~WPDsO zr})NWKT{k>fT1%OC?iup7zlqKWQZCgIO^ApTLd?1!oDZ7Tz}@}{0|4Q7ud z(InXallECFOn?+N)~s{DG?){{&|D4N-})^HFpB#1U&mXfOE_B^OR`5W-JQ7X&prUH zSkxFPhK@F+Z%H?}@Caj7J4lh3(|=4(Fpglh>^nY9VD(fHfwjsdfrDL!$%L;+{ zbz%4?2UULyuqO_^-31;_x}N+eMPFAs+>i7OM3#|W@|CoC%QWa{O9pievO5}3@CiTh zf>Nk#Zm8pxnM+UQKno4)zwN`x8Ij*W1R^Ew76a%M1qm1#0KSvcCdCOYJ|X+MjRH~S z?hu~+{#SEEo0%XA?05{(>777g1=I+@oeLLWdzl3_!EF`C$({V{^a4g1+_}4>X;J%9 z7734@7-3VIz@Y6vTvJbn=d;Yn&5#WdU2v*(R2Xh&4>~|&bKl9YtMb?E!f#hWai%O# zwECxzyNedgNQP|al7v`r#U55ih~yC`!2n+|fSTIJE8urU$G#ieo8ll+ud3XAbgDckv3hFdry7gvsqK@KXGK=`>ZWE&RMZ+l~_50H?|%iiVW zoC8JtB`%S5n=~CVONBMK%$_2EQ^h~x3Q^&(-j zrZfn_?Gjr3k^We>vF@?uf-#7Gx?0JkgYQ@s(tx zw?_u>915w#b)Um~P|h@w!~_do)02*+!JAk>0e?!SM+@npeBCSGQb}*Wh#QhL z_(GF78Eb}W3N>|D{9WGSAq9A*i{0nh9ve&sx~+>$-D@{0QHlN- z%z)mBOS>J|CnIDVI$<>4J@TXE;fZ<^dDQRv?nQ+MjX^>nBn5;Lp`^}<#1EmZ_KZ!Z z!&%`02hB(i$PG?fz!UUdB{60b=@rIH1Cl|LK?L+gt2lmf#My~Mh-!_-g_rcU9(jms zKW+VF@J-j%+9u1j{>E%4&c6a<4#VXU2NI;<-j)j|g{s2~V0-Pq*{=*(2jMWMOOIl^ z&3;h6HW}E4 zW6SDp>EH-aJ>xDQ%)k||u}o;nFHn4CQ>W)o10hi(%A)acG=!H9Jeu znrdG687j-)-@cUDn#wXL?27Z(a=?;?<;l?+O^*21jZBvU` z6jzg>K@&yoXy0T6Pz&B@3C)g2135L^v{njYTH$&Mqe=K3;9;e3ZZQbPeC1C}1EgRb z$eqk$Jbq-fR9n{-E07WKhkxU?8BU=5x`JIyXG+0vKuVN#WG0>DoQMDAi&uP@ig|Xq zH+n(ZK$3`HSTfnM;m6NDI;>T8RtqIO?fHAaSmV9F5sJiM_i2MMN)#O0+QtbVIn;C$ z;fQkG9L$wOw)E08wk0_`xUsunBBV}6ZqrR0#rb?8?%m=-zgN^JH6(|%9zgZBvC#c<_Q<7Eun~zT7r(^=U#~)g zpaVU6NqELbg;BCGNP20Z+e@Dq z`9c-iTplawMSbmoi!av45ZRd| zhE2Nf5(&xDg}=F?-K`QT=oMvCypbvj3-R@2qSIG?|*W2i?r6XpI-1lE05r{`~;`Ev(G z-z`$*2WHBsYaW08PMtOO)Qn{`-&Pl@G=)UK`psw9IcUs(g*T0tE z3G_|=Ijb!{JA^VJ8H4m#weq#_tv^yIP1^bPk?a(U^oSX->d73zV+%*&@DnR6emC+y zQxL)LG9jmEJ9)^jR-3iqHe3qZ#Y~$<)gFe)TVv(&iraF=IY*BCt3UBF_gSddYdj+9 zv=q;mV);kWKk{}7tQIPT+x*6jQGJf*N6&**2tObWQ zx$^MJ5N~!u=wW^Aaej5f%o{NhOMMTpF(UJUE($*Fr&qD7-@j-X+V?M0X$VLraM(`& z5+^s>!0pCzmt(Qn{BHfogMXmrOYmL=EBGPtw+pi{VAJDcE@PzLN=rp`F4AqxfC6(IfYGdQGCTOMG8xD4 zk@?Zk1y_Dh9Xv52s9mVU{@wFYwwd-HiS(mE+^^q#G%{YkTUkKO9E^x78_eQ-p^?J* zl6@&HqM-tZ`IzMY`J(L}fl?Ih^LnB<7Z?Rj#1$n`{|yrr=t|VTLM>t+XQ`H^bEpB^T$z)qH6`L3wlWQy zPVowjkky#x{I}%t^QsLnOKY!tK*Q^JBAncCf2P1>az&Z5K4MmOw`$k)jC85im4wuh zQ`~R_cF3~`MM-Muf|PA25eMRW)SNuI1oKj=EtKL z3cAsbdR?r@jI(H>lt?jDDIc|%out^@W=G(JI(&Lwz2yp_*Fa>N*W#?Y0eJc58MJf= zEk-&??Pm6nUpdWm#W4dFsd+!#&0WVHj+y_6otw(FI5E4GDvhPoLOeZ(B5n7j)Cxr6 zv(oA*OF>fqPE(@kLvCYwU1m>$XIz80ZFpV}xKDDjG%Py%ZBvKB*GZ~0E`q%}+kA<@ zIUpboKl>O{pHKf08sB*2rt_VSD~!i(C`ljNCzLdtE0#59(6loxMQk*Yi6 zp99mJ8mEZllQ-0u$}E%7 zg5i7O3}zx`+7~EP0=OuWLe^_3$gS84lxwD8d3mXVOIoQ$AVn~*&3JuZc9@5JvA44M zkLEakoIhdgqoGzB zjlQCIg;X3jma``(t>0(<&7332lUKrDYvgJ!i^g5q>-VMK^x z3UoO+|9C2r8kIY*saoZJ1An#0BHedhUqSD2OLx|LS+L~yz=HjO9zP%2BtJyE9QN~&^^`Ogya)qDC5ktSc%EmHwHW+s#0!Z#0K-ouv#w=1y;^ z&3NG?PESqLAA9u;#a9m12S0WxV|fYby%)f9jZ(g|M<$L7%X5m#cr0q>3QYAaoU4~5 z`*JMA$C9mqHMAtOYoZ({zbqzsh`oxIDCb2exBFeYr4-5{5MfBZAKxX6C}-LX?`Pb% zIwm?8_!09d=_JOt?-=bkUsZUu{zPCJ*e)Zk?UN7IN~DVu2eweBc@=e=nIDc!X7-)q zib4fuyh~KXPvELfpF*k1E2~TO#7m_sj|;tH=+(qyO{1HX83^tedYy&k7Q_T7_*yU} zOtIi5fVvWA?=;Oy_)}o9E#J*?zkh1DgS#!AUqCQg#&8sS$7dH4H! zqmivvg16l6So7Z^8vncxR^SZU8^hk6Ue6hP_KjolKq}Ld!*D|3Lyr_OI9)>|Vl@^j zX|t4}M>R)u2K7)FQ}=O!r?>LoE#y|PZ2?)#LD2;OdlOT=o=x04F^e)3FVW1sk`y~} zxo3)7cw~ke*QOJ(78@p$Tk9_Lg>E<%v5ZWLKci~dmg*22#(%v8i+N>vJcQ9t8a46` zZh0N_u#aTCe<|vZku2c8>Q~A6{6pm*lDzu$@f8JjPdudU2O6&EBe}=Ga4t2r6%3?VpZ^fn zixq2(E%=!4vLI1mvl{jO#K+%939pXn6)NjmrKS&q0Od9Ui>*a>+PD9=F}0Vw%~$^O zLlFj;^Umo>`wz98song1s)OQGnU%B@^;SdXm>H(lsbK-R>tAK6t7mY*-mGXU*l{Nu z6^jyikl>p46DVPCJIw<>HsvxA_{uq!`YVXyS@l-_tHDa$Ys{K&LaMGgaSxVeXP@*ET{EGb%O!c~af4>Cr7?24DuwsEb z-7ru8bafnZPX=?joPKos15wQ{SWdUiU$KK-^0W^n$e)m%8x)6OFHwYB+45!eN?Q0e z6!`~9p=!eLF#I>}8gJ^UORAX_^r%bKp}2 zRt_)qCAG}YCw(X3IN@9$-j*aRiM!NIKyn|KjPiPg>YS6NnBd-pP!JTMg~73fS)-{b zV?};?{m~l7re`+FT9?m#%qhth!h-v&Z zQfI#Ye>A;!Sd-cFKCGgkQnD^9y{L$+A0dEr2tk)sbSYVNH9&w+1f+&efP^AKM4F1y ziztFh2{rTphH4-n0YZlmLJLR=0Yd%d`(D?32>j8PrDuDoevb9m-jg%QxZfS5hi<1TR8-#h@6D4eA*S{v z=D|6IwQIqIo0+d;-plu0w(q^DI$o)~ZkhS-NNwdbB+J6%?C(O3w*_;!?3X@2RgZX1;%edHdC~>AbRH z&K1k)t{@SyIu~|lbo=>#MUV@hw0f4@*I%W)NghqUE?a!&Vcvvhbj`PSVS0FP>rC-v zgJ*$5e>rITbbS@lkNqvY+=#cZ1cbFWE0G;*emX1a>K8~Iebl2~c|T3P12zqDd-mq` zr#mTsIz72}q^g8}E||%>PnatjJg5|S+vC>h+_rJjt$D!1UQ=_zG)k=ZtI~#f!Dai) z>-U@g)Qc62m5O|dIDce5=N2}Uh+HTOHB^R}4$&X^_KGSx%hO{rs-sV)KcNAJuLH8) zU6lPgID+{#az}pB>dk4(!hy|5bgvK2xZ0OT8$`ceLWW z69Q*2i5T-4lh%D|Kpi-T==$<>&(tn&xPzfnB}O!zdwrrK;Laug^uG=Cqs5~dt?c6Q zD9&##;z2eQO@pq+ZdsKD0k?8ogbW)*9`zX(oHWnA44k_6PJPYxkL$o6xz)qITSbc1 zmQSZ{A$l$qUhO0FjK6DGB!-+v{E(g0UoVJRXBL|ZHVvnvdha#8_@uR;*ptw?aBAva z_MWB9wrI$5!=)cFV#7mPzJG1vdad7X7|~6k7(T8hBki>xKdG>L{G`nK0xKZTFsW?D z5E;Z6D|aQti(XKPS~GRGF8+J``qgchoev79KMg#E{bTYlvO>g0Y^pf@((K>PaQl2! zBYossBahb@lAOz1mDS;tt+{{UJ-N}lUJ)3+1heehd+tdY1or0v1+R66x4J155G=a! zkI5w?VhlP0r!|#qQh2{@DON91WnJ^gbJc54)}-XumB#J@?tgjnj$P?ipkDxbT>K5eLW zvN6R+0P9y-u4TYXcL`^&kh))$wfIjtkaI|RQ@gcBKK_Q=cY6yK8_R?R_Si#=6Y|LK zej5EL)Z1X8?svlSTXhzk7$xg`GHw8MyU2tub*>qV8qeSO)V-rZ(5VcEeAY)`P@<-gcwH;)<=?1g|m zubnghiLh&&$Y?Ll5miY=dziBSb-0#e@a!WIOijGx{XFI0eQoNk8lMsE#wx?$FEFz& zEMSS#B3esngMIVbZ@;&>x1Pi(l0nyQL0T_V>Tq}(asBVoxLz~2LAzR8mfIZFdS023 zjhF}Fbwzv*DYC|D@j`ENnRJQbP}&WnblvrWTMr$+XC6`5?Kan#lbDrHCfT#wqC|~a zqBibBdLxR*4p=F~r1P)dy?b2x|oTo$_S#>1`mocB+)?)PA0C~l<;1= z@J`r5Z3mJgrEoe=eO^9YU2{okIbI~m(a1CV)(Rj%1iLywu#`kvx@Q$@D*6q_r(t8M zolBZYElw%aU>QUBi1Kzrg=bi?9@Zn;w5NSZTc2zc4=}{+E%_REGRF?uJ;CI$05!7a z0Z>?jGfp8F&wL&Ol|MGng(b%4_66zVZFf>YP;_$0SKcqkI zuuhJXB_`M5dR3Iv5$W_kX6TLVOh-QTY}7saP+C;%E^)Rt|%Tftc-?ryE5h z-riA!;k<27wu7Bt#;Da(Zp#T?=tWCY5mK06utv)uLWVhB>E0f7E+*9ty1Y|#NRqpG zuCvc%%fpB9@8-X7HPKewlwZC4viv7v@VWl*3!Hn__~9FmtMeoGnxa4l+Xd0~9i4|i{PP>;93_T5r7J8#|I#}_ z)SA^xvc&~wNf-w=VI^}}=`@t3aDTYhZe`8Y5guNZBOa*9{B3XRy0TBa7${jz@e=u< z4n-c>&KhICq;B*G|FjADZRh9%F=Rp_^t)}OkFXzmX(OZSf2!Dm`f1zL4V(pe1Sb$% zlJ3>)X}BfrJG1Ch;xu+U$>Egt=@l=K#?%<)3`y4p>*80e7bO}yi0qk{kAC3hTrv5C z42$Og6FI$CHrS?+%H#X8W6S>e<6A|R5IcD9n$Sx56x%ajW+_OX(iBb6AD&OxP$5%- z>Nc#VAa$*1h2_GkfueHk*qNkKoRIAnH#lod*L3-W$rg_6hh!=tyZ_<$fA2Emq)vuc z)E7nn7tJ?3MlHmLt} z9LQXpsj_h4%@-o8qy{ zS8gG4Ii2lmprF$XfA36AXYm<~eEOM`mZ=-aXO;-tDL0#TOLrT7U#D6|EGPa#4yD?{ zTp>411nZhZ(Pl=gIP`*_Mh9vb9}I~{``Z*dEsC0%C1c6On&`6|hcVss6Rwdx*D&2d zz*3iI_mqekyq9n2Z9Q!(+6t;WM2!T=)wiZ>f)aVc6ysk$VD^;*a0cS&*VBr zlEo?Exk5`Pf6Js^S0*}#>9n!BxjYfQRE~}!=rqcrGIE&7yRupN8zAVA&j4+oP6<*} zcrw0|wgqUfslB~Cp;QHipR_8`j~ug;d`c?Z!Yix&11DN2kLSZsT0M!#ONVl#1WkhK z7(U2k@7GKVAVBtFLsHYVdd2`3XR8boWuUC|b6VAvEPIpCb9OM$B*Q z_T)B9!ao`7`dkSiL(a+oNxGJLcpC0D%Jn}YYKUc0f87`&4Boiww^Cg&uq=ftC$gh$ z5SCsOofUv*)WGJOtCM0OBYPaswVPgHOv=sn4k$)uGe~jpDP~k*?LGAA zX@)@0)t8C20?2xu#YqPSHh5HnY?H$2WM&Tftt2Uh+-mcfR^X?XFp|;TyX6>AgA72V zF@99Dg=A`0X`)K0Gz38MFqjsnd347dg&HunwJosq0^gF2>jtD;K3nngSSvuha91u< zGFk3Y=WzD_-pln%ep3p>q1X6$BycJ_~FZ7{w)7< zu3hcM3Hh@4oUxY9T6f5rox=Q>004Q)gWx4SzXxjnP-n$XhZ8jwB8eLEAe~v)lPNQ& zr%sYQi07ZLLFPg@rm0pzHu222uOu06*19}9+iAC*yiwiSor7JvJX24`N4Mbyg2sfgXeYxb=nqqP^uB_N zROy{}l$-N2Ip`r9U5}~1COcM}P`{M6F+R$7^Eb31YR$!WFx(soDGx^QEQ%yN2ry7=@v*@^$ug3K==TEcvU znUNaFve~kNVYGRr4HP`yXO++g%MVtHtyQP}be9>%^@I;#ET)`fc5`)&gVL94T{8=$ z4!NRI2I)?bWLOGyv2b~5>t087d(NP%ZW1Vi)!s+&l4AYkLB#r$5gi*=lT6c{##|$! zW!+>LAquw7sYO(OZ~d*)9O+-if=HDHeFi&CfH$tKDF0m8jzhQ=fVJV7@rKO<6uHCCNQd$e`r19Iyf7H!~j zV8(Yr+PumPp#8On;Z%}0W1Y6fKVTgimDJc(BZgZF%-+0j>TX|L1#cHuRSL|~OXkVv zDCEceI61w?cdmuFb(~et&_v{vV^}=Q%#xTDC8zX2QQ0}`lUyo4h5>A7#aS0SPCEF{ zp5XLVXigUXcUp8zwBzDKJyH{UK5+Ktnp9YDC8(zYxd1NbptHg1Y)cr!_N?G+8fbWE zxA^WXy&{akZX{=l$sG($nf3ag@U`h2+P~RKEv~^w&T>!5<>AiQqZNp!-Hpd!w04++ zW`@&H4n>|4_Kbg{!w2K~+f>`Ug;4Ilw00$N8FEt+NnBhmt-_~bwc~HSU<@++>fm~xdvLh?PWHP!$qe3F@< z2T@x=VR+0*I@lYWLA=S2V09wTa`oC)2R0kVMt9O&O&<|2!^wYP+Ro|NmlLX!R4P~< zWhOfEyKz5!jJHcUXz9f_?#8{r#AA3b5^yrrKx%aaijX$gL5k3A_Llb-Le2heHn4CZ<6@AncGcIWO=Ruvt?gt$cO{k?%8*8a9dGVa@O1x2p zs{n%|Py=2MRI0aQqotYFid7!{rqdLcTp~uq@&6W5IG8h3OO8YqjURNT{!P0%wrg9$ zLN|M3TnPZRAU^yWL^|&e(c{D%{OnG1?iBC4v;?2fZ6z;$H4@^y4z;;AB{=+Ia{Gk{ z+S|xSycSmv@tR7iw-dDYJ_+c*83O}Wd#h`|09OE%01$Zs8Djv*L!=Z7K=%nam>%-~ z$QV72{fm!293$tKYSzK!)J~m(RnHa=)wFTYyu|r-`zIV5w*eUK^&_HI%J^!wpww3P zXp2tE(q(%L-rIXSSynoIb-ZP4b=$SYg?wShDLB7r>6?=kOem~mpWQB622RMV%jIWg?kcp?pd#}H5K?b=}!O)}|CEYQh`Qx=Zpx~#Uo3F%Nc z(&9-Tj7xx47eXF(R90&{LtFg6fT6?-AFRJ@#HvC=ib^tP#2rt8jX z#}sr);E51NY6%o%B@6ADS0x&*t2mdGQ(B63Om3D5OQ9AAmT{|(<(^pxC9Ch=lZBU* zPgVJk(LguXn#|H;i2@>flWxN=vhz`vW|Jqw;Xo{B$XcPw_4hz&w+S7zTHBJ=^vzyb zL~Cy;J*TI(`weDn&!?1ChkiE@SxV<)Z(NtA-y+i4Ih^(;;V80Fv{+BUW?Kt|>+{Gc zH0dzQSE(yL*-dAw7nR1}hApe9M9(M^JZ(!l{NG@mR#XtV^wA)6ChvM%n5C)rtgXA6 zA}CzG{ep!{lnk6Ga5sOx>1EQ9l$9Mr5RvO48YpiF=fj9F=d_^pRr$T4h6gETo>%_1 z=R|0q{$F`DDlDZQJ|W^UPO`sxoEWme3c$PGt;;{Gh|oD2sDgHHShErqPpek)h3@vD|F!hIwD1B&E(l|IF%@nd(g-gMYA`6MMc z@zMsU3ei6V!+Tf=P2;OkelPF}oLi7f+b;mNTmFq@bwJMKHS(ocVi*G_mSOV88X&yE zb3#X~fkC?Y@~4-=iW+9zRm0fO(nW!BTC6O^%cj^g9(!r504&doJP|Knd3AYkBBj|>_Ei7DXBQ~kFLKRV}hSe zf9X`xx$xbore@MY^8LpjDTF^p?=GW7C;dvxilm!Wr=KM*79m|RnlT~HegD{wubM`|H`s`nkTno=OcB*LDvip>-} z;KiW|`L-%Zzw`EY4H2%+r&letS>mZ4j`Q-&k56<&aIyth8a4>c<)xS=p z#49&ATQWEJF5d}aE$0h2rl5Qj9R4Br3%R!n%=sWJ1I!?XO|3{N`01$YpQ_wDwG?p6 zC2I`Iu|W(V@=~ZJVrS#uR0O{^6YS9LOy4|rrV^YN+?;Q3MYbt+jr;vjQ~u@~INy*H z%uL1b=N{hTH*>{K@wt)kgiZlfM?_&oPIg)Ux4lQpmH;uNkGh8=z8@k&qAMdDrfi5O zArqAosG*Rb-k#B%v!^*)NbO{h8$e~A5%%v}qO z{tdBAk9$TZO1UFUL!ZX>*Bb#+R^E9_N`rT9Vbu9V8>DT;9}l70bAYxbo4PAJi)N@N z#CQ+yn@UwBycQdutgA^cx@_TM@j#$^kFS&}!Cg*#BKQHCQlai&RI`pA$ zIYYM*hUDJ`LKRv#DFR8HWmLeaOtwqaalqDk9<=I}xO$*amXgLv8hayNU z)Fpu{NI7%0i{&*68fAf(XPZ8~(KV^=rBn~_Yc9n)NiDpWqGk#)+pZIf_f2W@+ZeU@ zocI>kzaZI;hQsj}jC^cx9iTeC8+XUa_m-obje{*Fo9+eLK$2^$oSDUO^-KN=e13Dq zM}aJEG!j&-(~lxGTab2G>B6%aT&ZO#eY$2IwG*h)fVUzBu4~4DwvN92WJkXV!K(xG zwZ-Q1^a`BXlVcT-$)&4#y7FN{L`~5!nrNvsu zPhNI;oN0K?@{3019yV$S*uN#SAGjPNf*Xkh!a1=L67S<6m#E zvu49TXp#b=-)x^r6{tP^bbHlakY*_^GO9S`YP?;;TSNK8@;(Us8rKF2`8`X(_WZnj|9*qH+EEm%ojy%n*HhPPt`PFoZ#ZgOf#Xz9|#=k@*Q8mq*=N9EflyudQ`?FhUke}m_ZM>^(8#h|dME`m4 zR+w7scx{p8azlI;3HQ1lypp71d1(%#>~>GME!aSTdCu%*Th#M={b{on#Bx-s3g!DofM!wOcg<($+*h%!pNWGL@F`1FPNOv>NV z-2q^+$k67CF?#%j)b*;|a^V#UZoy1+mUB2{k{`K+k&e;@Xha-$_v^jw;cmD#) z*aiotg#@68eGxe)@~5WWq9Xp zI?w-brF|v2-vm_zX^sb(uXir@v^6+SLDYO37Y3;HvkO(JmHtZ@SQvYBA`sayIwA3E zfRZ*|AC{p7Q*cmFjI?f8!|BT271M1+Rk9h_@}jGsepZ@<=pfWuxrb#_=gX!O(&neCJ9y{C-F-u_+m@5;`lrK^h7!~RH#;er2DQAd3p zCV_4Va}(z1 zUIw~=LJh6j0niwZ`=uO8pW!n}ddJRCkP~n~;0+d-r+PFU9PGI`Li;aOecG8#YmZYG zNvX|d7Fq9Jw64j&?B){Z0rK<2*m6O!C|lo+1}FMJ84k%z8WMzdM81oeV>NGPt7 zAI1&)oj34R50ksQN}&FLNWjaaU%8gXz*HlGLn0pa;ALAQ-oqY5b#IkOmOymE z`;0ahwtufcmF_zKP+l8tZ%$i#TQa$@MwzwtZ>9ZNueBhWv4Y*avDfv$VPHaKeL_jW zj=8FpQq!RLOhccB9sALfCkpN7bpU^r5h34t-e7h2|7fhu4qrrI4~nGhjuuFG=IWz` zj<(>gt#5)AnaWR&I+r$4BnY6ITZkSnDjk05duu{c+8~{XIfg>oLUYXkp3L0(5_Ow4M`ruEyBW zoIeAMr40kGOM9h~Dso$?HxULAaHC%fk-_x}3E-frJeQ5GO0t`#fLPsvXJ@GwJ@K(@ zWYt7@*GiS4QA|`=TcokUk5{9VGUrwM@mD$#I}h8|=D%mwONC{ZwzvmYL3Bp3xyUfv zqpzFn+Efjy8jn6X9jrtFlu52Fwe@53z8!%MAHZKU4HoQe{s^+72)qlDE@|j}M2HaI z;MXVb{x6lH4AfOn)G$sW=9D9FdiO#WPKJfSv0bC9=h|3)#ED#3Gp=cd`0Gu%qI}P` zSc!Y%?)SCN5S_{f|Ae{DP03)Eff-U?3Xd`*<*Io|UQ$;>Aw=!jBK*5=7!FP zv!aP5+|JK+KWK^LDZ4=5cULbZG5!|Y0YK*66zP`es?uteN&IxR!!HYEjj$e z)~LBdc3*9LE0*)u<+-J6x%)3S+vPvr-6CCbuz+y=$Bbq<>yoJgp$6NJtY(i0E5U5w z-I)OJ1gUU(EO(mDQulS4fK(%Sd*Ci2BY9Bk-|4qgyu`+1?W2YD-O(Z<^`S7ZDIq!zpLBsd? zPhISq(IVD+^IfXrPXDVoO_)pydQW|6r)Ib{NavRso4|EPUugQZd!%(6&1w{@h$kEEBm>9-(JV-MC1^SzMI?{T~By2R|CFyAC6##;3 zeX6nspB0upN*ELgnEJH0&@~^T=-fbXOFIx(HzSk`SRzQMF6J7vAA98~jQjG&^}CBi z>gyXJ+mgbcLh5Xd7dy#QHzMxXSFLNcjjz*x)C+}Xv{fGj_}6~>iC9k0;E1SVBfI*O zYwTLtTuhIRJSyaraBR=vLd`OCl=0X~ElP8#GY1hzhO4Gj;`_NbkdeFbdS+pfI=q0; zg~Q*mfxTi=|14N;S!~LAXC8!KZSY+_{0K+_BNGY#LDFw{mrh8;mS%f{P&-|ErcIy0 zK5^xkGm<-f1#tUJCc75w|7z7k(L>YlVCOVgwIx%gap8#pQoo8nryT&VK(Ck)m&MUe z%;NF@lCqkD5HOe*A-UlBq%>K`H^P-L7xj(a-5RM<652rlI`3NW_^?iXeDLsbXIt~p z*CzAUsJ1E$mJlJoTrbde1^C%}+rbwn{J(-c> z(F>l4dG7bQ?C_nA(I1g-*GATbDjVdE*Tq#Va1+!-^exwS{b1zH{KK3kwREmdzo2y&ib148 z3(2b4S-;&Ew>Hl@?k)qKTd3!=(bVsk9IYIy+ zv|i|KZnsZ>oQ%b({x9aj3L5&Yt)g_gdKX@;mi9aX=S~o&+*wa|2&wLkBc*hPqV7~a z$BE^w*tn5_eg*axXAZCJ zQE!T`FKs>#9gx;D3vT{KEiFkbHQ%(Lzug>o1hV->_X2ChyI@wmw+}jhMSTitOC-bn zz8!KczrcwNQSbkJ3wWQpcV(oH+a`8!^!vLVFuBBhm6^tQ4(cU=rXwpmO6-fr`&52? zGzN9mo7fpzOv+xj8rLr4&A&oeB}-E?5H4P{`#mll-q>C4|Dwhu($pz7OA)cu=d9cD zC3~lVQ|SMc#0r4;RL}sC(aq{CZ^4`W~$`|zN|rN zf)djtwFJtqnUIPi{>=X`l#Kw2m>AiZ$g1Z{uEpKJn)xqV+X2<`e*snu_dVwq?ysyf z%dg7ip@G4&061ztOWCewv9wjT-<&lT@QRua#VtQBv(=%4U|kb_UH5dJ`f!L@$psRG zwte-efIrBeCYMCg=EJKI?cC>BcYv5;GUiE+F1&GZWcz_HZ!Kr;ySXH6cEK+Qb-!^2 zd)QKq&DWs!r_CBO(A(eU{t5fI>CAl5(PdS@A$EejSRU6=^R-U*DXUfS%)=Ap+X*#8e6Ww z+g@Etb%}V2ojd9p9$h(OmPmsb$u@2}B@(|v#myQIM$!5S7vXlg`Py@wKV|_n>rXzq zPXb;AaKGWC*6o>j85-f;aiLy(K<*A)(+9;)ebYyAc~dT7^(krvz8h^`Lh(nl;BV&r z0Qf;fVCh8DS|S1%u@k!=Vb}uThQl_9#=mmIf6003rpxc(0pDg0-(%i9$`BJam4tj( z>4F%z@R**jy5M&Cd2?4hyCmVHqlmH4_YAq?-5!&VO@muG99>Y!?jY*mMhVU96?GeApb5nP9|KffoY8YwEe_jB(P{%orlo0067x50q9Vly@@2pjYuCx!ln1k5$n z*;;epoNVLx0_z(LFN*qJJ{nrY}rzIR1KeLla8QysY@Is zHGbM#@89c&9`q=}_Y9LC9^Y8x+dJ5~?ciX~_=wRnaCqY{ib=ga#3{=G4=$1m&mgaz zvU3axlU)98@9kYA_W)2Y=hR7_UG)6E@V}+o6R42ifiQl5Qh$9a-K~U9`;V6V&8*QF zgL){M!aO%Xn#*E7nfej+eLl_xT-WvX;HpA(a1Pu8XBX@(lg_6!ksb|orPqDc6bf2@ zT&#b!!Rt{fQA|#KA{m8?um)A^&66ZBYHn7VO}P#e3DU!U#vC4`rgP?DX}4Tgmm`zT zNL5ljAbp6Ef#|FyejVN48l62&N!;^uPnLEh=4j^4MflQSu{C?i45j>nAy}x&tU9}K z_t{Q0vcXLUAvbD0N;TF2MyLWfJ5k3wZTlHfyo|X+j>$0xeRRxHJoXP9TRsQR%XjMC zmNcKDY^!#=W0C=(N3X&%AP&DGBK=#O7~~dW+$ZGk#hK{10fdjewLcCOS%BU5ZRuE@SpX!!Ofp|XnU`Q6(d4_-ZFjzKpMmj1cas&TbMJ}re z)w7%zN@@49@1Pi{e0K*+1DY2>(tN=~2WB4C zNN*6HRi83Dez;zfY8SQ~ZJMfmedj8~pUY2XV92h&Th8Sz#C^=GfymfN5U zBXdvwKjYUrU{Lalt~>CFm4D@38aqv=T`Lotf6EYs|9Tg|_Nb%&N{rYsWUPG^(>>^> z`&SHBq|Ycga)Ha3O5^W2*Q20ySEnpw)d%M$7gVA&uk3WfNJ(6a?-wbh<7t3WpvgI5 zbx8{QFx}oq>vO^1J~HtG5K6N?N;511%yatYis^V`fACeIKA*q4j2g%0BD)fhGAi=j zHXZL{U7ImXzfm7Gqt=G0tR|F{!6cYS$tg&l^Y-jlQn0e$-a~$iyFT{M_hFVYn;5LJ zbO!<2x`pTdMljz5XP4_c=#=QX)N~N$)j|VGg=I;2Js_rj@M`YB&i`3?r$F?d`nPKX z&VaQHqvppzn}K)?p@uJrhOaDO)hw+)02|Pdt89(!>&v;Umvfyx!YM%wbKey{*EjEa zqm*lSZtK9e<;?<{8Gc2R%sE06REO#?&H$?K?@@!JSgUSr;28K$S&zzUD(}i-d*l(P zpyGIJoO?r^f)%k3{i!mFzI^x)wjjIa5X1r&*CC!SC$fq2$$KsYLLJE(up3n#{Z`dxlJGlUzmkJC5I`oD-{n>;CJUB;^-$ zGl&)b#9hMQP9q0%J>45%NAKJywfn0Sl4ELYg5oW(^6GZK2f1qyrQOb8tnuTM{$-i5 zzIOwQsZd(7*}1(9U?(&j<=uodS)%yWyZZ^Up8~ zx5pPIzVF;fcn?jRTTYJ55$3;`xdj;f*Ev}*J}tHlM8qU^7o?~se5#Y zr!`?o_A6?aKmoffjXSi^A#Sci_e3JsC(y5YzW`A zZ+vRNP$a#D!CP~)Xy-8kdiKEUkZfXLLtVIPsLpmqGFGa^ns<8HfPvThUc2x>UBayH zNz~ny$y=S9>bK$WxbKl4QT>vIDc{UKwCSYV^@Q^_^|}rl_rq`5eGy97d}yb;v0(SR zJh=G)d~bpNDx+;VtgX>ek2Gt?y^lg#O^aq`c!tlX(O)SU=zv+WTipp0pX|Z|d2Z#) z|L8ZCJCzKafTCIS^MtucPj)#96aWdPQrGH3z#WOPVr@4-V$-WC7wR`PSWD_=idW9z z2Ye7()be7`QF+gWYyK4;T#xN;_(gaqKq()Hi|E?{{mAK<=8l8u{x#$^+?;f&*b`ru zb^4c3Yg>5>o$?~1RpH+h)7z}M8{)tLAOMnBPO`!Qt#rC}4!#>sY3w14@$9)YCJYO2 zeYuxcVqLfQb9A0zK4fx0Fgd6&QF^!Ky28(~ZEeP>hpqyLMA}o%hFY5|j?4PPJX~QQ z2dNNysfS!#N1fqOr^o4r97!^4@2)l?kZ&Zypj_`dww%uNAbIqsjE z7T?edosaTg+{hn7ZcQ}FiXR;cOF|zUw;kjxxWK_niT|pMbR2Cxipo0-UWr zV1*BxUWzsAy}$sES0DQQ=%E#UnT?BYR@b2Y9x_P?3Yh=?;MgAd?UAg61GwBO35(l3 zPW%EZv$ng@HE11ig}#2ltZ{*N1KBCbhcn^?b;;B-Ue}CQ*hNzLT61A(hlLLP=%>(< z?L~rR&R4^#x|ynJb{y=SOPm(Mc!aP_`zOsiGSid#T{X4EHn%lng!+%(AgQ{syd3p6I+{o5<02sgqHS9kIW=eXAH(6c8P#c=TI@OGpROg zZ{fqN169{o(aCmC60#MV;hD!1<~Awqc75qFmmKu%+87kNIM;R)UhpKdysP=JYq*^0 ztsj_}bK4;o5VcJTbr@}bjENnK?Y0Mh4KWz`Jc?8w33T0;z_`;yDU&U>Xy#HHv(J;~ zyjznaS`u#CYRf_yXfE3xknCwM9!>q7yvz0Y%&ytumuDtFtco511Lkqt+kLC1k% z@&O@xW+YTGXuY~#Aw;3T;H7$u^KN3@ zxBJgR@Cxo?*Ydn0BNonnQg4~vmJjiXYy$KmM}N?1_V!1ezZ`H!i?6j5D|TxJsM3{l zU8}9r6A8v{&`-W-Rs*Z19xpxc7#-5^bQzikoc+gfpt6C@gH#3FH<0sN@X+dkLm~|x z<{fo0UuH0P*s-iqwI`7o(*djU?m7W$xn};kktgD8s5$EL{F6tX3Y@#<*itf3d^c)$ zLlg%1T?_}BlUvo2sMu{}4tcJI|3V=L0@zt42hM~E;%3zGKBBE|9D(7U`Ojo$pa%hN zaX)7Nns6A9$5~g0iojF5;;*N#z#`o*NH%wDW;oNGhGB|rv-G_KU-0s!wqT>QiS_Hr zh~=-v9Mv{1uZ!@CQi{yxpKyqT8hW4l)MhOMwg|IsLIp0?FSJCNEgyc7j7V@VI2Ma~ zz1O1t7lk@2$pqJ|A9cNIJLqzXG@gbF9frrgP!8wuQ4z7L`;QkfYQAIno9iWDjnPVmjWNm}J)CGSTihgpFOT^OoI2X8 z{uOx3KJ%(w)kXfaAy2ITMfG%VH18_7ZeTvCN%5nKLN1K&m%!vHyRMNc@_m+H`O>{a z9hlvLHz%I!PWYi05izKH)L&D{sMtwdCKMbjiD2(vvN^2crYv@tXnr%nXQ^ZdDe(cB} zoFQtIJu|Tcb(Hop!kR<-2R3Rv!0QycQ6KD_c>Q?80{ge|fETvQ>Z>n}SF(OUXAe9Y zRC!ZE$Py58Fdn##!PpNxDcGFVbvt%DiwTVQc0Up0N<@_9B6Vk-|3+u4Wy~(?nTS|{ zR%;y8bDgG5HN)!svB`i6P>gx~@4M^HMmtN@PQwAKvy!WknQK+!ZU*~#k-JyR9C*9) ziONonp;*`rd>x$^Q8AFek|8hQfK4WrB!o8}c%sEtTXo#kOe~P*qM{VA<11IpD%zAi zK!wKs;FjJlXP0~K*mW}BL0)0kZ8lY%M#@?bb=z_^y0$)zj_ARTwVRRV$$`VBpn)ef z#$ArX5dJ|D*u;MBNyy-YflviA{Ke&l9|d(zBmB(m-zl0_E}49MihIm(-`;O*x)+6> znq#o*lcT033nRJ9O~Z(ig^$15?nc?An~TYj?)c^-(Gaqq`WUe;i%I zJB)mups(w}e7U4R_HMRI<1s*KmKSq}1j?MoLd00RWpGjxDfyWke~rZwaH4N4G?f zR;-_EWC+&}e?lipGXe_7&NLh5GQ0HZx&CEs<0W>}OsD!N|597y49<1Hlw>vjY~9@U z?3~1uvA4R;sy^3I{fVmg+k#A!Ioo{aJw5W?M2WXZXy!t?jP>EOT@~~g+r!w8)}ALJ zOqTBR0W~8dz@MAS-$)K-P-xdnd|4At(1riG9U>2n5R=`ho2{zbX&e7n4RbnLg&ZF? zA9MEcQY}%AcHcfl&mcgoW3M*sZ&()xCKCS8;HWS%qrwpG5A-OTQLI+w;&| z7^(_|umyV?D(KWUv`(5@qY1Xoqf~2Eyfd9w&x*83`KzIZK0V-#6htj?)l<~vNDJi~(1G(L4R?9D z`~!`@K|T_oB^!%i-hG}#R0QMlUBYl;VqzO_ox8cTnUPk{OrRUp(~VfH2{P#lUe1$t zBT|{IH~s%>0py!i1&l5{6i+Wx6NJjAq?uS$u@e*+?l89A?%}D3?(b_*VB1CfZa`n2 z+}<#IR6Im3PjZ%nxrmyyTeknNdB4NHKPe|QQBlHbTJ@kdf1spTpYJCV={B!a4w)Om z|3(pjq$9h>@E5=9Ot98CBeYIL0kS`*l|QnwesbM&5?*T1rUH{J-t!#5mh3S-=gAAJ zHN^+rBiJ#lH76TBE&b(serqYXFCUK2t|R2i(Gz_tte>0Wts54)Lf(5h=wQ`7)DI4Y zr71cN7eg(hs_Bz=lohWla_+2v^JY&_jyFx)PVE$izNXx{YJU&V5(}9d-#HU^fe2Q{ zFQUfT_I|wZKg4&;=TV2H*P)=k3_edAe>9y-e|xZ<@yC=5UZ|SaJAp88{HBi2rH>8r z@i#yiv7MX|sJF&R3w86ADqbk2@EgY{eH-_rLKrkUVDBWcAZj+?pRiV z;B!GH-iZY`$JHedBa zrfVHsQz7R(BW!EsdTX-g@`#eUWF8XHR0PB|52U27EHOn{>tKnBMxF&qL^D)M^MEH5 zL=*4;hytSi*!S`H{p~+^-}mdjuj_fbHoqfdoboOQf-~Jo&6BwGWhYD4VTHUyBKeRg zzi!c@pa1MErx`HD75~Ygi#DzMY^5={jXv!5>`=WxJ$_k!chw=ecY!qV5ROLLr;Y$j z)BXoH9DHF#qwd?^z!MdL?P|Gn?SG!dOAk}g<$hJktB?iprH!FUnf1|>|6vF>8 zCA+}qr~?&YqmXhtfA0~Fmx=I<^5)5TM#L%#l2E!WGjF4I{-bsfEbGF~?wiHicAScTE;8BideDuXa#ZTpvQ|W-ok> zu|4#yEy~TebDRXGrW^aWl14v;Qw`UcW|2lr!!M#`b0h6#hu|c{1n1ckxU(f6K;)FK z?0Q^^(fmYTK|g(FSTFyMpgVO$*I1kDhGjt&wa;MR!3x~2vGlc>`Lr8ejo22+*CY0G zU2iydk-T?E6Wgi#6ecMTcRn>Y>61D}LT>-7gUvJAi1($9@XjidD@+p)k5J8)(A%4g zQtD?fI4YPskvdG}njLxO#&8v8D>N~7`K9^}iWQ%}Im!I(IF*^9x`3u|tM~I<5FYS5 zN4vi<4`7Qfgy55vNrpk*NYA3}V^3MN1fM=~s|aGVW}Ic4uxZzXUO!yaa|@f>kcqKS zp@d1Rg4ipgpptAx`0Y`<@YY!Fb2G2};>bJ?#q|^sDeH7@sC@yOvQ^O{87LX`4uf+w z3Jw&V9d|kE^4V2MrnnWmCj87H?P5~TN{=RAl39&6)HRh1HXQM%&Z}E)!k0Wg+Cp0V zw`=f1oBs1#76Y|6-WiQ>GzUQ=UuiUp1rFx(w-hm3v*qov^JENo!VXTVA8KEauk_}5p(UaHG1jG`UNbgDwGCg_>p1*PyoMJFyEL zjxO8R4SHNZzh<5UEf%zpWu0xert5*+90$VbVTVAi^_Ql% zjb`S$%z&@d*-qZ2_hNa^yj1nPU_(W114~!L|JyS^rnxdC@c^Wj>MOKF=U`boEBdaE-BZ?4FZ0EP#UB26TnR_Es$`BJs#g8 zQHeVP*_EzZx4Dw2sI-Uadjd1y7m{hUbymJu>Vwtc#<{_~HavL#uJOXwoeHqxDX3^y zfW0r{ab7UauLC9<#ksgMVD|qHZ8j@bgZ>D5q)YOXvvCs2#YEBAK@q5p^H?BrNJ=UCfnrOp<2olru zI#}e^D#v*Pu^zY%f{(Fvy$OSC=60!p@cymnE@v4!KC(fz(JeIu&eMU=8qx=);fDK| zbWiq`q40kiIBN78SkufZbssH6P%_rLK;c_&Hk7kv`!iXl@1%;iv+pUJ8!w513}PVt ze7Fg{(ois$AZ$=S;<=kwPI8BH`9+M<9M>i5Hx*8^`$xsi*Mo3ftr>m(ec(t>q*jvD zeP(_DL1`NnTxc1dpV%h7Qvut;XUNAxnfMSZB9er#W?`MV<;OCkM2iK1v`hoK08wf$ zuync??+=b{?nZ#BY|eZ6dKA|0>F>U=vpWo=m9BO^NgJtk*LsHj>unG_1y+nF=0W5y z7{LTywK^kp9x&MEh?r{f42E{T-I0UFS{b-vp8vo3o^o^S;Hr*8_sP* zzD`=SzK%+?Fx?S7@Be|cm^re@^r&$sEmTE_f}oc4mhITSJe)hgU)Zwt)MP>QoD*-O zEy$q5f^7a&XZw(lp2Yq@9+W@2cm7H9?o)+_ESx0~Z-One(A(uC@5&{-YEL*pN4c7e zE`hD_x)}|kJonBP*99Ow99)qN$l{VwCGnBDN%5^ObXCEtIRZf61d&8V;VDS@80;reO7u-{%mrD=1}tT zDw*M$vRd8@a2#_B)lSFje&f`c5D6`F`JQJ}xT(|eOvPpDL9&<#>-#J!R}Cni`n)+~ zMr;P~A>C&O{k54o4XT%_LMv^ZqlF=kjT5jiu%#;^z3H&X1XgVasPk0ZDsg={y*ASM zn5UwtDKn$4nWH1sMRvZb#&I9~1y*q9iR&%#L1@OS?%OYkoOIhdfD^?kmb7x1nv$q^ znIi~ZTZwmP$45+KPnGyr4uVD$^*hcgv8r1>xdPzi8 zs2c~!9|)l9S9Q6droSv31uv&=LwrAwS1rQXdx!%D`6RBo7&uP6)n#DxS z23VYwAjoSYZzxHsO~9Tc$`Q9V{pqCP6A_i`m+Hdvjx-4me7${Q!nH;x zGOv3PysC)s*r>G=s?xffVU6=+hw}qN>#$xVTdgEDH?iVe$|rt&k*MaOSk_nw;C>A#}-5d0|gRZidM4 z=XsYxKuhO(Yle9t4ZJsO;6RoSbn1sqTGg~v{Tm<3cZ0q&1s)}9MESTU41RJ~M2Xw; zz~$Dum;5blJBt0H;U@oup-X*BFIvDR)_sqpY%7Seta+W#TAu!q7C3yhdk;Bb3ZQ0v zPiV1K)UQ4G{{8Di{JQ3C?An*!_D!h`2$Mv3) zx4d5e<#?J@BOcRn@5a4)RmoV89h$$J)Z()79#FXL;0vEHP~%LCt**d?PYq+cGN|_$ zO+>6-;ztP@i~p()rWokJx>-4uZB&FroGXi$BatbUiRwNVGR9e; zPmD;Mx0SASgBFq>=}*V1-?Ia)IOAE_?8)&^f8c3Et!ZiCnr!&2W!)j7wfZXW-e^_OfhX2l&03aL zsu?%63EYlksQ)cD^0Tk?>)+QF{^sO*qUR`SeANLN8t!+^apCWZc%UWQ?HW+a2(aEh z1=U1&z`iP>hA|H_xNlU$kI&8uk>F2YgvQ$SW_ZM0=d%k8TJT;7@}xHzD(Q28 z#+Mc>&`Tc%;m!zqYoB18_c)NdsUvAh2WzAA^cxN9PjP$UC|lyZIflEDD0 zddsM);_nKtM~=j2JeL@>a4mkGl$2ctAAqf7T|d3(`GlzL%ci%CR~Tk|r^B&j%^ima z^WaUDkSZO%d!I4YCA9U?&R8szP7h;!yyFvYIPrh0+N@===XBHRO%y52Xo9|r3Dv{D z4>J9$)HwCFXtBhI^H}M%SI-qoo4aQc6+;W38@jw3xDoZAC%2MRpNDTU=u)n^O{Vku zp}HV~0#9p`b1U5qCAd2b5}vVo|MHYOsID9n-o#2IY^ewNHPJp3nG2_(?}ctn=dDpJ z!OWEr1ODqk^a%?Y(9V$_7n_-i;|GT)P#9tulhs%O&@Znl^>B*7NQ$ zF|7p^joQ#=3U?O$l4uZ*!!`O(3Xh)BcQ0LFhO~_*C0=jn!nL}Y=-1JP1)A-12)BQg zXJ_R%*5YbD^3AmBZD->q*D^2_9y1uOU-+)12huqK+K!YcZU(X$CB%0t?}s~o7k^&G z4=$$9<6Nwr>>=T3H?U+ZBK6eR3*29zl8OL8QJH*6rgz!#3ccp>$_7%23EeadR?9i5 zovr){FMDqunx4NS;b*qFv_IwlKM)L=ig*`3rp|e~6NbRmsb!{;!bal{oo#s2KYhMg z_?J64+i{zADAYIABE1zG4JZ=s`UQUuY(LrE>EiwCq+H%#k)oZit_<53uQ;(oF+3&_ zS~rnhG(E!awsBSEQPaA}cr@$Kf=6XXL3_av@rf=Dsx;fOa2~CPte%CtX*^M)U>O2Ca9i%+wma zwm2y?Zh$E~V`poSq{J^UCQ0rq9c>sj!rBq~2fnfk0Q(h6Xe;B+7W&iuMpy ze20gf?_ZXzpbnY%i-#PSK&#kQ;-x@)+(NC(C8FvA6wRteY}&J*XHc%CGYoQa2(wW_ zdRzgOC*7s{fl?yM<>WOrwF{emnN`^ivYA-;V2}~K@K$=%%Wkx@{%?wXRUWI@e^k>2$`@eB9sINbHzfF)4` zozKiXZIZP0JYHJBaNgtL#a71MQCm3VlI?j^#~9G7)1K~@0GUh@6EBb+hptL)x+`7T zO;&}qi<1(RcVn%%RMlOUd*#)swAA6fXzrfmg`Trx^?EKNx@iPx;rKW?5i<2iv)|J*v{u% zt>pD#9>AZRa570cw0>s_>}8j+|IIQFNo#X6*rWIfrg`}F^+{clwpKcLp|NV_>$>@_ zRmGz;6GfsXfb5!C%0;RKXk?%n%y>5_69<{)tsIU&>gng@nhT4^9g4e;LcVvZc-b)2 z!Z1_6sQj+aE;D^}WnRCmOJ=5lH<}=uk|@?^>VTz}gx2ljH0YG=h6ii&*JU=rNP+dI zk_R1$7uWy7J|s52;oMXGeaQ4|&$|O=?2krC))Ij1VvrvH&p-&pZEnb|*}x?SrH-BH z{{^+x><4nsFgHWk+|<0uf%#4D@bJSg%q=r1mQlijX=eVSL-^j3l84+FCvd;b?mFEW znCe*$A1cdVVy)iisczfULG~nI)0fzj5c+VA-O2#TVPT|{Hl_?Lj$f%T3$QkCzOPjO zk*kj#77z{SfjmmKI{Wlg-YE85I6ZoJqb8JE3z~l6HETQ}Vz*^5rGcM-a5Cvtn1nWg z*e3($=R8Yj&?!4w3VxOLc?LET?jt9#stVC=8>v+W~rtb2X@=+_;nx>X>sQ>mFC z-}0V{lAbX8P}3AHx!eI|q7vuOAg^c$t$Z~SG)JRa)Kc3-f&o#NV)L;MtEmb=gVpe5 z{h9UKB_Q%$fYXk$q!`9QdfIx;tcqGKy*lDq;{iAy&6_525Y}BYe*wfFujkI>OXxF1 zJKNpl6{Asir2E1OfyN1h;P}=98MBiF0_nW{HIpVdI%Ca&T=9C8ZzYOp=`Vjq!GonE z-4RgIs3*i_^5QzdT|4JeIfV>+4sWl*qAmuhezzs{t{9qy(*Y(3uvSPDLh54-_-tj2 z*PQ~1tQHwURoZEWKO8;p)p1`#ix_GbNy^D};q3W8)Yg}VSk)3D-&W8Lf`FI516m=c zl)0BS-^;p`R5zZsW6(0QEg0vmm*_&H*xMhk#ew8iz5l_yKrNZNqrv{UJ;)Y{v6woc zbvyeDW+oMFx(d;3Sk`K^r=;I{{VY+1ea8e?pAwV>&e0LHX3@)~W6q(aOSe%2S94&t z5h2>zrN$HikIvEvaOrcLn(SwEF9#Fqq+lZkAsvz$5@y(u%+^6&8N;-Aslh5f1chnC zKPRNhz_dimET0L_F#F(Jt$ZghbhJYql?e!aXH-Sd*N28qTeWQc`SeLj($hRUPhW~H ze}tp^@i(ABib@ze1eTa>4PD?9+Yzj!ScaMNnw>5MgpKdGFT4GE^Uoq^uWM$5rgq@G z{n4h$jpbu|^%n`uE{9WygpCIXt%1>9`ZQHGrWuO<9I-A}@rUKpF8nw~C(0U@f{%}76Dip;#4|K+h zB4|~v;We9fh@)0@%2{66XXGvRYD;^u^@}2 zBiz`8A3n4_-ArOzmzgx4tqOY{WO{D!WcwecH_9wm3Abs}XOmb0Gpj3HpuDvmy-fhdwW*}5%@mH=a0STxHg6QUaRh;E^y-xQ zXJ{BBbU)z0Vf)lgWT^VfNU2g>0J@!4HNT&@SZAQQ$L7azZjNd1+Uv%3qjb=Z2I1}` zMYBqxj$18CZjxuJ%@d*q&eHWifxs^+wVKZ5@Det~IyAJSvB9nX2DBo(*eU9Wku|Po zr+T~1Rk5aA&tZ~IOJ+9#1QED4M{gh)^)USDWy#W!+8 zvCF=Z5$JmeAQ)XHF#uPgw(IXfevLYV9p?vt@kX`-Is4+3O1#x#^tG!i>Ay8^GB41{ zk@b<<=srIREY;m&JY6#b1RBv@!hnu(O_c(e+A@lGa{UhVC<5`*8YtREs*TO(kREgP zPtLCS+H&vc4)AL!M|Ph7z?k7)4iot@I4-=r(|}A~B_nP5%&-H3n@Y((kPX4n&?)t|WhiDoqaoK(dzROa!X_h;O9PjIY|n8g1OD0C@|+{T z6|v?fp6@=MIq)mQ(Z7imld6@U05)ldxNjDjsVO9G@&Km?P$;)H*t0k4T0>m*&CE#y zv)9%n8_CLeglF=gzjv6ZdSuOA+kCarqs)#G*yxJuIx^d1aw3x*b7TXeu|tn`2;&8h zjN@LV|AGC!%ga7?kb4EZwskQdBUQ{@KLdi+Jj?`ZmKStAnktm#~Sb2V-B^hDHVeigbb#eK%5$)KV8(|s#C z)XEaVY?$gDUPBDteijao(cUID%TVnMO1h2iL57CG|K6E3R zm$_AZwxz`MAIRGSETU82=WL&S4AX~J9r!Ws;z!hJ;u9>Pm3wa@i161#4^80wy{Mrx zt9s?c<{n`XCHBESZ(PFAomnk+^u3X8*LkI zwbM_C3+KF+F<_%4&mJX2Jqp{$_P}&Rig3VCGBbm*0bztn6^}VhZ)W%V*y79$WXO$I zCs`q0VSaqMC|ZOoR0ehi(1c0P(VS{N!WZ3e-D~O@bJ;3hKV069O>R(B^$KjEuNL*_ z$AL4$Zxf~E!&VYy+BSr?_Of9T8Q;40`NQ3Tkeb7tC+n55b0b1)iTHn4luK&EmY`*p z0bxNb_xF-e?%I_V+#iM*$=sQ5nw&ZxH3v}Fx;fAGH`}1S&`)ohuGo}v6CcA^k-XbN zYs0HvZEhO|zOkR30)LF^8=YSM%XHgg&0tLRsDbV%wl>?mlD#l&_|7M3&o%@*(vQ6~ z!|E?>!~B|j{+IT{;v>?b(21+n#<-F68MQQPw-Lb^&s-J12GGc?>m8f(YyXtdz(A(R z&ZM}6Lqmlu153#mvXObu_b3xaj!yupUjU*!24o)!WQV3sq zQf=kkBZYAW=B9aWQ2Kl#Q)D#*NZvIK!XyF2;rKszkDKS`zOgm9MFr8>Q|)!AIbyDr=Jt@{W1vLlyh$iB_C5M00Cnm-Xxg-7o4-wQNxiEqdT?ObOWzQWk| zkIN?rB6K+S4S*Jqp`)}01zD`?=6~K1{xl`(68R}Zqi;-2OMVV&jI8R;8*P=}|7}-K z9Y4>#Rizdlp3U#=p}r;chEsyyS8?Ba#aQvkVGcm|2K@;(1HEpDmJz1EOrS^Nb-Tks z!?waTHA5Ge*}9mq;rby90g;m4rj(6dWfGvu?a}L*o8PXb2r8}uq`#`zVV#>d#(3&( z>BnJ_ZKmh$6z!r0q47zfIUZ`HQOlp(n zU)^}Q{!y`C;v7;|YwL@Rf_&-9GW~Lz5e{d%egW4m?Lt6Kli$;<#0ayg{%I~FSs$GG}xwPhu`>k&#&VsqM z<(jPn-T6KU=j(_+?cMP0R0$9zTzY^wH-3L?R-V=0(~NeyR#;IOD6H7$-G=w6QK_cC zPK{iBJ&Z(l<Aj!X@60SMr9@?>H5t3r!;+C!@E7foOI8zseph#@?)zJz3uo#dvWXE(#XdIqm z-&8=VWIq{CDP^`luQ~mvv(}}a7|jbS;;2zi<*zy*w^lNFYooh9O$+~(e7mI&`0U=w zu?x-My%M-w*>=Sd&Z8D=bm6Y_S*+i>Y{zzb`RqbDgW~GvNONlsUR9sZEOWGv7!tYV zdom&w3$|yl2RUZI_QRdmtP;|Bp`zJ4E%-mKiV0WQ%kU!IH5hAb0954~HffYoN*D&j z6@EhR2=cf^z@@nj4zI8%_XUG?YQMpxHPKkoyh9zLNgsRQ@`^nh#E-spIb z=@ygS;yfpJaoXzEuYM>uXI^{SeghcLIfiT$@WT2B}W8*1ZPb9ivpgTG$fLYGHM@~?GFDv2?9 z^v~WOz|@U z!d|Dp0-o+)H|o$;wE~gJf-o##GU);C6)bhv%eIywfU7qIhdU%*$=dXSfR$3U4|yUy zGFB;Jz#NI1k$b$+<5T*9hO!n3`QaEU&(vyRziD0V)$&jMrcmm?{j+@VTT2xcZ{@4~ zuTZ)Et8XR!)!~Rzr93HsnZFZYqo2Kr&B$jgMy`JhG9OK!p8sOSD|J0vumwz85BBF5 zAW7N>(L2K>8`HV|Mdd|2cspYA=Gm~+f5XEF8a!oj{@ZeoM%->5l}Sj66uGHnaU*)K zVv(-;@k*C^5FFhZ=vOrG>vW&Nm;Dl83=_Q=n2a2IQ5maLzuf7X*ba@r?jEYGw-fc- zteBC@MopCqPVVl*@su$BC*6A&@XCncm#-fSW^Y>P5A#7tzF_$aB$j_so#;gyT~W<;D^aVfUwlA-er7@dp`(BudXh{HORix0 zB)xK5|B*BMkhH%;GB?!H)hT<}B$$h7UF&{cZtM*)h(xwJd3h>ktEwNX?0FZmH#17U zln!7bq)eQHT+UDtli@LeBe}JAEX^+!Qi)9pm8%4?*xV9h2QQq^rUcqs9<|7b#E0lRY*H_wY?^>Dt?z+!1fe?CSfV z7sVGYJ&cYa-EY8XBIo;E5H8Sb(Rj6s5xiCYh>||D#xpgT-~6`b8H#&+gkzezf8_J1 zoMBhbj?4JX&LwT?d7=0g=$&z(BV7Fr6?G4mx-Or~d#L+lbjbi-by7kIaec>2Q0|-jXQ4D! zr1c}_UEm7q&yB2ub>JE!8qsUAo2I@Y>;Gq(J8wIoI%JUbzN3)HW-m}_dL(}UQ9A^=>A%G{L7?3o@t7{o zQiZ59qNx^CWsOMT;-V|OQ=d~-V<^+Iq!x5p#Afwn|H9XK6577wEKItWio5EiI2hMx zt!4Pqxr0;Bie$hYJ$zL+u?|1=ySITLjNgA+& z=i7<#U(N!tO+RaIb5m3~P_%9{Z@hX(%I=kfLJOBb&6AcSj_H*~rKbE4vf-x$L$J+` zrSRe^;Swl!=ax8pU+6W%RB%gipLn6AWrnMXC6({$o{liE)|R23g(G31ho#{P!L=DvY#38|vdjTUCzB8qJe4{JE#kZK^|8Lvr0iV%z@R$2a-|HBq(F%U?# z=Xc9{$j_GlS9`>3QQ}Yn3b^R9^*edO>4vk9;dkma@1vU!WSBQQj%n5wksI8^j6F#K z>J0Vvpd+CK{~zu(laa8s@SRQw+5pknkS-4o!2FEY3)~N3ec|{NNpZgf_q{}nIvEj` zN-(r^jWKBVM(rcltd{U3n%YM^&?KxsBe!)hC%PxjiIL)i^zd3;zr*Nyr+6=~A_y-T zsawCRbc4mCCqs>G$e6}}hDMe66)M#czgR^%Ty2`1uM?fIoH*h#xe?nJ!rHFvq8isM zLErP~1RP(lVqw+^tOeP_LUY7`(X*?1p&7+W%5w0nHXo zEM7w+Db!by$W2`3y?XPiYAP)C`PS+)(CE18F79$>#uuUoJQ}aN-_HQcNxDS8qY5zC zO^EtVrs#BToHl~0F%PWWAhsNFhb+Zw7PDPeq|1JUhO}9ZamV4wt${W?w?C(DoLlN` z?~uz5Y3L`>`VsAAlCSxo=AcH)A+sh5els%AN8StxXpsDM5oFYNSX>^qB8q2<&VV|w z8B~32VsE+kRFc7t-oWiSR9NzmXULjz>-)bRQ~2Zy}zaI=!K)1muiSQ_38%kai)F|GR(%lTdTQr+{)WZ}l?l9xz;n0CXC`l0oROM(;WafGWmIaBBFFYgM(b+2akR4~7?c6oJa z@-N~g)%Ej{!!K*Ye2YXGAN8S9mSJ9sx5NAKTEgR9REUs9+g-xc;ZmJ@*9X?+ONS?4 z%DDEroJ>PF)&f0*u<(cqQMRC^mk5tBA_^m-zmquSrk6TVi=s9zUHo`QN!SVr(^j?p zJxrq7JK#na3GVhK>y7S0jAD` zQER*HrA_B+%HqfTd9(19<&thQ2ql=SDED_ju&;~s z&(m^;imJfADVAogFoM^rO6**GxXBy@-yQ+Fl_u}B}sN%UmJ>R>C0_> z4|HdF!P4>y`*|#oJ({< zDdIKDt>8jT-Vw+?J}eMHnOWd*?`I1uqhY+9P_|nh-3k(9Fd&)~-Ny$(hu!QNUmPBq z9}Ax8>il9$R=zKJzB#wn1>qaEDM-HIz+PXZ!g-{X8seqU@IEk&ukQ`5P5wG9e|zG1 z$M)f3rup2))+Snv&Ast(Ry!}6XwS$Y zKO|iSj6mVNOIF;zU-z{(5E6_DPq$k@KSB|i;#AYkDp_DwUGww~Y$`+TOFnwlX63%4 z`@${iG0XaW-5=lDbM}n;g)hJT%k295dQ371Y#pjE1 zpmleAYtkLLa&Xv(XXa#5To`AgS||?z;ifP$RH4ML18wUJZQt%X#j<`w4|I<}LPafi zBI_Sfy7A~C?U1q%aY z{QgU+2lf~ru_Ns^MfqyxFJ+nu!|ySQR4e*!MXzI}tPEx|EA0gikj+Yfsr>-fk?x^DrY^2PQx)cyd}x6-|AOaGwLKSrjGS55V`gjY z?n5*>nyn%)_yXBzTiSKGKk3$mZRZy7T`Juw3Zwe!I+%wBTZ~4voO$suCB{!fJ2n8E zH!2?~;zPj*aV_i+%3nBH@b)+=HT_@fl}{?H+4>W2uAUwL$9(!ubn`KX5M*pKeJ zdPxK?{r-0Q;Adi}3pAu>+=ZK)vN%*xpivVTl3bZSlw06!h)^z=6-O6i zuaK!>38fGwH)gFYBJKa-Cb zsBzSmd$+28Ng%jI`p!Hr5S+R0EnY=$=zfDqdM+&~^M@FwniIfr6svBxZ-ZtrUMn}c z&?=HA*<@2YBsIc6lY^m%Bh{1dxLJQp&uy2t@Anwl?$F34E-&QZ^k`wa+xE9xl4fF4 ztV=b(-BOetd)%{?@^gi+l5*yeAtIhSX@W;z1!PHNXS&U*6nzzH?%c(rDEGBOM-x|B zt^sBICK3F82wr}s*a>X2=d7p5l$@!2F5ZirEb9rbK|5=;ZJ6$`r96_jtkUp&?zheb z#kaXt6pio>vep}qXhVn^?a{mr_i6F$plCQh^j7A`JnhsJx*&5S3}^l7@A~U%sdtA* zL{&5~hc|CK>{hfK+n;VekQI3Dq~YKf=JnqaZmQ@s*wm_{!yRtMU-7 z2vZH+(pFzuo{Q*#CTokQP`6}d2)~prv}<9}fRJTgY=+WuQ?12?UPaK#`)u*N#qtl% zU8$^1@xujG^TQR$533nMaq|f(8|0wfEtyZq4tdzP$7M9LCwVqcY+B@gX+FAPQ@vgJ z_8PoAQl9v4`h$&uAFZ^u)bRpw8LJ{Ka>nEKY?mniI91`i2gbMUnX@Yb2{u0iS@W}E zIo-|;Nyxs^?29mj)))h}m;lHkw=TpzqGHS7{Z~hTkSLNI^9AQ9y`il;-ovpli|-Z& za!UIYWE#P_=dE&|>-2g$kP|yw?Vq5Juztj|gUFl%S$VXDddZ;n36RClg920C@wGd* z7FJFfv%ro$&U*soz7gd8dzKbw1-dqgwczAjDzaG7>J{}Q zMse>Hbnk4no!_ksDWfyr&X;e?gFW$WL0H`aTs2hR|4}r59}gxy&Ti0$PgoLR#46gQ z8gxVKL03P`E!9O&LxhT`yT1X<%8SdKTeV#s$;rMS*Sqkv$c^(GN_lli?HH#d2U3cj zHu|&mdF@bG_jG>-Kf}KWB|ZQ8TQB`+_Mvup(kTaG}h&g-B z_E$p}KCw%Xf5_tkjX=JZNGBd&=q4xpm@|>$RmGJIq8rrTx(f;zLy{vfmVWqu3o!C1 zMRRoIjqZeY_9oiPVgWgti4OYM2|a9Ho*GqlH`98`>xN|&nj`gk#!tAbmDzbUtYYS^ zy2N?y3JA3~kMn~j?OBOMrEURM9R*6wbi}SZCUg2&HRm#3<#WAo5#{tK`hHLtuugtG zV^+r&IW_&+lhszcM+nD>W8YVyQ~vNSU4sC&BV#7JFi9&4CuuLvc<9n{&HbahiS8rx zhEjAY-Ct7o@>9U>9=J>slYU_nk`XaXNp(lRo|1jnqx+e64E@Hx*!&^a%74D4O??FE z)pfZ-Gt=p}96L`7*zOh;AD`AQDnC4G^Ot2R8_-XwU97i9zA%C! z7JjrE7RtV3ix!n4`;~#rK(SRjgs4pTLHNGlZG(T$DW+ijsraCq*Y;ZlkiY15ztHkn zIr6xb%gs|2zH*lqz!#R{&n9{YcQ>OYvooAtS9C=Cg_{7^iH{Kb;Ey^~AC}SclANWy zOH0_5>`Fa%PSzY!FHisNcz9`x=*CJXZ{g3ymzP*U%;%E)hS1}f48=(anTLSj)+>+h z1_C__-T8UXY_%8CBNejVAi6rVLivZqSGz|;hK(}ek|BXp<_M4dx`^1V982zqx2CBKy}^bAL{bgmt9zJtVJ+v0+)_2N>~TdH}wDxIZxb$SITcIS|0b7cA*7 zL%UQdMO}cRpl$pnMn|(ljm(kBFv{J~e)oj%;bJ>KS;fsm0NEGiEy3ia58#rlv&@l4 zK`E=Z1;rHUy9-;d`|DT@Q8qkD;OIN-3`XUesoKl#|Q)v%1MS0%hLn8 z>Vyu7FMM4dwsczggzwg|qW@5OMteMrMh}`mPGYvd2Fg@1DrU z3$B?!PY*OLIsux@9{1;#r-GA)eFLFjczVTMh6@FIVxW5n&_nT_#H0C?dCBqbEv#OE z8}e#hj-H})gnu{YG-^?&OA;5vxfc>6yH`ytensKc{WjhynmZa%86h3*N)=sK9OjwJ zb{{jrj+9#|T!=}1oMUur?#%037Yl<)>^25lUvD^dD+F;YW47}N`tL+D|Lwl3Y1xna z`zZo0zi&Y+XGJcy)XhFIO~?;o#gxO+{fP!|aPDn?o5jR}S?d$%A=4025^YatCcZLl z?7y>f{UPzmx6URsO0($UUCL3q z+p}oxuz|Z!Zj=noIocVhblsWr_}J7i{**R z3+j=XZ|iKWlt)#QC0SK0Nw=w|O0>^EJZdbyH5=v?h50ppA5ffBWlGRV+?7lCA5{;&DyLZB$f=B!EP#+a*vxQtRtYa(REf^#GYr-?jqIS zaq!Ie4zz0>ioh3-e4U_=TvRF!5WJIbrF~jt6!ojM7cLeR6SVWvr;HwcQ`1*lLdjE@ zS~rLk!)yAlTIZT)$t`kj_V$$ku|d%Z3uJc4`5g?;4FbmyF_->D}UNZC{Bbd-}3 zD$1osQ9~pNZGO(wYmWYDSfw~qX>x_@2u*&`Ytm4aqCdCxe9^S9y{CP9c}#b|Lp9%c zyY_cmn`>Dkxo{U$A<6T8prHh5nE1o?D&F{d`b|dh$9{gWU)L*bPw^Xi-Y!F;K87W( zM;?S`qA{tq$hHT2^vS zYW8hoC-qnE*6Z$;u0@Aw=dB7NIJ13-Yhrn9Hww;-TyzsZEH}F-+Mit79`gGE0i1b+jb-P8oKG)038M4N1V-kDv8hRu{gVx-gx$@TklZnLOT7i7B`i zQ0`rvaf@Dja#`6q6zTV+^9R2>nkzp?S($uA_7yf-qg|T?^vUjGQfB3&VVWx%V$n9; zWjX2{6y;nEF!Zh`GQr7x-9yHyYH1jRl~k52W}1WZkVQPsvFZI!Jg!^42*09QIUgc!8Zz-g`GDv8VkdQ*JE{8Z&=tK!kIcO4%_@FO=f4|!U5txsYix_)NXypsHI z3mR6_NFry>i(#4tOeF7_QG;ApXq)N&UCgpPvR)q%Qgzg_U&#qw~t42I_G#$?Q`B^PUE7%X$^6CmWqZn=rvDnUbG1<`duep z0NEaG4*JS96Cc@+NT3WqP$7A(xn|V#MD6>E^|>nmWO02AEA~14g6gIZ(6PjGp-&hz zd3!Z5E~(3uOkLVtwA!2O%c`Kc;VA;rA7J0g7?@uwMLWc(!oRcRABQ@CF1cE>M!c8T zNY2xZ7PGefpL*l<-HT@mXwCoElLbCtlE$oisdyQ95n>f?R_)){0vS{+jfsF~Bvoh< znKo~w5m$$omaT1T+;YFQ}m?sHk{DL;(@M^m{yhfBT0IJ?DMSc|ET_He<#Um5vog zUi9a7D2W|ZA-$7FgitYQrPD6=t^?0c^lbijCh48kR5Xk~kaK?;H@0n_o*<7_cfQ3i zY7WSTS47KbSAzO+_$T4#qo2B8#~AVX11+9@;TtLMCD-D9dHs1oIQS?a8it_TdhyR_ zD!N%?yL>8~S643nUe>C%H^|4(UzP>5M&mMY`t5iOnX(CdBe;= zW2RXEa-w2B#|G4H2QS2g6g1Ap2H)m7FA(gS&h!Q?{5!t(F0&4hBhu?Z!KEvM42lW7 zn;5c6DM1w5FA$0yi?^hGO`_>?)`F*5)531l ztpHPmqnQuxfvG{TJqKmhEd80q$Y$=XA60uKg6f-X7u_YMHt=jHr+L0Mu<|q#;{&nw zdVh;izBF~htD(v%82BMmZYMG(qz1*d4I=5teb|hUrEdo%} zvM#}kp^y6u%zTDdO&Ishh!*B)gZ}hYlPoU9UNROUqtxBI><@F{bVDSQKNmZM1v-Rs z^SoWrDU(X!F74@$pL>LL?KK@*nf9kT{h;hG26ktQcG*MA zNS=N!^6uWWJ*5=k^uzYMxjOM^yZjz~dg&_8oihs`;BZ4$ns5$m{ z`3=G!=DnScGi0}xyL&Y$R$}aZlp9)fX57XFfKOzw9&p+v!Ww;-?auP22)|bOzd%he z=aSSG+vyA*PAwW?aKNZmlUpnWgXOc#ys8{HD(`9#-@fuzbQrD8v{WlsPL|DUM;4DK zeFA((2903PK}=x&TwZX4Uv7XZZY*G9mey3f5$=u>V$VxCD{Sx@u75PSIxc1ub~#a3 z-en;c{6IUf?%NG=-Nhntmra62rqTPNMb4-8074p+OtJ29(?YOD`^;Lq_UbYLD!ZFL zbUVi-HCOa2H?JJVkdzn)M>&rdoel&MOl_y%U^;i%V@853ZS?)Pm}xN?A7!_1CkiH2 z$Q%Ma*r&IiGa0_*Gp%X+AvR_5=!*^Q3yR^K@{o(`n)2TTldBM$7_n`}55!9Lx|daI zuqco5n1>YZD>rCfj(XIOSU>3U-9-`Z!G%@!6;Aea3FA@w`CQ_-r!}Iz&)w7AZd5IO zcVCE=y->aa__+1)Rkw=xb0|BrCU43uPb`12?ea6Bu(s0cX8yqFg?Y{E-w+TI0-*^0+cJP z)rLlO0IJU^`%YUItlx&eq(VdUQ}tZZux839H86>;pwkF6{c%#pWD4wLevCPCVvp3_ zCsPZX`Hk%gfLUdU9Lh(m3Fe!Y_J+Y zU(MqB!k(NAWiu^UNT2OgpF>81fH}(Viw`KMQ+{xmlCnk0F)ane`mkRIS_vlDOxuZEP&`U*N}a|efBn@-~@L9GIywCJj(=e z97tFncS1Rc?27r7SELbE8hJP;Ps)tBq#eocTcGv>)LEVw?UVvBqPy6Ko4lzA%EJ{ z{C%|kq>NayF+A1mNObB9MX%FIE4jjHldv+;$)vXreYmW?6G+*2E_U_?bbiF63t4$H zX6b$vcvxdx=Rd(Utn5ejb;UVi)2Wp^kqgkARFovr;fd~epl-*<)VAQ7nKe(kTDg|z zwi(JD#q`hfPHVcez}uad%C>G;Pi2HL7E^>O%t-&>&Xz>LzilQC`hfPxlY{-pSPt zW3gVl;F4Y^m)!xL1WI3>GYOb}Ro?jX829Gp_9?U$d-~g~{j{|4pfmbhF1%9OB~5$U zf0~^ct9~~)9v3g%qbp#Qea`+?i^JF4Ecyn2rkM2Yy50|xZ>}3EV~et*_Lb3gK&*>ZdmTbS1lbtsh_<3wb=<5Fy=FEN}l5!okMCO$AJenIgm&eEW_*TK>dj5f{n zvh-Q60$r}K*dAzHuXFDz0LY`bq{W8yEjKhdel?=ym5i6p$Sh~;@EC22@ zR=ez->{I#Pz_m3*@r<7fA2Haan+0a2jf7F4 zW4gmiMp4~FXeCQ-19CNcT;=0-8MNCB5I|CfRZvEjbBW#gHZgHD51PDxoJ}@jg*BxH zG&`aH_%b(OY$^p_;ZmNTIpi13YAg8&Ft1G`PX;Gkt~Ij|EcnHJIx$ZG&=aIna{FA^D2b4pYxqn|KQ5V66%iizu zCk(d%r1+?mzB+!y$LEyro+e8SATpbgMLS(3FBTP52Tr+sM9gPdM%AJ49d{?Yloy8FgKM|0O8C^l6`6~OVL8R+h{q0_dq&3q$k;NlU!)8no zhg9a9mN}@?;zX_m#?>(Abu6odcw6Z~kYQfT&^5-?txOP=MwrDJ_*B?g$M9lv)g!ek z-g8y3ZDm;e6VYl|(aiP5S2Y`!)s$e&NBM6A$$hP}^Xt6*5SE?X7^#+Cfl{Yj@oRX3 zOt@<50uDb8DT`S;_wNr8B6HkuUSHmOOA4aY@x9Qc%b}(3%3q?Vo_ggw$%2oWBN>SC z;FaQw32ATHm(UKOiwg+_aj)DFC~Py#4LW7m48qcXa57&R012jws+}F7Wd#W6*L4hGg+T^x;Hrggg z={zxf6!@Zazeuz~HGsy-%A=2(aen%$5d7?A?mj;$ve_tq<+;;n^(xiu) z`06Wrl*xQMPW9K#baUfGU&$Q$kYfy97@SM1dD;STm~{|~eEX|SW3&Y$V40>P5fo(J9abvq~y^Qk6$ z3eHS9D!ewt$fvSAWXWAu2<@BPrfDYvUgK4oCT=?>(b5m*@Tzac-_ou6X%Ke*gfHGC zmT=-tUZUXW!D#)WT1*bZi0iAFJ3$1i@&62F`6|7upI_MR?mF48bg?r@{#n!u3LBb+ zl$yQX)nZij+*Gt0noa6F8wMat@sq~oZqy24FlO-cPmbpI${5|&?Y`kGtt)&b)eGad z;5W`OOi~r;u8LuUl7({E>WlKR0u~A`93*SCN_6%)iMBT=PH9NzT%oIEE=f}dxti&u zyM0hEuY$(m`G-0_;6}#d^k^%VfV~I9qZ)-*shNs$wk2~mF6g_(8|ZLffLnL)%f)kzw$M4;hEc({y|Jvw;P$gNy>J?^!+qQ|qc&Nm+R@Cd|8i~Fs8 zz*sC-)`4=x9OXkOl|S^M8TZKu=0XJoMd7XM28x`Bb@U$3U=JEYY0KWyAmyHMa0ggq6g+pe04 z;g9nl|1ZSU%MQAEFxrbeVp)G!_B<+H;e3kYnhZ*#)rXH_%l@Tr9+@BT|rFu z^)*EoOwqZUt=zenh_v~+mvhWwuWNb zB3_l3C8P<9(a z)Z-1$>vk`Pa$0)>dcPg+%PU^{pFUN&C*;TsYcIDI8q|>C6q~U(QiJ}r^6B{Yddzmx z;PS@LnUnct;H0#s2ZOf~lTQCSku9l|Pf%?#8Usd=X(wKr7nR3TnVd&hkT zN17%$+#~84#!#3p$xpnM2?h8Z(M0ve!4Q{${nV{DGTPvs>-p|J@dy3QFe%vc%K1z7 zg0D>tn2M1Eooto-1Es<odPX#$^R>J zom`GJmu3kHQ!37{ko&ct^T4QIEio7DL0vw&Ts&-z1qt}sj$N!{O6Qabmr3P!W>t1b zP)BW8KvLbOtQG8!WqvG7Sr}p-)Q>V)>m?VgeoEC(mk(xUr3Xt2sdpFCJk{Cx{zb82 zrLvI7lOdSe$M&U3?gX`&Vjcn8eH=~kG{kCFAIq>^0QctB*jis{0s%{(f9&I>!7?Oe z1r)XNhAa`2zFtF3Q@sIizR5HB_EU>a0CF;vu3JOi8+qmiU@Dm)PKLFyQ(M{1N+mCS zi`O+gO$00mm z>LDAFl8w2Ky97CINnG4RoQ_bO?!-^*Ywm^YRyOjD-tZ zZ-WCX733IEEs}=KHZ=Mp&AAY-?0}RqiV)sy{=^>&UX!&$&$(H>YL~#Pxzm2_o;YhV zph$M7XV=8Ho#zsNzS)~6M4#q>tsJd^R-YdP@STc_TowpluLnDCW|lZ(rrBo|VJQ1R zv$jX+oMx9Rj6cIj5O>Y|fY|&5WU*tHOH)o}vssSBO`Us3((P>(CF?S{aIYrld_i1A zI-pFUorwQB&6)Z;iwM^~T01I`k6X))=JSMUAHwt; zxm`)-F-Q6?ENdokyyP@qV$DQ=8N|cQ=To`jUv71k>+;tRW=?Sv!~BV7H*v4A!vLd(a%c+4P6sT@23L}y5gy964 zt_4WoP+SbO#k`dgt8*K7)XRcqZZ9Kk$Kx3TD2mp52Q!toZTt~kpmk~JXhu%EEyY(5 zBOI&BaQQw}TOLy{bx??4wS2rFLj>Rg-KDr`s-n=|PATE~f?4|Ooi(DOwpzkqQENXS zpYNcvj5HPO#i@OD1V5~TAo`+$itXj%YF+$k1MO!yweejMA}i!k#oU$3z9(7ZEZ+;{ zLyv1GqdD1kx&a4JNuUehzgW4)SIzpV20lbeL|?Iz(Mj8g-0e-LWM)=l@meFWNJP>p zQ%w(Dh!=z5*}f?W2u-Yg@>e9H&G(A1HeqAld@le_%d}gvxI4e<;O@9LzDv(%Td5G^ zDE8D=8|Cb4>BkYF^o<8?Bpuq%MsL+rk`pJAze;?NFp2NJ5EzFWEDucFHrtt4ywNJI zOg15Wp@7%Asp@WBP&K~bb~`Dug6KSmCcIX~)>b9Ro@Pl!Pt9)Ey9Zcx+;iAo|7GzC ziYqI5!2z1aF#+ph$ISGm3W@~rC%!S`%2wEIt2Y31Fh4{(`g~{GKxa(u3h1@V} z%}k6YG|g&utjdSJ`bfg+>I;-%hiZxwaijgk^;pG9pWHj^gF-q~V%I+2ar@Ts2B+Ry zpHEsu+YXagf=sLl3Nr}KRVTDP3^SA17YC5Tj$8&R{Xi7^&}`}oEwbX<$*>!rJpJC$@V5nflUQN7Ph{6JE=+_{(pe@w)n3ra zPnZslDoO|GK72C0AmWq!@;1xRhv3_cn~U3kiJs<#%U(j{Q(azcP?;+&w=pccTGxt# zaRT@XrsuLaeGK-AIQ*{BmQ&-WFkihThcaA-F`sN$sRlv3YhZ)E6McGNuF}TU$*}x9 z&s3>(I!o4loqUU7>TgmPrf*V;TM*(WWiMnt-U#%*Fw;Ivh&#B9q!mlPf4qmtFKVPpVbS*w_9S*69awBu|k@=KHL$p}mrcTEvM`IWtB#J2Bru~cdHKhe%DIa`TIxp4YKvQPd`{Kxc{ zCQl!;4pcE+E|V6m9n;gsS-qaoC9}a!9aG{KOXg%4J;$=>sIb$JkRPlaBTMq0J4>|y zLM9|vwO6cb06O=oW+(e}qVRl{2!q9}e{&aZrrqnWa(x}WlAI_^N!XBe3|s1AnKU|y zsR1Q#-FbN~?ZZkxys2#alw+<=CM6duL2#zBOB#zMExyQ^>8}^Q?n;V3jl60$)h5_% z2kX4&OUu}%RZmQIV}%oHn;@6hKvcC z!yWj177f`GjF~;$LQ#c}&z!VlhS^xb&0t84Q?~df+g#dRM?_yv1@*}Emt9&JE>_Vo zlcs%VDL^g+&wx-gtKjX`wNF}`b6WUkc0T(402K%^&TFion%^xpJqp}>5~IrEs)h4^ z=89?T8_rcl?7onVc~`G52OqFZg`Nv+`@nnd3ZF`-xYrx z;(v?2;=&y00qJnFY-iQyr!9R^-ppd?KU)kKkd_HC3_-mQHl5|x%R=g zUY5GCRN0uEg7l@zDB_Cb)Yc3CrHHh8ht{mBU7kBIL2|Ee#-6-%;kl%{^)TG8 zD$U}~$3M}`?2l2{uJ%5fHKUut8lfB=|8%90;<_+&sESkQ#>EbO&qciV&Occ;W5DIa zTwHrwI#%Jxo+I5lK=g56X2Hxi6{KwibL&lh+rnCTyQ*9gQVZ9J;DJWKoDL`$$J<3L z!Qt$R_b&0BChRsI80;pR zK2Wj|cr}#M`EPX?4==oEaMkfXho)8p<;N^Ifmhq0uJ z6d;!zG9S7OFkkYl9&>G=-u2kD1QTgY#{q0=RwZ_w1y zH$rfuub=0@NE|I{I3X;;V>&{!j^&jXe=-CVUyhuSUh>zYIdz_g4uQhaLDP<;xLL() zq3qChZ;>+2Oy0;gCfa+=(=b|eTvDcvvrMXbi4|q)p{(c;KU9w|QLzQkaVYaD|81iO z4GzYA%<=+meFUbdSTSl=e;A$>MlnxY`pmPDMfjuA!N@?{ta>pi1#_|rtsTe`9IaC09wAV9E5Vge zm+h%wP?XUh)%cNhb|dd#BP&64-P9m$|IE4T>yx2nCf*ziMtFg zHH1so5Zh}ANm(~x%{@IK4ZfQQZcNqLTc2zo$sfuOq52rLd3|nddfjcxbr`7O>kk)2 z&h$9A7hsLc-yyiT)oPD|)%SOpbB6|ZwNn`2>XPBkdwX4@TBF{G?*zQNKry2_rRFlL z;^vdpUs^+8?Wl?DT7Qe32)x+#hpm;!XcF#|}98d8=r@lF=*ett1wTZ|k;y zA7HLn&%1O3eyXRtJ${;K_*qnW$rZNC>NZjGo?+IUmIry$ z?fyr_AaqeV{068J5n@%(Ryi5gJ$|8lmDL);yMU^5mK^# z$9kt2|2nz>f?-k%$0*zF=RARybC-AD<@`T?K|)IsqLwf2-@t#orT z*-gY0-rz@KBW*XD3(Tv#9W=4=fvE($W@AjBFLG^-3%y+k^ZlD_?YPlk+UyHeD$JB~ zxs0}89pQ(t`WHSUlE}n!ZQ;N#lY&CN;{r!FGLIx$Xlh@{2>2!{SUVgLYdxa>M7)Wl zMUv-_9*(vlSLc=aHqLjjb@Bp$EZoPy}`l$-EXb><|Qz@N^D1c$oOM#>6WUt?AfFNX%A@BuesSD>Yx zdJ;3!KdNK{V2!;%duX-$wYQ7=;amL(fvQq~Q#Fz{8~cfbSz=Yz)2w_{+$;d3Dn1W> zTUlp}zW>C9K!d5`PMusja^5ge(p0PnO16PLOVa-38x*{HB_|(~vL|w@aYFbfH5wh| zUhq;xWSs5Iy4#ns@=i*;WRFVYK)v`220r|Sp?a8dzR&ai>55V24ZBSrf$H}j%}el- z2mv`wxc)bJY6Dlj;RiVbT=@zZtNNdT>VIlD0u*f4UuBpZF?X}qwk_`n9 z3DSr7vlQ}@Qe)NCeh){zU@fjOR9s1ExHq{A{k>T3909VeHnZEaU3O>ax;V|53z*PfBXQBPk%jaf&PiCbDI`<@}?fU$UZqb5C%q_)eZ{UAM z6;89={f&Hu6#5l+YeWp;+{($~Xl?9t;dK1{1UqB4LprQEZ|}HP^%G`QWh>`3;-9P- zng$6csPv&a9Hxx%{`0Zj>5cfgxEUvZeY+&1vYrco$cy<6Vk6KdohzN1h_S}`ur{3e z-)&85zsUK;3+-zccx)71SD3%Eqsd7njc6}eCTV6#L!`@+!IpEiq=pqI9Tyxe>0SI= zxxo%du+x}PO2f?oz!+uP>7OW!+9UEXj7w}(m}+xr0sRD!?uc7 zAVH&Pl9L_8dTe(_7J@?w(c+5?r_QU|q1E4NSBXv}cqd4wI&fic0Gze>$d%ZZA(iaO zZj;D@fa^h$bF&{srR+YLd)k0|5q&0-9-0=l{x_g?V(k`OaZ9q3ua_q~mBxSG)Hga< z-2k1j2&WxaGoPd@V<*dExBy*x3FH(8Opduv@51}GYs;Fb@suw*F0TY z5{Y)>B6a*$#|sd>S$-)hSD7tto;<&3C_PCnYI$XhL(CfpQvtHlT=e=|4Yq)?iq*{W9?RIg{4u}VMFk7CPN5o8;)B!k*Tp}gTH`-Z`1r;Y%uN}Fhp`O2+0_sk7R}b9) z{30Ct7M}QgdFHmi9z7Qtn8`k^<*zpuSXh^}7xi`j21b5^Li2H$chy>m?$HIG9Ypm| zYH(*q$HWEU^KyY+rl}?l(=%9SC) z^T!Ol$HE!ib)|#W4MzCLZnTZ?nz+a{tn;8DQNh`Z4lb>3wy%~Q&<`VG+-QbP>PnM# zS}UYOx;x7<)=#2zm1M+BPA_GHz{S2HfxP1f3mDUt`2Oq zOkyc|aw3D7!atvQcDyMAFC8QvF8c4tNs1v2;44yPLQFlYFjR|VQqZU52cQjdJKdzG z9QOHXI$bTh^Jkz_5~3D6dwh^AF_18uKbG1CH-~%aMdM%y zkaP2i(ptpW?YTk0ehK2zNrP5>Ky+O%yTCKgb}laKh0@H)bl#<^@&P4aU_p65<7K{L z!!@n1xN5LGndUU7p6jmpi_PHhOvBq8xC(_3V=-0A%(0@HJQ$y=5jTpJ`@#su>5{|f zivv=(r`mOeJGE&oZp+Qbacdvlc}?;WEnEviRjt!Ts@3nSDFn3^T3+*Sm-|cD>tjEP z`gQfie>^L$I}~w{abLXTt|S5%I$6N40+aX#@FJD09@-RF+N^ zAD@6-Un7=dvoFL%jP{V%8bf=zVS!W;nq35}SK*`ZdF_0iIc?8gND>jxuYuE72B$5iKgyZyBE@&<+J9IiT`2Aa z!M%zPW`YEqr)=fdKN#TCPHwm*$8lQ=dj!}SF(6B9Or)flZSYys{cVPS3*7y+qRfqV zc#as)QJrV>Wy<;y|7kkkp!QnYx5iKP~WNS=*8h{@a?U!6K#!lakuvCaE20& z1;$M$pQ`eT|GS4h1H$J*IS05IAH}9MqHBQu9Ul>qa7=K{$n-QIvI>7x9VjzR6QxX1 zoB7?`C3O)Y-uAJmbbo2GWPyl^n*(Xoc0QYvMaD#jxPf+u*s6)3jocs5fBRV5L442^ z1nsU%PJ24)a)$7i$hHP<`(Xk~hjSA-pRwLlx(I zY2lD!sBWz5iWXe{n3YLTNT9nH`70myQ<9VM$)Ya+H4o^%b>BdFUmjqfL=%vW_^*ca zexuAc+B(k{9f%q0_^`1w=D$6^k#+?2O#U%HtK8(LWkfRdfI^XR+HQ8QHG*Ra*&HMJ3&0fX(RX6xDo&4omNMd1p>v;qbOV zvnU9J-<&U(;DD(MG^B1n4zk zskLKDPFd%%uo>y{0p*E}c1J)XPBDLc#tE?9$bH)$bPik)T%|I;^B?@d`f{vVuo zTs-8Lp-5}tG+S&vLko!f=%;o(;^tH9S@IbvRmY7s;!kRu))1^~BFcsQoJ!_Gg+l*}S#2c|V@{0l^>4 zMd>9eN0d2?jxMT>U<%!LbzhRHl#793lW411KKXF}#fXd(sNSG7G2U_+xv7qa4L%c< zdpYqllmBl1{bN2um0H%7+&C_C6U4XK&ze0&Dd7o^cgyg`u9KYUY|p zE|-9PYPN1a1F|=gX9??J=}B#;r^b!~tD!yv5WpL%WYG6r&*`*ja$9F!H3rI42*Znm zW(o{^T6wnEsa^}D(l)+58 zDUY1H+H*mB91$98qlv=YbMNgZof%BJO~av0t66Dm7jz)u$JQYC(M(y>R|aR^Hg)&O0w(E zGHtYNQb5!(bkpG8kaBx!i;ItG0xiX+ON{6kfNxiHFBiBi)tgGjl%LoS8)d1)yJIcb zakIFRGZPD^#RmlyL6iX(*Nc!d98Vxa!&z2yoWW!Jo35lU(AZu;)Dj}ia700v?BZ#!$g~TDbRE?i0 z-(k-M(^hY|r^HhX0;#NNnh6BZII|DYw6?$TxvFNoBCp7%y4V**V$($WHhYZ@XRQaK2=Pw#LLvI2v(BdR*p-Mudjj0he1 z0R(vm6H1fQv?A5GY-s|Lv1lg>5Vkxtb!h9KF zUNvWG2eBC6l775JUB%eVkA2l9d@BC74EnFbF*vX#>nB(UFmdDr6K zapJ?gf`{7l7Nc}1-rI6pTlj%=jc?tV|Nn$PX`YqmBAHyr<&^RF#|E{Y*hFFAE(>?F zPZXipyPqarYOBkAz3>gkvz+HxFMC(uIq->!Nm&ra!!ScxuF6Iw|Htj|<*jjCS(oRg zJHFGsf+U8`<-x+!{uG<_QWcq0r>!Z3W~w=5 zA&F@SR8r(sWLqW)pgkjNMZdDOc{{I#x$97*G1d1UcmSbMJvo=zT{TYehB{5`6XDf^ z|5mf?-O-pNBl+EUVs*&O%q_B}g*M*$m@oe^NfM_80okKe^9_PVELZr17}pcxg}DV*{6vAcaWC@XofW7u_q&Gu4R#9WyD#Q1ZgG2f>vF zKWV=-EZ<%BVD*hjzy3b1G1C0W1t({!a;iEhWR5xMp|-67iz4?0T8$?tdBJ&L*8q4N z@@kHm&2CNN)*xzYP?CQLwmHIuDfRbclMUgjrI1~~JSFEGW$fQsrfIXLZjcso+wdSZ^h=2q_xOiS3REkto<%X-yG^V}^yHz1w2pndCZE(!KbN_PHB zUKlxn{s)1o(GiVA4nImr`7taQlkkw5Yk_ytWHx<(dn~pc%+KRMHu&ZNhS0qD;Ldy6 zV0O`O78jcggk)*l)v^GaaaF$0*cjT1YZouP2e8$ zpYk$m+P=FSGoaf^q~1R9O%5p^HxURu^TLDadAwR?Lx00P$xT5<=#*G~;GbqWsr^NShu^%H1+wQMXH)3&+<@@=G~a ze4ovpiQ&U;9EOig&Ri*uudFMTVgVV1`vZ`RI)Vy&nG3iza+k>L2xN(54mmS^xH)-w ze2&I8cS-AI<9p|1uw~iM22mZyf~n+~YJwZ^JYU6j+uRGO0vF(w`6BFJg-t<~w_qNw zk+!VLlE&8VKD29Or}R)xS^Tch^-}Yy<3hQX$!z2Gf!cZfcxi9(WGKH8Yxm^j_R#GZ z?(~I~Jq0gEobHLN1EZl@x3R?c=B@a4OVi!%g%)ob(bCDK_vyN0W|Fm;m_+pnHI|mL zDB)78KZBNcnw7mBJ*2zzY@qZ;iyke!Xis#kU8Cb8((Rzsk4J3Ph871L+uj1Som8vu zx$PStjH&=V^L^%`myZnx_%6Tq6uL2U05-e)UDKPJS%X&*cq5oYSbD^zn5q|)2rdk> z@r>)$VO&E#QM@{*?)TA0X^N7?c0=IB*#H0#q+lix)QYTjMV1yW(w?X#Y}M)(5b|Hb zH{Qdj88-!r$&ZiB<%bw7N-q90o4VgDNHJzUfA?p&Ld1TVWGJg*wX#ipT zc(Lf4Cixx660WpbiCGa9O4a!13S;e^>6bovuRr(h#k94jugcqjglUy``5nv_|zo-I1G z_#kl*Tu7UCG9NgS$7l>(xoG29p%t?}UclZM)v-N*p1Wih*XVHevPe=bv`Mb)~$?=)z3lET>)9a!M8R69wwU52VV;sb6d>5|` z5i|1%8U4L-4268*#)2sC$)<@Oeq3SBh9SSP0O^R{yx(cZ9+?|qP}pk>*0`bI&uX3AVwczF^#O0wHRW)35d(q{n=Iqj@JN>W9dJ~9HcVI>g>RNjf_%Ijq2e|U) z=rvgN)%9Y<>*!!iMQhLvmXE z&c0KoFM=tMT)p+N0&QEY8OsNy!Pra|P@?#Q1{5Sg^LJhzwCg-18UD z`QPd}ok}qvP|3cV+ylhVi`tzbq%^Jsy_y8kfds`wiz|e`H*;)-d@AyLNTS8_5>dVf z6~gjJ+iebAvdv7ssQf=w_t(>wfL%_zpVZ+|em0;2bys;a3bkS%kK=|b)un&%RAeV<@7n{cB9Fm^v~Ub=+%DIm+7*-z>BW?*u;Pce>@MWUwKq+ z(BAdoEOYt$RrDXSy^Q5wjnS4sFcQu zY?JSEp=O zGe1?P*1htM$(bDKUVx<2RoND1RepK)sNwmpxh|e_&n|;J&*X=BGgMzqH!3QwkH3KX z3xt#U#|*8Y3;!0>(%Vc9>taWKYdAekkhUAKS`$WMG74I< z+URS?V^BL_PDXZrmz_rH(QH>HJI$V_Jl5sf80b_uT=S3FnzToFK>~ZiY=P*Ya{>eUG4X zb#*`R0Mz7EiiPGRF@Eu*=vUW9A>1QxFmo=rkBwDz^kNfx!`XnmWKZF`2j>k5VmBl(aT(v&(SW|+>XuOQ z<>ee%n5&aTpcu3BR)-ftCIjJt!!tXr`A(VHSzN=~JXR?HMXrl}Px$&ft=*(dtM+ji zr%Cryha0m#;+~qxt;-A{R;YajyX`_Zf_=RBLbDYi>o!`C@gWHJG1uNY->iy%kksI8 zPYghM#gmBo?VFb;umyGGazem2$X<2%2z!slVe=A7eyL1*qDQrDib8*>N+u$+@#^WF zU1v|hXpeDm?|!2SHY~M$YLR|!%T`SVt1ms&y1-<3aEukOARf7h-vUcv();M0GDzS%QP9lF z%bR3)Zd|xhZGX8Hxi#Qo6K@ccJ2@9C4_P=AmuY7bqjbu&`y52gsVsN<%O{^Zn(Fg! zUB`&te%H@AmCEixa`N39sUs9gHFWl{jS-aIlF{S&U{qg>tC#iWv^JWCxbx>42Y-g7 zLCabrry-ZMj64Fh>_q4Q;X72r!|YJl+2wY~U6+Q}1KwV{KkxK7cjI4|MqmjRMw zWi^vY$F+R#;9jah&oJo!X8~+=vJpZrnI~rsV3Ef#6>5VgxCg~-_2ehz)6xL6+?Xix zp+0uEbQFA#3|3Bbb&B?p;#mh2e}^#|uQFWml=R40*T7MyU&08({(0o)z0T>ySgToD z9NTd`{cr5M@EX6jj_h3x2MDeojTuhP$EWKbtiiM%dcz%AAh_qJpnMtD_P_~FyVpbA ztE>)=;@kSw>Z04y(n(P-L|gm9<`M2onS=0w~26E5Z^pUACO8{*7I|aZMW{UCe5185)Iq`J_OfiNX1faK{ zB})yHrOZ2ko$iUf4chu5DydB@j9pcd8gKKO@WC8!|Y0u1tQm=yxBq*v-|0eaZ#U zJh$TitVqn!sfUd{R4kDMHhp5t=H-WphC|9v&4V@O6*>g29#FSs?#lxnm)})=f2HT( z*q*H~$|zOZ88AVb#ajl&*}RH|Ntx~3>z+%iAN-77wd+>ddW(G!Tzj7=KvSiC1KUhkjw?6MaH2VE9+6(KRVJ(A5crUi?N@L$Y;Q&tq< zQ}`zTP@5E1HId`0b!2}S4U0^!n9&B!Df5R7#aUbtoBAS#_IWqx5P9iZ!kdg5mb!%m zEHw>rm2%Xt?JdWB@!xOv#<<20=VWah?O8s0R9HMPa`NIIFqCZJjw{k=^egw}pVQ)_ zg%5nd3qy{@ib>H=4R&MvsZ5>$J=3S$S6ivqbgxF*GdDvN+<6Dc-YR~$tg2de*0wcs z{Q%#}Ti>Q)Hf%D%r&=Fw485d7 zwKEq-K_i5FL6gi~Fbre?jic1mnj9A&YE3pVdgj;x;P%7SS?pEO41~yvQ~nd44=#o8i*am=cPK{2-Uh=t z9DrTQ8RSL5wbeTwkcMxyzS0uL-Aj4aWsTJREg~AJeKmDeQxv{da;w&guSM9B>HFI=R7|G`6y&}Rjy+!`e%LhN<2f!@H7KN zVVjhU1K?6els3RHf+n)Hd_Bo6Zeg26@>|2>-`EU&Xy0FMcFXSOvB77`b z-78A4(;7irGk>pE{vS=};?H#d{&8|=cehX}OAgbCBu38XB$gajw@T$Or%;BRnQcf> zIa3Z{Q;N#@e4g`RPBZ5@$ILl48#c^$_wVue{RyA<`ac= zDU^eK5T|$cLk`X#48?-@(Qyl~_O|0~jUQlsoEBW_M_dKvLNTMpWX)c#VdxtMl)HO- z)2O>K^>A&nPIu-aEmPdBFefT8Dwds}8JA10lYC#H%lP8IW(lTQueS_3u)Ke;8ahI4iOGI>05J~#S&4eD(8ASU>-UxGGNHb!H#!LULWe^jss6w9e<&7l-I{{lTK z{+t@pKd6HtHalFcNgK2DAxksfDutyn?P)|UXpMu{qa@FX;=ZemkG7|?hJ=<>Y~mE(?LGqr^of7(4f?(g9ARpa9ZNX%`KCAaJk6(unXujYGG>&+wZ zVJVHsonDncEvKpuI8mSLf0Qsd9ZNWCc=L9re2zIMa0aE$Ryg3KZZfGN&=Z1MZe}O< zpILLV!K!jzmV3a}&XtSucxlYExP(krp(a;q2&g}-lwTpIw}XHkS}Gp@&P^eEHCNB* zauB~9PrEV@ttR%eZoGQM+hV~X8-i-qWi4mtVMMQuR8o2%bBN%P!S7-wt^}D<|I?x5$zl8* ze8aRXTuqWq525ra2G4Ij>AYg=Sm_t=!_)meYU6(H!Ato8s^l!YE4!UJ^>HrRK(}#k zoj9=Rh7aR9hy0M_UO2D(fN-8* zVoOWhZ_FZU-Qlz|TBzwU)HDmw^`DcdX!gnBe}14fXz-60=7~>%BHx3MdG)aepVBRUc7dHDPs1-Ga+>ek3U9TkoRa{^Gd>kT(B(b4PPPf`*sq+ zfe`beIX&JBdLMk#zMUZIXVlX7WC6KvY(Ldu8Aa)dbNt|idlfj3IXo*E7nuo4wgD~D zHvCqod0gg}5msW zyS5T&H+w{VJry87^`m}u4_FHRh_ITCdc|0LY_fs)mZulo4XqncC)5jl10St2O2Xr6 z_eN+9Cqbuu6Sn^(MV+Q9hFe>Y2KUFrJ&Y@WYEu?lRxWjnSzD`H+u74?kGv-XR9>}g zY@U2vHuZ8a7-Szsd}$hXLe2f)3P@*(gO-qT31ZHBYA;Z?DvXe2wkp4{800!ea5O(V zJ!^jBiMOHoL=FzGocdvL%#n`#;n%uel?i0f9nG8T_{Rq)~5whfstO%)!BHl zmNN~^!cwDM^3(m7e)-(i`!+%U*dW*tAP^*=2}A+$kX~HyQsn6a-Af@o>l%ch{z2T6 z4e?8}joThSwbzE9m4geWZ7uXx`~4Qep{rVbdK=YVTbnfDpY_(EuyRAt*= zLNU#E?&yC%{g?bd$9R9}zxY?B`kd6GpAR498@-(zVHJ2D5rY2o1l)IPS@P*;VJa|a zoxGs2eRQ8W+gh|JabvyN)!~7)I-Dhci4z+A-x715i!3iP$JqTOra9HXOH=e|@!!z! z#{>05GzR=nd2_$ATziqk*UDh5gnwI}u$h9ha50oqWIM`z%1Q!{#ZI>(cK&xZF8jrr zY~y+#kGSYTiL_Da%39p*2*I0y6Lzctb6^f&{9%_=92Q(o?~+atRK6vJ9G2N+rtMS? zB8+qWZzf?j*Ig~Kh>_oWPHRet4T=>&SR1!8BCTA@;L$;O`{d(~-6Tb9XU4qJo$tx3 zd5$S@^Z251O5@#Dt{Guzs2+87Cm_EnzaI70#VoaMS%{|c;$YO$>sUGRhgND@_)N0D zBu(RzXUcSb?pF_UG2FqwbydS{zj;PE--1s@J4InxG9kB2?`@cgft4sSChQDzRBCDK z)aVyr2<;bWgCd(bK{5u5W!AGtA47Ot=Ulh%PTsBp`wsRbSJq#rwyccy2k6d&R>%B&5fQ|Dcz zYv{kpi6@{lALB3ubhpmP_OQZtlV2?Q&$+)frS>B@_?Y4G)ZV@}3ceAtjG6~(iX2F@L#;Tu*ix$yC0oy0dPTrdB z&c<=O14PI5XSH{~{Q$WlXSOj_M>rB6Y_BD+3dbnePj_YyN2co3l;-pZo}5eDHq)*@ z%SVeYK@X>hXpxX&%n4!_QLB=uPk&YJJ8;gO{dG)wJWU1M^5jzYsK#sK|NHx zOcB4t9j(ENPqct}@Wdy@x=i5YeCK9%I#M5;;&-Z6$B^|vN{EY|oa!Wc%eQ)`_bMWM z#4f3-dgx-2t+8Ii#0s{R*rj@6IJL%&$&Y{Ox z#a@=iK5>pUE+r$MeyOhWe4OqA(8ArHSn3|`Z1Fo%Od=!JY?|VkT~31XDoR>Np*;pA?;aiAB?NfC^0_OHm0!2aIOmCaZxa2dIIQYMXjE8W zgW;&>Zne)&g`-!(ZmXYeXM+3A;#XwLy^>$M!?G8GcFx|C3N9AQPDsil(+ncy=szPL z+gs}V&}9Z5gzinOORTgPzx7BFqj;0rWsNqn(e?1APib-M--|M1HGhbkt0EIM8&;tThu=g6 zjf7mhC(a!N9^5Iy=(658yq0zPYKe7c&0}b;8z%(|1o!2AEVT_=8y{A4ZZh>Li2vCM zU2)rQ150ns!_m*8`9Hk*B^p@m&zLa#!+TmMGdthEeBn-ZCoftk)KpXWhVG=@s%Oha zPp6q!+4E+)Nkkmnl>Kq?1E+HI<3WB&>0VAs!DVLVTFjN~slnEw0uP=y&E=Nj(9Db} zl6nP0R6cG(e$Q3azmbO=r;p(41?vaXZqH7_;tB{{Om~TZcBl4k!O8Yg9?iD1{FF#I z+a*)yJ6dx&aDCH9L_q)G-KXekMvP7)Yt3W)co!wMP@t}uD^Z zJ;6)zU$IwWNNxL-VtA~E^6#{8T}MjsZ}(?4J6DEW#>Q_{A|*7&c*t6L2D6}_ALBBT4}rLqBN*MW4zw5 z#~iUfkmou}ND>;@sDBc8JiI}`aCfOs%6g#3Q2Y&fv7e=~0+FD8X|CWde_G_U^YMqi z+pSoh;U?v4du9Cq5#Os?#NU^%wDu4805jrzhr*~~h^x=&aFY5hK3(13fQ@x$h^P|) zgOk#!`DuY#g@;$Ej;w{0k`C@@2106n5(@jYFM!DIbIYr$(7iv1V{|{*uHSwvQEFxD zx13aaW{#lUvwHdK3a-}6pxz$x= znon7HSAeUMfbOl*Aznmj5>#q`nVM72`erG(0DULW;|4fWqXZx_ABI-rm2rFXiJn>F z1&CVmDo>DKlW+)Wktaq%WWyTZf?>E zk-5|Adp@91Ay|7|xD~klK}g$Ife$7+Xa+pN7!Z>Y{`tIwl^R$8j(Nz;ALxOxX?dI> z4|o>(jw5+RyM&DXJ?%2jQQ`MOYr?jzOxt-<2z0!#1wug*gsD`e?p&Sx>~y`XZ>iib z4Dw!S^jYaS^SAe=~qpU0YA&7`|Q z(aJZ?o+&f%J#38(a5efH!3bHqYR{NRSGT2!>uIfYU^iTShus9rKoB9YMigkgOZ zrp$?Tg5BQ9c+l90cy;Ok-h&z$^^+q8(^*>-Y>0W$9ls&zWKdXY_kkWGsdz9q`?h7zKDaSj@$CX=?1R!fl?8p^vV(9*Uie5;H_Td)Mc36;#Yy& zxd&77^iOtt9c`%P-xV79A^he%LLLe)BYUcvjiMwlLMju(FC4y_;Znb+x99q6x0bJ|5^gL-^S%k5#?=5B1!5LUa;0GH5)2{@@2c| zZ#%UOaS{v~=Fb&X*K%x#?40-fvzd9G+3MpSs?aq+ao$qV zdGU3uH+<--n*ieGy$)Dez>lp@ero@)t|U7#8IP|wISx&Buczt>7_YJnrDs?Fd8fMO zN|zdj(GQXgEa^cL<-*#{G&!ZU3H!du=W1$d`?(5#3U%hRa0^<6w)+!fwhh!6&nZy3 zuqRVKmuXk`WLu~}<%?W0>)+mGd<4U>d$h=xd5n~?(f0)GN($FkR2_TiN%_6lC5u^a zS{LTI(Vw>FG%%jWFB%ZqUpXZej5A8cC8^v4a zIJTs^z3J1U6@;7WVnO>|-1wn$qS~$(&5xGbEkQ3A!j^MK!(lFZ9-}$=>e_)HI9K|Q z&pG*94yS<^Ffr3r9c@sYR)FWWhBk>#>fB}i-N>^LJ2hR)Mhv#wqRy82D^eHY4Y7Ul z^9X}Tq+>dNEf-T zvgvY4EHW)b;P@()Y{*S|n+Mdp5z-Nc^n!qMSI&vzG^g5gON2}mmy{+QGJ~ymdgXlD zEyR5~T|9e1k$l+P>`fWIU;*ukxPq!|_G%IPCFt70+aS*o&HD>!j;pt3KQywxKrFxl zhmXp67)~Q`+K2i{koyvJe8!)2=NZ-D6%$ykp3rj7>5wfz$g9Q8G>wz*KVinx3Gk9A z)g^nji|I&Gc3u%f4fllDRif1?6S7sFq?aoGHU{1S7Q`0|-MJhbEu$rr7ZnEA>?=b` z#}%1o9+aM*lTMMxAg;m+XVH-5gj@=7zI@YZ^9(h5CrJY9q{}2j#%>jAtuk^|OyeP= z&W$t+s)JmJ%J5Un3Yu)Iq$JDGOHbukI3rjd`0_G-k7bN`;TeiasaJmI&2SPJIF{rE8_FXOmj4==G~G)ixi1<7K1W~vK5$b4P*q3x`2A1hXF~{ zFhQgpXabpRY>m4@{cnkB$;Oa4a0={t6mGH$2_@bWchmjM#KcCxlKW8 z-1j^g=S?z>FlWFC>R+GdqRRwn(8B7x+@zR-V%u`r9iArJ%F=L**hC3*Z<%qC=@`r^ zGKVGuX{(F#zuBfWq4%%;>CYVEWeh{6WAc+WlGX|X#oruEo=7G?x^k%AG$Ccd10P5< zOpkgRkgHuIDZT-352q$IALTaDmHdcngpV4myiAYMiPegzm1{tddF1*>iz1!Ft9pL9 z>s|?Bj>U?k^68qIg>4lQN3pwE|9@M#!!KrlzeKC~pHS7Jk^4PwB^sz}{YB^3hKR6@ z_d_Q-)7^JUe?tG6b*Lh)Mt1H>EYzLX_?z@b96nAI)D(DyIa!nKr|)%&cJV;~1-q?* zEi2LT23`YPJRDZT4U-h4_YA;BCBI3_TU|7ZUOe&rV?C0^t@>9tCy2j>@P9t$NpN_f zpNxAXn8w%*A4Ybj&&?zbyZ@27Y)5zVEdl+~I#;8*MBD<_aab5CG77){`dlf_k_)(uq>zZ8AMeV-n!V;)| ztuu;34o8YO_2ZAq&&JW$)}~fNIL(2oj+A;$O!b90RzhrGm(gs5#MW(TEhV)!64!cp zWp=`GUv90yc3x=k1inPgQOL6t?v!q-`HF6AA(%KOZ_YqMwgdFXK%%Y9xJdJu9#jM8 z->xKRCs)@+klZPuhw5l~C3CeFFZrFnR@1fkA z-qu6E7_}+niD(VupKEpcAG$1gsjL3aaZW(HE@l@jKliJ^S{ZU_hn3k^HR>Vxd8Q->~&(Qk7!_ z(pXpY_OePIca9ZaAvpVaHxFlO=yksYZAYjs#xk-AmmAN|;iF=O#pS`&sN5iF(4y(g zCrPadk__(s!gosv7tB^{$@`1XN-k*m`52#uMk>)?08kzFg~cl?u^P1h;4!N#76OFq zec*uHgfU~eb(kF z>*p?aFn8wA{&F}J>kO*1nyGH4>#OoTk_p9CiMhP^J@s=4evzkfYThtY=NyJWU zs`fR3J!8k6t%=D|z0LI-kp1Zl)alv56sGqBz{MAgPeD9&Mq3~4LfZWg?>!H{7Bj+6 z@luc~_$ZCNA#xSr?V5GsfoK6jHSuSrsXJ}8f~xQTOIpp*7+{VbT`^~7^OusEdW=#% z4%S`s#wZJ7#R#f04$!8EzN&MQPA`={sd7KT?@M${mv-AzL=>Ub&KT2`9?3q;h zp41B;RD}lw2QoE*j^(T;qQZQL5^0_?E4^XnB9xjOh7RB^A^MkishL5s%gcZu;H7{? zU!+N=m6N=+ysj@jGnywpioZ4^@R{>a3c#Pa7`HJmo!cb{qCM`9%7g>oc;BCGT~-2A z^ngW$UUot)qp3OWwM)w@orM06ndp%+lN^L^`919o+7;>57{vy1kLbkdE-ux)u^cr& z>bB1FVQMtifL{bLAs|XgQ1q3&lsnfWqfj}oI!gJ#9FFtSJj;CU7x`O2!}UP@uP<6x zmg|D>(yx3j3V23RmkMqoC>;4i{#m}Dl6Vd!4Ul8%o_gc1hnfd0Rw#JLC)P>vcM7=M{5*x$RueOh-KCz&;JZO@x1&A$uiHahzj<{{DEf^8SF{vB^>;x|>d4WDYd8>GyTvf>fx;Mogp z_?e4|lY6!Q`tfg{+p5cysuLyxAn_cl8%h!IrtZJISH1u}1G}YC#BaKiq|;G!I3(TM zm+F2@^@96>Ot!fZx9aosJO~Z8tpY3C92a}3y}C1+IDh{ZZZFSma?bsYYSuwndOkv7 z;hldQJ+_vSo?p})JlQl|%yZ(1wRU^)*jKX-?*8MveaE{EkMG6*;)ptZL#Z0k0=le@ z!l+mSK@rfgUGA6Zy76EvfavLOb3;6*TTa(5JL+)&&S4OA^PiA;wWC$F-p9;e{mzU) z`bhXwtTKDZ5NHsTNe8TCCt*w5Mdf;NtTucEbzBxiW_(Xg)b~)3${1u{N$Z!dEV>C?q@#yO(+!`gp zbp$oz={wdi*yg;uv)hR+8El`KGH#iGev#d2BHtS;n7#X)H?o*BMNlQ;W%U`P#uczQ zZJoP3D{v?*S8gZW(gLheiifi4Lu`fT+gNdTh0f@VUN(3=>nhcy&Ww2Qs@)>R$S zor|6@FHfq^HE`3a(XqjtacdI2Uz6eP>;65AZ}OyEzDA%0XxcE`BS}NgOo0ZuE1|=j z&&utuG*)ePf|xk3mKhfv|1$01Y$9r!&b(s*b`D&Dh!VumR%!@W=M@?VGgiAlh_Fwx__OwQz{M0WL{=9c;`(v}!zuhT?2q)caR zX^-ikcjR3#`@tZ}(>o1}8K0V(T32ryfo+b0fkLQJa3#X31$$rznauD8xbdg}+$n$R z8w{nu@cGGl8((V$5>5E68HlhXX+1YX&r#dZE;fie^q!Zyd1wTHZ#~cdyxVa%1b@ZE z+}vKdTC-;TZI7Ht=*$7JUl(zcTBa`m-Op%n-Lr5W94P}fRFlS}(cHDHj|N4VQ}jpE z^^z$!8V*|U&o84(1}+bUb&jWrx>6#Tj$#Es`TtvX_6mTJ*wAc&aB2GInuN`{vl8a6*m8pZ;8vMLWt}6y;9c zZQEvO6~euAKKXK^7uhH*y8fG9=Lmc5)ul#EJ?qoU{U`&hpCOR&jH}@NfyX?;zK#(p zC4lJYv|^DL&Df~PLN{I=ZFd&^H8LxS$F(VN$*0?$g1{Hz63;~;Pz2kWOvFkHS>Nk> z3bN!k5D=2(Upw@;a+Mz4Z zBB|s_nXyEZD=90tEjL$ZKi_;N=frlH6m*MIb)$;a8)>qQwAKIAkhs*LwXbfMUk#Kz zEfuWed$c^6sy!+%QS$s~+0yDj6qJ+wlJET+t1CZqvyYlT8k(S4u7`SeD|K_yHxx9}?xEYVw+xLQ06|Y3 z!J7v>z@d(K>$M0m=F04oG$HwUfx0ob!c;)a_o@zZjLsU*?4(=Ah?N87OpvNLV!TS8 z*uGTkXqz6~6!Sqk7Op`bP_om8d!;mLaPOxX77Dl! z8HoC%))eutmN+$aVMc0AiV`S!sYh`7p3n6$#5zoO(AZX#ylow=)QC46dTfpxt5uU%bT$sLnoeyrPOc*&lyg}%X9pHNZ1s(phjm8z+! z!Q(a{n&EWv>}TUiC)a@r>g12*;@__a|5}y*r_V4hzqZP7;@f!T?}Un1U8%h|Ml(?7 zrt49o9Z#v^yB-@+(7a#R<099VQdeJ+b zmF%*jf%FaEu3tlshTBib9*CjNnXt!Gs>r2j^1YAgHc!Efs|XtYtBa5scKI4@RqEDE zA5SEO#up`%7Ie#@RXt4)uBBiF8~q$Km(}~HudlBk@Dv)u0qgCRnlEdT)#rYsOV5-Z z$GKBvWHmgo8hgPv$>}i^_1f06Fah12bF6t~!s=x!hSikd>$D9ns%nPGeR9GfLj>cOwv-C}OQVV>ABU1k}$ILU)Lf)$Y! zp$9sh^XEeQ4?5PNEv5DRXhG$Vj+Vp8rPKAp<`L8L*)WeTVSpCiGUTOAo=q7xaIYL% z7@Hs9Kl-F#u>z6S6V(dzIhC06sf-_*-v$sc!Wo5Rh+WmKk?Q|=*>V0@()rD84lP%W zv+5fTUC6T%BMnx{xRxzma+ovwAZ0ur;gVRK1dobDqnCyGYD6Z(C+O#d&Ik+5O&)Wy zcmQ#X6bq%cQ52jl{K9-sl^Q1kt#%mMx_Cp40ib*3InS68>GW&}<s<)Ul|;L7`iuzs)9y-N}W zl~d({6q21#{&#FZ(H6ik@2j@Jdq9=#RB>uTcDAwviNcZf9bAcnK#U=rf$34R=2#hWa&=r}DZ}jIRV5?!nkgQ1!8LYoiBp z5LW1>`!&VAGS$(rptm0KnhGlxnyf6_*tWmsj60#ueEGl)GXB?E2x71O<)2lzH9aQs zc{=~q$zrBQNNHtZQPFN~ncy?e(HQG)2*4QCAHhLsAD*o2#1p3L0@V7@b|GhgI2|b5 z;anX;b%0!*k=>K$Aor|lKHkxNUq!^RGuCSWVSoqohJe*84MTEaFT@b|%nm#vz~mIoCXv^CJkoC?`J5&I% zT{w2o{=s3Xj&1OHeb%g)sc8Qm4H2YoIg&I7e@wAWPZs+C`?IH? zds$+~-Q2;*&0H10h|!gJ`d#tIEG4TB<&zeo+t%*kS4wYd=5@WXT33m7m2Qnd)8ZsB zwafGUF7?P4+cw(FpEfws7mL%EFKB2kufID@j)cYIG%x60_#u#+QeTO#dD6Vz^Hbxt z5xcIK5;Eb4#Y|16Or^d%cV1}j)kc8~YbGZVhP^t3hKr;76odS;y!O1lbowL&gyljp zAf|WxY0y3=O}NuutPi*Bqc?x53Kw{NHS{@d`*&05?8PFg&~9(SxLd2fAB}c(mQkbe z(L?)?2)X}<`q_=s7L^v5L9|3FnfMgHuU!ePKP#S}d=^eKOy;j7Lp+FLnEavi^z?!S zpWBoRFv@E$fCJoI88fjiLt7ho38Fwiq#{rFhwy3FgHq4_a)I%)v(}#LXOlEBEyO<7s8K1?Az!+x4_d$~B{$Nr*1 zS*$2%AF+xBvAxFP|ftxp2tpTR%Lml6JcyB36N+lr1vo0tn2~OM9 zC58M4yY*aXx;)m=9{YO6ZYahxj2tHcBlDxFO=bcC$H_Dc_^YT;og_gyjq-!yqS&Ip zRs)H;4^R_d!C-pZ=&>GoEmAjR!|7{TkMP|N%3ftv!^VtJSf`){${fSbaOja@uD(+6 z8~QCY+`p4h7}p*TQ{Sf#lfq&EOx7FS!}FfryTXU=0<;8)Oo#W6qv4}R?-^x*+ZGwV z19R&yd4O7?*HQQ3aFT+%?+4Y8)%8>#O2A>KMWp^t*Xx6qNqHRTJ&N_AGBKn2rAxSY zO`hjOSnc_((y$zH!n5PdE0!`C^2(f9zQhm9(g%%QSJJ`C-Up%bV!my1Rj=qYjg5f{ z7j@T#1>#cc-or6oAI#4(o0Gmw(`0mLvOA3=R|S9nwt-$jTp|AKmpWXYpnh%sN28W& zv~$Au1CO4KZ+r$qv3dS0r)^gpu|)dqoGoq7o+Xm;OYf1k-M>Q*U!;f!83W^NP-!Lc zQMrYBzvtz^>0YuzaUPoMW99(}$nUEBp*iM88f~HW zI)HZ9*6J|fd)ecSks|~dX49}5FdM?a9nll=2&{5H8=D?-qTp>HeRTXqvkrStQ$%mk z=VUJ4R|{*J{>VJ4yGbR%Od!;G%g&C=YFt3-4`w-)%l(Yg(wl6@EOF$?o2XKHsoQPW zZA0FMC-6H`d|Ixds9TT4c`b_kqb|XgeLr~7vRjEs1lybI71t8KBw=MD1qZh9?$d8k zfB&)FA9ZF=8%_*pnTi4D%hTLb-K)iZ$+kxpVQy&Xa)DyFHI5&-DxoynVLEkXnJ2YE zK{fZI3vTBeTvdCX3-vzWswJJ4oeV64u9W6sLTX7_LvIO2|0py)#q&dOf=miqc%G8+Z#{!s&sOz9qq|c>{BIDfo@olMqlnHmioF~n2-dRR zh=4%{WyS(U)ij`uX#9h6m%@Q^BJ*4wTUP$eUKZ|4lG_xONdZS=kyLWH91=lt&hxK{ z>y&4nfX}yvn&X(105{}u)sQxFy6&mhB>L@cit&iJ$oTR z2&mOzJH6*S{>4D*2gt%Q6PH-vTfQBsw=z(9F83QOEnY3I^2;a<)6n2Z80epdm^oLZlJlDcHT-*zK&^4*y@%AZQoq9XF zme3;4*i2pEm7rYi*Pcrq$+FZdCsUib;h|DzYPFmJ7vkhA-2au*&wW<<0Ut)`&uYCd zM92cbOD;!9{Z*sdD1UEnnRFK`mo6+yPq%Zo#Wx2s3^NN}(PfUZG#j9QLD+EMtarWH za72{;jO_9~_j?slVKX=Ii9FtsMRLM^%5x8jt?`b07cyh$iG8+}@GQbF*08>*ueraqzcnVH5X;&t?@kl&c5SflHY#Z zji9@2DA5(y0tzN?o5i9+llzAumdk!re8A!NINnnJG7C~KqXqQLd%0pe>5!Fn!#Y#o zD6}3y{nnVa_EtPpccJ7DsdZPmU*ZykG&(!6D3h^CGY53pvjXWGdhKt<#OBk*)x}e9 zXsyi2a@YE+v)Tf)GTsnLs?u$_e<6WxisxiSYDswBljC^lX*{F|wn~bKt6k)d%U2Kg zt&@*`u-7k4LN*g!VA(-d%P)eG!>z0WKkP9rVh2*c5YV2YRW0zdo~Y}V)Nw^UyZiO< z*AB)KdZG%N*ZT2#lsDSAGjVJSXc6OR;F$@*wsO?U4ys*4p;qS2f@XI&wvO5UA$;Kb z+u5wFqNJcv$Y%*QW1c#6MH6MmIy;wfmtWmHJfMvium5*7Poc8R$sfC8I(_#8?B7GA zgIzh-B0KGsLamk$-_$p*`Acp>T;vN@MT|EhZLVhUPFe5cNwV5`}bLvR+Y*_}X1K4EuN{x0JmxP>YznvaS! z!c`}I(kgL|nq{>+J4P6#V9-vHs9O3&DiQHZK@D;^I9jw4Ua$H?0*ghSy(}S$M_hXE zGWFY`Z7B}vpZGh9GyCmKveM)bX@$r0ipXWzU~UoBvpXMb%m-*tfhz={Ev>yH5`o*| zo+y8dl|#EpL#3_u=4E*6xe8tz!SrRNd@Ea6Di_6Xt}ce16s;h^-AlfhLHg~>50pEc zK5xSp0+gQ1f30c0K1;a~r0vtXMC8)Cmt_uocY1HieEUh=_~1D#?kpHxPtFxozK>0W zENC5hAKR;xK%oa`-kL`eIxam$4~&QIBgJ(%3fnZo#LoQAY4=jvy3)Og#gLu%1rvLr zaNqN7Jyl{~h-Oj}sN-{MFu#pJ*U7P#N%s8l71tpR2W3rWw-ka#T~2(iB<|S&s%3ZGp_dIt@d5F-5iyQoyN10wCjA^ zLi;_UMz6pxy9mYECJ{MuVK_GpGHRHnlYX){(m>SaJ4`jz(YMfo3-PdnGOUqYgWAJdDD=TAR* zPXcKEms%1Mve0fHC0@b_8aQI(BI-^Q z^R6%N{+DTS*z5y@`g7?xN(S_urhCUo8C}iFJFBM|;xw?*v?wkfgFKEkuU*E&=Mi5Z z5&4=Te(E~D@n9Nh1W?KX#;lhoq0ZZ!hWOG}56(hW2Z_8B+$5ip5AP4>rHcB&Sq4%z zC1X{4#BoJ-s4fREuevLCJsMS+EB3i1g;0w84}OrWqSvSAGirS^av-!aD0;~%Zq%iw zrRazu*QoHhdSvC=>bx3Ad$_ty|W8EZ0k<9u9?U>d;zq{N~0Tl zo;goy()6E$$d$?C(w*|yP?Typkvk;j6XSPHbPLGVysw`87Zv9))cbVge9saJdvs3KRwrj#Ci zQG~YsX_Cdx|CHiV(5SN02s#2wZwT|Iosd(;wVi@RS7Z|{ifpjXS|ZvgAp`%jk z0vb-^E`rHQ>2GzJmm}Ga&x4Yo3}rl>VCS7SVp3zV8_A7%dwhzvv#v2~@Q)8>Zh1j5J8e<$`Y?9}+zJ zj|RmSPm%ZNb5U*M?#}gU0t@?>57GkF1&F$(8VukDkyvss2dqj5?H533-qy@-Em>TnRui4*%Ts^>6RTO3C-Gs>K$nOPD? zt5zvFD!F@~UIH$$mlG3!Ud{l)Oq4bY_w$`I>Z^3Re27OS%Lu3eEg~K&M|ys*eNpaA z9+D6!`=rA`f+(Z8Ne+V)i*PblD!g()}|%pElyxUcE(# z45UFU|D3H9-V1 zygQdN-v0d0A(M0Rf8s>TX%Dqo&W&e)ry5hE^&J~U)}F^Kk7VZRAs8jl{V_{U`OsZk zoz-=j7Au++p0L{wqCBVFX$&2U()fErte`pQrOsn3lL7Op#tT(B1eV!riyTvBL)vf2 z+GfRKxnu6(?k%YU!umpkSH>MQY=**9@FLQTl1BJk7LP zS1R3egT4xS7G;uoLxj(;;rwc(s;#eRXuDH5Eox8zL{HidcR}AFI+Xn&*B+E6-I(>g z@lEv#fhTKA~#$1#L;#!b#KdRr{X z9xJb`Fb84>kG=NQAE@#NCoP2e;|-y_1wrjDe%|eOc%9bcC#==URzdpiU@6>AidId zP3%Ibugz(%Ds9LcfYAz3@EQa(&hYa?Sz5Lo-{W;%zlJQ$+vI+xm^WnUEH-LazBgYf z#h9+H`AN4p)?tt@@XyYr##tw*m%8`;Q*P|GZ}M>h`W-?$SMD8+m%+Y7=_6@Nr^tAT zI^=RTDq1^uLP7MfEvz9sgBHw@@pxKq7@!w1_4Qi|(8OvZ+L9Elz!S9=o9U@XHr^FH z+7c{cuM^nt$t|Uma30kQj;dpS=R<_oAQ2#Dk!480cFXe+@p!Ct@BwFtf1#wn=RNqp z$zjIOLt70iD0+1HkJJ9v(}65c(&P!dGuQYLsnI81URDSrW)4W}X-R!JF`1=Wyd2tp znxj~s82CllOT^ahkxYd#4En(9J=Tfw<+)QaAO?MSTg6dC4UyQbuDwl4X?MZl2WRziMhSwU@d|a$;?!_=?D4Q(p;&`wK zV=qqor>qJpf9RPt^nO>mB@RD$^fEo*@aE|JX{}%fJJ2-65>2kFe>f%&SS3mqLS6r4 z>8N}ZQY<5=iLkt-1VW|J^%5k{4#Y*P*nwe^kdi6Hnp99kKYLTCOX9_ZlXNj4CzHJQ zE>igL$?WY`qYar9Sow*Hr1tcn0rMQRIcXIiFE~$3SIve_^va@fgMGNlW6sm#iHb){ z6FrZEax5f||1Bs<`u&aVE(Be$ejd)}N{Vw^q>b4C>eP z?0No!oXu}o)z?E@8Nzv2l3omIl%zMAjqceCiO0Wq-7y)>Nc0HL)T42yUH%qXh$(W2 zB4BFIJQQ5gvQpypD{%_wmICz)GU1&DCThJo#zh+fZI?{IAvihv>|({*A9bRapt17e ze7yeS#ZAxd(geo;?RVGqb+7JbFc`YNCH7@@aW*A&NoOM=ZF{N@cFslVU>$rS4ULFk zJ8IG*fnuRY?M^wrCW`xart4GEQX2j=PT___%u4CK0LQ$-^KPjz2bQ^>^2a=_9)gqMb1pFPRL^zaB!>p| zrc@K9Bc>CFgA|S)pOCjzyWrq;+TS&d;n>j^sbUi8nJVXIF4h;U$pt=DrYgcbM$Ugx zN!J$@2LCuZ=x0+!!KSw8E;F>>!RjloaapmGVt1FH<>6~b179!7T`TF7ZUxT4%**?@ zYwnMM51IdEt)a$mtIY`9CX?;~309Fiy1umn8s1Wm{gIeeA_O$Ov81yZv>&O#^hx~! zHMjNj@YrE5alOqs?}F2$e^sfZw%swBjSge~(FK$8q&W{*m0&R9+9s{Ku5kB}yZ~%i z|E|9Tde1j3UWsS!&XwOd^P&O?INRO8Mp5zP1%){jSN~UcYHHwmyrt!5v1O?iI zmi`o=MPY8}q$ll7SJ13NlF~W;!c~ag1obx_>&rl9UaH3?{j^voE^}|VrgO9($*`R~ z$2`K$18^|jj6IC?E3H^j+srnz5-i2WxVtvIo3y?cu=D<~LkE5M<`Xh6c=9VF3AB@A zw)0tw^kyZ^Q($WJgK7=3_(8}}s|BP=zG9{BJR+)N(tslz&Pyc)_~_5-_5z+MZuS=d zH;_NeTmtVEUqi!0msZ-`jx2 z&-kpBQ!%c)YHPekw2^f91TXLTQ%Qf#X8l@7dua2ftKz(M*14M;aksKP>CqBjEaryh zJBe6Okvj8Y(lmf+CfE-U9r@k;@wt`=T~agODJtZxfVR(?#{z0Icoq$v`qJ`M5;EqT z8+eANyU~#MhS>dd8}#;rXji6h3iCf(_dXB7HH=zzV)7c3dY9y!X68LJCXDq0tmjCZ z1Foc3AESrKrN{8MXNrq^eF=A%ikSo|qgRpy=_Xbo)TM~m7;RMPy{uS|Y#Fp-RxAC} z|7be*aHjwN|I^CqEmV3t#EjHba@HI-BqXQ2y>rMhbIg#lIZIMGn?e{;R&VEX&S!=& zXWN_&Gv~48+;5-nb^ZR_AG@yY+Vgtt@q9e)kK1k07#Ik3@#H$v{M`L|+h=#wAgAPL zSTZP#W~`FEQq?q*o`fPiTEPkT_)6T$#-*Rsu(= z1ZulKf@NR9v7z3Fx0!)`J-aP^oUO8sP_Xs&%tYjHC4};~NzGI)a3|6~CP?89#!B(J zK3vJ&|KOF#)_Vz|)&Pwf$bo^7kxIJ4rQs>902zP9i})_)h^sSd_s|%E*XS>$f078~ z336CgpDQR1NeQ?@Gfjnk$O_zx1Xnr#U0IG71G5EGuFkh{3SiFoes>#P=9Haaw&pg{ zj`9r*EiqHShgoW7<`0oqttYjhT`!~z5)*1yaSQz7-f-|e2vDjDqrGNys=U0wxIs&m zu{a%H4t8xZyUW2FCAA{_uXczY(kP8S;((@vsz0~wlAC&>zS8;U;C-wIUSGCL-4V?J zK$d@2bdWgj?Lx>78yj}+{hhibhMP;()MJCGb5ACh8gO#KiA6B?6{*a%+x@HiA64Tp zrPQ*hD6RA4!Ehq!Q0_>T{ z-M#+_0fMIm-%M4dOZd*?ofeLt=KLNeWd|#5jBj`;29% zMqp+LwMRXWCaJ>|DS~I$&fke=W5u@Q{2|5B*aDaB8=1*cywjnESzrU+0s3BCyVA5cWvqp zDiae2d0t_cI3NE)Hn5MX(JHwJGf$Q-SWlB9{goaq^@y-@l<5lHiZvDLE9|iGqdDNP zXs%85obc`6VV6wA7U+Af%?;q?JA>5wo`*w1tvio;l zbmmSlvdNtBNwNwgih!HKTnhU?dilif5biK$=BKzpd>ba@A`3M>LiMfF#f3zx3%22O zQrN2Il*e?48?%^N5MV?Srg{|wKna3h$5j+}C)<9FiiR|Az!)}513&@zWr-LMo0U@?Jo4{lFAZ`xm4%^rxx%V8o8lK#N$W!`C*k1Q})19fvD5YGq_SQum z0>RX*^U5Pcp|X{&)1ME$?dmzS4cDl}K2G93KNyxxJ#>*<*7K^}smnR8J2s4zxX|>o zHz2K*?JTZT8RI3Qr)IhPBGl&!wY;?c!e681?<5{gvCaQT1Vnhkaw|oIXwVA?qoIS? zwD4E~rWHCW5y}Z~ba!eCC>N0u@~UL-v)%Nr%~;pUq3mc5X*+c6`e#Soz@$(0ehTa| z2@^a!x-g4sa|ovH{*d6QZ;gCv*&C)D0_<%SKJ>*`z+8J*j8qhfzij;rN_}ziw)lkR zl&DH@ae6h@CJax@<`lGrWl&!U*R1&*iOTs^W05Bmf_ENTrNRYy-o^Wc*0nA@*zU z3w4fWUB`umhO$gNo6U^Y6)7-jI4FZ%^ttSzj@rcV!KDP{K$Dm(|Ff#`UPr8QT|RT% z_2-IOrio$Gi37VqiG(5h+!tX)+X8FNi2DmSGu*#MHCnDBl|39{(lBj)PtBpIulp&wuf+x!A|wGHF659lxPoiE-fzykRf;Cx8N%!7K3{?>Q1| zj~qU@cDDemq=rB6Hz^k-?$1OvQJ<9(GYfh~pkb|I{AVoT_LD9D3$+J_E#|Mr3TC_? zC!9O<1SP>fk#X;&&cKrj?* zSu+f;oFlIpDN+XL3%%Bh`hCc|cEyMw~&XSy-$Yn21 z-`$@~{6fTr%8ln7T&-+sN>7w2KjmVbIcX>6D!Ro+s@?t^cEt9dr>mdzRW<9Syq3wy z$zyS&0c94u?IQ5HYz= zKCJ0E2YgyXxD_>&7*(qrOf73l=a?K%3?YjiM-&W5WzV$u9auEY{+YNu2RD`S++F^{ zY@+FYtjdP7|J!aj7H0hXpf?^P1I1 zGn^i_2TDMSj*zWzkb4!CnQ(h&Ykd`f3AEFS3q*I%Uag2Rl=_ZoqAdFyE%$4?=HZOl zk)9aw0+m|S%gdeOJ%3qzQ>CG~7?i5yo+W_+QS)$~)|=Jor(wqR-6P#wgI%EXhSXN= z#lpf_wcnKbA-M(1u|-zJz#(NaK#X02s1Mj3#v_1S-Xx6y+cQD2>b_MB{6k0LxW3ri1ZKifysn)OxBCHjrul>ulS7>ur z=$Pf0B|fWq`KHD6@LGMYn{#b_jk#*JUzB4uC8usKde+&rQKB-3Q%WGb<%B{0;rBeO z0t<^(tX^WWUnXo2!!{p_`1*Cd&|VT(3o|7{2bsc|p0`%>mZKqSmZwg&4-9x_e&PVf zWufsfM*me<@HtdOPl?#TFv0jkPhMY|ScG6f$6J9arnu8{jzKK^C85Ntb4Y7#0?_)A*X_dsOMng6@4Nn_VO?`>)zS zmSHNBzICBuO?mB98I%Z^j`fKRq*Eq9b(v+2i z)(M+wVlLb6U3-Uk=u={TFvP2L;zIpPz(qJK0m|=AKNxotYl)9bJ9zAn;EzXVsKUiM z^)QBvf~=r=0*vO?GsKA6xUG|@p9^2r*ndBo4PRtJM|f-POB71hl7C=~lE&plrl5_;Y~l!7jtB zPE1@4^L=+4V!V*X0ptaD*9462v7ba>vW};d0uLi%drcnaLXY~xxo^YuA$64DFEP7>zHk~{41O2_K@W(YPGOoyIF@#`#OkQKcIesm zJ@@y&n}0VQ-*lI&x+w8iov-39lNQvSj}WA?s~oC#jDFgq#%CVHp;hw#XM~;2tW%K= z={i??_n9TQsJ<@65$kJ&ddq=CFscJmveSBJ_!%Wunz3L0*WuSH|BDJ z!EOBU>Wv$Z=6=yr8f%n=^K&%3S_28~iJv@_KIXU(F6Enj`Do@2Pw<);blTj10bPti zkDA6T-7ZxduFx^PJJbWM6D?NyZyOo2PTJR0__HGRhatJw+sybMmo2#Y|Ky8dFYSd` z;YE51=l{MAC4tLcwxL<4j$pchi|6 zMRR?9uTbR=az2A_cI&N#bFJlGSXE8Ieu9&cU^sH4vr%E#@{vJ1TjwL0R-p@wy8-CD zOJ6GnqHM}M4}K3A;(0WR`!at@MaBJ%2C?%uoOWw zXJenqiXiuAUdVF?e6nOO>8YiD$a*flC)~y(KzJiidt~<_Z_jpmv3g3-W;$|VI3HoM z&|%*N=(-EdgrIo2WGu_1LD5_n;sxiB?dl*~l^b)zlnVzTvD}atBU9@*`^6rsJ;FKO zzbYI$3vy3enF^U^7p1A;HYs@E5o}Vj;I3HnVmDTypPV0cR8(B@wZk-*Yc2O#P9X7# z6dWUH0Pf8N9Y-phR?79{+BSFoB%Q6GY2sYm~C;(oLGoLR4Kh+yuJxKCk^WoawD^@-s)6^!{zVEOXXHy+`u z`Az0(`{T`TC86I=i?FMVP(-^~nSZ)Tj{n?Kx@VqAz*Wg>k}JZ#QXk!3r;A>DdGo;F zHFis8d-W+T^UfwL10thE_Tl46`j1+&!MaWO@fZj8Y%qg zya{0juz?3&Ne%#JL3;OwMc7NMt<^9(a@3f4*BM9mlyaJVNDGm#5I!_n-~T+bLrw+; z>YR~pS4L0jH4=TrHkkp>)||6~kmdq?#=44)@~+(>tUa~g*?W|;iP-Ck&hCot&2C0H zmZXcVRI_KGMokR%^k(9pxFyf{gwCsAl<%uXKRVb`oZyKT2kvR2f$HF4R39jZL(%ou9}KJSb3W|u+)nBZwl(PSxzj7DpJVG^$&oLhCu{F}@ow1JZhYN( zx_N~L&j2uO7$!05k4GUv|E?Xrj*a>emE<))G%9jBY^0c3CUXr~XaCTQn0BBbR2GsS z)lGRXHi>?ud{#fzE@W5cjMZ%V_h)((-j&E72uv{H z5FbBt48D_f>YbD%v(1`(x_N_rP}@!h^_OO?3cDY)PsNhXZhc1Rj$sD$M)LC$fOfRM z<;xwNCw32TJVg;lnx!0uuscqQ^D4*G>Oyq&U9xBcv}bW3#=yNh+H-HuUn6wEEPLol z`Isb|Z`CE@zH>&1Ul>-%0y=a!AO;Fanr2Q_kjnzFCf~(z!{6`3TI#3H`FGw-T+xr< z98sFs3-2U<+!*u^J6u{%|GnSd^;EL!%BGd7OGH@Bs8(!GZ5?3Br~F@*x|P%iFXw!W z^AR}+Dcnk&>qKw)x3aE;Lo3X9tcmI!r^A$ayV5O*JA$l zsl|Wr zRKg8%H@+4Y+o%YF3fxj&+s`q%EQ>1G%s;++epP6XLmXVGk!CW7hiTIvkIy7%CV@q& z0#zbIP&;JUbB5ydHwJSQK$ZGVloA>>EwC0olz&OqOd;8%8nMFDey>pzkesU~Mt00zt4 z?8JU&TysYfY@+R5zE0>O>P)uGbbb7sjX9oiJX@S+&P@tZtYG^)pMAyiYFBe$c5VVFyTuz% zf3lWGz<9=>xWKYDw-Np-B@x_fS265x6@kS?7)Ez_A^%jxx@v!?lQpHIkP}S*lJQ-G zR^2hml|ejwS1|M1&Md4Cgo$1)=~#NjPOoHM*?yDkIdypKQ3G2tOl-$r5yK1KPp8Wi zsfB^Kd-T6c2DK}Et4DP`jxjk=05R$gU@>OWr0ZlAeSD0=*}1bo*?a5$uH4R zy(YBovNoVxM~v6=4(u^sbpJ;GM@410diT0NK^LkIg~`*2UEYRHBV(h{eWRH@vZQYNq;YY5qW1EipmTfI4Ahsd1WUv$BeYk9R1TWA9$GQW;=Z}6J08} z^W&Y)WrDD++Sn$?;$n=do#v&A0qyl%MXVKcN`$=@V*5W>l;+bIjS5a+SS${G)6=YJ z3A8ea~`9Z}OOLEr|r|-dsIubgPI_};$)|mrerwF&3Vi+~30Z zOu$E&AfsN%j5B)_ACpzqONWlF@Si`3S7JL4@6Gn@HoYIU!yA`!2s{F8y-$ji*=33I zY-8i_kGcW!z%LCybCwJ5)lzUpN1=-`p}t8V^IqQOut$1aVEwGEuQ{Wc${TKI_C;)_ zzL&YV3(q&KW>{1&kePmMJ(9vw?TBh4G$RPurFVF;B)3p!?&I!=d4*PuB4sD^7n)u}mvOHhjEYCa>nP)1{~4)J7Y*Tc4(*g>zwXyLmz6IT zf>G7G5&q4Dw0vR0t9?;JFf7;v68aPVNTvI8@xey!0QC8$Gd1|XcfWrDHd56ls_7PY zp>8{hwg;{f1%Ops)vh;TNHijcLowL8vogwAvLV9g4&0mI0fwZ(ZB8RBJ9I49@S;6o z^+&U9Jtj$@N|Co7pDAvm9pYwWl3pK&P}y8rhGz)S(SPhCvYlMP${Y#8 zWSI*{5z}wn5uh+eb?`TQq8*%j%hnU4`-faBxg~t-y^+#^>fQHj4hwXZhi-yf9GEKI zAizI246gffk8~>ZatOPe%eV~5)Oe8OBkk6)KhM?zwG5HZs7%DbLB7#Q<`tZZkJlEu zRhW<#FCA1dTp)OQNiHE@sE$l{%wyeDBiNU%A{^UzvM!au?^8eQ6vw;*h*(H3nR%+l zZVFSJeMs)o!Uhn zZ%uC!8qay{2U=$v$_(%gAH;kN93A{x2}m)+qJ@Iw73&ri4&SVK!VZM&4pf|L24jqfdSoa<(&s(v4fo7(S287fsE$B zn%yV4VEqbY2hxa9650}{XjuGU3_3J7H! zrEG7s9oSKwmflrz!-A_5p-jABoMBC)mXwgc##w~`Y?kMS6xv9vNuimXigvq2VZtf;=9F=*0{&Flg^+vL#H7!#f{2Gt9b{mM;p?`~+fd!{3@? zu;MM>__T-=^2N})-YVlTL5H|-FHnz~MM$f5{aWjOimQHa-tAfrW~`?g?HMk|6ET~b zO?M9%@Y=l}YZ>M`z1XkC8*t^hW#<#pll`Mr30Y^6#Hq_4-jB}z&|}_})K`t+I8Pb< zV3Ppa_@1qmOT1<*p!lp1NKPp4QsH&3;^zvDfPA99+RTXJ2L{P*e6KXIh2%8(q7BT{ zNM-n6QowB9mV>Ti`zRx^4FO-z@MF?%Ble$sth}P0FMetUTscR-R8vzPP_OP~p;=U3alPj)}$hhA?J!WLu##=v|`H%Wz3_bReeyjQo{#_h@++`kN{++)r z8JBUqNxCn5zsJI>q9TQ_4D|RuH;KJSQAC8#Vd*^kuUqQpM4r~Zd9JDFLNPU>Zc$69 zpKYEs9WEc&wfz1;tZ(G8IP6KZ_M3$}4>|w*jhU-kopsZrNx#VpdBhTs*(Vd08p)-2h7*qorPy7|HQEDs9dp%G z<%gOR@g?vD*Tf}u^_m`}5S;s=hjF=bhYU_gK!`f8Yesz66yHdTVj^KEF5tL7Tcp6& z8U<$NzeYwkK79Ipv>KW?k_qr!_5>75w)4Tj>~%s6(GdM3UXjZ0ik8aMkb zT1XNBk(^NE%3 zHExQo`@SPCXhHL310;32|CJ^%OmKaQ&jWR5OAQ$oOalcRfgn^aY5MM5Xsd!jl^F0- zdAp`fuKxX0Qt4zLf3NcggBA1F!XI|6xQCofn}4a;1pJ8tu`N#ncK+OapLLYJJd=r166N^rmww z2%gYQY^rKc=y^rAYkKZ#pEDK43tsUjWi~R!XU5bs9Qymv-=wr>F_%M7eH}>!`-YC> zfb%CdH8PiYEJ#6=#PjfMg>8?PJK?0cud^ZAcbrp1{1G?c3i5o}W4bM!?Alm*ks)mjS7qOAZ>ZSA{j4r!zkF zsIGNC;a8bjhxQhd_HdfKcQSL)Nx)ooa_~%^n=QXw{A? z{#b7ZO}?^UalIbF#Y2nKn@w6jllO?q9e}O#D3{^a7pgHRmF-W^zdbuXJK~u~tMEdID^b(g9Wgl!#igR`m46sX3*t*iXs@Rb>d10T$cjuBz zOa+Ppv!SGdR1R)x^gtU+3awB0c^NQC31a_S%@VXP#l)WL0RdaYZ zz`#rLk(!zstoO@g48m`zp}=;vDz0v1f6fJ&{*Ik4#3|t{Vt;y7F6qWDI#78() zuR!+#kM(V`GA<1{5nn|{=B zls=~2G~CuZE?-O2A+N<2eQ==3XPz?Te9%jNj<mIL z7%3&H^k*rq?5?TS?|cf>PCtbl}MM z4vC5^`KBG>LCsfCmz1#oW^iWYprf!?#H(@^|}@Lb87 z)XY~UJE_TB6D1XPCn)*X$F9zewX$c$HV82C;k*JU&~93^+@wb6Z+ z78_K*L`W;_A&wI3-6ZWF=P9hl(BP0%~_X^bzl#0HH_?W4W$rH=X@;SCC z8MlyKe|!^OJa;q~;kW-LB{$(6R|-VuU>4Deb@N8nW_r%H{}`z?)H>OoSV;)s?vZ_k z{$wv0Z|Xrv6R94hZah9d4qZjJ&k=J9xCIx|c3j_-LaTN9C=>z12nZ z{XJ8>7P5W!Xw((`qw)D0df9*kLyguS?ES*hX0TtG{}1x}t#dWkei<+xUn}*yfpFOL z34~B4=9ER9h0fRs)F2$*^wxeuXn(?O~jwiwZbwqo~cH~b3otkxF zO^eSJcA){mI88C06nHKw0bRhce<6^V?${i0<61EZA5C{0)-?vTM zsm@RE9y7ulN)?h^$>oS?>gK-_p0)WQSl1SW{V2rUxrpkjlbzi+QYPwRg7H0$so-8S z)Z_yFGi2hl!6$XpCo?!N!^Y<}wP)-|K1yHGm1*uAcye{VFG)rklA-#7T{=gJM z==bq~q+<~

d2pOMcdTjE20`$$U2)gEdTx>e(zSwwjKqeDR+Qcl*~NF|l7+BXU>! z=3dx$e7#f4CtE%>J#E`BKItG^Wz(PL9qjz);nqE4FhmzMG@=dvnfdXmZ#f6{7$Vf) z$@*9>tgq(Su!6g|*Y*JC2FN;R$Q`^v7SJ=X`0+#%U5}Hws|%CW?0qCAZa<205%mjV z?DtbgxnRZtbHUA=Uk#@praN`LYtrm^bFXL1iO4HZC(#Yh%gE4gmOHc@dX&P*>U-oC z6f`s+OOdovS_6O zOL}e6ux=3uS}r&EvI**U;m?7$g6@z4$kq8AE|{T@`CEN2^k9DVq2!_{R6i~+s<}sD zY8L>`PDtK#Jj9o4wZk19zae;0Ykk6=*mUHEVKE$;z@nnb@_EBUcvo9){#!d3wVJ8o7$}guz zs=f6X4e}MB@&O#lMVSo$k>px#A;=|*;rYJ?9b%f~1&V0b7Rz2IKl@Vj>K8eNDjVIjJLTcUI0RZ{re)q?r zMGdrhLj~qzdK+aL=~SWoVBpc6LgmA-Aomh%DORq#Mv}ac*to33En+`IRQ{}Hkuj^9 zed(WBpnT^087B|IULrKnv))sVJAc8{{v`<4_ zLaQ~szqj}haSu#!px|!OQZ2?#oq!1_l9qf^EqdO2Kwv`B_72)Gs{2)HS4d!r z^(TamT6PJ%*}nof^9JRYSt#|MTiO3Hi&y?AJ;;WH#{ul=_k-j3oztSRf_(fg*>Jug z@R1HiK15>_3f0H8Vm(`NuQ+ZeUY=4_UGDMSVCS}>_DAxEMi9~2Rqg7;kKz8~k6cC` zx;{{T(XjTGHOUZ@-Bj`K6D+BYf@fu^6$yM8Ge{TqxqWe?t*CLTO-7PSdrt@MNQ;O< z+#x5*+HJV7!{yoZu^QXnRVuOEAhl-!6w@h^_Zpi;l zyo}~_XxW#p6XbMGmVfAbGwHtL`g<;tZnU8Zrx1$t3`BbIT5Q*S@Rg+$uQ<}#TcIK2 zk_|&;fDE13cY^o|_z-j+mHlw`zvy1%JPzT$1+}RBOa4LjshY(xKT^1(?L@6f^ zid4_;3+#i7EM^S$;m-hOlhhmFeH?xEmec) zr8LFd^$v!HjsX5~R+?_nhksV4@Q@zXRp&lp2b&$gEu}DjrbJVyUYTN2v$gUue>!h6 zYN;#=n&lf8D$LFy&DL)pNM2AW$bFG1%aSwJPYV{{Xg@?)QU93;!)9!k3+p`8At9{k ztt=-p=3<-HD_om0$>4;J{+c7dJpSj1D_1nn0F3lt1UVfIip}sqOix)%N6@n70F~B#YIRc|8HX&BU7hOKja| z5``}OS7R3ls|3D%-+n)hv9I^p zK}KAp(qfZeTVNqi=TV{(yQU^vARynd4HuxrKc`uRitL$d!t7J z&ic#U`G*)if1tQWILh3&SPkVU2&M(L@Y7q*w2?#K66*dHE4W_3zz$}x7&5Q`h9Led*>UIcE1O*Y>eK9~3aAR76!qkf;~*c(v?_fT z6X)M6dP}4GCZOT`w37s(vw2rwI1$2?BYQeFbeuY_;3VxU-I&c{IiW}DOGM4I$oPV2 z=R*3)x-89c&jeslzoePFr4rI7<(C~d);-0PkfH$JV1P(?Rbh$uQ3~cc$35<&uUp)h zPyS-F%%c)Ue`SYNc#FQ#^7i10+r!KK7tJ!aB+@1k*;ee*-x}9Uk}1>&m2KdD<%0(;&v;FZ zoc~FB7WZAy9JjJiy|HSUS==K;>WlUXhn*a<`<>PGyj-8pul{7I9y@9_K8w^|fgXK( zkdRj#vbRYj)`qIQL(6P-72g@`*F1#~I%W9*JFM$-Bs)7YmtW+p+3vh<&ZQwNB7N1s z@ml+|lRxHJ3o>Eoud8p?R0-M_unLkBi_P50OeMNFYG~kO?Zs`RvbdVhVUN{2QsAfs zKe4aC3nQF4`y?#8_o-=Q#X#JpXXD9^O5b9tGm@6*zNxN*u(yJ>_vWeq8!`ebY=0gSr|2q58|AAbnr0;ZaO#*(;<%9@pgtm^jfN4$e3D@s-XE+n!nU!hD1l7vJSO%R@qQ_gICXk0SAFo%uDabma;f6ENPZ(=4=i)7Y_!+PK3A>b}ztB>5J_&$@b2f_ZixBmU` z?H@hmxv*EI4eoC}e&8%5Z^FFB0vwYMU}QzzdB5m|mKmLmxMqk_K6T~p)0-T&C3Ke)7o zo|dG26X+05S0kn+N~(v%wLMCbNu0S9YR7~mHoUx`mPJ^jqcUYtWuWa=6Vo^lFhO404t1wW4Igi9LEyY~g6{U_ z+$y)3oa~-zSsv6WJs#%dt1C~a-*Fdp>HDyd$ZBalr|PS2Yi*Pvv!!fpBVgy(EgwEi zKUi}%w4&gPbROJ0qtg zmSfcXZ3P`KRFMqJBhdC@dz6oLw$&8{RPl?IoqUpv(@$JIN=EVnehUeKt{m<0U z2NttaZ5SKkC;GiXXI;sfF!zc%la;ir($+ zj%O5=?WCC7e;$jT;`0OrfqFCJz!vM{%1fUQLvP=d< zH3?o(g7O=Y0q53^{smgNM3jHl(RrRWX_mGWq8@T-?d86Lq%E zy({)MW{{5@yKDk++DzGIX(5T0G9^-I{5Bt|G?pP6;@zp^IuikMNCM&lg0mqr z8Zvi~efCV|vfiB>jY$%l0RmC&6t1YLpw@q8H4;EBBlMVrDvyfMARCkm zMw%QIZ>Ch1YlNT%ksF$oN2&@r9Z~in2Am_}jaxY(wFuRN6s+}W?5@U5|7*GT9Su)5 z-rN1tsrPr?MMd3iDEijv3!pTV@^DCx+j7VTl9=tK-xnvtNLFCmuV=n(LDaK|7*#qe z{i3(?c24^*?(BZQ<9?fGbAL|fEGymm{W_i-%tV1}E!8n8<0UEa#zrmI>)LZ}nu8a=t zCijxA(G^3#Vj6brJkY0;4=ORb1Y-1tXJ2}bn#~+z!i>`>Df_s6d-8C=xw7`?UjwP` z38&`d^rOKQC<#L_Td5&t)bCQG=tl~IrQv&}YB_)3rY8S=YvpZSXg3MFDtEQMtkXex zGo=^r1c@)=RC@m{{GBy&?urTu?N@`rk$OhzF9+dVN=X_**7i?%;qaM;P8p4MHmSB{ zopU|sde|x`0E(OCWl$3*ZcUFlE@Y(y+B{234}#qR993*Qcm!J<%|RhXazZwLurorw zdaSNBj0VjH`5o`0Y`8m0xhk?Z`KI%#t3T9 z3U7wUTX$Ppw|8n}La)lt-ptf>f8g?_8qN>nSSAeK$Q_3-OBObJbDARaq)f4s{20bO z$?3?9_i~Gv>k-ADetRN;-iGx`aKFi}zDhnn0rcG)8ILiPO(?(b=&)?*=^F=ZwzCPx z(<2+j3^$D5_8ctn@QL%JE}-)4t^SLWFibk2FzBp2artQhBkSI?$Z*plA* zM)P#vpnK^+@i*nNvw|S|~{``Z$_#TlI8olpcOonNuQKdi+o2grStaKpj3q^Ks+2=5va=q~0UJsU9;7+E5A zBv0fENoZtrY@yRtCkZ4lAmoJa*)T|3LehhuuQy(ME_% z)*l_#*po`4gb4C6%%NW^D~V9wO9|sxjgqFFaxu4iree{e^`1Ak2p;Qx=CmIWGiGTR zPQKYxR5b7)++96d554I3NY);x9>CTyd`0+GCR~8>wCk|{C0I(j{_^Z>_=&|5wcjuRzbI|%y;EciqK>`83v_GpKV`_@&WLO!>HozQWn`vrc;km>JMt_u8rZBTdtYO9v};0WrCg$lcfa{c zP^N$YnettqR&`+$IV1RsSWuV|Hx!E-K~^Sq7W7^MF#8V8F7UBR2N87qsREgJU%hILkKIbXK?4JnVDS z=tFJbx|rCgSS1g%eJA_tV}xJ0rfo|782*`%2KD{iv1huS-yYTBIj)dt?zv> z3PFs~C8`3aM~u^v-EF`X5ZI|R00lfVrLaYqDRrEwLnA2bZyN*cd>)?hStQ8zScxIK z7wE~`E`Z`z6JO*CgS3o{K5gt2eue>#l%^Dv`3S4rq5sz_sWTCxAlL z0h{OJ)i6AANoP6yvse4sCv`*3LlM2ZVymM1W4h+l%YK)7#(@s@f#4(-fuRQiw>bdE7EJ`k{gmeFq$ zPVwkXd^+9eV0o|;%`fh{GT`~Dp0*N? zYndqf9Rql=$MK{EUSa2T!+w|kE-jAh+2vv?J#WNYdHQ*QHSMvLWzVB0qDAn|xNm*+ z?^LKQ%x@r%A}o$MI<4_HTC(V&%cL2Y+kCrAH^}MhQCDssMgnV*{i9`ZMBVw9t`)0B z@Ur0pm(3GbV*k4!-*<7Jmw#sc`^_;0`%U&}uIb4*>KN>Mu(MDZxZi&;&2+?@u9%H> zHTcpS#z$B6d0>R?j7krtO-ZlA$E4%CX|kg`WLj-<_I@>EX!yDE(QnhSnCjk&$wWcp1L=t@3q0v^(g{?7>*|n8hsZ(|jte=I1!re>%b9>l_@$FoxYm zediQS6lXhZH=3L%4s$?1*`B?)H8uKs&KHT!5~BNARF-NW!$dpoRyqO8Z8v%|5I) zmapA!GTTb|{39ctzF%tcsef(%tn|@TP4;nMn~e223sCDRw)DC48oJ-mS>rs)_h6iF z(@*4z5B^dK^(Tm`<^A~EoNq#b{?I2@WvrX?#Mx_!Wiv)REP}sXBLOX*O;X}>d!LKI zQC)z-w1#Qt#SX$qOJMUb?1wdr=`1KtO-!qb*Xp=$ewQ-~``a8s+uFGfzPQfa&e_HP zJZ1EgUs7`a#KNbuei&912yT{+-5dF@p4b*|m{l7eKoziZ1#u{~vjLk$ZPMy*(GZUf zr#k&eW>_;qbk*QwS2$|T$uuJ@OJBW)(Iz;#w~W5Wlnm^1eD37p-oQ79eBQ9ybQGSh z;Z@(?3;uRBc8{@E^rB~(;vIokUfCe5el_+TZ(%($(>mxYXh~27;FY>#Nmz#?^+7P> zb=Lj|M5S*Buen*HqLMIXc*>((0lXfb|io-o-9k^34Em;6=cmW08h z2FZ%gi_V~jZBXX|>jDjvLJ7uH1SUD54k$un5J6pQK)hHq41zhZL>rx4rVsz zd(>CCy&v_8;om>%T~JLqVj-17U0S|=2epK)M)lju6{*k5if?YmR5Doexj=Tz8&`K- z%0Q2yJhAIEn0>L#7PWFG;2>nRDn|ksGN`PvG*a20q{ge#W3#Ra@i6BB=S;gfbIjKC z&y*_V3o8bO__=aB9sHCz!j3!%$IE?v($0x~Br5g>(?YoplvGjbEGn{2(Tq)0g}hn` zk+%S>94O$V7YE4=CSs@i9TAC#%BWUl9$NGRxALcLlz73jE2NHgq3H7jrB2Yo9V6it z)K0W1VJULw-zfy)NH(GzIB{xWj-Fhck3cE9stS@V^DE*Yf=&8{CVTnP?$C5WNtsba zmkvtI+(A`3q3kIg`L~Pv$#URcQ2&_h@tVhYgKY5klcDNqa~ygGM9~t%3m?zMsN=vy-#bQycele79z5xAR>!|)qGpqCu!Hs{zvO4;dk$=a?w>m-t4iyuz zM|#&kBw{#?Ikd-~VP^OgrhGrEyYe4?m_kVPAX5hQP53J=R(|T6?un?PtW-}M7c~Vd zB+je*GAN-3Slq#^YIPu7-P7IUI4V2nR#4dPSj1@;nG&x5rXOqd-Si~c<9juF*ndpS zK6z!w0yu{DZ!9iV^V93Y27LcCCWb52)2oD4|4;EtPuuk(XXozuD){bS&)tjM7SHJ! zPl{D`m1rE?*;Y)m3BHI(@Vxpsf^~5hgV-m8^5rae>IesI>FVz%EYuA0p^kGp!dLd1 zPLF-*eahogv%6LEOP>vk%UbfttPU`#h_*ORyNEcM!l~8>Mmek*-0m5TTuCerL%D(K z{8}V^egMPWCu^>8WH}0>HC5KX0h@YkBQRHlBb1u6#@s%R^C_J1K|kVPDL5$SGcW|1 zTkA`9>LSKgrvq9TQ-imXT97{N)|Y46G}TenkYh){#nSuO0Xq3!41MREUL|BFwK z@A1w`XAfBEp@D0(bJ@;9vyYr`N7X?{P7HvH$6*kBC?^0&IB6al$#oU6q3<{QRnPg( zd;eye$@UF(U$a5$0XVkay2F{GkXz_g3lMQ0BnH3WdKx*2c&-lzQA8P}aYPnAP*4&($O-+yc@1 zw|8ttr-DU}Xxa?}llL-!tP}9dyW*Ct6jRx3qm_j;{rfU9@XnZ`wa{)IJF>zmNxum@ zSz!r6rr+#Qs!Zh_8E;(tO8D{G8{7%b7Gus!FcO1L%T?>kVYmxsMGzCCks|v287h3+ zmtl`C7fr*|Py(<@mgYsrMaaKzin-4u>h`zPLp^U~3!4v2)fDW1MoYp`AyrDazLUI> z>#)labr|8e9cl7?C9$A-bM`|+9@%<-!dJ+1pia;xwW#idT7FOZ&P%Ft)fKHJuOE=)mcM4U8r~=uEgv7 z0vp5h9mhM0id^w`=nCHz**8|&>c_hZNB{?_yE}58gOacbMYVEB73q(MN`3<>nFH+0 zz8E;7uVrX4 zs*dO2(>w>fbQ*bpbwU@4*7xgdzUw9>;cmte$WK37sI6Lv20H@0-DkGqlCw)JFYVdC z@sShULDyDRCN(G&)t21O<{p?e$BbBh$6;pRoqzW~ZP+lt72;|cMf9DSECx#b3B6YR zR#1XPd|R3zcj?l&mwT35-(nTX)g6~_USQ{<2oIl|m`L&R8?kqIFW6{6Y5(8*Dx*WU zfq?z_+ew8kUL#+|*Y(;(VPoM_Y?B=o$V+h@92%!{X=#!35j?3 z=tCJP3}i)0s!eOZG`?+Q{znYV*l)QzJ+u=hq8qIBa!MILl)Q@i!%_A?!DHHnbgtPX zr3HInv+i#}Jd}?CGmWaLpm^Ic=@rcW(wKFxThr{z$~SR!=G zF&Xky?esy4(3X)xT<{bdK_h7x=i`ts0kAR3=;n)FhYjs$)*jx~$0EYKstaTBlqs>K zk~k=%B?O|iln3lRYSGD-8zgtqiqhZ&*cJ!uaq!;e$xPsAk@f9py`A{^v2#_?=TAfA zh2w55_5#z6o^;TJT!QqgZ^G4P0JnNNrHV?;RG3K-={yICqaPZ&2DW{NVy3-%e>sFV z+%62N`Z(U+XlYMJ7SkbE91yb~#vrAf{!;xU2ry|V5=BVRi*`qV$IEK3*6m~-0c6MC zMGTDo3M+6?sqP&R2_Pu#L7!2BuouVPVpWg2RD)Ny1MNKt*jZGgOfR-aoATWv#rj3W za;d0$vcXboX`Av$+EU>WOCVc(6!tV@|5!QNKr z0c_w&bK-4ZEhP(BAR%^1dRkD{s&~I@y<`cM>BIV3{yX>7>vtf&R+8tb$Y-ZdXIVjm z%$xFA!FVM+5@qYQxwSpcNb8zF3@MDr=7tH!g&_A!pD74frP=F~$ad{YsKqXc0hLd5 zs$qy|$CnOnhbp<8j<(f;;DZ9HDQ3x(GlPf?+Nia?{T_(Ne|R;$f7x97)55ta(XjT3 z;~2y}cr8}Pa0<*{jmcf8K3vkYi9!yJ(=_H5%!upgD7SRHyw)93JVqfPgeha%n`O zU=u{)DJ8z8guz%E>uR68>OdPx9_NJSP9*{jgqb7(WB&^__1%1JM}zIBb9i(Fruu+bYI(z@E53==TJ>}#UYu}hpVaB z)!4o7wp6rZWT^fW(x3UAQH$!lC3OQ52YWuZYc!YiJpb2=Wr>nQ{D<;%iok9_p$&4b=R4!Cm!XR)GG|ca;EY82s>G##fJ~N>S{= zGwjiezDGlX)b<5shjVU4SPP6Q?z~y2bQP6SQIuVxvj_hs7_8@jdyH9hV5|;xzqG2W zGK1fV=VDc+Jr~4}OJ=l_X)oQ|uS?yFwfb2d*Qu!SPz1yVl~loM<*IPD7>1N}+~-vJ zhyWu=_&8z4Jo5a5lm+(Qy0H2f{rYLu1?NXQXIGj7hDNF9nhx{VJnvfP#8!pUXj{%K zjI*pae=o5+xfXrTJhbzlQ|UPU|C`^=~yo>U<^Bk09K&lZ6S#5_cY zs+7bS7C)r60i{zy*;oI_XOG(~UK5fOaE+bql~{MF-ST?7^cfX=T<(dc(21<F;Ej3d&^SEfxN1!VTFekJ*}Scvr?yT2~viZr7oa%?XFrM zV4r*KE&o%Eh+=J%`f_YOB8iLal->y+)Mf5C`?@>r@n8;xtp3_`g~Ur25~WPD8FUC#(BZB$4yXw$?O^K5^7KdzL++u_wN{t2jU zL|_O^EpLs=^Vv05H`j8jxSa>EWK273t}cRTB(09ux&3{KyuK3=f^hDgb6c`vQESuo zJ~F5Ga<;pG*^>{k;nfQ*et#K7B@}R|Og!Yful6s`g!6=ehz-f_pKC=THNd}m{)o>G z<`7?|hb?o4e4<|M^Eh+KwJo9S%$z&5 z-gRuRGe3??3L%Gtl0s*h)<1GUK&Jd!o1(P?LtMLnoB)~1PIVb&bM`l?~OV5rcrf@hWI*3x`Vr|6=j`DXa5$!I)l@Lx@$k8dq|Ma=W zi-XVlk7(gb&?l@5bqY3+maAIpqrm^MOA-#BPJd)zIKFfE`i`ZFDigajoQx zmmp?&RqFGLjcQf5QJhx<-KMa5?d|MdfesWMQhFJ3{}q>6}Jx57RG|PBt2cC+jj*4UOa}u z^ThqFWQd1jPuRfLy<eaB(zN5j1>`KUN!(LO8E|fiFo;cfqM4@Vmhj{k+nnUtd+D zdC`|bgPEk<`b6oYhR5|pX9;`aI#(TS6yQzk5NsM#nFL9A+I9rA5#Py3@kXm(*p=SQ z!%bh>ITK9a*}WO&CPqUXep-6cUwB8}!IEq;;!06USxD8@3cQru_uy?ui=r-z(%C^X zc!Rg6s1@1F$H%6ylU7#o&WY}o{&7KTZwu+s#=zy)0_rd~aQw?2?D@F+j2YPo+kf~T z-*Gh~8;BG6-fBAcT#>H)Z0sF1a(G}2ciaG=$kxv@e0T3@*nSk`TNW;OK{!D5k=KXK ztGe1Cr+-Pv^U1z8K+;SOLvM|wHRgD@aZvgCpuTyHF6QUE9pq1G(zW_J0pFuibPXMc zehQi>D_nm8t#67Ism(1#u7jxkYVa4QN1Lecq6fc#&^X*)3VvEV~@fJS@c)T z-pQW*Ip^Hif7&tmJUf)nk_|Y^=9}w+qb5W6cRKZvi92jB7&>74K(Gszf zDO?ZeyCR?0c~YktL|gKn;g86Kz<*?+iN0aLW@T|LQ2ZkB-c)c-3kPwq5&t7$cYf++ zX9ig$hSyZ)x2BdTQA24o0U~;q&H_rCC2~2m=kl-$6p1N^Z%s-BgT*y&N&*9;n?uQRv2mTX3RWDiiNTT^QbYO^35*BKbiun zRN~rhI8@KGrX}9CrsH9Uy{t|8$M7tl>BV;+OgWWko!i`DQ+7NTnnQK59Dk?fhE=Jh zK)Kk4BNsw1iwOfBj3;u!5&J;=v18>j#1=zQ1NtP|j*yHXxxxZ9fQd zp$z+Jy9Em<$aeRPjrY%1x8IF4KG=->eRtbMlnRcu;N%+XyVBst8onWTFKz_1S|9I=EbR;c7Dfntha-GWTbk^?`4)++9 zLL1kAV2Q8et{#pD=4yF~Jn?Ub9L*MtSWRjuCH#`45xWpydb)>271~2xt0Tk$y5A&= zb=>czHM3PEB|6@;K_rDopSW>2ZLzPvaTBCTLcBXOHdPlZ=cY7O1J<~k)HUoM4n^pn z*Z>2?a9cThe$PeCrvT|pQ89(~FWB`rB1kGb=bh5|CDZ2Dmb`5+K(OTC=J&h9UBdoT z2-z$(=5x7Q?tj+8-juDfVQ;a;i+gTO4f33^m+^nb^HYMWp(0dL0{)5nSOMxK#fRjXaRchatQwwNGwWr^ulO53(xyIe(<2o62;WU)mNGxWKcJo>yrqMj%sfe*96RP< zyQjCzC)1)^NMbP%t2UbCUPmzT&*4PpDp&uhSH)GYfTpErf4x^ zlS98^;?AWXG=P(n;~FsuVSL|Qgo`tOXvzg&+asi=0B3aps{G<1Tq;G0(;I&t_+j7v zme*FdwavJb%2Vq+64(lY?8HO}MRUA}1F0}=P-|yNDFqGk;W(f}Osj&K`uYvU-_sW? zy7=v+klFn{*2SH&zb5;-4nqSJY4iF*yUW*0^H=NdCsfa`b>*$RHVGsTkpE=!wj{v2 z)m~aN)9a|RnDq=rB-v9ZG89^a19xN%_P zd^pO7L1)nF;>HaaX-9weUb!|WJC&-E9VuQ-!e3WguSy`$y5bEqDp~*z-U+>F(utps z`t+pOW%}z`U1(Q-pG&II9Z4a`?Lr&tCvGTSi#=)PcU6?zWv4}>Ki=}ORPim=8m?A~ z?5Njh9@=rNrx7LQ`Bxf=&&5QQ9%dP4wtoP#X<(WU-nkzwCM;dN50Z!oE`tRSN|9v* z8|r7^Is#qQWHyPApw&6v5NU@1aUH4x1Pb)RD233`yR;xm*nkfwE55Y5Th{Udc z;yS$V`Mjg8O;%`GD98wZ>6Di#1o){$BImcyeu(x95?KyXZ@)#!YxFdp<@(*jVZ4D^ z@(m{DO<}U;==*KAjr6zsWUXJfCfd~^vkD3oJf}PFFZ~HsJ?tV=M~1YI=OLQ|uAaFX zj9OTstRXCk8$&`%&(R3+0}h$Bsk}tsqTagcXoSX2!i(U*e9^ixOMs~(^?UKz5^%S4 z$I-&HeDz1JLE1C06)bZ`wNS858Tkxb@HnjSi{}MiCQD$?7o1eV+XkHsye{~8RR56x zdC#G8nVCLt80G%kZA`CvEV4p}vTvYQ`FcN1wc%uN8kAXhtg}p+$o)lN5THxRy7T#! zM$6lWm4U|~kFMpdAn&Qor|WP+YTr0Sv9L=DuYjyOh$Y@PMYl^|5?<0ieCt)$w1&ef1X5$(gh@YU1usG6Jwd&q5%uJvy2wL z@+0d=6R`8Ze2#cciX%K6jQaRK!W*#tM7i5ar|w|oXak_)@M{K#3|Mgn)Ey-1n1g~} zY5w)jijO5iY9reG<+W+i`MQ()*)Y59Zg^EoZRKkg2MVm;ZnlZPs}%chtZGyNUb)syrC_9C1N%Ndr>^G(*{Uc+UzPZ6-M=3k}D0Fs`U z7ndT(;lamSdYPW>Anye7n>O9v@(!+EuAsQd0HVBRD@%2-Bku!hd(&GJyV4xiFQ3b^ zQ)(m}AKq_hBhr}`Po>p6B8?=^9hxdK)A~$Fj-T)?Dou?8B8B;L@S=fJa?|7NfTzoVtw7^ft#z@h5oQT*l2mZCsX!lA&9ck;Vp8! z&Cf!o_0cColZ1^TWy*B#s($^hKL|5Jg`vyvySY( z>yhE9em(IhzwgmMMTR|T@B7H;2jki1-_Ss76Wu`P3))*V{^!RAI#{8ul~Yj@0T7GD19MWc#R_P+}4fBSmX2b7=X-clD3vFKFO zAY?Ksv*ODQlDeM3Ll(>S%R9oZE@qc zaemMz#_jeMub!v{A+akyIo=|4iHF%FO1WRqP%ewwqw-4n1<(qCjYRR7DGT$Z`NU{I zu?GzyM6U~W+Y5-%f=(=6#%l2)1E0*k_7qc_e()cLgEt6xj!BpA;#bM)>hgVBm6+hD z8?U3aeis7c5ul0e`{gJkt=ibE6t8POh|o1AdqKi&8>d365@T8(pZKr}(op4o*Ah)X zc~xtQ-sL1#?}XMI1B4Op^7xQT&Jr}qqgY1LxmJjC^;BCao0Yl~$<#U;?B)yy**VlT zxHk>=6%C^oI`(rdM0+8#JwS|QZ!wZbEMKuarChU1=W0r;^CpW^E z&3*|4PMp~jVw?jL0S?2>6U%7;e~m!!%_y~j`o?Sir&a(0%fu!-+dcf0%7nJP+T}2y z>qaxwk-b>~CK0&rFtq92;sx>_thnzG3Y~sgx9UQjFkSkbGMZ+28Ba@`(q0ur(XSnvhz<{2 zy>#lNMNy3GPyIE<>ne&x$sgYfHs3Q_)MW}~m!i{hEKz^v1NR}UII>rW68B)MMq$6r z7FAycc8%O6)LZ=vKdyrNr!$HxJNQam6FhqM8T!V0E9g_Kw9z;{`wlz><5H+Ws5d)Z zXhMHK*^R?^qZh_!jeAh{5V50JsBfprN5Z0?(43uB&wcOPLE!@4YOm`8Q#z*dsuGj= z?Iis^+MutgofJ1s5cYP3=)?}0jVux11AmUqj+@T_;eJ_3CO{BmfJvH-p zhhWMp{$enLz`LKsaGSdkX0>;GcVXgr_`jD#18qJIx$V@Sf2Il2e%{0c~6nxeu=U5X*CBZr~{#P*VrtKLp(|3gxsqI^zG-uD^rc4E1RO`*EN+4K& z624}RkxhK-JJsr%F`B|JZscDWKX>?1g{>+gc-s;j*jMR$)B%4X+qkz&N`%vk$n+xh zj0{IQ!YSa@t;7$;wWHoQWQ{CS2lVz|;tOt6Hw(~L#(9HYQdZzdx2*c@E>)lL?cSTa z%U=o(U&+r2_qcy}(YZiHoxBm?k((b1-(1X94L8)NQd-+yGhXa^#I_@K60->BjrwVr)1CcfVh+eqN^`w^Lm ziGNpm>dv8xanf2tw0bJKn=;DuhD4Rv5cp|?(Ag@7UWC@AxO!ICX10Q#!H_eA(F`V_ zS4fxQZlcx_lwSrcGxDv?Rk?cf1pO$)j_cfM+%_>V4 z!ZAP)_uwI_$LAshRe)!leq_;-=FPRmLJTRy9`!kd&a8q0HnZLDcfwW?RAH!@4NAA^ z9>b06PP)6ul^yF?Ig|3D!J23}uG(3p%%nno$V)i{|8Z+Xh2vEuNkBco@(NK5f)4Fq zM7-o#zP`|!+CqFdlyuJjap`d9roEQM%0DR%p4H+p9ixt3_v%l6^D-g_)Sqo0?sNF= zbmpr1$z^}2Ie85}Bq%R;mCKHe4aY6=3uhqzhZWW{!6;Q6$X7zscPbbq%ZF8gK$>PWLxfBT`;nSIj0GW#U}OxbMA9LrCsI{oP37yVmNS zdyfvU?8_EPl*diI@d8lJ^6KMxKYi*ikfj$U_38PF?`@CAO}`k&48)C4XAgD>8{s>L zJJ@1t^5x9r%+dOFRp5X_g?Cjr`Fgc?p{c{@jk*_~vjdkAU%SHs|p<2Y8JEin|* zGBy4W91WVtiA~DrI=}Rg4c73pg%+-ko(d~mS_87rWQ zLta=phgCcv>;5E0GZwF4=TI*0mRV4&P6M-=$_VI%GePV&KNlc2Ii5Xicj0prQ(Ql0 z7M`<8v#F@HW@E#;1N_bQaCDA3aw0(7Vg_>1P>jn=X9byQgBvJL$0XS%NMa6%vYTOT zNiMA=%x--(9qr!U6rJU|mHcmV4D@+bef)wtRfAqz@*^!dvvQKT?*CzlBfGT@O{?Dz+?ACW_ z0S3o4zcV8;p=ArrP+v0Y47i@($9y2)Zq0>1-Ob(Ni&T6HpF!OSyOrEQXZ)RxJ%w%G zAQJKGZVbByl3m5_S4xMZ1DmTT?BHF56=HPu4xd|3L9`enW>CTF3d+yo;NmcWby6~E z6IbG_7DvA5A3oLQ)JKtWi$&#cKzN~d`Q)rY<>l(a+5g~nw)5%_Pd4z8k1yVFYkTxh zfy^VG)}59sO*2TJi-JiY_ZnL>On&Q%kdq(w)~y78o5}JdcC}Q^OLxqYo*SC?{FdQv zf*?HOeS%ib(8|7`mzvx7nyHOB8NXXw#UKDaJBpUqz4y^MvU0z<_{7ds1zD*Ysp1!d zz|mIN-4Ro3@V-?CKCtZ}#drNAwt$SGT#RH%w!j4IU|hLvhSm%@8@vp2kN zM*a0e`~g~3FgB{l#rN1(wsZix|5%-t3!nrw?ZNt*)t(;mHB~LgDokpM{#r+174M=v z-rb2FDuJH=bS#^Z(4}QN&C|U=Lq`72&ribX&OcL<%I*&e^D6Jx_yYa%zYJz*1v=_x zN-5EqDkXTE)LQnBZsB*E;GAMH3q zJc&G)?p*vOtJGtbD-6L6BCVNaOuU&z59&~cFS>UV#iLc9&fD#g#}8dT(ftM3mh?tKb!imI&{uleEWvR{6;;NM#+Q_hRj>!SoC;EnV;z-xQqS2)#JsJ?{TU90a z5=%;PC?#gr=eM=y-~G3tNzhlyT}j8)FC}D`VA0&U&WM-QmyMZaYxl*nG5DGNGDYaUaj@tp~{g$~x#wavATZbOuZMl2az`%1#R_YTj0}84{{S});)oW54coJtTAUXx_mfKH!nQKJO z4K19H=u38S2*;clb%*6z?K-jqjZT-p0_(5(zD($Q?c96xCBd7dt7EAmC%kW|A1kV^ zYWccGr}x+UFb*5Gcw*&3&KCgh>m0St<}leKH|iua?B2-^9=TJ-+AMc}k=Q^WrFJeP zLP^p-+5j!bk-*OZk#V>-tW^B)bzI}2PPjrI1tqQ;|#rK|Z8| zhA_9Q5^cLG6s5G|0PgS$G6x~xolZK!j5gYJ?4p_ofx6yO$yrLaH35121$4a1nMBK!Z)XHv@2sU`xKfynl*Vn zcKzMKVu8k!?1Oy>t<}TBByN{4u|-pMy*%wIKBm6SQwB%1?kTD0)Bi{L!kp_LJN?)0 zawdOvYrbL{Hnh|)T)jo>OfO*Xv5Bt51Dn}-|+h_9;Z?D{@le#ZvnCgBiZ&c zonqQV*r?lVY|&7K<}dwy)1lwD)3e^Qf5G-$K{h6EE7ZU>EjmG=oNLVBqUSe`7_m%T zz%QxrRYh=w=ZfKOqIJ4p-1d*xv-NvaZD5u!g&~I#xUS-M~l8g-c0%8< zHC0lBvZ2d=c(85;yI8@agsWGuL5R?=`CHM3h!RGwV|r+Zok_O|Ako#|^*T$G-)DP< zL$+h*5e6rsipncR4i0LX)N)Do>q1w$TRC&wOng&Ao5cdIyBB*F|6%8N=$Ls$ZRN4{ zRkIADZjx?8w36Hk>#7Dv6)KLn9R6%XUPq@_tUhvof`T zoo`ojrFG^xyis|n$b9H2u`{g;ik(?q3wtru`EsFN^>;WGZW*+@QN*|GdWJ+yBjx`4~oC<9eN5M`S!kSf8P^XKBd8LlY>J4{^Gm+=8}@ntAED?O6)2;EBr$r zj2@1i1TP0RZYokX1G)QW4_yVjggutiy<@jQP4X}4r>Eo>1A*9ab-XP9lz%r3yxMkJDP(x9GK^uj+sYfSg=)x#uA#@ z1IN^mu|Z>s5y8_sJ71cVOul*L>dn=c7Zic{z8+1!RJ*xRa}lv^^U(_^rR|oQriCWd z>{E--u+B!mtY776ELrQG<)}Q1-s?=|Mps7BYGpxEFriD@^w{n@y}%K|9EsyriuI|$A`On~Tn0p5 zktI?B9IXdX%ZfO4xs?WQ)PL2rHLL}c&(#R^haVTychM*0_VQVe?bmJa`p6}I6E&1Z z-)P$!dWZjx20yOkhep}3HO$g-bjeQH?TgBCO^kmK9kqUuH>k@NzNf8iSo+}G0=5{v z*jU4-%;PB$>-Y=$CZ(@0Eor!X4@Y+MXu`(bDf@8RIVzIYv^OQ1{`OeAX~k1Nh&t6H zB{lZ$-GaXZ2nQ3Tp2{rvCn1hY{ng7vmrK{B|0pCcT%>+wNN$C$cSP?d9e&o*gei51 zk$=LsQi5D&(d^*{P4e?=kHtB~R4+6hK8DKu{RD?3)rdUX%X(ejT!Xy(p~1 z#hRY}Z(M&%M+SE`TjZ+pt))NMg43_c4XdPr+gmm71Mc&vq=3}_kEZL6OFIAm-)o$e zrIjU>gX=2IGa;`Nalv&BuN+)?Wu-`3Y39VO49`qSaa>ucp^{mWnc_rTkONFjEpaad zT&Soxkfr{(KYsu4KabDn^Ljtuujhil?Qmnbw_*L4@XB~of+-wEnz zHb~ibt&Iqx)7RF>i$F2j*^7wC-WPq!)#6DmSWUG0XeUGd5WacR&}tMDn>Bj=%XG63 zSmugFuD0y6^XgVD^RxlAc)&j$*K5On(0*lDrCn66Fq9fvi7+_{J?x2=2kZH$aa-cU9XC`EcM|{?d0xAQf#S4SXnAV?9_u zk|hb-I5ZGy4e%6YQ&YyY7NV;O(<1(ofA zCQL&X{btKEBuGxJKVUe)tCLN03IG?F)nCJYf%sp~!JN_2+wD~Uq80#ou-wzhzO=As zH`OLM3^#n@U1=YxO|)|?=W%jsr_FI4GW&OmiD!hLd}+RXvE$Vd^iVCfIfNSnh|SIk zNqtNGM%+EEr5CN%nagJ=7OYh5)YMxH)uXzU5xqGb?M9Zu=WcgdTC3V&T>_-aj8x{& zo`U^Oq%Tg4lcTdq>Ge6$4?e$Q-tt|Zpv+*{A6k3J{N2tr_nOHj_>G8l(`C(jMF+8K zz2dUPVd<3!$^dqji zpx+ix*6be0(56^oi97o*-&IxLl4$epffY-Ye*et-CgP(+a%|%iH7xeeMo#O?4+3Kf z#I2I%iW-&Q4PhA9-K!8{I4IRT*pLyzUeyWNAPkz(R8WwE<;_ULZ6*m;V?zpSfw3mz ztw#nv`@y+fR+zfKuik-P1z&Mub9fS(BA}hgCH-!X|!0LD9{!xa1Q$7<`)fNKflM z3GujFV{r)*;W*fK8#Dy%=}-gJT5Qgt$)wG_nt!w;yT9!hxnoLi8bHv`BKq&y&!kKeXi8;~9NjRGI1cd8j-eI)dN$suDjh4j5L~EfRlPhq+{n>_ z$;wV?wWxj@*l9o*OSe%JoLFd)QZ=wvI0_IMzjeSSUK^YGeK*P)T3sDp_I=LSy<+l! zvtSRQKeyezEg)1l?PMK__h>uZx9)dWudg|9D=&7E6H{m{G!7Y>v`|2=STsH%Vt$|j zqDtM{(;ZygttOq4usv)I7uOoTquyr8*)(IYO*0=sO?uF6^?r^q?Q{On<;oaGljq<-oh z1t0i~s6%+$p+<60A?E6UfBy(2zO3aTl!O@*810x$c4+2yrsyenu%v?f6%3{F!3*0l;CDm16 zY4RF5HB2rvm+>Eh=Qmadr>q6PI4aRYsN%?V1I5+hhRef-GZ7NC?1kev`Qt*Y_~D9{ z6KbzW=BcGd!lav1G$8ZJ2`~eq%XOM#6@NKu;JBd_&$Spk`yHe*!hS7HHm;50ua!?S zse%ukjCIU!#U;>R#2?m2f=1?M5z#9jQ<=xO3`F{P&OxvqvwExSyYZE%jX^hw-L0ka zBGuv3v%{ZL?;!09Mht6b-1;9NUOiyblok2iYL^i*u%s3L!|?r8ZPQxy947t&s4Of@ zcaN)O7;9(I>QBus_7)C~xG?kg*rf(T@k_7BCou@~6&`|&vUr+a@-j6HS95z@keeFo zh&`AZcJH)pjS(x;Qd9tjA+00Uu1JoC9|ieVHuZOP=?@OyEh`s^k_$7Subpp21?P$2 zs5PNJGI&P-cp5wg`*GAL6UM>Y*nF+7>I*0iE>um<3TsS`=Z;_>8ESY{MX_F#CWpN!W+APg2hRM#1xoee-pv$5qq ze0bep)2!eZxab}2j)vBS^z0&C&UEmE<&awF@y;4pZR|Jk;x0ep$nl3HhTqY?M*2_6 z11t(`t)L$SQTKFr^&PUg`&I5*a`SjLoi60u$rH1ZUi*MZg zZ{ZCq!u-FIO8j9Fhs<|LB7;xEBWRCI1>aJfkyi7odBGR{u00x7-jixu+l^&ep?STN zU@jkl!H1OBPd`BLuOWaEYOxP6i=Hb>LiS_2* zG_@mjUpfQx^=sVNR-W3lmhbu}dZKW@7MK+FHoHi1D#>+pP8IJl7P{+Kji2$4naZIi zbUXQPA40!@yO4KCr^Y&6kUyI2P*e%YW zrSdKcJ|l$x6sejD3W+2(OFeSpR%)9M`*$xVa_{*s+gt}Xe;Vw#$4DUtxkdnDx7t2i z`2qq6JBU5G4clb5&yjY99B}kDUBb?D7`vxfeMg ze5mW}>bWX!YW?)+x}kGcM;xO&nSK7lRwQFYI($w$@ujREiYpat7IPro*&XJ3y zPH+Jtop{6ax)jiq-z$`lkC5TJVldyjR9Zd z7z<|%Z^APNu)T*(Re$Nxy*&T~dg7LjK`lKP#Lv?Nh7FaKzYl;7JYUWh54O3>n}d_8 zSnG=(3n^Ft;nSC{5(f5T_LU$_1#lYNyhCAoC!{hqCGKwccj)|S18!FV@*=1WR$Y>@ z;^A*9Gr&?l4FGhgmo#I2Kp~_Dv(lB|6G2XYc~Q(YPSvXV+uZPYoeR3=M=eczcEfS^ z{z})uE`FB&>pKhWnY3w1XFz?$g_9>eVIf!0V_JIiMp)PWLbQ2tg7+CG3KGOJHc+n7 zllFlyVu>#6DmSagt4b4NZnaK|tbl8kCT1@Dz3&`Le_3s8;vu&sHz%^`RL5?Ng%`=p zb>L_?jpxqagX(Z|3@PsjyPCf^)`{}wmJ_I*6uc_!EJR^hcgNJc(vVgPdQ1e+TQkW+ zBk4^&1PbXov$8;wip+M~H%zIZ&%9WOt4F`E+FD4Ty2jnu5kEk}PU>l9{n1}X@0a(m zf!3?u`%|R+zXXQ#=j=B(1Ake596Tz;PjJYat7|%qRGi4idA>T;3!iMfd6ZbJTUJOx z+_Ri?F2;`kNsn0b(lO7r{N4r5w)_OqFirGM6325=tFS%7rGJ%eCS%x7H)yw4;&SZ} zwt-WqI$ICg+6ZIVWj-%ec4xs$5p+}Sc)A@E7QnV&3Zsu0tPLzUpLZzpI9_w4!sQ|A zQ?NAfTJ`?gr)!n&=t4?y@-q{BbxA@iZFwlfBur;}$~!8uc+xiYf-k_jp8Mjj3YLc! zGb`|KY0HDG70;$uWC(D8eX*(w1$49-4pHqONX^yLZw)8^A{QSSa=P2@giK2K4q~p- z+fB1;pyfGHey;qlI{R$A?OVo}Ze6SHJl5;rg9OBrq12_x=7rw_Ix1zax^&^BMru<4 zx~YDAC-|148O43?Lv1|3D0j;qRsZ_c!T!2$T~OA&q_?_j0#$&C858>F5qik#WMQ_- z9si`^T6F4n=fK64k6q?)OHpf86#(on3F>;q#7BNyBkmN`OuE=tn&n_C1%DfIG?}sc zv!V0^2H4Ijsh0BFW%%Ag^dZmOo z-Cd86OeGZ!B*)ZO#Nuzdsq(X4z4(Ci1JFQ)sCZvx(VmFa{s^x12R_Z=vxiYGQ>pTeiaB2 zwPIn@(&0Q9(qh6%IhcA*b@C0p+idR1fryp{=e&G6=L(zhNibh*cO^}Hrb*Hmj>@N& zYQe`=i*+@#`Q|=LvW35x2Ck0n!e-*FzLyoKz`=9)Rc*K~=)G=RS^&CRXzmu)`09ze zR@G}0m^6fAULTc8rRF?`jWWn?qw;q?*-1FE&fa2N9oDNJsIIf%B(K-lYA)-7)z*!+ z>%J&*k4)zl=&qwD4y9~OlsID>1)Jkm)>9{HA#m(+AUU&pq+uNWSD7<%D`XzG_~rNq zgtb`JDOyP69=TH`AGKOLj9X@#GtlDj{coGDj32Z#{WGglRb6x-c(##~Niu@Y+)Zq8 zgbQAIK|&)cpLg{jMkcI!JEP^}zvdiOrG=&BO}k)MqsW`Z+4Tl49TQR65k@i!KzqPRUVqIpqv=!AkJ2*uo z6uL3Gt;wOn!qdQ|$7)dO9G{rpBC>R94&J zPD_^)bJLuk=1kl&B6>rT-_saj8%q(Q(LR)wJ*=d1@aaI%E|>ZwL$~E7Eoaeg%8A7k z@W|?D3-m$kwW&J}#ZbxG#77%b>C(3XpQikF1oEqs&n zjk$Yuc*)tomOW?P1}M=`U8hyU0D401iD2bqqUZznn9CQxa9=?j3}r!z{r38;A5A~% zA!ZtDit^zEM898dlT0n4Q)?sjp19KAv98sgu3b74zcb)k&mj0=IyG*=;9mx7n%v=V zb=dHd$7$)8ujhwZ9mS)b-HvU$L2nUSac5w?h43=fa{keS3wRUTS`N`meH?rZZ)u>X@v| zaSFl@I_JK1TJCX}s&*IKn|vM)s>EAHYDFn_!rgE_IrdEKvbt8l+6dgehvf)xL+SpJ z{;rTorFwxiYTt6Rc=Q}@&ekCa*P~*SvaDThLBcDblTeGs2})P-_}XqBe1ii=a^j4~ znp+T*qKdx0(aNIL6A-A{8x0-F8=LNkw)4RJ`s$V!0hM$~Jal>5*7j}%$6Lp4T@NRI zzJxC4g^_QxpCak*hQ;NK|J`^vZ6A5_g`5M_FeHW120iUG?N)^=#^%*sSTChg%1#G? zyx~5PB$`tl)~E6`_&FIkFtXRkRY95`2tkfQ<;@ zqjWnQq;9SEYSz%Xg$c{|UBCsKXH!ps1u3NBYO+OKVf+c%`)RA;WMJ5`kYHk{xmWYl z+?#>mM@-=)k_LQc4@Y~tbI7Jbe*eOGNGPwjGPw{dW08;!w%tXYEIZolls8{E;FYC{ z9fiq=I*ZMm4pse?vC_ek z>8&>|);RqL)49=&Yv0T$ogA=f$2X7SE}XHHH4kS5hHT}vSDAib`7#B|H{v99P~|~f zR!Gp_br$)to_mUaT4ZNF~0y*+y1L zaU+w(IzaBcs*CX^zC0((UHE0bOY%J`65gsEAeo()4+U2CyZW`{kgB-HYQ0^`MSIM0 zbpp@R(ofLFEPA~{_y1}-S2f)+3W+qAqkKmVX*6QHL1vof;?Ly=4*UIT{!=}klz;=} z$K5}Hfis$aT>BjK%<7O#7V)?+xd4f0W!DVmYz_@pO#a=uCJcP#V`jq*Tn#yyG&B;L z)^N}M(ZH0S1+uRBXewS{@2tDA6w+}|yrQ0#1LWm>o9?3M>_Mua2m|7qHQ2icSLZIx zC#pj_2iZ1j;%;xR)Bw45*O;kxqd!CM-wG{kvNPt@S;et<`G=NbsY5nH zq)Y2pOhxEzi?y)T<=OKnT{FQ_3l&NhR0A8vgs3z#K zA?rqed_xCQ;cbn5B={>a-2s&|I~GU+GXJ_(?B1KKvshr-<;rVKitMqL8~a;N!lpgD z)MB~1y2CCTOSE;`)-QAU4v4A;_1oOWMEW+H%(%7x$V+#JnXp~U=5hZWW_3%&YSfKu zmZT2$H7!6gEiU+3FZ=uDYlNzYEv#y5X-W3b8NYu(a?r#}?szHM>rCX~6Jwd0iss>q z%K=&l5+nfuoNm4kz8sn%R}Ph=Rq2ZD>+wHV`Sym;jZ2dAbO*mQPar5AYHm!Z{3?zP zeFWxffid{~f|SK4?flNJ&7Va_(XC0O6t|ResvZD?6=~J^2XPGR?s&tx$&LJ+sEwt{ zLF47D>IK}|O4m&wklR{oIc!($2*k^UjUR;rh6YH<(yDa*mRxvFOj(r`UfGD~E+Cyi za}dn;BW}`#_XA5;b+t$iS@n7#J^zi{%Qq0EOcAwNpQJ28x-KQ69KxdoI%@X64lf@J zUv6wzTDxqw&(^tka4@mqvZkGF1-iYy^o4ot+@A?nB*q_0d`|e;6`f$bpo4TEx|$nM z9eIL?vi@~L1_^Jc*N>mnvNgn`S36F8zd7*bs}ssK4mq09XjRAJo=Zk;qkR6Cooge| zj)g6hOup!vCx9JGJ>f~R=kT!;>yRnq7Vd8&o~zAt@E&cf)oXLg}VkrN)_S6eRiD1CR` z5`_%CgUVGn&saSorbDfmR+Awce?79w6Z!~vI`{yRY^g!Zpz{)~-X7-{T0MpN#m!a5 zI|D&lR~8C-q7f&VC303i$!{ZqQ|NL*Cfd;PiHf*HE;8jA)L)?4^5zZU+U3qGafQjY z$5|ihU-U;BsjaeQy2YEM#(>nspcW+mLIwo5z(mC z*YNrHaolF`JjH`jo~qD)ZnMxZgTDnD;>#{+heeb=B{1My<1t-hN8}T`ex!Bd`Xa<9 zDN}GVo7eJWxw#&Y(VA-#A3-U0+T=~z-)Zlyj>v5)hoAfv;H1;}LxUA~)Yv?SxJzf43t9?koc9ZKSjMhmV}noI@4v?(peD^gG6RBr^p3qQ**@6GRTd8WVBgfI72T%2jpNeM2C zMCHUnvkU%X^FOUU{Z$A80cOj|8}p*>(zed*2T{D!X1{g^kN^Bf_i z->pasT{ug5S5j9EFT;nwsvd3eBL0Zm zFt2een2y#QUev+D;+EbRKrR0b3Ai0EdOz^!I@T=v&KZ0WPCPTIV&mOb4+R`Jn4B5=F7bnK}PgB{+7QvH}gKo&qA(>g2G{|qSY}T0d zC3>iG@No5WF$sOrD`{kawM3 zr1-f;{8Kw~#cDY>qRDHxf4&u;v_|3vb_5G3WYN?MuD(tR9vpNI$STSwN48k3B!YFh z^&tHyM%!20;o5Kb-+llCp_nVt>>hAS&?9^CY`QJPEJwLUB@mAHvRv9m?Xd2mXA#0f z)%Us8sJW?Nhf=c{>EUP^FCU>4el!Hy>+%FKU6-9Pe2MFtOdHJf=0MgvE@WWua5H07 zHwig!?TU5F*kshp;7xfS3!j*W`3G}D!Q9Sry$}IE7`(rcGuEt^9#%S&bgnZJ&gX8w z(}{hZ#{L)PAK^zZt@OFn@SeLt9Z`L}FjIaJg3v$gZx{AdlkzDxoXeaxmIpjLl zQo=rTdBmfACv0@$Dbu2-<$N>2L>pP{4X~?kxlbWOdo0Ji*7XyyG{WGQ<_pR}y}El1Mt7qeD7OyLv9Tu^nU7`}130n&l?hPV%7WRUo6?=vdML)WG+}BuyIX}6J8UC6NWd{+T0o6_c8C)6 zyv2;&LH@4_hN`k5XW}2p>ciqxCI4&qrQxhk-t$G3%ihF8Ox!uC~LG zx-tihif&yB6cOfq2Zz;!J=l-LbD}g`#fyoqe3O*xpfvNXqv3MSqB>dfH{5Nxj1S#mtv3R*1BRV@vuV8%##C{Iq!bzbAT6#?dx7?DqsD9RgURQsIcGgT1j)1T=P~{ zy3gW=s?OJeY5q>tGrfDVFWvC18~So*rW#tgPETk_XisiNc~*|^0n*-eJktmVnEICX zD8j^rgW@>SW*T!K@GPd4O5E@N3LE%~M|VRSyP1L=Sc%OnU7-*%X*gi~=aZEb;PBU2 zzkn`g)Rb*H0?*#V*>@cy|NLxqwxCeYz%BGWsRk$9@1Q%RL!@o%cZ+LvAYLm(x7wB zUDoRvHqmtyc9JH3@d9cuUW*f9=qcwA5M31Ois|iKY8jylAgWrLjpVLsM6+2}dP>BH z%+KhUYQH5rcEHJJg{z`yT>rh5XO4`k_*we&t>)hKyJ7W5i45~&5ed4@rk>WmPHm>X z)lb~H_XdsyNP-R*(lYeij$tBn=SRb*Bbt_sQY`CVe;}pL&$8cS<1JjJOUC}XJcICi zR{#XlOrNfcjp4}wxPQ@+0lT6**Hl=+o=cmwpL;Y~<2OHcgG=AIc3f*T?ybYBBIHk( z(uXfAp#W08gL|4i=oabUiZ^FN@EZr2;8C9AxJt(HK3UgxAgF+Q={gL1B}(eyy(qi8 zl3a_o#@P60VB2pa_d@)(0c|Bp)pF3(hN)c1B~{0{bJHVwCJ)CKSF+BR6;Qw=n2l;A zC>?b$j5LB9IY87)k4V7Gj`TbwJ)zal<-53AY8o$Y6E@$Fm-FoK%kP z2d6H3bWI;ZNqyx`EzU+>(Df`ynuUnj6nOfd2hNCua*Q*4_Vb0tLZ8L8V8$y>9BS?( zC_2=&_y<|-dWX*cnEKaBovPiquSKaAbz5q6TdyN5bubQ6h}eMpcBuL4 zhHBGVaa(c($Kro%qFG2Iy&mwgv9;Ge^HMbZ*>^4iGFE$irE>^wNb)nkslyOG5DfWE z{-pQ__RFVA!E2hZDhuS+NEu$|q^pMNLHsgezF9Q=8!-5>E%PDdcq=K;RVQKM|;Umf(<;x{ShER}M?cghyHj*3dk)^%&haN3jG?h+QWr39( z2Y46`*5Pbv=59Q7Em(HUSt6Gqe+Ijxftim!IO&F95~ibQOO*LR&*XsU(W$~53vJA- zN{mLDb1S9Hn<O>VKAQ5`K|#FRo!~j zE!soym$9#K$QC=Jy7n!~uiAE{b{ua#zbl`7vZSHeC1thJOV1IRDH$5jpGkq;b z(K*35np&jmhHDf0Kkt&kh~ zX%|Qu`jBYRvY+5-E;3W+#Xi^>{So$ihvmX9$F`R?1^Zm|2it)0ixUO=tk7Zy+z4+u zZXe1e8#k4kOsURL3i;$}$4#36JpI$YGouro(JFBeU2uKcEBcFRw&X=%dHnZ9ft>x+ z&as~OIP)#D-$B7ZItG6oTJtJS_6y2NG@E{$jj~<@F+C>2f6-1Vo4yK$B^dkG$Ys+M z?trk(f)TVQHB|$|^$p=@zG_xS8KvNl&@WoKgrXA<(4yq;+MR8NMQF?FfqM~ay^=SI zcZ$znZ|ucE*NkXO53hXH_B6HkJ;`W!aY zh;t|iIFp>5GvUHL*7($Hqk=Ni^q$*d5tp4MOLwxybS@J$9X|y=%BZ)8LFl-Y5R8kf z(#PCft~%?3u5*k^&UML+$0Z&he(E`wP}j94^OV*9P@!lL0W^2C%o>usu<`6Vpgj^-K?tzwe=J<7<;!Yh&e~U;Y z7vGu}j#m&15HtBDgab~dsX%1|ux^tv_FoT9Wpv+`DQ&~#chg4jN5OB1w(>{+2`XGi zL)s_1%1!9x3$Fu7PX^|-8!l1*)s_bFQ%T2hI&nyy0KjW4krr9nye2MH8^f)SRz z2^Slo-?w~^f9@iI{0?}pl%9mT_wI2OL06M+Cxytmj-}`kbaoqo{b*DBXd@pg?oMHv=yj3pw%w3Qg%6W2f5~*^W#(ZR7&w zxdcGn_|7>k-7OcXN?=lpoqEmBj2uYUzkGHUZy$qdD11od4hZ&|ue^@z?i%5>j%j-C z!9>QBE5l&D=#TB1Dc>Ag4UrZEB2f>5mCNU4^A@vB|6)H1EboA)z2$LngMt;OMf70z z;vD^JTBF-Yf}gK&wyOqW4|QD~oXB&aLU)A1(H-&STO+o56IZZ7U(MYJhSt19Af(=M zb4YxXV-A=cJbv1(QupAxjitrXclI@mMEDE3gkn4`_u!b>3RzSAS>Dcf|6KEJnm>gs z9h{7}>YVjm*co!}N0*xAzbQ^yb<&l6?XNUwM>?D&LKmxrS^jcn@cm?KosF5p(f1hQ zc)@uwnp(P%ykJ({g34xMDc`ogOK=_@0R6;2e*gURW6qr5 z=9&CUPG|W4Y4+CQX7KSUCy6w*|7?kd9bbBJ7rW!FgEkefiKtt?mR7ipsiJ3ik96I;8xC5WWVKw|O#UHX zcbQf6S#V<)FiKbUt;r#V=rh#58!vxi7CtqT2b;~)=)#Px^bKL&NT0o8Hd@6+ zftQ6=o~m@H_~qwtUU}C8_BYV9l+)Yg2$vavalyONO*AZjZF%P)QQB44Hy=pB)0#y0 zp0vZW@G{O}bDL2kP}H^-FSsL3IgqGRj2AaL!bSBjd_t|$(h+i}%@CgGxWyB4b@!=q z2SbJpAeHa}HxK43;xyNq+4tQMuJF z8|i1sxrG-0G<;eI&ictMI;3FeGHsXs)kmbOrBFYRmM{8@>mq20K2x*b9W7nZ)X9R? zCw~&Th?hWrY(Pqgm@(^SQfWINK<7ipNpRH8s$=@a>c9Cy%#d|MppX1A=Lvm$^!di} z*3pPG`e0(N!^fr%#wDx_SJ~ePYvlXtarFzpn+|P;8`m}J8P%lH#zThOv%S0?{+E`a zn~KMEv1q|N0P&%*uQ;>6@4%1gcv#3(y{XXLQDoH5Q9+I~{u@DUH{sE^xQ#>cCLr0O zIGL1VUn`mTgaG)H)o|9cB}2iC)%9&w?Mdem{4R6+J@q_)S6deg;yP^gs$hR%Se=ah5((GI*4&|d z5GV-#!k%pJ9(HN)$wHsu4qB8;ZtFeidnIxI25FrzO|70>f-TNzb`M&&?DXT*JXNLx zH2#2;?tHED#nY!j_ONg_9;Ys}1^#DlsE5p|{7mpq2m*H7L_E*d(_`QwT@i8HWkiZ@ zqz^pBRM7#Sl>o#J<)QQ1$4zu<(*BQnSHf^Idd zp^~Yeiuv7L;_uTs`QpCRbFR2hbVWJBF$#AuAoxN$LM7Gb=NIZZIv9leMZwmH{bR4y z^exx-U~1;_2bBEpub69B!5T5njUN*%ky(R*?}E32z-#Povs|v>lE%ZtImeufISb-F zbquAKMkUK(hwA6Pg^v0&qi{%jU#yT^2*uG`^6ZJ30S;yJ=!t9i|<$v6) z0Xq4~pTe&3Za%%levmel1p8xiNpoxIaF>Tb(BhekbKb$s7;_f~i$C+iN_q1?&o!30 z4?W=zL6@L4f8MQ>3DWYQ9z-YDSM(J+Skq!&DxDU0aLZ9`{ zGU7i>HAbY+Q+=3qhJtM_y{WQ}lg@8a5=oybeHVUCCsae2?9)KO^Y*NOs3UVqQ{al} zobB##E^eLI&X{l4Ag@P~t28bJV1|eL(zkC-1#Ef_GN&;NuhA^4{j$Y9_$e>Er(XV~ zz{*QxF>)2tq00K6x`TZSLYSH6@4;lKOgP;Q_eqvf2dQC}&_K*X;*j5tDamI6A5^~GTQ32LPDqJ0?FA$OT{(crEtUO1m2KAMduSGGNWk=_K zP^C@zSyOyD(=W0E9Y4i){R#luK=Q%D$QIgIrJOBnr_@Nb zVmYZ#(V>e=IIGChK`#j-6}8k*a!7#DG=Cg%%y|yJe%M72Lofv=VoYHc2dbTCDz$K~ z?{rsnz{uzIuk~+obw3Q-1*JKm+ik45!t`vA5dtQAA4}awHPMfzh0H45^SieBfkRl8 z`pVHc>+K_3_b1Hj18P3&$sm&tK3>bdfeTYRu9)Zf1p!Ak0mCiu&1m>Y$cn?9t@AoJ zTAAkndDa@xRQu5SVQt3X;Lu(Z2oOqxy50|j9wN>^eiMA0cA)0Z~YqBLn zkD7rQ;cBIDeBxj#flj=RaswUINtVhO*tR?siV*(DiI{kM(xXdRF?lehzOGyx_iQ`q zXGY!3ZW3MqLPdTzT-^hwP3e$nmG{ESIq8VfSwUlFM@%C3OrP`Kohjf17acW!!Gv8S zbIOcrq5P7n{K6wLrNs0xqPlLM)gX0CPDRO`>t}DM5pum?E1CTox7l&iK8z`!zTDPZ zcx6j8mgQeRvEu|;@<0C-Tf{1_cdb(POKWpE;o6E9f|?C>5z#%fLS%hlSoDLdw}RXA z5zS^0oFC>ECZ)=nCo9ji6W{GcSLBqOM447j)1~ZlYhre`Lo`?naT^F>b%Nc(1V6EM zX+>k9ySU4{@<5k)2;cAjp9K(Mt+?(uWl*R1r{0f2LMRSsUv}s!enEixdVCwslYC^D z#-+JLetXI7DNok{$s(J+nRRx_mmZ|0c84~2>V_2i;Pvh#?F$!s)|!5M86XpK1n<;| z6me^9^^-KU?8u*#FWFrPxDKw)cg+xRW@92Z)=ME8FBM%RC4Tu zVU<++cXva&x=y{tb?l=B46Sd^6q_g;`t#=2l%L2;!+7Z^BTEIt@lg-0GPoXTzG*d} zH)>UjW!53e`~0E++?>4o!d4ZvQ#<`!)bOJ z^%!#iTd8C2sEg(JP?~P+^?RGMk`P;5H!*4m_m%SxU)X@VG@rgHdwM>=#)n`UK9q~IRhr#Iu~vC7lE>)Oi%r%wfl!=jzb6Nd0eS+`3x`N;+grDX9O z0-`vtozV%dFE9F@I$(vN)oX;MHUPu%ln^X}B_P3aW{)C3fs%jjz%e+>U|}k?{y!Pz z3Wckyc=pz(C97tW-^jToLdYe>K4+}pz6vROF0c+F4#l*{|b<{A(M*F`(dAG0Fc!mb!`2h zr88F|7?O)-R=@$to@|<>#*tI{QGWNHyU?IXB<3H@h4C?6DLz2M>?0>JDzNm7F*1-y zbwC9Emd?7tnWiGoKzumiPv*fg?s#-GJ;=3O^zk->C|C}oscbgwlNvU$Uq7`v44ZYU zyl&a2wZ=HELZQRf}HDjk-P6; zOY9w2NaRxju;uFojj02MNw<_?-Vqp)3 z*0*M452`NHvCKa^C6B?bibFy`v>4DYFKZ&6dk^jPoh){selr?^8gvErus;6__S8bKIt9QQs{26oM-DZiV zqQqxK18_5?M1+gN1~r&HklSyp4ao|xvy|U!5G$J+_?$#g1^FhOOKrr=r<0D91-DmzRu!n&vhUtL`%c;{Da9`DW?!lTTeR zvlWy7IFZ2L4P;*cDJ2f|km&cf0hkey0+zLUci z=5jqlpLt`Je9CX%k1$77lIX;@>igk3-zCN5B}5r$#O8 zd-Fj)^YR@xNemiV%VN1yZQyPNtLNrQT$)!_U(=Bn{+7}SwRZo-p>&PESSl+n;sEBV zWC{C}@v9ia5b9_%HeS?MrnW;9olFccrczI$SLb1p&En@}8F@=a@PaD_=YFsTLRqC? z{F-z0+EN9@#t&yPs&xDgUik0$qlU^qb;&=O;pLg>h-^1WS-Re)R29>Ji&1Hs$J;`e z7ej+xgNw&KjX=c-R;=W5S9DKjz@k%DHD%^Y*0h9LzsTU(R)tIr>*$m3;<@WMZe{(P z;^nHOaL%A~z2hZf8v9yk+1ql8u)G^Sy(>R!W-fg3Ab}}+wD0bWbWp3gl3x>)T~bT^ zklf)`hG^3=|K#(x4i(C82T=b&`SZm_YJN&=(qZ`CTxZWQIeMAL-Dq1AF%D^Jte-pu ziY(Q#SV0FAzKWjf7_)KERgtAyS#0-CX?wl2#CIv!I@!q{5=Xw16vUZo(RLQRvZ}?< zHw^L_x+-T~)mYue#6+&BL#FUo^tcue_ez$(4C}rwfA$|3E*CjfHWdv|)w?UK{_x4I zTHJ%IkFriE1V)UvMXi6Hit$5Nn7mTSj7~$;NXhU0V*Gx=;jz|OSqPNxb%8!}*QBK5 z{=G(HrQgqZk4Ap*@g~^-mz#q|M@b9x{x|Zsu13!4J3|xh=2?_1L6vuqXh$8jI*E&% zC9>jE-Q3u>7?AgM?mh2RzW%gw2gf9r1-}R^^tIg)oJGxf{y*rZ-(Y@G=58>##zl5s zK(TcE8+-c+{iN59uu-f~w=QWgAngl62S_4ns6|8S(EJ1Hoyk4NEdC~)U`6f6Vv};K zW1HS1x&Y}%re1f{CHm-D+fRI*ia!m$H)*UXo3+}{KY$=JqY|-N=tJ}p`C0kJXt29P zE>}+eo`^8NhnSyGhlg^UYq80_G0oh&^0#35+e&y{yYn)k+w z#Yfv)Vw5kQ9@m`XJ3$q;XV8aDd!OL@3WLQ5-KxUyLeQJSMl(UP4X*KTbILAHQmT!Y zex+f0m_)KIi=UjRc#P??#Wvf1s$YnC@ArQ+eP>wG?f>>&mNXP9%L$TMj?9so6S1;1 zbJfoZ_so?O#f_Rd$ed+r<{)$3W{$+YaPMvIfq;lxaN~Tq|HtvXgI9cy1NdCmd4A5J zw^$p`5zx2qgapN{8tOu<&EVkWg# zjihLd4zzryEpvmvLmdy4G{#~Br#FA-Ghx53&z?#Urbxcsm9U-%Qr+%r4ys!U0pdOT zqcIhy-Mf#PcZ~^%@=7s+1`r9{Ba{X({VIo)g|*51gV6nbkO}7MW!tl{s-G(Te46=Y zE9GX_rZlqQ&%NWfjNzOUMe@d1K=$}c8;=g6>|oa7IV_*}&Z;W#&5_~jO0vgH#CtON&HQ-8Jb;;kV}{)SuT-_!JCN!vae_U_ z!y1{F95*r<)#m==>HY#f+8(oKybu#C*&Dd$9kkcA(kdB9C!PE%I`|bLNxf^ndB?n@ zZ5~4Rz#dMQ{b`ZTp{kxT#DuMnOZ5&*cPvio2#0l^18)2K`S^qUvS3(4^w`CjeU*lp z>vdZ)-V4p==YAIMUXgzTsBz)mBDo8OR1j7ET8_`y&qyI7J7cugh|PM)ad(04?8+lL ziepKrdCZ4ioJV(5F1}s^1HVGHwoAO>5;qILzNz}Q)BBlz*9~%OqNQYm76SspOea|{9Od)GWGzudCVKN=3j3{H<8GoDR{$c zT~dwWp|o;c>Oq#AE~Df#TCZ%$0$0F9btb(w^yWp5qt-4vE1?)OSoK1Rg!Y;W2O+g1vBw5xI`fxUa9C`|$A`^&C!Ku2 z{^N(Lp8L>@)SkazQT!v-SF`N9ULcn)7F#tT34kUDoRgkagN^OT_TzPGpa(Y)*F zuIpGUiQ|eq1Q0KG37(SD8|yjk2L3y}NI5^oG8{6dY{-=kJzw=XQfnig^MoJR?>CAY zJu~nP{N2O{=(NpW8nkN{v4EMe0#$h;FUsOi?wY5xwV^TwO-O69UPs@eXPX~nJEkx4#yT!= z1roV9vG)~dL1g(r^7ko4p|Mbv`R_E=20rkg0KK+Hrs>FE#0Z8+#eSmYo;3AQ&Cv8) zM0}@m-rQE&!IFk~kX2-B3?5MY=c@l`UAIaroVftK`Jt@8w`^sk%%PWN3<_f}`ss|1 z>?|60LYHiDsQz}GJkTLxQIP&BiEw#?{T+(9>MixXYrCl4&psqBE_LPK1`2e0T;5J^ zq(YlTpO8G%!1}`tmK;WoNAHw*OFgCxWGp|ve%Wc8l#p4@Jz9wFxvFa5JDQ~D*oXO= zQddZ`B=;B5hawHxRy4SvtJf8-ae*6|(Gg<@yv99Z2#fL^!>Xzx@Yojym=bO`O%H-~ z&A3i2V#vx06)PBi^c+nx_H?nCBYj77O2c%Dz4zR7u}(`fXVY7-@caxr>d;>+wIXk# zvSMuQen|kj+_ct}5!tLFd58y9pc{5w)+fBd>4&MxKm@DORGg-X|(37Q#4|> zZH_1)%)}|Wn``>~*8ayU=JV``GGA!+Rojhc6HY0YdKfhNX`8@TGW$;P@AsGP)~iJo$BlyxkGKez*xS^rU=SjCr5a(VQi7 z*5X9z+?SPg56@s2n54|A9Pekc;e`EYf`Lb$u=z?Kp6}8zzPizgyV_}j@>y3!v6SA_ zrN*vT)SJkZ*gdO0pxscqvra?zBqNnt6ha4*#mM;M-KjBHN_?ARM$7`W%Imol+@+Qx=KP-J^pwK9}w_~jrv_+t$R0br7U0)W*gGFc48A?;y9|1 zR^>R`{m8{<(^=b8%gTm)S<+nL{yu4BfyH|5ca;g{tQbGP!P691>tKQX8z%2+(G!;R zDeOTT1{&+L@TkX!VJDdb2M2kfeOj80V;D*zjY+X^pqIZf;rJuggudJ@U>*nNDDNXypzPGu9^DrX%kPDD<8Q@@cnL-KL$^9_e84 zC!jt4*;7uvgEgai%Nl}{-FZsa?&)VpKTs^q`_LWv)TMGwOdM3dL&KUKuS~&Q{Fj8r z+U5G94;MT+Ckng8IcHA!s+I@=wD^<$6=kQC#Sd2sHWp#qmBQfJy^B-I0lHJ63WwnP zLi-Ax+Oc;pbINb5ktR?T(?JBHGc)a>xnSdTzgYvewzLvVyjj}2^@Vd*t*@>4rPHf` z%Qp96uf#tBY5=*UGZ*@8>Eoq0FuYtp30cLWuxBdUGXsZD7Rah6sQTw~$e59M_MtRM#r6q7EIIyMRd;>-cDAG`fjw?&g9&j9H)I&}aJ`13 z4w@r=*KrK(zZXbN^X9K7iPc*%3{qVgiLQoRz5g9Sl64#03O^WwS$O=g_k%fb+<&yS zTW=C3NAKK6z3(RTKm&M~w4OWa=JBTF>1G1nSGq`{w3jQj&Vv8IEL2feoiHX1ScNBh z&;%Do4-7q8xt>9O_psNh#agAWWdQ3}(UcawdZ5p{t^78}-kF=|cftL<#$wiGT$=J6 zyLn`-+$&|3Wh3Yn+}QuE+Ycx?I-Bg7F}U5UzG!h(vgcaEc+KoT2EzW6a9L{LcK3pQ zI%zy)v@c^UI$;hu{MuyrZA|Na?^V8&cZv<7qu{>k?H?sY=EutjNpt#s&L~&&)@Vt*5fS>6AQo=rM=l!M-wd>(&HiSI9*Lnkw z*->FT#h)!-%YSgqPKmFx^{9cR-TM<~r)>sK)JQwh>b}z@IH#KVRGR=w?lv?foLwU& zw3ns(=hVP9f1uAMP7xvn8#uC!OsPV{t}qmRd@lIY4tIu`T*$E-)yv?D9)Er8ygo1J zF*8$fLlV|!CLS{zIsc_En&cU5Fg+?ApgIMyBYSM8Lug4 zjO0<1WUU+kyQPT5@h|hs@t=54Bip;ixY3{99tDO{|CxVCED}(D6|vSBMj$q2tWlX! zRbvVPUv_Y+hd2NsS6W>G>r(mfcc+*+qpQ^c20v5ne~4;-8Z(yrYO+Q7HQ+f{EdA~b zo5^2^K#!HCa#ojHZ7zL~S3S6pJO-+mnPJz++c6fqJRa3p37OwFW&y~1VM~+Au7~BW z#{Q4*sdhCAx^9tXN?D>+$jX*SJ-L$02Z0FruA-x^A{d%^A=@>QJUMW=xtpmrOATD7 z7T$024*6rZ26+rpZk-m<7YcVhv0O&va^?FBOM+7jCWff0E0uGUHQtgWCG9EfQ2?g5 zwy_d^-SHjUZZqhp0R#?YBnA1toKkf=hgWPWN()?Q$qB_YIyxWS@4+5*Voewwz4c$Q zj#HlCQ9d63NLn=3^lA#>y3$$YsRIViZaDp#iob9MC&bQXAb`xKI!HpDQ0gB=royivJ9Ghg=|AqJdQ2=luHtnNx! z=#-v1ZLCePY>PYMlATf-&P|~?8-+@WpJP82mp$4yFu{Hwzb%)?mkZc5s&&2}U=`fH zz*KjYSvsF(IuNlPJ_bs2m2&}vHrp%xv3S_xjF07_%Csezb$(4iRN_x3(Ugs!GZ1Bk zQ$lq#hRm?=Rj9U5Y4d4iYHa4_*V@Cz9zBAgXU~(qV)rHBTzJJTvWySr4E8sT9?`!x z)!3VR>)2lB-gIE;+yJGK7=M#n@puV)vP2vUTpJs0HVagxbEy8=+=^o)m@^VuH*Qin z?wgve{zJPl=99t2bG^5LIWP zf+s82lWFJ8Y3Ie@za0k~XZ-HY_V~PDT-Q4p4U}w^&^>mO0WkUlxp!uB^n?Q49mR;8 zKK`Phov#zrc< zy8Ej7RP}`ZbKjw@0z%+`@a7i|wv<4F2dAXsgbGJ}zHsPZ;oEpExiSR^uiK*7WOQ>S zo%R5?@x%IOMG^(1L6BrK)E@vSnuY1u-4SuZ0w;1&c2M#1((d4Ie5!^qtzclw8R9Vndi4_=O2=m9y|^xrJOj=|!fH z_%As$pLA`s+F~nFSm;D9DSAQ~s*no&pVXvFDJqXnkz7JxB0Y_pttG-!E6!?EyW)b)6D z=jo~YJEwyPFY>qQ2+O3DKjSh$2Hf-kVKkFIZoJL`d`@doY3BbNYtk*?kNk_8$VV2x z{@!n8i!Ix|4!;BpEX&_BsLX;{#3x7U%^lhI2shm(SkWaB;7^X?{{GL`sz23K9u!88 zjy{+-3N2d?g%tW1`TmusUb>nzlfG=`RCmFp_BJ!7N5VX{@Bys&ol@9ePA=7@z_ggy za_;>|QQZJJdbQVD&~)+g!6a~+7MV%xxhC#Os|eMw}}gPM0^S9ZH zYa+5*sZE9krc&CLhl8hFYMf^pmLM07#=8U>as~N!;fnMZrHrHTr%pjf1%w~;;#Nxg z1CkPWUqTyXt}5+O>DFf=qV1*OgTJjl+d)i_Jp+xT6**nCBM)Qky3oL|*tOZ5H5xrmjT zClYd1yX4xWx>Xy;lOs!&E$T48g7t2I09i(FA@;bYex+t~`k?TOFRh^rKHBP9nyjJv zfsx~SkhA0c4*d9cmCq)Vy-F?$iT1tPKa0Fc&pVUCh|h<5`znx#cG~a@0F@50}jkBYbgTCZAP0P>FadZ=6B62n=jhv zPkCFuZAIbIR)hxu%d|g-JG%Z$5i$2TCz!L+No;Q%k4158jR}h%p`SaXcd_G-=aubS zr>JM+O^Q_3q};FdH#Z6A?6TI~D*xWgUy-x>{?CKLbsiNFW3DpK(%j*QXnldUmub4S z+e^&wkg%AU$qB&1N4@)-h~{5 zu026gpe1l7r6#Fzc5zyN6|!|o7_Z^5?=8%S)2KQ-@AzMR7e;jQI`j08`+UW;+_zu@ z#)ZbsC4^pib72V>oM48!;5fKswiGTqBXD0VBqc6O6BARzB0DZ{vHT4AQCm5zBQbmE z_m}5ty~BKmr^=)s%uQ`e@YXhFE`HF}tU4Lk(yX{$c9Z*+ZbY8sejQLOn zFjU$QKKDWt!?6%q1-{vL0~69X*s#h{O-VF#e}QRdSTtk}R$318mi2vWys4(d>hCTL?fVz_ z1TMo1&RJkfStD&nkXt4I^S{8{?mq@@do%5#DrPD7v%G<|7re_eXCnDxy+Ohl+5Owb zT90-;8lxlz&tRmp_NKeGrtM4fVPYU(-l9pMiD^Qtxn^u@%Fcj*JMX)Qqkh`|iJjF7fuGes~71nvxR&oEh2P za^Mz4;&KZYFR9ZUoO0fr^1!Ir^T$ZnjiQq-PtWIs{jc?%Pg12@9B}K9O_Hf{!)4Pa z1ZLL6umH4Yhofo!(O5A5RCi!0+N}jtU8oEEM|(nd=XJVI`6cm~k1TppS7OcL<7K-v z)CeEaWt|gE6kv+4-ENBkevjm-RQUP50UozulpgRlO$hJysqhat*!+yl*)jsua+mI^WK>cAy&^*So6!|3l%2bJ?k-;U4Sz1MU(+FL z@TL46`k)$0EgluAN0>gp7h<9f8NtgA#uZ_Ng1GIk| zHzv#Sy>9KR6?sN2clpMb_qrf&ceF=Ex*bh86$}~<&25jX-b&jHB60<0m?_$9els1i zjL;9N6$AC9<}A1w{b~~9?``mP!CBeHb?Bw_!T6E^ZaIcCp#NHCW_WzDk zK-7LyB)3%Mns|`F2EJ4bi^S1|0OE9j(*5k@1#s>Z_$f0hH`Yx$RbzwGEg%47% zp$y|$FK5}wt^FHC;<0XfUGDEVwx2<`y=CkwT9$IC+g)YZcCwxNN+pf``}fV-6jaF$ z>D_fo^3!b_3ArvngtI!gqJ1X27{XoH+|&J%$Ftb-qe3YpMAf*?=o?xbf7sUS6Nt(p zrcO=k6{6V1i99P4nLGaH+~T_pW!AZ?o>%bO=uqCq!pO`(%`KWi3Yc z-TQOCRQRLD&v_2a&T|Q?sMzlfDTQ_qZ;mz`z06TdULWM4A}Z~Oi*mjX4)5?gA3Yz| zl{KD0j2bG6t4waj=I&^pnkEdR>gh!R|6<+z{`x%D=ZAevLNGzT0?|H`k}UpMuR6Rc z-wsXcS1~HK^)^;aHxArey=wONyu`k}Fa0@TP=JNrMEikum{F#UE>FL`)w6UHkPC}s z-1(Rn(cyNyt0cJX1`oi&{X>5adOFDPPJS?^rsN>|`ka`7C#S}xmlJ%-CyfvsRx$x=AgWRPki((RtK$)j63Sem33 zK-jC_8%YM>1ZKg*<2~HSMYQQ*(NO~af6-MsL!16jXaD^~rmReYA)c}!^wE1VdCEO# z=bDk>dm%hxkZRpm;1fj`TfEcJ6aD4~f`V8d8Rb4Nw~~(0Mv>1MB^IDPxl6aa-9Ntx z7@%nT+71lnTy~?3H)>kDLI16iJLsX36J@K5ZE2tSH$e-kdvXIkK7j<+0<)RbG?o98KyLZ@_NX%&Y6ZUNf`=V#XjFK2Y~UL(Vy17m@b+Wt6hodbTU; zBY1dnoanvA|FJ%Q$ne^jH6;)Hy^tknkF4=p`-MQVU8Z74KQo%&z-@|eTSaJ5TP_YQ zDGwCqwl10qzXL_wkvPgA&d%~Zw>gcngZ#;s0kYPMW>7@>&QhLqn{n%Y&>ai>UalAR z@`fY?&}fh2ISbPa(n}TfH+AXkNGE4Ja&wWK1l(fF^;w)*uLQEGdAw3!OHArN6;$1s|K0c;4mr|0{;T);dsN(=hq^Zpr1oyO zKtwXP;+cg#l)8-o*9Xl0$_VU!gi*TEWcz%UYEDKcF5sBYcKa*;pksd_YM40L$18O( z++;#Qc4!1~D;_mRMTIG5d5RPz5SJfjrlp6;SBrxody^pROa43m6V~;UNgomoxi@mT z(2cYzIbSvCxSj2~RxxrJ)W2Zw>F7(_cv91vwp34l2W;0iBJ}4B{(n1*t9Ib`BhB|UM?r#-60S;G|W!Xlh^!~8_L~&e_eTBp`g%c zzz?YI@(fdJMojc(JSytcO7^+F@JqW=7Rzbdkp&mcM<6>YMqB_=*|lii&4boytD{0|<8i zp0kkpf}2$huBDVJ9Nlp*ij_Em3J)bsVFV-rEggfuFKC4QTsfjQMHE*6VxxXt{Sn@x zNxCuzzRfubII{pXjD&|qC$pS@pj%iZT>>j zl+3}d3^SzpPYGBEZ-<^s$gFZ4D>O1kre45l?6)UXD}1l7Hs?{#0XnoO&NPn%>t^1m zO(RVPWQv+z<{$v+(YjjX$w_YE&ru`6u)iTLnIoGdePa&Wg(#wvdU3XgbGwg0zJ8=5 zf*4(2?1h&;RuJFwaj=Qbb>1sP1p@~z8<0%lJDls!H%hl`omU72I2T zv*6%)wb1FnO0-<@n>c84&0ZE(;j>qe>b0>Phe%s|Fp-y{f8Z6Pskgg>SP% zxl50RF4@VK)r?j>S3}GRiT~!C?Rr#0`OMk2X1`6z4k{>IRG8N<)K7K_QZ`D3E&8}{ zS0|Oz1yz+V1W_({+oa4?Y|)>XW_}^uta})I$fQA-Bcx?1D@T8-)^G+-4w&t&g*+MKTl?T(3Bts zRU&1(_9gh0N&^BqzSz!gr%$6T8Dy2%q&h?1DTAc8pVmX8JJ>}_Tg>yD3eGpa`pC5} zqhBC(j$7K=j#}Ev1-%nfT>98LQ;TkHNb14LCDlis*}nMShnrVE+`iIu$F1ub@_T{# z%BBlpZLiFa*k>c)lg>{f5IgTB0oP9pVw@c=;g#gnyPP)g>71qbwh|Ba#z8A zpPcnPHy**|v-r&77w%SW4hVG)8)JK}liO4&!ev;z-STT^Xd5I|*m`Fn0>) zPZtBBqjR}73@i2Fc9*%vnt0cElU2z})A32NUD>K&B+dzS7Cx_S&I_S@&JXFCD=f5c zyu`o8O;v;2R6Z9jq)Qxkl{WEm+L!wi*W&C<@YC|&N%IaUq8@aW#}QcSH`gjqH2f$K zW$34o&u6qKKl#A@I$^!FOxm;^gbK~baN60N-UsVRuI&$!Oj^re(OC82o;P5xQoT)uUQxfYXuC1Yi0e4wl zrbX3@)tCCa54J(&v^(9?eB9lFsZS?UFJ_afZq>DWd6rG#j84=Y+8u*n4CR93pF zC5bQLs~;kkh2>pNr>OPIz+o$5smpg%z-j9v8#JPz&H8w7$#GcGy^X`QsVna!#p2_Di`NgSs23e}(V~C4fUyt- z1S?Hm=c{*-TZ88BPvRsWaaV~e6icSO=E(6(G(TL%Z1ep)JiLN45!_|Z)ttok=HIkj!9 zee;(R?`ESK|B?NbuMnu4n`FIcf#0Qggdg*E8>63{84@uex`X?=U?(qf!fbRaG}>h@ zq9w;{uHp3Yj1;`#mQ4AgpJ0#sS3h5}w(z@)pJW;>anq&Bxc{ZXVluJ?Da&u~ZRAB7 za@!c*n*ZI<4sw)Mu#FFGj*C}|Nv!Ya`PT@X&hyr@V!Ji?6@rrdhjecc;yR7|@HY*O z;syFyCIcniesa`@ozwFpCBrNL2;empl#~cqcAJL>aUdkg7zFG%l*C~qGDdVQ*TX8B zJ(MQ{YAy-m=u~%Q(D}0^(!V94iN*?!guAv>(oLM+un$_G+8eTw_v= zu}92`5FqO7Fe!mN;6m@VC7K%ocQ2YE3(Piuh5#sv9pia$-RgqWL_J26;$84{4M#4i z&${61MKOYCp{0P1)@2T2fmz|?50-MD`|mwsHIU0W5<}%9Y&LS$%a}sD(uDJBo|dky z%{A=*4BnCi-22;)bDwML`*nG0$>MU>F!jfVAt6}zQeVH*6Ic0l5$Nfrn$5;Z&jpI| z<49!a!OGT+`h*}|KJWY5U9ZkjM;Liajqk6bZoD%QdOYu3{Xf>n*Yz}gspl5zFY1|O z^WAaNyDt)|Z@qOd_2)}&Oo>R8>^bdZ(Wl*78KRl!by|Yvkl7zR(CK(?a~%KZ{-De!YD+_N)HMw@ ziBzScKJpE9vzo*)AqV2_P2_uvEo;?X>j%-2|5T`G$Z1q;01Sr?G)@+f~r-p-rxpxNU=EJZd=;`yq^F4Y(pVQk9n7XwL7z8JS&H^C7KK&l>O zsv7O}i0FYeK$1Qm1ger5`iaL{Y}X-H&;AZ4uzixPJy|P$olX15bDMM&$Gr(Qio#Kbx6bu|JYMQK?`t(|pl=BL?K# zIUHQCHp@xyap@<`bdy8>pzSpy^}3Vbgd^e@6wKXPf z(9eZKkIklV|$dGLkW8&!}Y(aW*XT*#)DGXGLOJ+jS3VM)uv zx0mEK$Y+Gu zf2VUoR;6agVGvmQ1nkJy#q*^ZZgA2yUVO^>eZC2$7_Zw8EPv*^`~jNl&%#>%NnGZI zTK^n7Ass@Ziw8Bc1p@os5Kwdpa;T{wJ1NnF`mjPJKVGS#TofyHblLUW#b!yT0R+Nf zkT{16dz*vy{mT>B<*Fo5APY9FozpWTqB1Qn0et0L*cLKyaq=BaniQ2RjrP10&SIfL zDl+y3@2b6eN1FN18RQ>_?)BVRLp6jT)fsfSyT~#&AkBIr$d?p0TNXDnQC#q|?c+W>y#=eGG z?rf=^;?L0|=4%S4{Z<+AvLF)te$^&b{xw|UFOD@`oG%IsiabQG0y;cmb%Hr%lrBd78P8uF7~5?Zmn z_~ZUuw*X(Nw7V;@I5av$CwrI#nP2$YmM8e6hA3hxrd8vJdiAIEL131Cj$5w(Qdxyp z5!zCh^7)S8=P)(6m!_f53)Q80J7p%7w;g3N=$)W@Qu#iQT8uO>%2lw*B=V=*Yf73i zbnIw3CcsSCs&!<1dw`gEVCle((M`Yb$o%+d_op7+iIyG}KHC;^sEvm#dOmKIKcig{ z&Y}95Cdl-`rj@tpW7%M&F88N);neY$mdm##l?5bgDVS!HH||1-nKHw^j;nnd-7I=w zk(AM}F|?uIxZrg=nW6znyX4>HXDXw}v@18|@7_t&1;46l1KVo?H(emX?vx_TWfG#XP!y)*{Ma9ucPg zBV?1kOO@x2VUpA(a$Hh|nE^N3?O^|C)fU~0K>=Ui3K7Ydv>zSGP0ro#e?^vh@E}ds zL*w;r|Flu6_g|5u18v(iR}t^=UeyFUV066xlg4%YX|VfXD_6oAPx5jp6iv%e;HYt| z+g+`yiFsGis;G2btwjoH5M?EL@9F6KC~a1~9JDQOUa}>ou-!Cf;k4H)dl;uik8TZVrzg86?&& zio^=7XUzFi5)iL^k*LLU?cw+40!CgVMx|Npd_=Y0k6~h~p4+v@td(sI8p>Qza>*1? zT2$8TeKClj&fm7n`eibLA-e2~rNR}bu1Y72K2fp^@4i34!^uR+cWkEoH zhzT`626-#Nv5KS6)?cz}p0xVe-!lPJrMz?722%fm??V->8T|TI}sgE@8=A5Nl$zRKr zQD=(eDFuJMM{Z&543?$5+@{Tv2EyxPx5C+*y_Z5W^du*Eed#~r$HHTwd*ZnnIweV{Z2AxQPzhg?!dS7T8cm2lNH-?Z zu6nBYC6w6JRAk4Zx1TA<7POqZdPcBl7F3kyC`nRC9g1K+jB(T7yabTEOmQDPYGMiBskwPLZ{j=KaeF8&nIUPk?fcI&vm&l@9B*{Q34w(IHP$ zeqMoZa)^y{%}F1dk784|XTLHpapPNTd!>Y9MB|@SwuZ?2@OVSVR9!*KkG9t;V(gNk zsLW|Txfdw*#`U0diCDsvCETj=j#&|fgYb;DOT3R-#4_`@%Jb61|&g zgjd)QG-Zj7l-#wH;@dsiZh306!im=n%JK>=3OcSBIo47N8>?F{TN06!1Z@O};1r5P znZ=nk!&m*4?Qi)T+z#6ZF?4^ z1r9^M*gTIIL0^8^RfX1As@ph@q_puBN`l~V=7mAT2N|a`2_T=^y}BTQrJ{SWcKVEb zGsdUQ(Te&zJE@UB3&qAv51ama>ia0ZkkAqKpto`*w(|#-lJ-X{YODHum@-Q$$<5Sc zW$)o)^Y#tNAP3$msAQc=^vTdbN`KF2`f{pSAmh%BSi$6iloTAp&;G?Bxwslnx^&1o znp8B4^iR~fchxMOk_)(n-I>5|eVPlwwOcXh zPKJ(epawXyCck-`LzPaj#qCCWdeHzuw0;WLEM7isfWz?TLHQ&mT;AOw0Jdgc%?w5XdyuD`jL*y|EQR7%tnLK`RI z>+?yPi2CCx!e^fPBm~0@HQ0Aoulia4;>D^4F5N=?)a1^LI|DLG2lE~uGfz=dRkc0H ziqb3(&h=l`Bj4v;w^ddiD(os{=z-F9>3@kiiwoG(U{$_Ue0EoIea7qIH%9A< z#?9|79U|i2E<9|nx;|5tHEKRSFH(0D3;&Moo=8GOha7X^7c=9%ZM{}^e?@vv(W{(zk_WG`ex?y?(P)+TLstY#&?$uGyffJ za{n8Z|6CAUxyu~MSI3QQwrI_uryxw7v8{F)p=LwwvZJQ!zZ`X5L28qnHUDHb#>9nj ziKF&IW{_bugTG7Vr`?>L^+WU(I@np+gTAr%e^%>y0rY*H`U|Wen<}3?rs$)#~p zEdAbEbwbxN$<)iC^`lNLt?4q!Y5i`>2bp#|Y9HiA%5&v@;|iC;YLJ%ApU$@*avDRo zyINv764QyKZS8(qxi9XHq-4)Hp~+XqETN+!QU4ig?BoRBVN_uHy zVx1r8LTDCU6u_|t5=xyrP2%ohDe_yoeEcc&$oDb%07coTb94-KTj+X&n)4?N!m{( z7ElIzx~9=vy*s`^U)R1wN=8_3PfpI!x7*}v|Crzozi*Cb#*Pd!rU)nH?s~lMKW{3Z z%ws>^>K_e1Byr8WlIZ&1Ikui_rg1!1(To3@9}KzX5iBQDKet88&%Tgr$6+IxUhT_; z5=k}}$>}xgcO`2V!YGIMjl&OWW&*nH^cfyQ{B3lA5~Nd1+A5HW^|ND8Pqzaou}n7u z357P_#EPgM&8o)hZnbSL$k$aJ%@Ypjo7fXFrfV-?V=qaMaFDmDuga)c{yiEddTMt% zOAtS$hd_J8_BTW}PPv#)lpezIMl&JC;?O6}<{%b&V6hxz%^347IDwutn~O|^^g|5c z2b8_zc=wfDc!Hnlt3dfurs3{Ht>C{WzIWcEC@t54&+uqEHlO>30mk!yExTm!i zVDFmxx7Ra=C}t=mqh*J(&WoJ>z6z~WbuDjwKS%x2Gvp=9e=@9wEqCPm-1llmRoD- z&>>NqFAN zcBLmD6b2Wo?RrMMyBEYol`{uQ>k1t7)_F|!o8Fs1hcurO651ci^w|$29hS7@0Yg|W zttfvY3EJHK~Tnm>xSjl&f8$mO2Q|1eEyovw=%{1Ja89SGZ=!&C_1V*)O4 znA?1#cB$QZ!su=*J<4sK7d#Y-KSLD=6k+Nr*cpSoZ$Xj=b#aEuTIJhAudB3{(*8!w zSXXoe-1YMKxA}eS0W{)xn6;&oeB!3`)F!k?G>ynM7i?C!{57A2e^%b^$`5e4as3+d zc^Fa0x2&1%`0elhp#gCO?1%R)+!YOJYmt6h>co$Rr#VhHO|5X9hKEAJYlE7qX{Zlt zm|P`X0P1_dtI=kEXrbSo9$au_9F(fAIDd}0g$XMRz9-&@@oT=0bsL6TvgCdWqNVg- zyTNC#t_A5dJJ?AM_#c32_X={lT-|l8sBf|H3vf;+Q07spSxFKo+iSUX%f^R!;nIik9#=L;020Y(rgm?@fBEc+HMH z(AX}vh~q1NYk1ee$|Ps3bvVir8%Y!PNK5YowLEp8a^c=4_zN{|r%@wB$erA09qh)a z(YVSV8rpg4hLjuf*o_-^9GL3m>G=C*@eUU{y=7&A!p^;1-w$!q5BlF{Az|BYX2X3l zaHk9Yi$slO@2feP9ZgUIwrDiG?+;nHn+iW|tJYAERI4ZC+o^7$f->zMnIC(8Cr~N-Px10Fc8tOWFTdEI|?sD1%p~Mu;zV24$eR|Tw*8fO1}4-^kb9GSsJtR?67-*+ijbIiwv^$QmZyz%F#`tW?R=VjHscHiXgzYDuCs1o}3^q$4+`MyiW5WN#vr~2@2`}M{JUxW=-cvJd&Dv#3w>SC$6gc%|6Dk2c z+!y{;n3ih%udK^q6BqLz?wfzB+H<8K2&@!4W(Ol6sirsN57YrX7|JB;y{dU_%-kVw z)A9o)MHF%}f~Fv^NmUA^8VX;_EVpN$<@t^(%FzluP=c=J=HM)q_b&fG_TKU@uAo^L z4S@hj(2(E~+$9ifumlM1?#|#4U~mh;g9T@h0fIY0gS!sygWE8;4DN@0_TA^c_uKsg z&e!U-R#n%pyH|Hr*Yn8MIP{MqlN;JvTh^nUV#=yhsL|C)KbP3V8zYGHR^~P8>oiqIv_sH~p9de_gI5ET8?~WDLt9OJRd(-1)E)!b$NuMNb%Qpn%8<1H| zY21boS<+ftKO&xxKJZ@tb~>a_?GO^lT3K;>7NNYXXH>PHR&BX>xpn8#$f0z8O5pkd zn$mJ^IkE4@JH~2sQLa1LT0XS08C^wTCQXUi615$#-#V zgM=%zy8Mj{rd{aZS>)c?41%i)`0 z|Fb5)JIJR+Q#3w#cfa{xJNvUT`jQjSvENmSU#uvk z$>IfB;nw)Nub^mkT2w+%r545^+40to0MEH5G%C0}BhFaYY3Xoi%IAYLzMj#}fx1(A zC5m%`gMdS^Nt|6G|7pd{@mX|MU?+v&`UzpOnXQn1*6q4P+9d(Y{3TFF4=mqLCZiPZeS^(7{jNaZDA!e`leog;kQfhZlsA^|9lhsuKGC? zJe^!A}c4IS;%sc z1>&8UgoZT)I74u^6q$IifF_<}e3a>s_Uo><`&U2h1zPrgLH84L>6vKheA5rB5>0r{ zi9`eRZ-yw0i)oo^)UPZy{{qs){q8^IZu{~}6cQlD2lRL}t!NVfiX& zOEn^e#PwZ6g;zf97_)NvPedZudyGf01{&y&MBGqMQ=FdEZccqcr?>kR?ClRv5AI%5 zWUDGGXCkW4rSV4=2<)ETpbae&ahb$7* zT*`~)>#ocXtlk*V5;9r&6`sxy6!Tz0$jD?M41NC?h|MWy1bzJs&1cMh^$W^b`Z@aD zDcz`jVzHg&8y;H?F^q@J-T2rED*wc9Z8&2%>VrqSDniQnWW6MULySuiMnd~LV%{nj zG;YX{IkJl83SX;B)Me0AbdqwDiH6Uw*sZJ*VeI=YK6XuYa;ZB|1db87)p9SXYyY(s z^u+>}|6Y{jp3O9-elFZcEdUx^usl-BJO@NBH@iRQnWWfIQZ2dP)YTS<0zVFyk)Q-H zkik8UhtdJChKtT&K-*pOil&>QkI!JFv4Lnt^x2*?CDmQGSP_)2a;%J~^-1Fr1uRk* z+@~afJ{(#qLNzpAKP*rz-<^?R^17daC)XTc1q+Hcjof1bcuj<0u)Q=szy)J*zn>eT z+$y+FLSWvhdO}(KSgA6pTXx5aGPdxQlq_z4rL>nJ!-z~lx(_0YDdKIOpJ?DvvIjuTON+&vzp1HiLV3Y5i-ao>5a} z>lD@bX`oe&xwXJ4V=IgiU^`ng`sMFgTv975D9W$D|5m`gYq?V1t6Vwos{`%dOs@K$ zYhJ0Xuh)YG_uD2-ii|+L_K~c2l_Q)XjDT!qQ;EGYSx z6I;YBz8;x2REqdGB|ut?O2&XiwKtl)AA5pA#7gKn9%cjG!Xmo}4kOXi_Q{XQC+Aao z%F9ZaWg~03pubf)R822;r~aHMGO#kN)fPpen--`yG)exT5xWVkflv8Rvftqpj71q? zrM+YO^wrKFw0V8I?5QG#Rx+S%ye)&pr6dQ)yE%?sS5M+Mzx;J&WjnXETLNGPdnub%TX=l!ItqQgz7c_wG6y zjdh`Wn5**$?@jM%kg^5m(9s|DtdaOtmrJddZGB@+Bhb`^CC7dnvgM(?q34T2^4l7% z$IRy-37e&13LGN6@wtVgvM0b;Fz#Z_5XO1l8gT2g@!22|K+Ym|PW0%@M;&05JbW}< zEpFuY*hwX0h?KLLy;yaDrVqXKKrqs61h)#``L3Mz%@v}Gl1u#io9s3bl8kf2>Lk-P zXURE5B=!Vjduz`wc7k|RQ1n=B^{|TgxT^FqF!hQ<$aRe!bjeQXT}E?S@ay=TPn`Dtr$RqxU4yFsOT_>w=9bCvg6 zn@6JS?K0KyD4vP&@BH3@py1mn5$@&DZ=**2M{0v zwMzNs!IyF@3-P#*Xy_#w-7kQtn?(SREc_Qa?iA+ry$L%tANTw=@;@3X>V#!L(TKt*pdV6-peG|3xhnj}0 zN1YxL*6bF!h=_v}YvK+RtxI4h_`pQLX;PccaD`>W{{tZKs?;2JK9>d6W%%{#6g;X+ zyfh@|t({Lrp3{0ochL<<&y#-vIrEHnSh>sIpcgtrtv^aKWR6is)iQ;x<0wOxAZ<9C zZ^i>7fcrxUSKEeuFdxbR+$7F)$W7{hmm6TZbJg}^#>85R5yQrSb`tPUaF$p+D!hp6)}^lqbu{d{RW))$O5%xnft#&4rg3mxkU2XN$RS zA+ZI~qAgc}zg|deybdfvc9tg}!CMO`R&`^sU4$ zzAoJN!id6+FEIlaYs7vZ{SIl9UNqZeqbjCqLN;}2Jj4|G?XvP|JoT0hKP*S4C@q#b@Ci^V3!Y;r@@chwF}!2DlTG6JATqAqMK)VrDV$a>S;!f^loV)u zU(Bk@oK89Z)@A8xU}eEkKuHU2NC7CLLci?wKFf0E9G!F{+b3}X95`NC_!2pW{mtf1bM+}?7dD%L`LTn{+Rq06-K zpNc5ZP|Wd8w`5R{D7aJt?oCWrWxWsp`U%=Rw1N3eV*1HuTV(=1*QkN-A}5`~Us6^~ z1+IvGSta8r5c66tSU&7P>~8<%@Vg{NpTj}y{oIo)j0H|P_`0q0knYYRIF9@K`p2Hutr zNR^fEclQXfEE~PmM7<%<^+_>Gbq?;z-oHDDkNJ3k**wk+Oh8*lIL^=T8N?=d?i=So z{79z93JKPw#cIEs=4C_3QPT->Bi(7V;P7s!U+nbM-aSB(BF+yWZ)0(UP-!u}oQU-m z;K6oc(uS*};x0Y=JGee2om)Os+DXC7b!(kX(Vq`$o6bF=pv}Nw{+0W~aT)tZZ6|NR zUg;a9-Z?8MeH>y}_yEe){-q5c`Fr()18THMpUUXgjnK-)5wb)(zz(a7^V(Y|udW!B z_!sDgJIQ=IM5W}g{6A)v%@i2^aqH3=u+ISo2QiYi%YC~0jK9ZSU-kHc6zTgHVz-O{ z?nJl;Vn!1HaNzZ+dE4s-=9&w>;5*Z!915qgsLF~-qp2PI(6`VmyjS8!^{aI{b_P6WUbZGtTn*=x37Tw{U(6XX~~+ zh7Rs3!p}TJ3@DLbdreGaW4i@+Y|-%>sbWylC%SbFw5+6dS{{1Pzw*7BV2eJfSgKN~ zA7M)lqx#n@oV@F#G0@nzINT{6Oq-mojHK_j6-Uw zZaC_qVGb-x9c{xqo>Oakb`|n%_v6NV9Y+2a6$`2lr;JZU{`W|I;}qkl_PaLZK+shR zt5KEE{y9uL!BT{(x8-^gYW{^=ZBWL=hddiR+%f-q_@kE9=c%T*aVZZXTcnX%Ucdu# zi}e+<-~wyYSZVdysLsx~(-3Aq0b*Kf3n25h3c2dq5$0vG6lJv)J=9W3iI3K^7#uOM zF=290j+>5ls95dq|8-01ZCNIdo|GpRYi4k9vAMUEaaZy<-Ps`w!&Nq!jJ?Jao~WRJ zaFug<*kT-dx;Pe7;TQ~86EGLQ#0t-Kce!vpm##uPBo>ip9Q(~4*f_B}F(&uPD=!dN z!V^BzJjCwgCl6$)D7)Dy3Jmd12!g-s^JWsGb>czIb>Fttz3R*meL1A!wA_?)KyK7m zQotq@K4jJA5^$3haGI4&br(m)=Hv^*4uMfL-3NM=HK->o2=+i8g&=*cx%s@+86$$j zepu(dcdDT`o$e{oZ${Q#1V|pURMXj+{iZWOQhxlj3j_XP}!NVx3<=5}wvj zZ){@NsBzr~^u^;etp!lbiq%Btp9yd}_L(zfz*_+F3hWQN==S4gcA+>dra8O%r%MoDqWKY9}TPSbBplNbtbtbVP8jj)6XOK3eg>#l@bCLFgS0`~-9 zx7orm-|dc*Pv%`MUD118^9E%NO>Ll1{;s2b7r+Zyr$gZ@DScEu3MjQYd6n2av~f!fn-0)5@Pu9HQJU{2y` zcAA_B##+DXo<*IPE>+}JsGT_gRpVMal2^;Bj3XDY=bMyS=XUzL3< z+x7P;@GJc-&+QD|`ql7UVcXiIyTT{+i%-RM<1?Oq5DFn&3{6Gzm?{)}v0A=hRM?JN zlnVa=+kWK$dhIYeJ8LepeUIBQSlBpK0oLWB&Ok%hUZSbM&V1)gWWvXOk7lX8WoCPkj6@Velw zQhZ|b*-xa-Bo%<9_m{YGmQ1&Z<1Z0x&K3@GI$-xdy?=@@JVy<_4oI zhzmkOqHx5`9Yx9d=8WSNomJ<%VX>O^Ng>$jP;=-C6PWF8VB1!UH1i-m)L>A{YuCFEMP&@7`qBD*bGC{3@k=r_he6he`^}Z)Yzd>U9Zj?> zDi2Ktc=Ss4Pkva}oOppZN%(_AI;VUbv$?x~8%;v-aQ%V)@B@DQFd6xc&$Z0CotHj% zzO5})K$MSasrs*zjcu{8r%Q)Fhnt8%oN;w3Q`6#r@gx z>qK|mS$aUf_n^?A=^)NSJO-R8=iB&s*oparv_d5DJPB)wP*Y8u7nLe zz|09I1xn9ZM)D{iq2qx8+;TlYk)7GBtD9|O&RTDET~;6(9AJk zN4&Ssc`7h4 z7u0_^@HGL25iWDNMtTBznX4EvKtfB&lwqg-`+AFN9}~G7+oYPU$tuo-fBfsY~VaIB@3Udn$S(p!-~}ri!sbcAgE** zhan?l4(NL}g0bYcdmlqcVty)iqjU2b z!X*|jw+)gpB#4}>|C9$If{XdRN;3HCIsV;szPZhft**KZE8v{;m%hPsYnW!iv$Sx2V(6VR4Xs`qqa(zA+?*>lSt?Zp98$mo8h9E8o*8wTxfbz2+p< zx%0c%)Ga+A6&Qs^sSJZUOa>Hw&wSFq#IkG;E;QJDgGP^|CSHP1d}G(KiS^3^KLXsEcwXmIK%yys4l+S#&aUa#mIPI#YbYDPmWtq91;x#DFaaLN z%Tnp4nwETW%|xZLNz3U3z}&X9%0aW&$_%Ro2e2QjM7Wg9DTQ%|1Ar^-SYRXa+Mv&pJs$u%_bMG5o6WQ@`ck`6x--C6ur{F~(N$U3XY z;AT!6l`vH>&w>F6!njR730ab8@9Pv|)TN63n^8HIFH9PgP5axO;S~`2t@qqwqcWnV z?klH$Y#b#WMI&U<{A0M7+e+5xQK!TwJ!T)8YmR=V&_TUQ@U(-d3qz^;n_v=w*SSKl z(rm>f39m(Nm#8_gTu9aRv=|vW_aUD;$Kq%G%RVnA>7Scx>e$YgSXgYC9Nj$I<8GD0 z(w-IT>vnj_RT-1hwT*Ggh~6B~H{%T9LrH|iMm_Lp`J0i=sA%Xz=bDM9{4#C!`8#!Z z0hGHb`e@nhsWS>Mp7G9b!vT?Y{gywmbn4UZ)3|{oRN0FCNpvD?7rlIOvdXt7qwV!M z(@8kPds_*>)YAzL3F8H{ZO0<3=rJnQu7&6*WgjeNGOF&W->E^G7hG=5$3>Qq;lSPq zMf%W}+w*fcq2%^}be|(SAs2$_`y!41iqMB~EY{xDjeKea%z&7hox$G8v}dVOOVe5GI+5c{Wec%tBJ=tD9n-84On zwz&UxsWixcQ*uMO2Qt&dplN1=~|#{fqe(hobhDsDE65IAs0z5oo28nFJE1 z1d{wrkL?vUisMvx_Q{0yZ)gP)6xIES+i@UVrr?%O0*g`UA4|^r5Hj*w;n|itoKJL8 ztZwi5HWop)yujV;q(H`1F0xi9Ln$l?TbBMNX)S|ML;TA3&`u<#Ug&HwJS z@n!xl+E(R^oSsq=jwG?wVC!=s7=KJO>!w9w_d3_Y+PFmIzB}Dp^ zbhbreK{N9mvp@YLxuAEZ>r+b5ru|cRsf&JLtUsA5pNQO^9tY)KqN~MA`G0dH5s5Qf zbnOz-f>Dp$dkU%ELVJF2?3sCtP6shxs-*4AOeF@!0Q$}4562`(}4*g75#;y zj|ze0ms=f~3LEZo3j};P?a@APrT2O4z6AlWXoQm_RvbPXz12G{gp0lEDx#>AaoPx)JyL}FkD5; zkZ?jYA@l$}T}>6xEA_VWkSQlf2|EZkGYa*|r4B*rsTHu5;wm7;mGQGYqn#??O7p zKaw=5U_d5<_++${lJquC;3_d)BRaS`bjII{s89;J?JdZ$EN8}KCC3(AOxVlRPWwMv zR7q4|UuhLm>y{UnOke+M2H=)ul!#^83N%SWc~O72lRNwwWRy;`5hPHp+^MvOJv zseEMWHgu{CxG^bT%fa$nC~El?*(O}0-}y1pKXue5o;GIF#UDr?^Se^6(s~j1Lh$c{)r$%^NWi{aV$qFL)BLTn((;q zCDbKrxLqY(`MO==HvdNaK0vam6_$1-?sa5ZsS{J@>I>0-F6g%AvKcVau)a<&E}!WQ94qt9@o-RhvGQbuYbv^ylT?QXo1Q?> z1ab~NWeY-LX}6oqokng4>CrYPYr793Xe*XUYVMMa0kD7g@wL60w2Q|Qap6-}bVktZpi zb^pz;v^OzC4Ed4LoLBLxw&Uvh1m3 za0G!Lx# z_%1=$V(QmZy<%i9#$H8Rsjp1six5y*Ju@TTuSTt}7Tsnk3R)!qlPpf6F6)zgD7~=W z%27S~tB+vL==mi)>cU_d{{8^QqFGvxbck^ zjy_etK!TPM?5-5nm5H7#Sd8y>4aTn*=rartz}Eum^Dx!BZJCSck|$WAE1!+l>kF&e zhVrGe0dsTH50%|b9V~?7vL0xFmlT09U!=2X$MJPaF+tMS<#GjQGx$50p#N^_D4`vv z$k7b@M>PH)LcMR<&m1$F+?kdC&%6KiycR{^5oS4{r}f8w2xnPdF5~N!#_#&N{lB`Z z_Wn!L4D~Y)?|%rj@ONUy^^z12rO(Fvj{%y}&zeecoH_r?!v7K0{rch&JX>M`F#bQr z?_ibz{!5cvxDU#I3N_K1Xlu3Tr*58A{*Nw`=l;cvmq;wV{htp$8*EZe^W4!o7VxO{ z|MtdzHu zaRlz2k<0&Sgm_>IpAC;qY1$kPzl?UBPwDHM*tzVu7)T$Bp_7k3tRjv^h53p0mgY>d|4C8gpid6% z!@5qEdR^=3&p~5WXrp=Bt2&uB`MgSyF>Ch~p_i=q0s*(n`qOf{zJ6n4gkuahm6g*@ zpd;QLOca0mYu2o+*9C||E=aMK$fE%*SB3T}ai)#kzMM}JKj)|$yHIOP$IX}Q-KOex z=O)pWf-&jxcG!@C{}9dWkMG?#3hrkLrgmg0yxW*{#lw|EwXWX~`|#Xn=);fWv*qn8 zQupUgVaT32`NtbnYs7iGJKCT9&ApYTQJ!w(1&49YBZ!_&Q&f))vhV=*+RfR-%uo$Q z!3$Ncv%-d*8f;F_Zak`bwrBI zbEeTm$ot1YvjrCIs;*Z!iLb+hS*GD|`CgQ!F|t;bVOr$M@(6b9yAYt)$c55n46-R?n5}_}F0W%c&fW$t zv`Mi|`6(*;5IgEE+I^Cc@NK&E=Hm^JYgRWBt{hCl#(gWu%4sEW-M;sE*GGE;BQ}n> zRP}8i^ps6@yeDK|@&d4Uq8wW1SB4^uIpplVaUu*a%9J!Qe0iuI%QJ{5F7_S>n8D1L zm$m(n@bT#+Z@nii$6McDah4=zhjY?) zg~?e=VKJh5?n)4*bhFpB@XsY3p`&Cw|8)v@|{c~{Ob&jVV8o)%X$h^PDqgP zCnXT1PnB0jmZi|{_YSZlN$J4TfrcME|!$GPCOrFf_zJ|yOAyH!>gQ)T2y&X;> z|EkVV9g(pv10Ol-TLM>0TW9?Y8v0%oeIuFCWSW~kJY~)m6-FROIJX@nn zsl*s1GFN3#$erpcCMKwf zL$02KFo>Fp?9&q%O{cA`MixvmZ0b@9I#(O`&CFO{Me|Dz67XfpYEY_N{nQel&B~&E znQR*UnZH8cxZZxzh@)kv%VkXam?`$auc$1Rr{|fJqmj{A7Ff!lm3A;rWI#3{_`k`FtWz6sP^jTv7hLmwj( zoON6jI7a&LC-FHF-N4j-yO-FOb8kITQjFVG9(&vG6mEI~$%g7-ik7CPjS7m2g`DH! z`Us(<h z=@Q-mmXb-OK>E<&GMzL-_1Z^8Akxf>T0YKe#U0ev;ygwRk0f$pZ8*;0=m$0=!9u{| zduO^BhH|&N!#)aq6{G3%GS_;4{q1`2|7<6~dzK6uZ--c+yv{!fsoz&^Z;Xuf>>C)B zxE8)Xkd|KC|Mn3*t%iU*@~yn(Lnt;pWX_0)OvIQnz}^@B7P!cw2zq17%ACY)%DGO6>{IzXw3FnS3%{I2VHpnS~p0>pl$XC;%xHx z*H-Zu=Ievo;10VYS>@|-g{M=_S`bCOYXvc79J9R%HAdZ{7Pxase z^V*7Vad9!!9bIdh1k5yrmOUKn(%^Lz$DZo7mbypq^!OLdDQy9MDus!F!7Z6#RHInq z8iJpN^pB!wHMm{1F_II&ua)(71^*>aO685l$IU4A9g1>ds3;#-hBpvPThY{r5g9vs z8OCRKxJg3bubm6^7raaxh;9`_f57_lZ6|p2bTc?>oI^R<_l6d}>;fGsqr4`g$nKqq zOZ+I`rpk5vZS;d5&W)z%JFch}#E520sDSu4^NXW?7FKJR^NvSo$iRe%#tCcZL+^s`H^FoJOr6($ z&^!A|D|z#b!b0fOWJXiWX$0rZLS4Sin8fhzGfZZ0L(As+=GEqD^rfecyb$H=k>MC< z6moS*$d&)x=RF!DH#}-)1iW^6|PkVuw3a zK4aATZ_F3vZlPFKy$iD$jE@Q>d}%!syt0iYwYp<5pLes z&TWsmOZvBU9>B!{@Yc{2VILjdh|;EpU`fnb<*v?-q!0OmDgm;ZJmx>rRSQcCNjcvN z3134^^-@4rqL1IbHlvA>qSeXbJ*Cm*(#0+Rmc_=UM!!lO4jt`fi`;!b$toQ1Vn4$j z4f5(Gc~;cZl(tgg2-fnjT1z~^-@~^&WJ3mozf&0afwNZffB^!yC1(>Gv=4^outyDL zS0^d5s8PB7(TTr-&I?F@5qHYvHT-dKM zX=C(z^OBZoN5eCdn&!{Il)|cp{kDb0MNdJmfaD$YLl_k&lu@~_$C8B2>O$K5*uD%B zt0JJX^ry}xgJ0U3{DpbwjpudEe$A**a|K%}0NaE>>X7_TAz6GZ!S3@mx<)el@a8YI zw=;DgpEvNl@srZ{!E=7;8-hFtwdape)=jDzF-``PHgHT;w}GQiRO%yP4;@lr61>u5Z?NQATj+FpIc`%HV&8f8Q4lOc!hn0glD1#6hZxPtaE!HCsZ1mGhjh;<&{!7 zx@EZo{;rP_Upaano#NtuJhn)gvsZ-iZ!MMfg^MRr`A1B#lr`2PcEl*BTI;zJDVow4 zmsI;7J966eKO`pJ|4bH^<(bbDM7Q^>Zx-T@ici#?Wm85V=Zy;N)7TSG*tK9B{!x4# z(ssNR{h-#pjiHaaWcGPyCity`QUKU|v~Sw&#cl7ql9r*AUh0ar@&@{&!>G}XJ`=dG z`cpTXjiBmoW!<32;rKlJ>%N{sTiy`cxFk?-WUrt+zh!W^NeKwE2izS2-4<<}yp#Ne zJA^u_bLz>9RoEsMGTgU&n`8v^w{B zmAi8X%yl_GSDBbDO!qP4z2tf-?K-=+lj*`h`B6qi5$GEErIrOShtuS~FuiS>mkp}i zqj%bo?f=~fkjltcHE`SFnbb`M;HQ6Q+sta*8mlG?qRds1m%X>hpjnmOeg0LY6QYcY z^3&Y~w#bRafq(3Reyk8r2BxWwQ`$$T%FSz#e-x<@_6qvwAV(Qt%Syfs<%uK0;hR1r zfWm(4d(n)JYXCzTCX_G10tVX=N(xqe{HI1UNBxaoe%JwAIHZ4TSzoMD<03B3fUQ>5 z8p$_V!_~^YvUSq-%%+jx-l=9~MkTTKT zB_W<@mlFtoje0J_99QLmTH-6J2nAR*jU$F$w+64TTR*Cmp*5jl9$nT=; zF^nfk-nmL&{Un_HA1r{i^cR7EMO`us5&q$DyNyNhUA9(@wIr0~KlC+&_SwmhDYdK7 z-U#kUfa&b?-j~TV*1I{Dq0o zv~GVN{3&O%P{oK1LQ#;3xz|k{@-N2(b}w1LGWN|b-?GgqQ)9hLsKG(mY^jbLu@@y; z8MTC*9btZp%snZWD>TL5+FGA`%%k6(dmergYl$1!*j|zip=#f(64f`2ZSeYZ*LtAp z0SpZ4XHxC*;Eb$+C>48`3Mi}t9QS>+6F!Mz(OBk=HZUyAVgj!z;e}N1$ZNG zn!Z!$1~s-#fkSkoW@C!9y?6(NbEpE%aAhytrc@rkAXR zkJ>*;v);gx8L~F*1t>TrmND|oP+u zg}mI?E9_1+6UnthLn|j5lrgH&mtD>dlynwF7dD=#3o|v_P#G8}1D))pc*VLcgkkE6j~Hxb2_aS~AK8FlsA zmNAgukziJYOC$nwMi)|SzAJ;6BJoD)t3Ih}i9f7^n7f* zJu#w)#>(jjp4s}gJ=M|Qscs{;3+HM^B!_d=ZGgC{0OOceX%J|@6TIX zN&63F4eF&Bx#a!m@3OSieBNZ9ijPh_{IHs;>x^^o4c*U4G*Hk<-PBLbjBMt~vK$;f zahBS|1HXD^=w=h_*-GWYDI;lNTpV}pId}c&YD7-0gT*<5wNij+QBV<4w(CFV^HWK@ zJ>M=vs5Dr`(X$YS3NWW#Lgdi&q?z5`H7IQ{SdM(iVPGh%?Ru_4 zGHxL64If8T+qk<6a>fGlYTm!nEy4ag)dF5z{@kuJSJQe_eD7v2#rxVwB&viC7dLH^ zZ7VvL#IDjb3O`keWJm<;lW}dGrAhXX%zNL2rOYdOlg=qd$DSr=mdCI^ChVD7 z;pWco)bO1mB7`xkGKInE1s4kxdPC3N$I^FbQ6M~P>AE2)?0=C~c+3n{evZYi^{0ZH zLZkJz8u>8E5rb7U*K;48i3g}JY$+7wuGJlRxa)@3_!21|@`yAG#6!p3%k8xVHD5}U zd94qlDN0MplZ?#bvsx-^q37&HkiHT6cDyuKebgP!hHi+}r>V>>HzvJf>xWcrYH1)S z-XfE}wAy;x0wB1l6VB+CHo#-rqPRQPswfLz`NfTd2 zv280R^&ZIU4yA-LRukDVI5+~F7og+oS}JD7_M?i8Qia!1_S3~}@OaLT-KHpqIa+lG z5fQYVHuBFHw^n?$^O0M1xIk*EDM={VPXG#Ei2vBuev?}xgIn6)9DZ6jeEhN?p#g$i z50NqB+a>zL4;0^^941#V5beZk+L?b*mMO!N<fK@u%dyx{Jg`$%NiL zcJVixCo^H@LH6PsX9dYz&RF~b`c&2#uPMmBmpX0(ruj#SPPbNVDRkT{Sk(?J4{Wb{ zHk(@P*JlDaYj1ucL7*|h&iv^JCHDMG*+%NVNd@ReTdU>6`a6t2iROX{hwtZh6b}?? z{&8h(42(tD14iAQqRxn5isY5I-OE+FzPvHEmEnv}1K+D&m*-8*BVEZ8Y=rzLC8_H0 zz>b&=wic9L+>jdjyR!54z^cT@r+)VD%Etz!*D@`h- zwEDZSPqb;Btdx!N_>S*e-td>GQGkWF)~1KG7fIY9&s7`8WAbU$L;zL#l5CBMIqQbVRFbrTpkCIBm0S5Ie)-Ww4b@nUo=!-CvDUQ-TLNR2o=f{auSfU*}C>vcu~TFY*&Mmv+wg6ka0O zKOa1;{a6EzH*CR)>5nCMTn~`u>W#OFkjn&{+a>x5l?J`Jll-5~8YNP=FJRx&ol_M-LayPfE7sC`egT&NyraGY2ahb%gaP4Ux!nh250P?1Z$)Ug&cU;f?`2$n`6Y&XchN2Vccfu<_hc4tb1in3Qdv|F*L(6j8_;eoGQ|Ifs}j zGB1azTX<~8f0qv{CGTpm*CZ^))pq~wcus@=nZnTyF2ETx4rY1MD9a*sDey%w*y9a6 zt*)eZz`Qi9RuD%GckT^(wuhzK>_(?Coj(GJ?fdbPUrS=KQ@S zj~;4#`HEOH{`EC+cbeRjl_FhTeQ(cGn^d&vcc8f!^)YzU8cl-=EZ3Apu_QQTif@V6K;%Y!7cUTbSP0 zYSa7(ZjhQH?PN{@aA15NBI-%__AMVj$}StvRb_I@XY(}W`!?PA^pG0!!{F&Xft)Kb zy@1N}_jf~7p5oYIX!vQXf%{vJJOK*9MfE2t2v$8g{f{vO?-k{nf6mf@hLFv~1*4xA zbISwAG1iXrZr@erh3{uGi){bY%XBVk?r1Rb*t^4-Cdr_Agf9p=f2LUPZlra1|Ao$) zoH@1@WAfzlb~VkDXrU^p1Ll%Em=_iI=#_ABbg|C6+RviF)-qt#yxce| z)|#w%9{q0%BpY_Mq+g-{+O-Nt%`_%O?ghtK<$rqp>P(#wwIr3CwbC}VUtbz2UdE^k z;f4R!lCb37`4jzZYJ41;S3yo%y3AYm4bS-{#jjf9p**_rrqEFBkGlRJSQ^sfvKxVf zZ-$Hgpf^U3oH*!%V>X<(_{RJ7MWU8wZx+}FiEY7%ul}n36LOyu$m6ko5;wimag8Rm z6y*CFEU1AQ{q-IH>rJcIvAYpRq4(qiE+iFwt2x9F_xt2`lr9|>;6JtO@v=8H z=$IpfB_AmbRKj!U!VLzBXV=b!KT3-Kdy~*`-3ZG6ls5sA(J6jil*`N_>O3=Zw-co# z@kj2ZvbetDmrar4H@xws*`v&Vl%`3EYnhKCa|R(+w}rwp`8!Mq{nf^dxS);KqnN*K zG?oAC*I_nrsnIZdVVVTvNDA(hp0k@yk9?pdawD`I$Z=I8aD^53K#WF|y0k~8Lh9uz zTSN+mnYO;7+xU~BK-pByv#7wRc}XViA{Y_}IUCFxE0R-xoRHkiJS#b+UtV!6-el>7 z1+%Cp-NJ5IY)~v+%&I?GXuf)ZMLzvPAovX$p`=&+qqUq5$~b0$(CHgFZ-5Rs`P{Ba zN}S=v>ED8{r~*B4CmAM9Nashi6K}@1R67x$Mc+kon|eV?CJ47F|4GKaqC+F>QKzIj zq2b8=k@$fprANf;^?(h+Wlo{k0khWA`&!ooM=X)>ra;fWYLFjzG7@hiZmAsp1j1LZUd9P^bj>)PQ&r40D)ET;DunQT zI#;?wr44DGnZI5FUKliSdbi}4%$l0TrZtXoR!$dfdtuC8_=SJAg=d{(^(wrdDhjrG zAznuO#Y-1(PQM^G2K!!P@)82D|Tr@3Xxd zH?tryhA0NaF&sGsA`nU%RJ%Q?i3MR10ETX>vzG6Tx_SA?X!egRy6Rsv@b=;E~?1 zJR}?oNH*o_&&Vg_OneF@@Rd?W!1J6&jtD@3H1}&znN@s(gD5XK@ktj{=cH5T&1UON2{Ves8sU;^A7NNqXr)t-YpG{a|LZm&-GRZ5cNLzDri0Ha+oFWv^sm0 z8Xl9j#Wk(?lw>jaNvrF4KpaM6!0QI4mKFvY@h+dGS;Wf@2y93L2hF_&^A10gW(iH6Iz$0AJyTlg z7t|u;XQ+3m4Fv$lT`#Y4RSrs{_79LEt^l6D*|k|*N@jV9Ri~WBFe3_xpH&~?cgZx- zRG>(M!W@@ASfBz&Q2#7HceO1$?IPkxf*u?MU8Fq<+I(u63|+fJJFHPxg}xqJ*SGHA zM9EdLXb%^AS(O`pNcTh_l+fh}kI!)+6r_NJt616XnYsldO8`j_>z@2_@(9Z+Do)+g zLU{rgVtUCmIX_Azo^QQTuzY6UTbHlJJE$kb{gRoG%6!)o_A=u`KCH7 z?X0YhN1cV@5#I$M`364*pbxFDAmJ|c5NYJj5vFEKu#txvk~%U#kZjZ~Iyw0w_$Z2Z zxzKHkOo>Z1WPz$Y@0GJNQAj6XC#@FFiJo3&6g5!MiU^{QpCNkHG4MV5W@!ZUP(ngq zt5swj3L+WQSt+@;w$O>_r_NBLbA*V6Shyu`0z=DoXQ&zQ1whL&lF?2dk zf0=GH>ZC%b18MHux!pBMz#ZyTKv$g6f{%RXaJX53fZ8Q3V1zayfGrRpknWwhzz+55 zCSCGyZIsl9%7cGFbIRtLuHm7>=U)ioCbT*5zxdrX8cN~mcq9!62eFAvwgSy6hwn{A z8%xtDWU|tC(shtdJOm8{GU#E_jiyg1kj4b`0nY+L$fM440Xk_iHN!~dW~{9%-WEWk z1_J_?p#<{D(f9D5wx?B%rNwE<+~>9+;dmSJO zT=M-6-~dO`E$d@NcTPM{cMcal&@|{PeUL&NpNYfw`g46R_f&Nm-Y5B>0;mkCPk|sw zqBP&CFN|U46i^Lx28Tt|tp=gks*rQYZ?5~Q!&WGZdufgI396eMv)&ATRTf!HrLwPy zhjZ>uK_4OJq^6i-L&X7=v|>F23ez5HSa%)z{Q_D5?Laaz-=nr7VyMgfP0 z%xBhzKodZ!q7ogpvUXmE*(DUE7MHL~ag-CWz(G3A2A%0%1RGOI*+4MO-aC1KjmDH! z32A^&OYso2S>m*sjN;|HkVPe`M#URxVxjY)101bLz~`+;YF5tbbRcQY)dOgZst=XW z%&8M(2ljLo@RcWh9;ZG9vXe+ojqSw;mBz~VlR0Vl2DM9QGzRIiG*s^>0)U-?LA z$$X8Z2P>jfm{p;@c#ClQ=J)p5H_P^q9w6w*%r8UKMt8r_zu0dUmm z3J^fpY=IeB@Ii2J51G6937)Kv1#KS*hyf31drX;N#B=J{vwiM|(9CS7t_3dOpcH(k z&Ysu;_tN?`YM9{QFV$zOA%LQe8|J`=q1wa@mPgZ(>jT$NF7|~|TXVodDO)&8`&K8+ zy7AGpgBv;&zF`!;$`k=1?BS-&(~3(c-)b^FyFSFbX`|xtI=qF+AYA~Mp@D1yDjd4- z9tc38Mu-KNgEy_!Lpu1lz8l{n0T~KS&(rM2S4lHGYs}%Ht!q$`O7$@~VGp_NK5JC= zxz^PO1!$>E9T_xpe;vx!%FMy3wdCNkR!55@(1FGYGV(3V&Pxx1O>=aB3utpYHKt;J zMd;7H6yM%t=k!{yz#PpHfTUS_bMuo}G#mappu$H= zgDJIrmvNF6oO8hoxA8IT)X+he`8Bu zGiWb(?W?Hcif#Gq|FL`S__h_ga=`A4b=RaBR2^%kuzW97XPOO6F9F~Y9}HI+C|t6} zUh&4az>6i@al;qw?(6@rm3K1htjI(I`imH5Mu7-~)T0x`bb>uDeYmHMHwCy;fEa6`SP$ySEH>IPgu6zHK0>uYSUhVBF%O+KPfpN? ze1u{a@FVAD5eY}0_v_*4l8#}3Q8Du2yYhGxyi$F&B$_$s&2$hC9iaor} z9y48ZcwM9WtW+7X3l?_U!al%bcgFVMY`Sr%W{>X}#F3niCs(pE5+m&$3F6xGboW-O zLF22)o>bS2g19*&8d4W6K*&h7&mMb{&XRhPP%TJO!*?|t+Ddbaw!BxIxCLQ4Y&j%& z7XO5XG%V@;)NRW4?q6hEcJ!;4RimJ#2wc-~!vo@!jP18Ve#jOr%rj^WCNY_)n$i?f zlTCn1CO^jpN4jnMX80;!wiQb;@gn#^Oz@&c#AsC6Jv;|rSOw4mXs)m`dA)$@zj%gi z+EKMVy8$9KI0K-UrNbbJow6!teO;pf6aW!v8m)!4nRo2lkEs?jbqWB{puN>(nx%mh z07MSpSTZ1O!*=@0ZUzesUf}k@YOme*M9KzwMs3X!XsERCH0D>q#t((qIAZDKJ-#=j6wrscFZZ;EL3Y}?>5P)|=56p$5+2yu%cgu!%HSEmA zIh)r*+pc3q*U|*kO)EW*Z#CODC_so05NWHlN68KWANddEn0%lm8q%2|8bC+$!z}Zg@3hwIH7I3>y5$Lb^i%(4bJs4X?Wpf+7le2*92o_k<2{WSN524q zBre3*3K<#Qwzr@%{!&fuwP-adWP-L`G-ep^64@Y-uGumK4% z1h>pfDFBg%e9a8H7L8hIJ%xP69@tg2Kl%JUw!E9B!e}xlEzRhVUAVZ%u6^l6RxK3l z)8Bf?ZreC)`EGy;O-v>YRlKYsI*tqt*|jfNV^^Mky4`sH9{cpI8?2{`PKo@M%q!W? z{KPr-Fdfssee(g^yKldh&}`+iSvo0!Av!vab%eB=4K;c$@3UpyP5Y^t2A6u4rZzKt!5Rz;+$5ZGioUA8px{KlLXr*uQtff3XYC>$3{e ze{;D4+8lgj(B{+{_?2mQaysdB{uCP=EZJ9Yd(3Y5`g;4^^fWH&bd=$Eah2Vjw(XAf^E+m)~Wi2c?too0XbKdzvy zpjFM~ZQstiz5ACxZr^|MNxT0$@3b{5aQZF-etcx1flrx^kBdydUH`?0?APA+FZQ8# z&$r+H_16dn`rt^dt(I-r&f$Lh&|iJS{`G%<)&BO6F0)^F^92B!VVXDj!1F2SeZyDo zvfui{FHa~g&e%R@=-}I5`_$F;@+(ipPo!lJKQ?ApT>Uo(N0{X5hhMtJE;x6Y)o6p# zu*GoX6i{CwQ>r_%a}mt48X!o9X|MnoqQ9s!kanG64~-EyDd>~K#N~ST3)k9^4{TX~ zhe696;83w#w~<`Yh5+mggRwv`xTKD958Y>_5?V=bJq$w8tTS9-umayOxQ=1w6p)yF zPKV%|0tsNWpym(c5Hm|CG5ll%HfBp<;uhMF4co@TB7*3p7v@v8q_@jf&+D=0t)6FJ zzUyK8%DtN`QL(m z&HF}eP-{leoO0!|oj$*0b4y+J$o{(R8XRGi0RTb6vtt+yRE|vuX>ch33D!ERpp`m* z&01ST*?6U0aOP6Gd(*w%scBlRjDRu-YBZ=di!y+kKE7puw0&K{4=PRG^*W82yq0w5 zY!5}1b}UCnC7*<5U87Ufx6%-`*kF{-t_Z;z<^8s%t7<>@$}4Q~+1rZ zEnAcwv6V{;R_y7sVhOY1&@M~}lmnHpAYl+85-yCK{SG%{m=Ogu>qL7vRnYLjENDYC zt~5Jit=TJIdYKIrsAuYbH~jRspS;;VrH25f&;H#{*&ALm01xh_Q^&sr&5Im{>s5(z zv-8ic+ciINC0PP|(Qt@^U5PJYog1|tnWZqv7N|qm*ag4u7X^49DHrWC*MDEx_~`e? z_wToJ&%sQV#bk_@Cxb?#g()kQuP_qcM%vZ()TUnhi;sTS{^4`~;pyJ-UoJp{(@&eK z+kO_8+ci|Rzxb$)hb|tsp`%KbN+F{)G3`=%5A`57-sgoMqqtyC?0N zH*c`hf9^cK8!Z>#D}7Lt#+}Oa*zUo!eg3BVJ&&udz0R^|sOqdXo{@*noM`_!kuZ7Wa7 z*mbYC2rUw3^r{A0qc*>vx~a-E*n?I~v+}y_oaJM7^))X*Q-lnnGp*8&Gw?tbb7qRQ zX9l{dSE-LxficXG0%5QqlbHTVb1El(4sNz|KTFPssUB%_mQoL4#-q00kz>5sjx8JP zMSuS}JL~FethxC~`@tXmzCHY@f4BOzueUe+$)DMRH4Fr9{ic2OSKn+H9;{0q)zl~q z><7Ug`3eaT#V~UUJm-N>LOL-qBAiS85J;$_Q!sT7z>~+OtCcbtY}x<(+I_ZvWY{Wz z51E+Gz@%{9Im_&_bt~;P7q3G&b=eIMY_wGO96AvihD;CwS>(ELZ^J%%{kLsDLa_z* zcb^C~j`TjFl&lMlO&+0KuaxcM|M?>~tTi$ES2nM=kG}QgHfPmx``*J_?N4ud%+5ny z)S#2A}xGoyHhke0r?N*p+wvv*>^<+e+)f2pTWybx0#<(cZR_l&TQ}S9{N7jXjc@-~ zyXAks$u7Neq3s7y4BYVI|UX zu9tSU!v6NtUk3!;z?)0<#ZO*lFTCV5>+Kq#d5*w8m}AFk_Kw%CurGb(8??8b0I+4G z-)q-gF~_dH@})o(h9mhi?Y;+^4umedWTn0LH!im<=4YAqv?6c4xf?C-UfRZd_*g&! zwv-5vAC&VVZL~OOFMI77_UC_RcH=kJ+nZk#G{m)*Hq%uC+HUSlyZg>f_Ra78*xvLe zvn8w02teNqQ~PB;)DjfcYSF%P%WX7Zf`H?~Hc#q287>HHzE;j)& zLk)1OfvJ4sa>)Mz3&UYlW{DKt!<1sdtH4EU6*8v>;7vs$$LHhU^?>frsay9# zOw?Vt70}1bY3;`N%$SBji3YJ6O0@7Fa@Y%#!LBhJ1qFh1JBkcW?4;_-rB*}?tJ6R; zAx`#%$mjr?bn;q^%{4a&6Lt1oXfx)NdTk-vmhMu?HdZqBm*0NSZoXrK!LRnR3s%@1 z{E5c!3&=8RmZ?g!QIv0$yh{CxthaB#=JgecSG1n~KI`pWV148(4U2$N4M(_qX^!>x z_A~P1UHyz|0WAtGv^T2;`mCp~-+JaQvF_gB*s56uO&m1qbV%ndN?U(1ZQr{43A^{v zE%+#zoqOi#R%SHOP4km)P*^Mx@r)lqjnS;ejV>%*laQyGK^e>=z#lp&%K1l2oK2$wDbb1xUJAPII zJz7gi)2nl&71;D|q)sHvW0*MwT+<0p2(Sv7G^(2VJ!%E|!qg}twX%oKem5QAE?awQ zm;KV4F0_C6=+F8K-}~X4ZQG7fD^h19rE>->U?Nt?YnpC-7y0e5R(S`&f15QcTfnos zFcaga13xqo^x}_Z1-_Dohjgvdq zVXIG_XEg>988oa_KwOIKirJju0#jK_oDU5;Zrp@)@`@lM}CCYUHf8V zR|HbxXN6`JA;V{NVfya34}SOt`^lHi2TWb!aj*ZvcPR_)fW`CZJKYrCs*GB7bQ{2O zE41E)@6@Qr1zJL<-DqB+dt=B(@x@EgZsZRpUnUK5WP(#OEtemm@Z>SJlfe}Z+I1#9 zP*)Y|OtaC#z>gQkFe3`6_n@qDeH@Uiq~N*Njvon zHDtbIuTXQ7L8!~&I)hrwU8)_mK?ziy!)?4#?<7Y}7SMC*K8B;Cz;hl5X*FGS^uQfD zbw;xS2{4uvIpR0q48R22Jd_ecWA1g8at^_oN8Oyw_F8e?68p-1kJ@9~cH*m(v5VF& zwY@b2HUOxFIZ47xY%hLADPkD`56ucgxHg+w(HBuGZHw3%#8GBcT4Us(R+2@C3Sg+B z^iw%oIFzQ))YLT1Rw`DUvE`IqX60PX%DUwA1wMMX>#5!Lu25t3EkPt$x$nLX8r@Sq3EdWcA1Y6SQHrK^=3Nk% zZQIaJ_heYHY=Ny?)MtCPKLtR-xs;i1T6#db34tuFph|bcOA+5bqT&JIDoo{e(ZG!u zW7cR%WJ{_=lbWiP&Lsf~=4 z8BEBOt9)paEnH2Rv8nQR6)??d>LNLar<;ItmMMjo=8cS_%v-St+k4n!RAO$Nn$u+3P>vZY&=qi{@Ef;L{e@U}LN6=+I>WWy@u3i>U@@qFQh7>-Wy z9w%&S37872mT6_@nnrBSPhvm`7HLFaP$2_FL}X@}y_HMtM(v59PNSNpL&yMBw0`fl zA!cms*yjv=!CZur=8WSUs+E0(+$D0m07t!y&iWXQ_BWVmHny9YRcx-vC{(jfwE8cr z5W(oE+kM6kBXJr>SbIeRGBm6LLarNumtji28V$XaPp26M(P>?_lU6DJku2XUlSiS+Ca!=KX~ZZg-z~d0U`r+g8kqLAQA1@W zHZ($e#OPfc3AzajA*;2OTnM1nS0iuXWAURWw%en7&;)g*>{qY8*xq&7DqEZ%#EE;D zSuJTB!z4B){}VKDS*G}wb0apwejybEMNS<7@74^Q7-miZ3FHQ-U5=F6gj5SzQoF8j zX{ATuF+osiY~XD8r((=L!pZsCtIqS6?uU0YAOJaY4QFVyKp4u*Bknr56(`T^D%;mu zYoo1|t^pGC$T6ywakGxEONH5EV_60QUCb8TveiESAOB&0{97-zQ&tSv0!+KFy82xE z_$N2pqmQAnVKJ29>=3iq_E@UWvhBO}+Lv$qj=%HF74#OEP#d`lyrP*jn!N^aC+`se zO$CR0nZO$Gt-d4!@E3qjs{`S_?@XQz8Z94EFv!pr7QSyF{O)EwZ|53e2a)K59`4C( z>|2r4Y17Dw)o1kC`R6XTKm5qo?U9XpaAIZl8nf*7Vx+j|!A)M?*S_RTTeEVx)lkAY z7{gpu1%wQZb=e)a25@)LSv@v)!0gfsPxUn4y^mFyv^9L}NX88iwC__&L zFCCyq07eU)rX?#>m-=4hLa3!N21yI><$fMMVlS|<#sxOkJd-+G$~!QHxdS`(3s7^> z<~hed$BF`KI;xkdc(A=rkTjqI;ourV8+^ChSh#}GHNezU2FEo`9zfXF;fXLB2Lj3J zz;j9H7>3)C< zAj@}7rDaGEg7^hM=!$%VA;6<^-Ko>DF)6d%P7u~E&?xK3Q+DY~E~ShqTfcdi?HH-s zf_#tN@z54~{o)07$;v+a%HxAJm(EctSnsj~bjVMOu_=E6qJq{o;=HD{iYUK=+Nd-& z`WB7cGjcYigk=)>$eIZBLp}>^2dgrE@|%y@&%NMGJ9}x#uDbLrJOBLEcK@Th?AG;9 z*}Z!i(X-q@T4pgcX3AAd0#GdEgw}Y`+x5~2h5{ju{IAsW!Y~c|7P1gl>zPPos{Xt( z#ozitV>pKqCm@FD^u1j!nQbSazJdlO4^L|C8*K=w@PoUavNyitAK(uyz6ngg=cGQm z*FN!QtL@B{EAV-MtEfMjc-%a|)Zu;mi}tl|-r?zAbnzHv*kf~g8up8CKHt8G580hR zc-Ssndp>3@cv3)$^|TrQi+k7avTI-1YfI$k!Z;xhc-9O<`C@q9bSh;rra%l+;kDg{ zG*eo-!VM4ZcnqIXPT%>O63CpJq63j19A8gbc+GiObOE%rdCrXv${N1R$!VIlJjS49 z&FKs6HP@`OyYGFnL-o%AkmRQ)+8f7O&_z&F;H* z3vq6+KYsTLJ00g}8{KW^tzBX-yW$-CgO7gEe)^@qh|@G0I%cA(*{ROzZieRj(YPuI z+=Y5{DdloWGE1GQba7$D>t1H(ZMC=m`e&JCgeC|-Ex8eX zXqn`sZ4H+3c6YQNK~Pv<<+09^Oo$Is0YoWq)V)}vw`4Fg4< zy7fRjE(xq;34B*3G0cPls-Nd<5X))NKM4=-I1nW+RNys<76oZL^wYBGGVIjwO3+AJ z^SQJhko<}y@Z@9c{-~tUH1QhoGnmHe%<2GR@FvAc+x8tJwpqX3tlGlwsU3`*5wa4> z5^bswEg0>ZDBVL)`+h^Z&rc&i`5ILiWx7KiAgGJZhy_M%-9W)kTRz8j-~oHb{hMqq zi_Mh~f_FUdgpCf5*;y+W+M2mJ8$mPU@(&?hN6^>N^k9(kGKv;*Ue@$a|90+bmY7D! zp^2))p!3u3;tLPk|99g?W{vG-l%KVioweBh>vb2~ zHEa7RFLXf#m#P(TMn|}_4pL1%Qe>=eJOGCH<`|Bg0#uo6MFd#F`b^4$4)s8b7gOp& z^acdgWkv!_U@lWA(R0d2NQ=K!)JB-jtI)+Z6N`Huv=#FnvZZr3*g)64bn1_?lmi{L zhOE3pyzb^s_yRXi+q!4K{_JBn+G}31#4ft%d_Yy7Ucy;kqQl4iUkl~eEB*qGWOS>xCOr;XjdrN z{SWT9@87o3UVAz1aP@pZh5#K&5ezB(`$nrJ`{CVtl(k)W$>o^S&q8C1J) z(D)~DlS%DIDDHy~Sw{zc)aBmpZD`mo zyQJS1b@kX?+xOe^ddoOdv*I;&1P8W=}?q5f)m zy_*Aw;f|nOD^_T5sQ4NEYSnB??PeAF8;T}hC1%%AuDqtwv)q8z&&c){?WRpz?91D- zcFN*{{p{L>_WV;8+0VRit?e3ph&5S;@argHT4*t{moF9uLVkI^OCU?{jA3RJkd{tn zRc$z$Leo>{CmsSf1AOT!`Dr3R*l1MsnPNJ6pKaYMjf2_1T&;4>UHK|>NmCP?b)SFM zeEZl3e%`vWICJL0#;DYsl~~DHzGAg(nI9mRbNRD0vUBZ*TQ_>1i$L zCbiDW&cE<;=h!Fy=56FFOg_RtYM3;yMcWjpKqZu|OeqxR&kj4fZzVu%$1cm^bx z+^X1myRFIZQjjYuzGdp`{x7@y_<>Iyn2wR0xkT#BR#D+eZZu zhLKFmJ1VsX2n0>EPg$Ks5VbI#wyc2rZQU8m?a~*ovRl6MnBDczCcEPDi|zLB-tXV| z_FsC9WlCslB~-v9loAqqm)4)GjIQR{jGqc z*V&w6oxu_94(SX=r6i$!>IK@2RzDyqWmHF~OlXAAMW0y1T&SVg@+D^Pf6tq3)nfd> za4c`2*~?JzU1+Wwny7#_O^aB{Y#+n1rGO;2WLa4=`tXYk9ZryLsPuAXv30|F9U2jsnkV3X0`|fD8;MZGXn_M7I6JhBUuSOLEU9#xnrB2ALSl|WWa zX#qiD?1_M;<8J|E8Z6qT^>gadlBltecO4e zij-A@XgR*BWoi^&q?|={6qK14Lm%>|<4X$^%5*@)G#UjN^#la#OwaA_)vUC-ZDk#o z|Mk=z)_v_|c0Ri;pR>HzzVrAFfDfZ}@{_quboM?89~O;x)Q!Y2GYSaMY7E(+R@8w9 zSc%}2Y}K@Icqh%&Z}}IfLv5B8+SctA`@)xQ^B49M0NOZo%G@MPLjz%~z?N}VoP%#! zaSU}m3?NXBK(3&%Xp&!sxM2@Hu}Qz}9m?Cy-@41w{{1JuYx+$VzIgK;_{*%dz5?x~ zF>DK275%4w@|E_-cYogQ-7snwpRaXrXd4v?e>MPS_E=Nx20)_~mt~EXZMGo*q4p*X z3cZY+`5o*hodxlv>7?X5=NadM8Ywy>aiL6E{>beW7{Jx`pr3C%3(vQhY%r%dZ14WL zOYH{$q3_*YxBkT``_w0YXv;}>%4yJnjWFvYtR4?vOYbzAn`1w^{}G-J+MRcsz2zMr z^>7YrY_p_7YNcy*&0Nt|NMRdFrh5r43=7KK|_!OA)W1SqeC(d0o{3>S~wT=T0se3VDRH ze9SyBI?-*_t2W{ma8-~mo96HOUV7qO2}%99>r#@oEInWhGp9i8X(T3LD(!jYz7o#2 zbRilsqA76&BptMvQRg^QAVd&TbnZxO{By=^4%3ide#P@_F^jj|%@z{(KeFBWF;}^O zLaW1&%x6kzR#l!6Xc@;(ZDG;GBqdo?K>c6k8Tuo9YNi$$Hvad0H<+M3$k+EXFJpzWfWBn#Z%Lq{7HRRvG_sO<=?wTdGVore>EsO03 zkM3q$kWl^VI@GAV*-@Sboq(LCl|K^J2QZ46$Db!(1^BSWO9P-HaHN@Fb^OADr{*76(jMaRU` z8ui35Lka{K6u>;fS3^&rFl+}9K$}3FXqEFOPQxusRokoc>_5Nx1N+*yzi&VLQ_Jka z3zu;pr+G9LK5;-A4uTdxYyjkIXkF5-u>?fP`4$e(riSUS0V`!`4T06gW%k3{AGe!s z_?G?3Pp`38{=^!#%V6+8hYVXF%ZqFQQ?U2_$!F|i|8%##>#eJ-w4@JwGRoRmy>{7o zi~OA*eBbBo?6co$7oWX^$qK-E%&#p?Z`WW$>)_x3JT$V0cC(wMD5TpG$YYc(le4t4 za$ZwABmk9Y4}b^mX~lNUic32k=z(aAb-r1_wL~0!;sE(+cB#zO3_CC{4cg^rFYtJG z-ZzFO?IGJf^rZd2zq^*j9`o$+r@i*nqS%gyymzzh#pl0zqsRaFU%tT>&d0Bc_Nf)# z)uu8ypx?oY?(hGLFWXIDf50wUb0r0p21+#!R3E`XUr1aaR@_10Qeeh| zs+5ST-3+o+E)fdaQ!j_vI1T6xYZa-^sCOSAi&rJTV>lWLJg0jav6E&-)g%ZxYL=M# z3*rxSn3Qg74(wNrk#82y``dEy>78x zbSl~y7IB+{!?HGFB|F})otC7aXLV|XbO~Tmt7(=TLRC=!M8PKtGmFrd)cG{fH1@#) z!WH!o9U+}ch1G%=^)scpVjBi`+cxs8;qS1FnQ<5N7VY#!b6qpFi_T)_SjLvlkrs?K zP8jK`k!vqCl}GiV?~P$*6p$%LK)hK2;KOe@_c38rbo%*yWAM&!mko~U{yf{YGi(3M zS~j2f$LsxN@BOv&Z0o(4}8hK{jD)O z^DPVD{ms@I-f1tnXa(C`Tw}lcr(dyO{>^XLAN-Fi?fDliWCd%M+|16ip&`t9^|`if zW8MDzgI~7y{I_%M6)&61+B(d{1W;>n#uiIUXcnS2k5$mZkiI?;yq$rE({%T?xomKkof?Y4aWYWu+N|BSu=L;q%{!qW=Rzi1gCiFU&n zL<>Q;jYA1I+2(}Ia+bFIeuNh3_&7%CR5 zj25j<$68>pk`~wlAeQiigHOo8V#5E9iiH8EjS;dE(e zr1{ZChuWe*Bf2uHeU_O8wgNwh_g;Cno4mRaNI5NYk4zHd{%B9dzH{GZyK~2|%_{|! zwze?P^5-(8Db})iMf>IJE^#52!NF77ny@EL-5zbsv(J5h1N#tRu0WW|WRccFY>dFi z@Ntk|jz$nI^3oLZ45MZ(W~f;@^SVoR#+fVZDW2cIV~;IEW@cD~u7|Zk3}BJRY4mJH z+CRSU5qsI{Id+cwzXaK(!FalGcTi)jTvCbV`fS1ZjiM z^<3Zn$R4(1z#NFMPit!c*I4KaY2$RH0$-Z#6T{3X5V|=4GpjE* zw_A5#!5-cGgxz)LlLub#ZdPc1*V`_(b&FXVVwhF{+g5=0+2TqYQ723I>`j|&B>gqo zh|H=C45%yIg%Rvk78%`OAAaA@v)L${2X}SbV-Jtn|MTHbqsbYt^Uhv~30d1mXt!hfOZI=ixXoVolS3>bO5Hd55b!(f7k_>oOI3{6AARUM_U3o|ixPk;Wf_jLG1Z5O9+c$PIRc%OjSDzrtx_o>QOFKIxX+Bl61 z9wWX~FIuZhw}cc4HTHXwFc9XKu2^70oT@>HBt`+>s|(IX+d_DJJ1begd@*}>onrOj zGFx_FPL#$tTLKiZ&)c0Fh&5<$e#6x)q>5Q&OjF(gi?kiKz2#$f+L9Hg+wcD78|}|N z@>% zdmp-;6^py+cZ+Dw0FMG@>`-3JjoE+y{mX3asy=ItN}J2~pCmz5INO4#tJXJKfG5!6 z$VpEcOIV7&0XAc68fkbCp7;UDg`cYoes+2JzQG>&;?=OBfraR=xZ(BH(Qieqp3~`Q z{-}q3P6s&(I}u=}EGS(gD|aG9$Y_72QKpOR15|85!_kLYKQpi2x)G3I5PJ$U*w*dr zroMfb-SPMy+cQ$Ok~Y=@wA9K79Y&$j-0Zhw~3dDlj^F{nX@{J=c4MpD*?PE{jh`B3zt*+~^kR@ujzM9}I7 z8@912)lyr)hN}Z9X3&tY3j#X7J2zMCrXN1eY&q7g>0x#dps3zrH*ZEYS{KDlDq8D= zs~BcZ0be;BAm3u9m7JM-yN1|%s>^yY!!#>DW}mmRtzNLyUh>w}fQp*E;G%VQ@p;Rw zrx*TXZ#&I;lon9%p^3(B9zyyxFI{RqrL>KXJdSAxU?7tXPW#e6wE(j_Sv0YU8QA^k zm=(D5iM#CVd1h~Y-D$RPCF>92v@6puIz{gYvUKnb9O+J9IA$OEor~<>{{2U`;gKbF z#q(EMMcODj?Y`Vz`|V%2%$|SNQv1qR@34Cw*kyn7cQ-j<&h2G$;+L+l=bhJMZ+QI$ zzK>mb6lZ+~60}g1l(ZE_Drtt&x#BKQvtlV47C=Fo*`FFuYsYpuOy_7H8l222gwAI< z&i&H5)Bs6cGWXGz>hQW8Q(J)cMtZ+J|I&H(o_Aencighx-u5%6vLGU|1Ltk^X_6}1 z0%Y^{N9>_{?yxsqRbbjW`+Ui_km0*e#6S~}$7H9`e^*z{e&W)ied7$X2On9_0+Q%| zN-Q)fwE+O8yJweOb+y@P0}IeLp$A}woJ=M(aP^e@1lG!Ec?azcSF;5P3%zRf@Cs{| zNd+h0qB=fZ=}fN;?%d4o$LC;*?t=m+S4(rLF{{wfcww6OX~AU3c4RB{E?l&NTm1m( z>b}jE*}2QQ=tI;Woi@lO*;`lzyx4E4J$slC!;Q$N~$cZ zJjmvOYfrH=o_8UFnEX8NV_mQEgOSfbu>ZSH44Da$v@ZR`mE&`h*((i3$y)g}-5R$2nYqX+#*zrx8bfSt;wa%IpCqN1 z^R(uoEN0j276N>%*oVU>00X}vEeuz~Pe|sfJc}o4;ln*8tyqhX5$3Dmu0BS$W7b37 z0%qD?BMk`CKg|+qqV{J~5G+{ijLo~XiDX5-0pu^i?|~UQDHfzFBjD9B6d3sn?4%ib zi~(vgIEQxO^t?-E1o>HD=8}W91ijX}=)&CB!pA3zw`x`$FP+2)jaF;S^l^Wn)NKU> z`d;QkYu~d9Ya4Y#yIvMil;Xcm$53lQBg_&hIfbIVY5>YK0@t+fV->`6GQUX?<&MMf zK^G&f2ky8XaJ$1wU5vuLf`e14_}lkq>nMUK}_q5V5N_R9U z00ONSM0_bB8+88iJHSi9w?2_yjjt?CI}uoD!BgU8spp#+W@`~wrlSmN-S~cV)W4od z>(NAO$eci5IwGfOQgqg3RQd&0lg?MrCZX$30aTjsowj??GSI30fJZs>@kgrX=~8v5X@}Ox;?s8prD98-jkbd6 zp`B&fW@9Y9h_VCV7Mwy1LUZ~3YrytI}A!2V5SvnA(?Hp@M=z*knyYnuh5L7 z3!^0j{a6lvA3c}vlV$?d@Mo&C;9)K`kMEE+4F0dNbb!bJfNU|*AXAa{3au zD@S{$O=VMjOG+kr$}!x{mKzL8a`^X@q`i`(I-x<^_StUKV~g}|`a%XsuTY|{8qy|f z(Mf1rpu^NG(iG_-7iFaVg={>pXaA4*pFSmfnynu`%YN$p-?h2@DVGIQ z0b0-?rG@ks2M>F@<*0A%l}Uc*eRjdN`)$b>lQ59mR2Omdo%}gYL2u5n^u(6+8*SOg zK4h}ke1c)!(o;=)S&)mtiQI~_WbxpTsPG3XqXKTASbe9ES{is_`So- z+M@}4&e{+@USj811qm~?GCBc-0y0>qUP0=zQUV;@mnL#FHNYAwn3?D;G^*3|8I?k$mO{GAcSpdn z!6vT_fJp)1fs99pvWq(#T&kRP)aPXH<)JWiIw~8ZPjwFDtts~!rMCc2-F&Y)_$ETq z^Fe5)=(yOwo*!|%KpJ)Mi7alYk_xQ!ldtw)%BV9V<1o#bx68Skmp6H56Obf8)T2Cj zr@-Rgy=ZyRL`jQ9H)$ono}B#3ILT_Mc%@4--B)Gdqi9KV+?-1BAH&QkAV86Ys4aj; zlODl2f=zf;3(dB$(8}I$9xOvV_3s4LgTPGI>szkD1bD>xg8C29=zPU++)S}{koL$E z!>CKrbIl@DS1W6roavP|Cw>Mb2sWrgmfLZiY46T%LZj5Z+L`aw#8aG%ygk-vKQJ$O z0N5$qf`Kkuw4g^Z$RCZ3+5_)y0D_d6K$)CUW$ppe;Mgzl-eT4yU!wBEZ!%e>WtJmd zlbzxHI|S}ELyO0nmLCd+wL%0UC;9Vf0)fvsqa5T4za!N37#SgO>rU5zjwWSNn-)bF z_Y)D575|i~00`9kn48+HTh3GjiUTLp_NeT4lPxX05ng@vSN+S*kR@D$wcI(q=K+8_?S!A!pJS<6>JEh+KLzpG-u6+t%Iwe}{J>z5e_H)b z?X!YblhaulR0XPwq&>~bLQ<$%4TPQ@qKz}EDlL%?S~E+^qh>8i^t#);)eT4&Y|&3 zAhr_|U+EP*pZ5Lstpm^eor=>ghoXi2dE%X3lAb3WdHX4Ul(*jEd!~8j61Kb>U<6hQ zfp`aKMV?9<%I3M~%73A>AxZo@a|#GREBIf|fh_IJ0v9Dbki=_0q~3`~Z|gOxBxK+z z$Nz9s-Hz^aGpRnmqom=6@^`ISNPQrF!ejK@?I%P$P?&Zm96XoyeSbA~8VpW?_*Xn~ z3NO)_7gFC6?)hVHvr6k)e&r7Y_-$*3&SSmNIi)Y?OlDDzT;opbX>1p(r4dYcL>?Gy3Ev2SoA%z2Lf6+eQ4OaMX}O z&!-A{o(xJoKAL?-l(uUZGZ>YK{Iqy)CzziquXulQ3MBNM{As)!DG(_TDG(_TDG(_z zLkchu#ATp+&2roM$xqnkTfS*UR%uUTrd5z8!a>j^qs4Gb+9bgr#n;TfU6RI?OcFT>KbjOo0f5W=y)6Fj62=AW|Sw;F+PoNv_jCD^$R7zo%!Z-TLeA zXOozq4U)&0<}J!JqjOO~&eGBW3EIemNYCUH9Ts*78l=8c=UINqViqXH=^vk=7>g*kAkz3jAfG(bpev}vZFwqX$<^5`73CWRKE2znx5k(OZ)dW<;e zs5s*|0-?!3Ppr+Os?C@i<^RI9Q;W8 z;|r}SKL506r`C)TFw%y`TG&&IZYDFyyvKBH&}99ozasuQ3&BY%r3jM0pD+cF^A#mlTi*war; zf{vHmr@*mzn8@u~85l;uXUZ&Wj%O9Af{uCsDA2d+9);w$Ay0Kbi7#QTlC89G+k&O- zt3N0(4CEhAXg3~68&baqU=jePn+8f_0+n(u*D|^C~SJ0r<1BYVH ze|#q93qHsn>7^cFwDe&cg^$5lGm#Uu-J6bjT9rkqLS zKkLPuP>?@O1IMn#tVrKq5*4LC%XQj7HmEX`7fidZP<6w_zXkpt8osQ0>uD@_iF3_q zrM4DLuH1YCW-oC(iz;_wJo&NrRKy?gD_#ege341V#rH3;ua}9yF-0Rzm+qQz(WU~4lJpq#^OWzvA7nqeSK^b{6$hrwvsn=U6-&k ztBpQCM0~M~a%tmP2ebdYO?XAT3BQ+8-@@x?gPCyY45HM-J#q{UIewFB*$mI`7o%2T zvv-lPQKCA?G!|fZ8&-1*w`{q-$Lk^9>scJBs2*Z^Sp;?xFh^+dCTw!d^?f6wI~xA& z+AMMzCUV1Xy%XAWf%5n4F!X$)nrQ0$ZrBD6lIt>Z3uX0c+ZNE8z7QfxHOq%ciDS*r z9SJ&q45XjQXwx3C-`CDp{}%W&0Z7(LL)OaSP&bwJJn1ZKm3Z~(0ddY0q+xnNM`hkj zQI{KFvBuDE#L@AIk#0Z1o@svbS!|G{lapJ$L<6cQuzHolOR4C3hnDiryRM$qyaQN1 zJOKN%#|h!>r(u^s`70=XmZ3{G`DT>f^3z8?=3^G_rWkW8cAgaFmuv8(EiJ^2#e%*; znSh+e0u$I)VtJ#{@8i2HLlLVKomsJkFCX?n_Vr(;jm|54yHD)4XhpYO_ENpqeX7TY ziPsH~vKy9uqVjT?Ag=FPbannU>Sdimy8Afy==BMtK^sq0NLXBYuWU^0(Dw-%hNC8> z&n~^~--Z&+T9+xQSGD@o*&6Ek?>Es=YlfT^h*wAg$%w1m9_UbF5oWn=)@>T?Y+)Sv zF(Pgr-}Cs(il-MsxqqWbNP%peyfG_4PLU*7Z_)qTJ>^O=6@_TZJlx{8!-?%( znItMz2&q+XMdgEd?~LzMml(D-q@fqA#$+ZEgk58=JX%yMgIK#6EHuMwiw`d~>6^=M zK6jEz4_CJx!1!@Uy;cF{orJd3b#U)K?kWBboVYjgbskn;6Bb#gyF%;*cpP&x<)6Bc zT0Vj?78J@-;b3^^Ot0R*Stt*+T9BJ5WE#zERwl05c`Q~ zblZk6hmPfBS5<#ST|bWbPWe;|Vsr39`%}U><#*okyh- zmHWk`se$)Ch|%UlyCm=J+`H%eVaFfjvtDCP&w~1T10zcoTFg?3#FE^`Y;bVs!zWHY9X$((M1$l=v4Fd-b|9(h~ z-`}Sz8Wg(7e}1!OMC}?7GQ21Vm0-Lh^z60yzCbAJl*aX?#o6M5U(Uec^lLKLFGU{m zIRZ-b07D$Y&G~Nmm+u{wZ2Y7q{FDYInR-Y`2d;pBvV(_dk8U8almnXb^H70lSx*P2 zclQ6*>+jVDAJqA8NH|JG6-Ulb7t!25B6KIU}PElzI8kLO1lY zH(&fj<~Z4@g4wJ`?}q3kld+QsLtfHxNu8I1*%xgCzTNw-W7f0?bHNiTGeNv!yuxz} zhg`2MThCBRs*1>BHC=luYG`I8A-|=a);lueQR%x^49*dDk;zO}YUFh+up-A%$plzM zFPUHC!ioKti!Q2)h=a&fN?i{}Z|e9afr}b8`TLs82FZpa@TNf-Lu{8fOGssBMIx7K z!>s-J+^)JB`^CV(6FJYx`Q$+^fJojmdd6jzoYs-00p<4KqU)cPs-AWDs{QR`q}Dauz7&V;O--f`dz)5V>&hoHlwF)-yC4gi@UQC-98|T@5Q}p(SgyNJ@|rkKr3f3T*HR)@4CE9(U{~GS6a+!>}UwW z)jw-+?)@cNY>vMrt(juV7MMD+#>}|klbkDLDIJc;W`&y$J$e)-;Yej1-)ceqaU4wE zx#)Kq>~-8>XWQ)4wq7!mbAG|B*7lR6BvLPHrFPi8w_$J2W%m4__V>YaG0KXL6dL&Ms??*2f?s(291LW4y|K&O7%@aBld)&D(new{qQ~Xl2X@>A(xV z#b=5_-1Vwg89%Ld zFG%xH--2haUDFkQIBzHJUNBZWP2R(Eev``Kj0P|jS=a*g)sA9+y>CyO0F`N-SBDJ- zoiCFm?pQU#r3;$Eu|?q1W8`QkbJ-Ut+ENJiS>88aY6) zhd``uT)dZ($EneLL&UlIm-RSf%gX4(`P1B3X&p*V3Q|VmDGH^4K?C7j$tg{5$(9Kx zw=kx#LIKtoo+h8=%C84^-EX$aE^FVH`cAPSn>{I;K+@*hsMkhESKsr|&0%?H zg~nKLg2xQ1U)0@{gLU*`%b7Gc#cIn(d(-GmnR@is;v&mCt}!x&1H_3tN=xqF!%@>t z<0BxkTQ4f?svgnY^rCsdX#SyLKiqUAvDNb!r$hPn1QGt(zX|k1-S(XMedq~#tO7){ z;YT!LSN&w#vyo+uiDb&Fc!?NKVJ>34Q~bKWH=Y9Dy{C-rn`VSl(T`vf$cT>DrrL=HK2T@0>sdkMP$y=|-Ac1h8-mnyG9zhj{lu@22Ql>jv2A$Lbn#hA)i~lJJ0uSsO3p= zkS+vXAto3NmepyS3DQy*z4XmH$|If3^e;}0e?gTob0VNKaXDMr9B#%c%}GYeSQAK; zej`RZGTEa^xmfDD#74*&Cd?%wF zafp?RwyI_C(FVr)Qu6AEvq2_7(bxcpbM1Xo7LuH36^BEHp^-#=y!3->^&`yJ3UVcP z>-SgkYVDajT2dqeXhUZ050NuxkdMA{ZglCt-<-m+E0CZ=pG6pduTfhq9Mv~@Mf|~; z6f$>gJz#`%5S(Qf|6Cx8&f{P|-!gQQwNW&Qxj}sEBb{r>NG77Az*q6zKj!ilP|Be3 z>zL+p@qtIsCQ8VYjyo%pLVQYA1$^(AmWdq94Sw>wf0Txp68{{ClT6x?pa83d z>NdP`;ZU|2ilx6(7uOLOsl)Z%3Q{-0$_LEpvtD?poin{x8nX(B?LlBSMMzj|8zNB) zoFqXr$)f|br536DA72Z4`9bc8C<`AWc0)jTpcIRwphMLr#XsOJl@EGmhLj2CY!)Z! zMmJ^NJ`Neu&wXjdAJR+|+|X%OZF%(i@qi=0#}hwoms|^xNGv3pU(77&gZCQn#(Fa3 z?bB?)n=;IChN*^XW}PX{>qPZ`{+9QNV)j(L0Mc#Ca) zl_vZvwrE_9iCwu~=JyYEr7Q0M$H#OSb`qLhg!mrk?@lwondnzmnJ93x{E83#Wxh2m9kBF|Khr+aoku815X3RZ+RvDK$0OR>H-kbWy) zA?_QMSC9@NK6@?g8WTq_ZD`nvK_s^deb)Pu*e02@Pm?utTM=eAyOH8mTQJ6wI7(}- zSPwWY+BcB_=%Zz>IUw||pkgKo^7t3Up6f#%R1;^06oAd!(p~kJ4sp>3^W^sA=iF1# zUGmxsbz70r6+mvT@_xtce0Ilt0DQQ|hhAtgm8|vi_n{`&#S7J+Z6!BZv^9E9`PJ0E z`)|NUBQ>g!k!)oGFk5iz!RVr{fK~lXLyDy_P2)0TMV&@Ib6jDcg_?VNoyt$aWHIXu zgZ*jEp;fZjuc~>PWDF8)l-XK0WuJaHeL8BSqpq~|mEoC;mxU7IsyHDFWCRC)M0#+s zJUELxM_j6yP@}hn)kgynR-3hJ3q4NI?6t7wE98%O)nmJJ+7fO=0M>jvhnx2M_J@QL z%zg_}XWT#})(3G^DCP!YtUS}q7CiWYiMJdOT4Nh;o_bPF6bGe%p;iEf&{)B38i^m0 zf9zZwU}a0Vc$t2TuS{TX$={@iosG`jIRg@)9f@glTH@v^W3{HfcWDJgTZ+;Ko5?X~ zm6X}iWc!YnMN3C13VJniIdn7CH*H7%qV3I4p9oOS2H|vW#C_x)?h1};qby7CRc1ff z_GYE|T&Hcb2oAg<@R`<>L#R9WE#Bp^{=ki&-z%-@5r>(ix)i!cRriKY*=c04-pz8O zYFUqtwpWC42q%O>(?s>D9S#|ay%sdyl#UyP{c{>tQ-^Jh!wd#s@d0>|ZI<8_*k&MN z(itQ8*e_drkg!^kAkQ69Rtx1$NnT}sMb%gmqV$k>_1Ykc2?2PsavFylkK^{r$S66X zI?urey{vOVw{9oZ36n&d^!UulX}#f}7^eSWAa-cx5{H9okUsOi%;KijeT=?tVKE9> zW6q%2ClrKpR*_M38&_}eR|OmP5gG+g99 z%E?-Q)P#((ry*Eo%yCnZgeG?v+?9KSE@>j&ZNe>|Dv(5&TXt>$xp4!z!gE9Y-#Oi) zVTp`?^`-~O~|u9B;99cBpKPEI{zUQQg?t5bH7@6~&;Co$qa zL8!&EMU@7fdaByDAo)}7vIio%GU{;aP>1sW8fX%j>N{GHri$1nB*ll)>LngF3)FV-Z$j^F2SXfqoBu z#cejH7mhb+-G43k+>hFn?%L{@1rgRYe({CwCn)Y8r;~%hf`i}5Vt_*E9H1QO<+lY|=}T|EfDRKU2@m8{spg6ho{fvBn*^&{aEWaE6M~%262I;V`44UcMPQr*QJ`IrFg~F8 z5TZJNJs3vlf4bMQNa$_iHxGlX1fO`GfM63aNRE)c+Gvy3i7^@%5V2B!Ae1M&A8?Gg zKx42g!3#!%BHSW<1+wrQ)1MM(x4;F|^BTDqRmmVKtJUoQ^qTa1tzfR83G^kh$f_mI zSLIL$4>a+s+C=k#b3vw6s;h#VOnu37xjRbIFa6M*C59!J;OuQU_}9laNj&TNFuTfO zBd#7+b(mEivh?N#afg7h854-%=)JEQeGc7fw;*5wBA7U3;~5Z33g|E}t+wJ_!>2{x_5(@KTr}tN zmhOvqHle>2H8wBO?A2AQmTPVuT^G*?c@ryHodu*(+=0D@D~r3nx^sR)q9{Qo*}GL6CRhmXdC+cXb?`(YfXR!x?TJ6r0r?Sy^ajp5~i zE~9CrY!nyYY=r37ZjLGVAx*MBCH0uPzTnmQO4E5)(+rtT;f}RTHWXiOf{8Hmhqt{WmR?_U$za# zTBTf(cgbmrK9OA)S=`gR)Flr0MW#cKmhRrqa0KG?1CN#UFU|x+T@yL}@)JG?Gu|iZ zG3sP2p9Rvqq?E&0~{(ySQCAVjO4v1 zeDFop1Q4z%O#3?49uaC7u_Yx>pHEWrd6`RRL*_lPe+b13-a3sD25Acjz9h5lR~@11 z9aB3zej&T=UrHdI z^09&Q2L9EgtFJEVo7@|RncU(BR<5t+EV2~2>@u`lRn(LI^2i}~@AFz49&LXj9a>gY zrFH@6-|yKHWkRhYdKz7`Uv#RR{kU9}7XD+aK60YY#6OwHqM+U3lgvUeVRBJr;dABY z`0rHnzOp%bf4NT`O3f&fttHtm9hONzVDe3)6pZSU85)Ev+S%$#(cIdq;WFL7Q#JSx zX9P3uZ*k)%g^Q7@1ejv#Igi)>fBC?v5HeuDm;iG-u>CcrQnsRm$ieet+#~qk!vRGD z7|7Lj1(PHb|6(>nf)ISTHjL?r>lbSNZ|kTvA!Po{2}EFS{mnx^E2R#voUJ>5n!w+h zZ(X8EqJ>kzu2Kp7r6|v+2*hPd$TRdY{6*YRg#|Al4~kwpe)TsmwXX=o4WwnhUH@-X z^yeHh@h1kVH95KH`kRw!Edp`RjEsBy{+0&NF7w5|#I_?w#b`0=aw5V3)-}vP|S7y7#D%#0k2baZsg8uwKV>F7?{(9s=z zOMjA9;}D}ZKu3343!=XA~{ zoWG+#}?uE(H1(|oc)K=P^dm-UbwW|y_y%i-p%T44TD&xt);)Qv+) z?nBJ<%#D*XpP!j18nKtg$sMam_SpCtN`6%6U5|oxYXmVwstpW6l);8;5v2 z{j}9P$uAMGmkNSOgPl0~-6OVVIhE7IzrUbgt`yQ{KP3cxNbS1i$pbiJr}(@;b?wVg zNa}^s?>CRFk7*-3Zy)S?*A;f2%BISy`6;Mp$3vW=VF!Ef?C&~SUHNAG{McF(!@0AM z?{M*V#xavBHH2EG@0}iMxp=eHT$C^Ag}_&;aB!iNHQU8r_j*Y)&{?406{Gf;Ih@)0 zttn;W>V^#ZonUIC`DeF;hzm;ZufC3F;(e}mgOT32DejHh>m75}c#_8YzP+)%ClI1* zT(7tUXk{>6b3BXtzHWc2d1m%&Q(g})CJS!hDXg@*CK}@Wwv{&sK!3{WES>qCBab=W zoi2S+RZ&pKG?o|el#aLM&dIY!qCy-Ws@j3$kK5SaJ+gD*%DGo8aqG(@*07+KQ0@ld z+pB!JHS$k3sGw|385pCdIQ_BPD>mJ^0+%=Vjwpn^+~MU}wPpQs$?KuX)?r}ClYY}>OLjb*6d$PK`{|{m=dqtpFkj$uRe-c%*3yxX`osse z%-vMW<4Ou2LV(d1PGq0X+%a%{7T5Q=*Mr;GU}g`u|0zg^vt8Ezv(w!E2yZDM0y?Cx z<$BJK4j7gGP5hybx#B}xT*=A86Ttj$;UY^KnU$kH;r>4*pYjPrJd-#Z{Ox#&>f$-4h}a#zu={f7!v*;B?w`DJ z_hO6oBaq?KLe3s#UCz_sIPkCnyVn!m9((HyzrH{`vSLK45<27vA=o#;M?VI*S;}-Q~Y+} zo6MxW9m@;V9>L)^Sd9b$kWjp_s)agUO(&EhaRJ0@|JU&e z#jlYGN=8ybNf-4r1=Q{*>pr+Qd=HXkmE)riGOGAAVC?R~B^@IlZ*i|EJLAJxW}ShN zk)+YOevIjbf*&R#MuY-C8}bLdx-Zlh=!*)7u2Bxo+dH#)VZpy|yvtciB!yQjIZ548 zvmht^qvHGEu7}QYE-O+I9NtpGQVUWj7i^Z%T$0b3;48IHY&4bb)N3#IWI02B6gYxdFOqmUZb8g*Yn@}=JB@Afkih@0Dz?zfbf zB{`ZeU*|x>%*me%8plY?gX_H)=2=PPZp?>m4P-X&CuC8*a=p!A-4VBkPG_MK{SPz0 zUJgf1$T!wLV|vEUGOn~QtJ2riA<^vdY{ImWt&!)dedfcfdEN4vM)$0nwe6LrM5p?j zaW8>7m#%}Z+r8<(j?}mK_1;@rUCwPbC`cBOa*|pIe?; zIKvec6vYu06{n5!z$xPbaEPm7_pZlV-CP@Kao0uZ-qt0gEyeZlu*&Cq7*Bl~?C|S2 zI?Fgq%7kQw-|M_QDzTRsQybIbkl6+`dqy%Jj70rFfk#J1AGuYyr7y89p$-AjCj z3>L2~uJasc35~zaqr=0iII6I&upLMx5`QL=D|$)0mq<51-Xt_DY{{(81iG)fZQJf< z?YVA2wxu_T6w^J>n&kF{J?M5|a|!X0r=O?I9&op9pJlgxHo(itQ}6i0BVUg+9VrUK zhpmPY!&siSKfU$TI1FRprq`%$u;6rX>U!z@PYa>r2 zA+oK36Zg?x1&87Y1T@@IK5xLwa0Q-FaAjHjfx6BM`SUt2S+9{oPsHofufJ(9f6tnZm?nQ$ zoH~XpzC4~VnPT|X%lqkO1muFaw$!_KlB;t9djiy~V|fvM-}=(?z&i>1njv}|0BEp9 zq zjGRq+(NVjgUDjRRoa@?(5;~7l9$B>cVCG|Tl|<-;cN|WFR3tLtIrHssN#2ghcKj{Q zl>d@}P2VLt>=+tYC+`)x+|KOHXl1Ck~B`vJ3=7YAU)O zPvofWTv`1%(3HtuY`I@#ZXQ(fEibEly6ybe*D*@*d)14xW7+dsmWXOGLRDIoRq6f= z<2b8{NQEg|VG!13F~6q2u)nEb9F<%?qnxKTpHtCS5nVxcm~dbwi4KT?x3d+>_U}c8 zHf3x+Be55U*59p~Sh!aoTao%wCed}T`~h}%E9s}0Z=z{pw&e@U^-9oa(r5ArU=f^O z$>|Chrus%bQV%rI?w@zrURX$f21N9~myS;9uol9g7S9Zg>XY;_4lLe!-)%mdm2Afc z=TY32SP0`mPlDfXy(fO%jJgyRO?p)`?>oAgyh&!(V1`Diu*k{=Nb|@~!XBx=ffzLz zjApjQ8N`dp4FqC;!a5n|U!dMx7UY%HbEyk-8ObB%X6jXDFaW)&u3f`MvvRX>$ZgQL z&)4;aiI~NhO~iKT&BArG017YG)gumT3A`yceg zKIeqWPPvcOC3+PcpjWomfw%o_4w4QDvl#E?b4#q_gIMt1mzBH3Wpw>A#Q(9&(=fNJIJ0yX3gbul-YxzWTe4TD?t~=cKr|6*nk}=yA1y0wvy_BTX zlT;mpbdAuJKxd}6`Qi_qDFCSt;b){19y-&ai)aUP4M!avI$>Iwp6>V&4!RSx(h=GV zI>Py{^1UNB=#KrZ{wN(?6ol^hKl

zQ3MVwD;GTzkiRtenxkS_Uk!NJYj+1*({TxO+M9$%spcOI!gl^6~L0cs+8IH&ng%kKwdmidUR{d_3d<0Dpgf zaeqm1cP}Tv&D*zc10-$%Zru{2^$_!hyZP9{#N52E{(X{v&ZFw!ZSMu~@PW9y@%@_D z*3RA6NAb#)Ukm-~`TIT{V32>W??X+z9lTWBp|mx9K>y~~Ki2)v z#(xY{0Q@5TKaS$>=lr)?+ChUD6#)NY8i=t~D{Ga;M=pq}o-yr9ld@mW5lz~k8-M@O z%14gmc}7LQprgA(r=fb+7>zIDim^u!p~A={A{An365>{z znVD$>B$LT%o)&=R&dmb5?ILt9+I8E!w`NJpAq4K)iW%`8Nm`F{&G_UEL8GC? z`O9nN?T~mi(3UqI1aU?7CFK$`f1(q&D4FGBk102bU(GtS&1T8CwjJ~a?LE+>_@+V% z%bzX;Vs(KixDOQ)I%u}Id~c!1ZzO2}ri~UUMy#R6oij=aotwRNYvn;bui}RNC{=n* zJek330ZW#CvBT6Y@6`NaFNz3&x86_*kzLXQ_pn?rg66h+foFR|`YPAs$hqd^Gu-m! zuso|>|1r2A_F#)JG3q}qrX+~E%G+s)R&ck(BM!JRMfpQy>2=>^ibqVb^jgH%q{<>T)ME5w!8_9YGIku}W{i87U>A!4ft z8PPWCmf~LzS=@{3y;YfvPfMyN3Ik)0Cn1#)9IN^&Ip-( z5&BGS{o}Y?`K8yhHm}p>k7cUR-=RBt_6gl_KDr}+E6%AOKZ#R1Ynh=oZ+^Yzz@|LA zLCXSYeX;APYR#)xN!h+@K3D65y6$VJ(^2C-0gE93Ae!w_ImP$xyVp|e=S$-`+ktI)uERP)U=0;S94wGkZ zQDmaY#a{iMwS7x9r4SIKCIRQWm^&oXw58RSs7v1JBtz;9EL{YPmdoucCSFnSW1pZ1 zAS$K4?IOksvW@I8@;gCTG%6bi$+2IBabr+HhV|ujz2atzouPa1b|u+0Z~f4a;iROt z9Q5?m#w&i6)?JKJB9YvZgWfQFfJYI^;wSTe%JkN(d5;k}j5vC>9Q4*Xye-Bzd*H1} zdsTJzgBrn)ysPaJt4AQ4u^Z9Z*P8^&+Rt(2{opp^OH{>2PS+eA;%T4o%aG0iDs;egilt!R^xT0@VnUt ziix>Q0w_WYn7Cy?sYbRw@~&UgP+3|&QCzMwY}gEWfKMVX89C&M{U`t4jsw-|mvoSZwuF^-r-=|=O$_&-p8cRnT0Aa9xL1o@RbQTQ za50w%QAEH+qYt=^En@bUz+2@98<-qFL#6D|+*Yg3gO-_Bd)dJlh1mW$O35hHjA$|g zN<y2^+|ud0n7UqOy^Q;8+sN3h=G#ZLbgwm8@>{*M zIBqf)60P{m#|Bc}yX6hq_8%+RPwoHS)`wcaXXF&@l_N>jU|cBy2hE08Lh8#4^O-5T zWea=xh`qLqS?fVxj;2`r>rsbj)-_NMwqB%kcqsrf+Gi@2vhSgoY6zBW3GTt--Upy5 z!~Cf>9R(~Dj8aqnYz;b)3!b)@=ZZ4mtZo&3an8n(!B0N&-|GBJvn4psei}Hs*Za+q z!&Wd?_gSk@KLcQE<>MWm0;`zgXdrUX2(+oOK7TYKn5#{XxRs!&lS}@j4FEiuhEr;o zE3XEccmy|{L1hjRH3Ru^A<^Viydj3r59>X_MIfhc5kb~TdpQR~o%SA-RuU1r?^;$& zC_x70H@~A4WbBVrPD)Kv#VbcQjn&b88R#jmL3iUEuS$MiVsGa?iy5yb^z5b)Z}ty; z>b!aT9gv$=N$;A@f%Q1?_T!2-Cn>`-TltG?38U*$uc zA5I1bPbRz?1?;w>5Uw0$Hkyw^Gz0x3*J!H956zU&E~^%6aw}*xBQi!?yK_x*AXw#QV@wK43 zsK9f3gKQTkqeyt2&CNRDDqc#~lyCCBtN&t6H0z_mHgZc+PGT`5&6ER|>k`d83d;`+ zQ+Gt1ZQN-4piIc4t5FL=WNaI;_@`V20qkkxrqpCYRS7DEMMW zD76>*y=`%g!_CakyCS}|rxP38d-Dc4#CQooXbEUS5!G&GC)jrP64BY^ z3zY1jF;rZeCt*pe-NXb-KAA6F-DV z2j!KRyE>>E8O)UnLRSY9t-+Al0@wV^pE4t;bzyJC?B0h+tQ8zFJPxmP$4ril*Ts=Z zqpW*zF8+~|`E^9(fKD&uuyi(f)_2sO1EaW29s&vb6Gp|nIiuHWAY=BQk!>^?^-8v@ zRRAG?Xykfy0p7bhgDLOQ48}TW(cB~uW!aB9pqb(WR!m&$hT$RPK54pctBo|YB$McG zjkxVcachKAfW_uAO(A*AgJt!uTP7BF;ZY;St!}*AQ=lHdG;}e(L}y+YyB)wF~I z#r2}sKyohaK7VEA*3~X6?7L(I3l5EJqwJd-_hES! zvQy*W*v;~*6rq_03^yTNkD@RCqYVcKWM#=D<|&@awH5?af-~i|{efG0>zaXXOM@YC zMxg|*T;D~f)U}Y|nW4>fuVIHbNV^l+y;#>RPm2=ev5+4YhrQ71U_=dSQM~L22tHCc z0==lt^ z7SV0%DaV^t2V1Fc^>u=(t#`}gkk?E?N=+imc@Y?$TK4&EWxw6rDNpVuaXqLm#wNvI zK7KT$f5`Pse0Z<0cXeCOP)ME*q+f&L!@1>eQ-{7y#s+g0D6j}?Q4H`@H+5fEtzL*? z<`uH(Asv_=Jc|>+c*_fJOo0`mfrK*trjgR?#v}ekH*;#TcKoJ&G28LLwcY* zu!|Y@EVtQifi|Gho>wVmByQ17U50|OT3sJIJf3lSDqc`XVR_$R{p zm#RKIcS+(9P2xR9_PW^1WeSG&fBy1(x2>~5aeIvYx^9Z`jMhX`%#nFz<#}nbiPE4C z9WjhjuQp&7LDB4g69*RNX zW@~sd_i3II6x|!pDw5@!-|B5?GDg10?5H$Sw;&{kwzP4>*md6Z?Fli$95}QQ{2pWu zk&P2&T>#wbHpPk5Q6~;e#-vnHXWBXhTv{FCW>#nLAW^X*JNR~b5(Yq6>}?kZQ-u7i z2Wb+G$o4g?$Bt|o@@A6}xrv>)R{&QR!AMuTVl%v{O=Y)Se|-4D4rP9;#}h~n$;Y<` z_n}<_zK{Dt&C&=C-X4J+B3n*H`C^pn_RVy&>fSi=)R13g;y_7!n;|$cdpV(X5xG~5 zvP0y`Jm>y`C1GkR}uIwC^GSW0U`8 zD>=tn7HYO>-3c8|nn~;+Xs&CLyysqRCG2I}-w#ggAYn#I+WKwqA(=7`X567sqfw+> zat=Bzs`cVXJc%ensUDd!85e((%@yUXauXi2L@RSo#;I zyFwY-%R`$t;p)L-cY9?^636_|j3!*hUG?uFez#-QQXDWPZ2@K7z>5 zId5a$_4IDt`}Z#Jz_pSeB~TP?|E;;`pi7Y8N`9o2wTWO+uGcn#G6RnnsxTW?a4Y*x z(ISbY?-2$)7g7mt^`I`f!p6HTj)&z6It5m{eS^LudKNY&*X!^3RT{A7PTg-CO={~c z8SZq*EAEZ97C*$+9gLXr%=((3D55)PFp06k4TSazGZeO!2E; zWOQrv{DH4dFSo&G9B}74K)4eNL@O%{0mYd?cs&zNi=jTP5W8XoL4%ZozDEvNgeVS| z$J~>tH6CQDp`rq<(7<9ja-~S%SjK@OPh}$BL5r-5(dEF1#*;Js5M{s_S`#}i}jKX@d3bY*BuPG)ZW~0*r8QC zmkA(kR5GQeA$A;g?#q}7)A6k~_A|yfCIJ_90FjJD&zDbP6)LJlV|!~f3wRSnZkQsM z>Lql`2!fmb@Uo#zFW!nNK4kf5c{>PRC~xsLp}6|HX+Jno%)MA}w_FKuHjjIF{kD(v z$z4nwL1&!@jMp_$+VZxJ$8DAC;*(m}CS?=x zWINvBigzh{HH8w*ynAW6{7{jK%9H_rS$88}#es6}VOO(yMdo?Q4)TpHE7$cAZh|0r zkY3a5v>blmq=uvo6o(}xPZjLW869I*D6CPJ^9=4N)C83rwm4cYIM~{ui zscxN~3t-}#Butzg#dI^7uvmaz+v>p{^wp8$9K2tF6N}qebBV15+_jJV7t33@tpH@% z?Y8xNQh+7~klp)guVo2jh=B_0ky~Y%Ad0)v`HwNUPeW*0A|hvf%?YPf<{y6RFX1uE z@tk7QtsduquAhOG_$x1YWpmubw;VAz#~2ICUkX%YkumWKitjT7)*v`=!%%O5IhKZ_4}f3 zL*pS3PGN7ji&+ikD|vcq4g!SK=F2GZZl~^vq!SYT(?`tU2;wG93x)?bUG;)7nz_*F z&0g$&&$c1Fc4PQ^I6<4#hV#od$-xF&NlWe|kDc0{zZDPM^d>+8x4ai`4VKkbPL>B(LQ>ZkFhKsz?J8&+!4xCz zjfYd@b#V`oeb?)S1O0=<CHYHYQUEdRH+dU#ac(p*fo)>Pv5E;BU)_(@mXd0)i04w|Cxdmw7GSOwB?`Di(1A5&~AEdsC83 zxl}R_YYG$BF8m(tI(i?i-Rf)>=ScC6yWJReYLU}tu|@YoNhbP;21L<`^dN#}{XzEr4ZAs~}X5$Wy=A zYS!O9bWuTu1{d)ygzvb?wQ>|*o0Job(c9)9SIBZek>s|2P|V<0!31kT_X6Q%d2#Qt zb?-4x7laNRQ5`FV)^jte>z1SGCgsP1)Z^ZR+|5xGwAF0bY7ps5G@@lRXd$p$>KcR> zZB}7o;+Q&FuIr-LyQKk*ZGObt|2^0$315Iu0^8KL>d6rLa|k-L92yzctp&8+upSU8 zelsH-rvONOO0F2$z#`98*XG9sD@6GeZuvhL1KSMlDwrx(B%r5)@Qx{doLfd99TC9c zhPNwk)0tR&VJRkVFHabu$Xu;wBR<}To4*%=1}253=u*(uGTB7ZmXQ)dWJwo}4;jm# zl*X^==GO5bTr~-~-Evm4?tsp=P8l4EWbSt&o}Uc%L&)X>cu!E^i_(wDxzH_*wzq!O zytFUJdf2CS7b?E_I!~tnjb&;%{g5kLXn* zEKzWrjm_Fw^_}||yfMwYlYJe%Bro8U#5L70dz z`C+O*_I?m#{HHyCIZFl8%|D#jrLN=8&{3ZctMVpFa7g+$-~b`)?trCj*zPO~69D_r z+-|igrdmTXLHDCIz`JRxg-f0RV2_Ivi{p3`9?1p-E^`ASJD;7xy!%To@Hb65&3M$v z9e9;d+`YNFZ#n3JYqwg%9tp*5YGqrkD<6G5WS(dism>FOE$qKOp?2c@1JUvu#Xl7q zv|>*w{hpopZ{fa_c6_XA9`XI#LK8cyD|+>$?GI^Fk%|jIOPGO81>;21(HMK62%uZ- ztLM;9KK2X0VXoi#8+P~ZdmC8yTlp9Oq0YZR!f~V3cT!6jd$FQ9HYO@bhl$Nbpj3{0 zD}wzE-?RVDkp0fR&*$buvChvnC)Q!?jUn4g_=zP!r z7J}19kM=jjTsH;OEv|k|Z!pvnH*k9h(SXg*&D}T$pN;Xymh)rZy59dS0sk9W5_0rd zPkZcCwvD~Ub(z|SmFfQUZK7qy2G^OhwINA8H!n%V} zo&%~^yyl6a^zoo1dcYJe9+@vATAl?VoV8Jn{Oxf6TLzwdd3a4ijb_gEUBn$ehBOC~ z(T~mTUNmXi3r^4yZ=#>y+T2XQi(*>_>bh}8vVS=8I}g8H_`LG*#oH9ExQ4L!$20-4Nq0cKWm1ir4;ca?qH(=!GV2=bUEH_{l`U9mEG z@}ic{s@ASgWz3q23`q6dk>An9@A|`W)PyDmf};*|T_0>Q&`Jgo(Ms3bV3J_EAND0T z5M4Euz44M^8D_8;E$)Pi(fB>K_+22(>D#?KPfSE=00wk&6*K5%T!^fV@{fyI*&e_? z)ZB8&`cN)_Z5f`75s{ByxpL+BA4t6r7H-O5Yk1MdCSW&lWyaDy^4xkSJDb%*)pw6k z)zJ{mM{sh*U}IY`mLs0i5}UT?U}nY56TG;3YuvPAN-dks0z1_N|Nj$~V}d@Q6Qb#O zrVE0Rv!<-@)e)%b&Q+@}w64O0J* zV18k>+$NY@;ei`pX51cGU+y|r>^$sP@S}03BvVT<`_0NEHvq2Urau|es(H?_G2B}9 z^q;)Mi7?g-41YUtS;2N^Wn$uo?AU2q6n8!&WNUb3fBgdR2cY#j>jy_yPNk6jzUZEY zM zhb8`?dwdd?=zY{_+Q<0<06lLr&6m)m9J9vQVd-P=a>dZT@y{Y2Frl{YQb)>O`Q-8I z!dJP^Og=_DpBBAnTOZzGJ@+Rn-t$WkpFz}P`(Ft8ChK|^;WrH#0c*OEY`MLrcmiQ~ z_4QGH=Kp!fU*7ZSGXhd{(#H%D^HPIWK|&Giff}x>C3a|`C7P8ir3VPH{z2tWvmN!N zsh7!un8Qb}{PYO+@zvJ>vqxV>un(WLG1ScZg9{Qp&cOsou_aAvrA8o(oekt!O6Mb2 zUccdI`QJN#$k(L->(0`w&DJ*7t+Z5)8eCE+qD@C)oc2H6(1)wF0}F_dF^0csn(}EB|IOe{)@7VLCrIIYZ7# zC!L(sgos~Azi#>V8*lc?$5HWEKkR*vlARv(#Mg9=#{X@Hf5D<73;_I?p-@rZWzsEQ zqX86REe=txdi3Sf6NtFDxYA1#*{XMs{!eokc31iRb*%F(MRsr&N{ZD+wCXL!`XisD z@4>NC49YowLS`<N?&l+OrALy07DCsq@KW`;3FRwf* z&Muqvj)qp4|D;EMM=JxS#Z7(Mtdgj_o3ym%0yz`c$}K@tL!LhmkBvlV&R-*3wx=`5 zdO)*jA9HRUl;0%#8Pw7K>w9SPby6O_Zs-$g0 z#C*P%tCn(1{N*-(%*89Gfi@?bPCfsVdq}@i8Od%!7N}E&JJRy2Mq=gK?w~z%KeqN* zj;IPu$l%p)&huc%^jqw6JT1_=Lw~D@ zOM2j?Y4Gp_5PEio8>9}|Zz5Jkv4hhMXEda)e{R;)dbV9GS>sbRTjJD6tQ<3&Ii+dm z*kPZ^&=#pOn(DC!duOV48kVn7xjGpO0l&EE&$9*ok+wmfxoqA2NXD zHd!1(-U~R+D4ZF!t@ZfU!I|W&i`nZ~8C`c1T^Cqj5S3eAk?<-xXZzyBER&X~6xbX_ zt!`uj)Usv3sM#yyJBq=#n%!&H-GZ-q{oiJ~j5X|b6f?7u!p5YJ+3}EEGkjLU7=M@jgxaX!q_(9nc3P!PjXjZtZNgzNRxl!Sd-xX8 z%Yj`|Qq70H4L0JrJh?>#hdP zu$y&!-nr6Er0|Z5pN6=z$d0eW5DdfF4b?%wcbA1es>8U)MxJb z(%dRSyNQii&sV!>+;+b=eXv;XSAJ*rEC?8hJ zQ6SjiaJx?MmPP&2PJOfVf|gC-RFTIFl6vmMyZR^uSp7*}t_n)z=w<_4h39Oa0>jj-#b1pN8LOt zHT^+a^nkJhbq2cMHz@Ij-uQ+1QcdopR^r^G%sH^O-2krGntd6TeEqWzZJ#UFgFu`7 zoVU^9=N+O0IC-py@;_a7m4_NVX-QaSad+OEomRGak+V#hNj3t7RnyApGx->Gfz#7R zCawwg1b{+A&)U>DMy>QDceiSZap_V<+?o!=;PV8}3Cc4JFSEbWnl@~v$*jS9)x6~P zGiHW1vAT!mAumoedc_FY@P%y876V@|HjaY;BfDRW;NH{xU9av?70RY+-uMH?wI22Kugo;$sg=nv@7eI;k0oAql{tu z@T7s=;p|XmL2JLqE-vrx!646{9sP^Zyi@Hu&?;qpExLd@dS|@AYF;qV-jzzz-fhCeAN5+GmrE@{>l}$ zn3wMat$ap6YK7RR;^WjMxa`2K-jFNUzKJ>0>wlw#<8QR^a;=4}P<`(WUiKC2oehPX zz+{%(=G}&TDp(t4w}+&-{F{+Ot3B4Rvg%N(f|e(C-A#RHisTeUp;CfeP}*0q#&%!n z|H=lFqoe0EYtDlM%8G2#1!AQIx@fyE(hiyzz-q5UI3*pmJ-^2IRos8{D=*<+a}m^y zqNPZ>-|_end=gjs570u)q1D@~9$hTr!t0uR|Gn=vpL@LK?%F#`UkN(0-`-N~ey$*G z*yM9YAtq)+c8>Rh?sZ7xy53v69j7nXB>L?pt7DK%v8qEieFx1Le2ytPXSU+IwsMIh#1cI@|L*cK%s zgqii~Rt&K%`->}UB=@&6=g+=-aC~ic7<_mz{&~@kDI%Laxt^;*$ZUis#HSnF8f0>G zB0HK<=C3j{e)iqDiAVPqwtl!eSC|~FUilbc(x8dA$@S{LEbC_Vq1@cV!1ZgBObnp) zDz@)chvMvK51d9+ZcyW%dYV<`XTpUEho)=nj5X@_*aHB!4o8|i9lcL;pU=qH(CnIA zH3DF{eE7XZa6Ns@;@?FpcaGW?(0s#HcJ6a*mJc&Nf5A33PQ#X)%1Yv$CeLZdD*>yA zxL0Nf%K{ZCf>Sx4Bm$Dv!kdeM(x&EiA3jevtkX^>-H?m4@ogOtsWi5$e=}-EtY33I zvegQ98MFA&woTfUu|^?yqGi5l2QeA1xNZmg&*`lGf+lrYDnw~tg zt6h21rA^tfGo3mi(h3)Lot=7>c=o_;I{wn}j?57MCYmap9pI?&*;i<1XN$Fm2lNz7 ze9g6?XKCJ5-0Aza()SH9xm_{P`jQ^dCVK12ON)SsN!k@wRLw(bY^BulU^IMurx<^2 z<3}^;R z&{Z_R{a(AI+5Fl{?}e#ABYWw?5pPypUXh~X{O9SX>yee?!Lrzu9?}Gwl0k1azIq4d zt9j6o#!rSe`8!syB2E_+RjICmloVHqD??>~XZ5&FU%g9Wmyo>n_rxuNmSdJf(<(uj zPF!bPoR1Mkwy85duFvJ#^m_kLzTc&JZ}iWg#+W)P`|PWzt}Hf1Xz8*%(Fl`7j8{+;at+;Zr%9_FY~Q+qTICQE z_??aWrhkx4#|5_N5u1>MA8YG7kAgtsTu7+VSP&-vg?#Fm`$32oY>(y+vJhZEY2##I z>3n`$)DKh3lCy~$Jhdxpk0+E?FIBX;*8+@d_0A)sJEs`6B0N`@%D=DrKO0+*%1FC} z+9Mp?wW_%gK=C*5-)m<7J#IV68lBa?PSYq;gs8FmLdhFxjeS>`;<&vzxv?t~==N0W%#g z-`>dejZqyvXX7^vQwA9(@#vOXE6pIaGYqOSUneLh=T?mQxTpANXZ7s|T5H#adP zDwU#MCckj_g*?Cz=w2PbkCs}mB_-rG&gxYQ-yd3dvGVam@Tld-PO#ZsyRYu3YRNSJ z#`=^RabC4l5xt@MjRgIQPT5ei>1!8*Jl-%Qtb5s#yS3PHetCENt)whH#5o`HuSP1$ zGEr*%i+YTvs9y|n5xaGobCN#$QI%(=lB^4@wA}{=L#Y(29qO)ZlqK~5CRsVzBE_9P z^O07j za00W_;+1jh6T!L|j&Op0Ap3Zbdzadpb+DkXs+IisvHDPh@6NTJR~soGCGtDtk3Wj! zTn>@qTAR`uF9jL6|2a^4WMlUSyFwHpHj+RP+Bj$4`1 zbLFjfYCF!rXMKWt>M^~;v2 z_nWC8uB&uDb?4csdmj+{l-lxh4h+8FbJ0@d10aOGq6Yx_3l6Jd@G%QI7mFHTCx*{m zVLSlP@~6&2w7UZuP$^saD9>h{Zx_LSj?q)FA$lU~s(-%2q#pTB_fuz%nyXkYcJ{)p zk)Vq500boXcD?7;=EMkT$z`FSULUk{)shu>J4N2~B6VpG(`Xh#nT>v}FFM0r+88kL z1vLM)P%E1gLXc16;&ZJqtLY>C~Z;#_bk45?0D=2I6qLbv4J1$mTR@bS-opS~X zUUK9GV55I0rh8a-b&C|w3?6yBK3O~tWR7P7%IR+(iyP4fLw$jRqwmw{kcUJQ<^rPfw=uyq&NJii@Xxjvd21K} zP3f+Lklk`S|DkS*>#%;72BF(6`B+`xU6+NoNi7={JJx-=h^2@qs_f06y=jrBllS{HScs^-w!QUVgRPuXD<;$Yld*Gy&$fL8?79XS@2WkF_=GwZ_vl6ok?ew&rIe~tz zo^k2{Y47mmbCc!k^nfep8{*Fp>U3MGL>Z5P+u8a8uV9@ko9m~*yCB8Y#L1m&+?-N_ zX)2AAOzoWa;;piJ-B=GCHr&99K2?bZlrVp}1Y%!rN`uxcN@EE5<8w@`Sp1b%93!)m=fh({@)ITtq}K z{|epHmxaulfz0BCb-jGxkzTMp={Xl~TPF8y`MSC9FrPQyIK{TyOBcM-**5D#zv@hw znT;9@x~J^osf2IbmkP3Sp2o(l1>E47-*Db%+K8M<#mHr7#I##H)DCAu`wF4`(u^a6 zc*d%Yhy_!h#1-6-H{QSeBr>4;p9~knrRR%}9 zH1U(yc>nm~H+^L47`=t7?(L17Pra@|c`F~&nI=C?HThUss_)l{m2_cOfifTEwuIPO z;z8sT4}+0&hOA!v%0QS;8uF=XrPATl#AIM$XXg&gxHn+cJK-ev@>?F}?9AhvA#*UH z;Mr?eaSId(3%R|QW9vhbO>$JudP?K3_(;6wP6@`*XKS&0 z31J-vEQ8fm|B&jK4cxyRdM1ioWwTnXcaT;`MX5K~DpmIlKb**}L}ojjQoKLid4vhz zqIrdM89by|t`}G}58p~~PdDT0PV(kytMt4<%Np(`ue#@?G>!~BZGBakt8`u%=qfZ zijr`&we0@*DcSQGx42m2RjPLYn@qXCTrA!rsAR=&)S3k+xx@*kL#fHXIAH_pr=uS1 zcsEUk)&;8C_jfDTlnF4`4DAx?F(2j?Z=@F11ntaG2E`*zk#kzYm!e+1pK4MT!yoRk z_(vEO?^zNJl&LXuwNoYXHXgkVX>729IEz;H?UDMW!kwAwLH6wvSnha#t?(tM-L0_Y zVoJfz;8gkv%iyIxzAyn6yls{mUh4ixm)jX`&o`$Id~5vP&Rr7ev;^TFtbeFt`mhiZ z5ybN&0)Y&&i~782Au{M&VE?i1tiOse1JFXQzuS{{ETE{>`c7;FV)t3+W%0x25MSIo zYdGa#B5-!xcx2X4_Q|_$O2w>WL1g2k8!I`(YiE~O8HuzCiYaqQV*s05SS3ESk z=#PrE`zm$_$5x$s)FWb~Otndh^_Bb(LS0?IsuiZ&FMF^d6#20KM@|hHHMQ(BGKQQS z$#_1glF4_Iq{WNJo>f@Pj9lT4zn!^eUT^i>BYoX{-)uF52t2Yi>=NtIH)c6h^wPKf zW!!YDnnf^=F10?r(c-&7*x<6g*r>RYUrSqtmmlcm^BCDK{o%Mi>Y_(a* zm8+p=vKnGi4y+WGmY;0b<}Tiy91_PJqI=8AfekScRpFBfkqcVmw}ZFypN<{ILo5B{ zU>ILgw6Au$YOTVwwywN^Gr9j8|`1gWNxDs+)DteYF-;6^4z1@X|N?8l_?)_2dlKxT^;g`FsN-x@x}O#_Pt{PyHIGq!T8vHP&w z*O!cYW`{l`AltYf<2sk)sQN-5o$m&fb*A-b+-Q$v9~@L8fuqN7S__Yx**+R6^7Rcm zE0wC{lsWdRX0Q674b{0 zwt71GRS8=)M1E+=L8?oatoy7E={bI7rxDjoX=LT-ymZI&^b7}OOiNY$q;Ph#k)Scyc7ypO|E zQiC5Yz+%qW|4rgZlvZm4Jq1y0qFq?#%C+ z(yx2z?LmI|+WY#1!E)XPx}&Ld)MVci6GHI1LSRJDz0fQ1lU?T?dQvgNR`zyrn?VEu z)4!vR7Derrc5iTb#7wyM#5MQbMwjmo2CllGPPCFRT+BfG>+RdiK?rJ(8Hm17Z%BO? zrd9o3u|&Rxy@?uh?GNra3 zPs%{lF23W{j=7Pv!X0vL?WL84{FU={6)so}D zRdd%1$hP2|CD8oQ&`L63;LI&hg4;$n(6AyoQsP;V%2&>-VILWx&Tep?*(LRRUI2pA z064FR5X*U&r(SEfLA>jbM{9B8eT&%W&{VEVF9_t*aw}ZpB0S-;iY_E7sD4d>5eypF zE_-71v@4pLi`$)LX9pg>%MMHO3qO-WpBvMST^YPG>p0dOK}Yx-Z>d)ivzttBtmC-W zRWuM4n2hn{*IB8T(54MTv*AE14K<#ndna})V^U~| znyH3(uMPdlloP?-o-|wl_^mJZ@e#(0GoDRp4zB|F@eIpGB(455eU8PpeCtZj-p*{s z{81;O^v28>>v#Qz*h`Q3xg`N#404KmGy)S1=ndTpyqa<^pZl9O3bc{CR;RsoobGWO zech|m4jB|kvR8w!RjkiuB<(chyE;?-6Cs&av%kSUghOzOiNM6*N_DC`r8eqeM9<*> z>1HX8f3FW>V)Fs3c~^(--dn7uGq?XL_`M1Iq{`U|dBdpVxvj2jML&?OBoO+qzoi}9 zx=~GT2KaxEJPNY#-|P4qv7Ovc&vRQW)jCD(yl4uMP?FZZ7W24X zS%1rpxo#wV!JY5w)Gx<-Br3_rrSy3j2knnLj1yMH*tSL??zWZBU;p3V9<*5W^wvP&YJA$6 zWeu8p2I97Qdn4{bmk`W2{W30HJdo}Sh6Jvu|j7hFZe!5HhFj;k1r;gHow{!`ZC;+dq$tPBL3`)*vP9`G}_AqNxOQ& z6woRot}uI*;}y@<6&wciBDa>Gr;(b{^Mb=q^4~Jf`ofUWgT@zH90A z`RAw%t<@-OX7yo2np`-=+7UBjUeG;yih>oa+Cr~5x`P$s>vV9T@0<-_LAtn3@Dyj}p7E_nV=&tQYT=*- z)j|)ue1zQJ?GiIA;>%Wu+^WH(nr+wF+h;qWE<8jI_A8o=09vciq-i6+M|Y>-Tw6z& z=%I$ilaOJ)$9_jMu!Z~B;mi-;>lfr;_g2l1zofS*7%N}AxGP!D!e7aSEE4v3c|2kb z(W?>9v7_s80L)2EWO;wBxvP33iVz)rtEKZp{Dr}wnUsfq zb#0x@YpJ(p5(W}v(h8JNyK`mO$1-2oeb;Vh9UWNAS?-PK-ePZCAf|_gb?`LN$z^Zf z*r5g*S(b5)O)jea6~ZJy?R@1^s#9@L6Fk0p&`DS7#4SAro9WTc+n~q1o(mJwXL8hr z4{Wo}JjprBw_@Fg%~@KV^L--s8~%sz`C7nth4j2k#51O*#HUx0kjnGIU`p4nVt?YR zx~qWtfZXOTg~JJ!?niwRa&y>fu&-7}8i{ zaov)pg#fI(gMDW*rqu$wOxo4nm*ugw21kDBM+YbT_QMgx|7xoMs;ch%Rdc&A;F3Ws z2*E^{b}d=HlZ$(EZ9l0#$9?{3 z+A|O89sxbs6t0@{|fZ2YR8vuz1;tN)_{HZ$Pbi+_b--t_v{TXC3gY2R?vr4|MFl^q{DnRDC^kOvLNz@ z)eb<&bstWAe6R7Yd+a!`f1~8|UfP*#`9fP}1kq6C?(OP|g|?^lQNWVjw;Ov=u>J>F zu}7#v=YEfkyRhbQFbJxnZ?@w+JK)_=D{|j)tHlp!71C4dQtmUkI81AljaAa))iavD zWl_6b+PI@bYG7ydz$Cxu4iC-9_Iea(q+u_+Wh1EYcSX@<%`;1=a1+Fca-w?VI`DNh zdBup)k2acC=?V9qo@3jC2sxdxAvtWa@A600gs29j#`)Te(Ct$tSm>9m_E}W#YPz=& z-Rb<`nSSGfoSQg!_CpNceaJZ~+$nEPOt{4M6?92@VKGgarEb3|` zY6Kh%BIZtw-PN&s=_cBYAbd?+T`-87U)EzI8wnLAiITqdY$*8 zrJyx7fDp!gtn1y)a6SX9tH^!6hgYI}LPu6VKwRF2aM80a?_fb4gRgY1af%w0I;@p@ ztDR1pCLJ};k+zl$UZt-hFxp-P2kd^XwzYgv_>5hm__kj?kZu+>JZ-R3<>sqXuRY&5 zi|cvL5o-k##@@3WW88WXMWRvf3GLgt;C7 zDfyDe+V*ePzlVZ`YVO?p^w$NbY9?X)XDgQq3ACH*k58}BA4MNOpN}VZTxSl1gRdm8rgbd2$OSpU2PMaG5qx}F@38lYii3565(-sC zm}Y0bN>BXyT_*?VQDep1X>!)m~Pb=$A>mbj3gWYj*&jKczsoKDEtF?jF*wPU{Ti1INw zzxh$%M3VIc;U}AgU*mA{m?BF%>x!_K!$tM#X$GeBLMOU~|05kQ`*TLzTbK zckHIW!hPmwOh<3k63ut6B(l^w1sIT%h+o}2j=T8&5j~h@g)?pPfdjI0m%(-X$Z#bX z1v!3^go%85X$(LX$W2LfJrPjo-}-_n>D*h9E^J0bT^9$kLOe;gLfJTMrgc;5#qE0Q z)pSO8USu~wAaFkGlhT-0SggOe$S((i#Sfl;>84D9YeF#~XRk)|NE3F*GJ~>`n2Vcg zu`7%M-+U0ch`Fj2pFZhpSii}+^8mfGTR7B9!XOHe|U4wUQjNsi=}X6uR(Ot-v6M)rxW zjKXvgEvB@;*_dJXOob11(1dN%y6WdvNGd2jzgTmeliMsgo0X9Pxr$HkjaST-)ebEJ zJ@|@(hqG6W7{WBP+fe;ir>pG{Y_h!=Bl+06MC-}^X6pNnv=q9-tL>9u5zR6E_<_fV*KOwlCJ^^mR{3Z|dHq4o5z)!R$pqIKw#hd(zPTQi0g(ZL`@cnB_ z026YRsu0~~F^v>gf@%8hpMin^N>}ygj(2QcT*&>U3U~RHj}Ux=d(h!hj{;-(w3JM< z2?MZ2KDx>Pd53@EF zhb)i{YvlTdKQTpnBroPw-PI+2OJvQofp8f>U6JuVw>S!ER^lq*NZE#K%q|gtU%yMX z0sz^r+&RF;WB1w3?rMpIK_&|v>31qxPAyv4VH5eP?lBf|*!yQdXG$N&{>H(e=&aXM zSm!WfH+Y#AN|#dEr(@rma@{EeD7`*eu1^nMP+E}0`Ar+N9UFME0`-TzCm7o71@X?l z5;3bQTL)U-YFFnGU;RG)k5|+%F)S+AJO)UVqx3U-gZ55A6!V$qaWykzw)oMMGtr2^ zU=ObBxhVWpBA{4^mtjYa65sm)Q_Uyc%05|lDkb?%JxF<4ESOcsHemTdJ3%c}E0>lK z>?*PYaFHl~zIwlsHSYd9ar|8nhO-e-LL4>%_Vcl_sPmBp=ud7!v`&+`8=cS}2A!-`hFcZ8)AufKPC& zDmEUpNAfKD|E7QzV&Lh6Re8-yQYEu~@jADwByLEL_Tyt{wJ57KKHDj%# zAj9B0DJaud^VkOevlJ=~Z83yR9jM~1v^|j~gPxwkG&DF(qRcO&eWFPXtHtba*qO*8;VDo;M2 zCKY-X<%Loh;3 zXOnV(j=}e|4eNZjfc5EGrhN}Hsahk}b$k!tcs(ms{)ve2fh}kBHS4>C#!|}eF~yTg z2?{U}9vbL51b8AA*5VD|mxEgX$&^I+Y5A+$nhFJ+7D72Lx9ZhCbgt-%{?4mFVg9cFbx^%@d-C>nJJ0X*t=U@+ zrX`t%Hdgbsx&zI-j-W8{PRb;R-;u&<1H?%b7M^U~eir;iRxLQ82{4t&Ds4l+R7$X! zeLsG;$chBNKc>&ius%h5cr2)?J5gy=#Z6g(v??Fvdw(2Q6f zPe36wL;fZ9Fg;{));xc^bbfsLC20daP(RexfzUqrF-pI)bP8XoP+es17Q>MwhqCsc zpYB)W(F^95E7;~fhyTn2L?9HlylB8&;@vyC>J)tQcT0B*z3L_Tme=(PDWb>Ad0qke zhfD_!efeI9*%i<~3Z# z>|D(`kp`8fcslm?hRZXXIBz|d9-QIsXqP*uU%;CvzIkx9_Mw!+gVA@-0>fP>NC91B zC0`0l5e{oe*4a8-kv+f%-mCoi=KCKWzp6Kec^?-RjW`>hw;g>zTxxO(*$!OQn2fU& zeQloS6+A-K9v5ewRPOzdU6dw=K9-Txs$>CXA!=q+=loR2Ya)XV!%QGbhAAf72@w3> zRJ+C)1TPt%s2@7rSnD=$3E~*eUw0eBX;^(1ng!Jzi2?KbPq8= zS8`wJIoZ)G`Av0)PIID%JZ)AwXI%!|X9QR_qGXlC`!8rfS4*?b^Eow?4WYkVrGWRF zuhucJo5N1b2y;g9>}?Y#XtzO zbJ-+(gUoBZgfuLc?kIlEORguSAB0Y;xR2l7z^5nHySHyVsNsVaIjc`U!T_L7h$$G< z=NRC*LKND5vhG%L#j(Z}wo-f~Nv;}^HsQ@!DivP@p!(^fZg_lssm{W=Xg|fAobTGv z+o))F8#d$*>jmw2(zI~&mVBS3WBs6px5CBgC#>G|MSd3O;Ox5@6Cs$v&FPBIwc%eQ zZuq^)ZP=RJb=?K(tmcU`5u81z@SGJVqK%?Pd1j=|V^WD@=LChw*Glkms;n74qAx}K z?jN2Y5*dA;NOy=vMm8wMBm8HO$`S?+gWRQ|q4VTgVpi(~;ovqFv=!1sQe>36!d=g9 zj=XKaMC`WW#i|H5Jve8fg7w`#t75;tP?Rq~frt=Y)#I6=$T~E6*Wt3pk$IL1&mbf6 z8uT+68|d(2fz7NUV_I1TDWdT=si(!Ak2be6X;%n+r}w?os6|?%{y1GBWA5J zm1^a9aqq*z#uB!b7##deY;Ud${t1>)7kNH(h z<8m>}P5U%@U%%YDuyI8WEV;dJkExY}(wW!o#(}2UQ_cDiR;{xl-rVcUr z-MK3jJ1<6Er+rA_B-JVkVRcXV^j}r4wHser6H+7iUR6E!k#QGDxg^&m0tT~CWR5^~E^aw6Mm6!I`UZR2-e?bn3YU40L2 zRuM)U)GWv~K7&(B`M~FNIsektiXfjWL@Wg=jW|#2Xv*Qy{u5689f0B{eM{|XGP;EV z#7be_Jji#{kF37jO)`QD&>;k(CU(pp{>$$FE*1iWh~Dpf3dY+8xtkH`ihAX>_nF(* zDwV56g&{s={4W{)+0y>|r?%?;uG~Mcb_OJosPG>hF8; zHsD*~Sc;KyR`IKc0=iCN6Rq!Ajf;Dlm9oU4gJ&im<>3Nif3y%lOh_C6Nch+i33!Z& zz*2U~%}UzR@Pf=hl7BKn|0a+N`2I9qp&4YzEla&i?M>Rht?jxRp8b2PrqFN${J`MlJj{p5>K#6|ebWYCg zQ&YI5fn9w@qH7nBWPHr2i}x{9R3RlRQATRI=`cQSJuMBPL|_{PWId z9*wN69Kg@+ivMJr{k@+6NO|`Gdg)>ww_rx`1U;D2I6`bFiayzGuLU0$vi#@wzINj| z&Ld;EM&BLt<;nRlSF-;H(P6)RbJyxXR#vK}xM~r3V&!Lga3qIW=-=P!AAi;~{SHSE zh(wBkR_J1}%(h@H#N5j9jhl0p?|lLjZ~ob?9{@Fb1TxkbJTtpvK9FOBKbI4v`X7?i@6XZ=-~&eD zjKV@sfWq8IG7AB#65goy|6vY*4U+^&kwcZ)?-{(TSj~LgjNl;qo3;K+YeA)agA96e zsNtv4pMNhg2lzcJPCv2#*l>RGRiJl0oUfsU*WM9cRaG@IvzGZaD(beJ+^>9r|DIw& z_B;0yt!cZ8V^+~21bgfog9*TFvVT^-e=}w62W-*dFJ73SlDXoCI&5t7E*}*kSd|pL z`(yaOyayQ-_6D@^Fk2+_)3?}Fj-h4kio6dFwF|!m{=b{>MBHCq#cL} zU`RRM=NC3R0v42(B6beyK7NTe{`~g|e?MG3ZjLCJoVh>H){J;ciSdfTK79G(y*d87 zLA9u9A?lmY{_Go=__2ihpRlgo0v*ctZZq;)4YXCeA0ayV{H$UE)S{{X?tcFjC<20{ zO9{ap4BigIT6VB{c!v^KH3zRodtkSm8u;_Ax2%6&0U6ct4KEeA=yvTwu7OR=x7ckT za<(O7zMZA!E8fT0H38iJc>DKciOh3yTa_a;_Ts0jS%|Fmj|Wj8V*c5s%<*|*09O1u zCj8fB_&>elw_nWa6wrB}`H;K8wqnm?_*@S{^k#pm7s7@$6o3Q00SX7Nm4L$ehzP)V zH~s#+9sC5p_i}d$>@RA^T_p|;xkWul7@An=1XuNQ!LPf{;#KWp>-05-Qvc#Y(2=J@=fP2^e&RTn~6R!k`k*X z(M{%gz)$~U$CO$62Syp7bWPH5_kg8lW2K@ysfqq;GHtncq3$rHt*f8sxic%VMjM0J zs058Hc{$&lVQ42yo6m4!7hPXf8~HN@T=BXKT;0&BtE1=uNkaKQPIySfyRofj*W-M$ zdejq`dY0P-IDyIqxy*y&!+kiK!pC@a=7hgEPW?xKmkzmeJYvAefQ2;y_W&4fx6h{U?&7cm_%`#2 zo2OAAkB0q@QdWz=|9{UM5TIR}%h3 zu>aeqo!$!wcLU$`tKa^9VW&JpuMFHK?&3;KU>qiH*=j6lF7TBS9QIC5j977KRO6g@ zhOeE1l-%yWT;t!|&i;F81w-%Sb*nUt+18~-@mLUuUeM~hoXaQGJgzfSGH4X)(r~Tv zKfqW&@r@|-Iij(@v&cTPF9@XetikB6`>iBA>LAb%^Pj^N(}Ooy&8>tajG2)g_BI zdlv_|7 z0&vw)bpdvMhOdC>Ex><5-R-{hC%E3P1w10?`nnkrO;OQrJ||aF&5YdNXHk&+!}{KQ z`}KQ|yqy3y)*J!I{~clwcp(3~|LsezQvex63;;pHxhai40uedc$T7`&yJacK*c!tr$6R6V}Sgni>$4()cbQ%lx+UuThbI+ogcD-)F-! zsiS8WtO<|dyr<9FuJ=C1I3TN?=+^oF8SwtS(@f03s^4l5fvqe8EBAJM%RfFW=FsBx^O*`HPdQ;doo2ATKv&G;$7f9XOn340jK z0-g7d7_%6`F~0E`&&`#VkJf3n;TCEeRl~;)i;s_Dm4d6HN@ofV&gpAH&ip+!Ypl^y z4tjdFn2VPC_NBDT`c@PCOLf-GkA$Hh2C0qx`s(;utEsYm?;4W5;xbM6O4V3%7b%47 za%UuK!{-NJe-*+3In~o_MYSuT!~~=%CmYyqm9f5A=}+CM=(j4r)Ncep+4^a(8i%`{ ze6s90IPy2#$4h)5j20`}&xpRO0&yQ*+d;XNZXsUT04K1@f`fa3N;*A75A+-t9lia~ zT;{n<;?%frUVE{ZwwVPBv$B5h+sH3~87YBEr|pa4Ccvy8v21I6oEDJD{dba!Vdh`J z5NCh*@#jaU?vupt=ox3d+g{5tUNvrJI&b9N-Ws~}nuPl^uE?{eQGym~xN~7kIBEpjy2%+BkxJ&Fq2IGU)kifDK!EVeebbY^tgcGzp^ z8U9e|ciQqT|Kc{0J;T`nPAk2FFPntxc9OKM^c(bBl5eIV(u`!Q>!^g&^e(@tmrfT` z=0C7=W&>4Y#C=y=qu6a)r~RoDJ5z3qx3t~{cNOGC{a#{UXlUQ13W~Poai#Eh^ z_9`GS!7mTxe&z2KJX7YmLfqw01I&snJi-qTxTA33)S;UOm$>xa9l)+HL&^xW!Nbxu zyr}bCE#GWCJ|st}uJ^f|#dRQ~WAl|=%SDqZUXf$>U;Ez@rmuBMi{jlPoy%FtPrisX zISXQJMfqI%AC}0dek;BLZ>ro8uZLM3%svhXGj}9cY#GvMku*(@U_ic zo%L9>G#SNO*Dc((@^c1HI0z+!e|Gvjsu1p<7|OG8uc&u-pVHZog|6r)y<}m_ve&-}7P!0af0^=0`Ss%dBX-q(Rm&7V_XaQ3FKPzZ&Wg{_(`E7e zcBShW{%nl?W0MOL>En>x*>M(`q*x{b0-OXejw~|hYBPuN79;mhPJ-5mH)C+l(XU#Q zCr#Y}A0L*_1SL7ty4lRo&nJUzEyPLXM!uQ0Q@dovgX9`OPpUMr*^+e8sZy`Tp|eM8&89SP?Y;;50$CS2>9w@xwLt`3Fv0+?=o;F(0?7;WwnvyX9e?lFZOd zg~7rPPJ-t5mx|Prh|^rgR4N?@;eXpCS>7r2mQtKli?eue24RXJUR(m(lbh>J?zn~t zX6BE+YLIlOyYSwO%$#0n`T0HTW~$(Q5E;j84!$LiULwWl;YE}xqonIxx&t9j0yR!< zpu7YW$=J02cJ}zkz{gPOT-o3Py_GjI?U(nuVzousOLsK06`riEuuXh%6)N*&$T`(&iH9KLVaG5bLfx~XP(_=MS173XtU z!t-c}XZIL7C@Wg&mbf)HVgjhf2q*-WCi#}l>>H+< zM?Ufydfa9aDDv=>qbYe?HsZHUmh6w^dWT)~cNZ!7V7;^*?mX9s#=ATrM4kf^MpoX#5zh}}$+oKZcw z@tT&aSN+kQr*gH6<|*|Wa)MX*1;Sr!9XApkjKm0nrkt{e1++AKvKq0^3R)2fd~1Uz zIOlZ~%upPWuN{aKBLU`WMvD2irwY|z{2SfR-jIPoskPxsuB>55u@hogj5GJ--ko@N z&%D-5MSlEx`%^z9ViQk3=EQbZ27#20DyL8UeU_>BTe~bTaei#!Gn;bR1i=Xd*}g~Z zza?af3A!8gMzn-%e(Ao1vPJi@9MOZLIyrNugz4~v)>>;+=U)p;;D(&WhTk3D_#AQg z@G5xLtQa>z%9@YMb4F#q55#!(T1iv&p)Aw1AB$X6(mNs1@|FL&fDfn}bAL8*0fxd5 zbI-0@wagT~?=ztGA`BE6bPnbFefOB5d=jrIK)^r0?i*ge5d^P0b_xX6ctx#95=;8~ zMudSdEAxWS4yClBh;V*V1UTQb0c9PQze@;Qx91o{{)kL>i?w6#uK(-BzddMG+Ry)V z;Z@m+IO%0Z?jZ9RG9sVclsDlN-HVm^|6Wl)EJ0~GP9U%?d56R_cAOo&Sc&P&-{itK>WCi648B{&mqxKYGVBq3{}( z6ANe`qF*stl=$AOnJ6M5$7e}Il$o`gqN~TLSF1mABP(B@+uUoiwNoeHtr1(yR}U}t z`I^A3M!g5hcC-6_Vj=E~kC?uXrqbgYu&ylk}7TBji`_=5%oAlRggDbsH z9+cFly6P5wA5;AxB}tENL_}>(%7|NEKAU2T%F+rY6@@}xWR5ZAJ9kyn<$)~E#oftL z#%sp7dN(9eIGd(Mf@(X+Zs~aRekviwyRhOj_#9Eak!>`lq$RY}l*;CNv#I8SJASA= z14Ti3vHxVys`Kf|x^N~A$tSFDPTz+F%{)X_*7^kfM16R*T9Tr8uG+zZX28Q2kQkJV z1=nnyxFshv5X;B#;>gwX0J4upyV)L@RQynic`q|U%6Cdui*-tt2&f?!r|x4zM5Mh7 z=eUv4UL8f-Hf62)`4=pIUu8Y<%af`V=#qO-zro3YH8K)%X#Ius>6rvJaU?Sk) z&Fw;`TY<-Owf@r^sd#&<$NmkX##cYJ3i%d-tfQUgHaQO*3t--3n@L=(bEabDu;^Zz zeZzcDZaz@B{n?eGwOVSn&jF3=IDczu`%#qG=9RT*@yXoA4YZ=bfziW!Ct?Jf6(?o1 zxy^(Erhjb@eP>n|SyN81P5+u}u$pB|@X4%?k<`2?<7`=~(5=(9=ATH_>Osreo=)u? zu{p`GuDE220mg~1&x)g~FQ$GGR z@92M)ckYcADBvYOW=Ccnm%N#(erBQFfO>;y7E^*pyXqD{6Xn*`DDNS4@eb~%RW%dF z0umve4{5yHgpTUtU>!AfMe`#WzEh^$-D=?nFf|V zV@nk2BI!sY`q85=g?>+VQ1yaobSUr+js;$&=W6l}p99Sy{?=znmLhxkDYj2Xj9WF- z_6>HU%!7{aiX%K$yB*=}K6nJ^F@Xa|x~cLMkM6`Tr?mqm3svv%hzc&ha{CwhY@Y~W ze|^$k_ax0|RHCfYQK(5;wZGKv;{>41i%MU1*@iHfluEm@T~WQxK}AKKQ*cg=@i|8e z&rme%nppr*jU6r3)t4&6dDq3o9gM)p)uv%}V*lu82{OH*7F(lo>p8TJx7+EshHjUK zNmCV7hZ38|t0@As9V2Ki>1wY{VU&}NO(%0wdMa|qC`M?tYoTtd-GK7j9n5lkdDi_` z_C32S#mPg{IBvoB9mUjpBeXdb+Mc`12gl)+S9*36Op023@)Wgi*jK61TCcRN^M6vy z(ZITV-h!lTI>_8=Ae&564o2+OF8o@LlYq`jIX?9FpSuH&@e?O#Gn5TBeEV6#S=twb zO425tY_Cu7)K0rOQR8Eq&M2D3ayNdZ!o{D;Q5>{YV|BPOa0fhM;`O$3+J_z84!Jr@ zjBh&1ZOTdX&q}dq`H%}AOZD-6*VS)j#-O3+i|=Val2QA)&K4aTT&Z+$WH<~<$FsLt zE;f!{8L`2TIvOeTtC*@fg7T!u(R#Do8+&5;R5hlKKc3h*lf zTFy`X)Y0ro8$Onjp@NN+P&%UZ4=lAg3p?L>FgQw078lz!8W+_e${j23*rMhhTgf&M z8Ef1Qw$1lUZcH7Ba@$-I*%Gh%IoF-F6DeN^b8S`_@g@fNPLd9#9ofC ztcs}bPSSD~)8NYBHMzK2Ezt1^nmZ;rw!<{w~3^;(HN1nV+uwDMFPbJi??F!!b*(SOMD=kvtl zC*d~&GHFPxDv8z+o?y!Xcbm3yw@ZyK>S_Foy^)%N zVUilJ)Eky(NOnf^oI>k%GW?9=S6FQmgoAr$6hDKyLk-=-DAFexVrLl*MMdhTl`qOa zG8^74c(~CtzwoaksoAb24fv ztx2s5;y2cbBd3s1*H!GBN5V0bkpB!*e+gj|DZ*c2T5u*ML7hx!swXGyH1&AyL%B*R zsY{NXopgATI?5vn7b^`*RMUA>J7EuWBsPy0tDTxqL$8`52rG7v*o;a^U)~$l63bzm z)H9|0@T!5SuiN|8GwH>^yE5L}514K)OP+~PRERN-x;6*RZ?0)Q{;Huec1h%GoTrbd zLzyaV>yX@$5I4@9DhCTvx$3acI@9a8G**QwKYN;dO93PmB*}s{4 zTztE%{FP(PlSvqH6g6~Z)pj)CXlVQ5gFzJ0yT{azG*>2+5-Xb%Up>9Bb3grIX8c&D zKyxonN(W^}&o5+J#=j9Dp13L)%QE?RDt#x#K%H~s5`G{sm8Y7WbTr$3)Fe&4NN?v#qmyx;Vyi(`)#<#R*jUiLyNl<$K7SAopctL ztSRO9`$HIH%)0NX;8MXHlJfd#DfJh%ha?)#B#=&NQ9mRu2Yy6%JLJ4Gh~+Tl#>Ga_ z8OC%WPkn)?I|C~<-WKiD6TK7L2vt2}%9M>nwC4*^uqJcD*&)iIQA>VV2Wn zJ!0V4NX0XfJ%)CeL+?{)cws3FnLUJ5v3~dZb5_^RDM_A6bzhdnhEcrB*FGz0@+%7S86j*QgnCacN!YJ?Kvgf7RN<53t zK_~M~#uN`Xhx;a|tSQv82}(y6|5eMWo-3e@r-**t4=XyxXepi1=)2Bp>CzN2*qUQ4 z-!lJL-$V)))yPaluGydPckV&OiiWM)>Wh4irw;?`-vN{#3b?F zRNzJczU-XNmL6e%ub$5LW-iL_Z$P7K-*$d1tGFxcJ1&Ttf5k^I!Jo*O76=@KY?E{I zyq?hu$1bULPBu`p%jgr?PtCYl4XiCF#AQ}X+|vl6x%-Lz-Km=AXscycJLSi+AA#vJ)MHIaIg7<7rwtC&30h_Z2!$X1dn*PP z-`6ph)}GWm-w7_?C_3&AIZ4#E*w!A=59O5|tkpfTu8Zz8`1-i!Nm<$D#?D#spy0r@ zQfZ{Hx=`wi=k%2zb-;0Av~M)S)>R}a-fMa>5zA2*ZJ3halXB}VThgOqP zT429Th`P~y7o$T%efl=W?Qh262;2^w{+R8fYu?sUR5Mn6aw)rpL(He_{EIO3r)}z| z*LoSz53w`NL{ciJB7SIT*8oM1;Y^aHFPf3y7K~v7n@sEVQ`vpahO1A-67o8QyRa`u zTdbCvLAc(|`Sz|SokZS6_lI2Q36S^#-$T+-Mu!1=R3wNq9p6*A-kRg$1ly6CtA#Da z%S4fMq6u^xDuzlo>@k?vnY}=u2Q=296x%EXvr;D*weoMnX;nIo^t(FE_YywbqES(nnZu@oP2=> zw<{<&jkl-xRfgxg{cm4C_sgoU#p0%AHZG~kj}p;G6Ly0%8yv)Ny;iGklQ;6hg|v$g z^bV^VaG)vcMiNdwrK=Xw@2qq&2G^I$b0eL88IxpQ-@B&eo?P(ruAauiOz7Csr8YPG zoCbYicOYfGJT!VWsm3dIRjVH)hiughF~MAGuOVsLwvY5T`;04lZHsFAx*IDzxS892 z_EGd#Q1n8rY?VKgGc)@U#$vNO`EbE-&mQ@5w9Ap!H^bK`Xa{dnh}SI*&h!I&6JxZH zcJt21L^9K`BOJfJ>PCD$4DEFQM6cfZpVJT(w@dlk^cfDyU-9X>j}{0iMWYd|%% zjv;!^-kqTA!a^Ktei`63{tQI62GBD-dca|<;?knI5)OohgTF#U7-)Z~7D8|uY_sy2hWI>FZQm^_(urb0 z7rw&mb$$6F5tE?4ppRr+>HWMc0Gf4ljEfe4Zm$bYXx(}(dnH+K*~p~%bCY6@Gpzc< znWrTg%(UnE_DY7^n^3V5+7qpkQt|u?&(I|jnZ#HT?Ha>Ge-&-k`^(p3o@ZZ#c#?YgQ2#`#jDbg8 zqWC&C#tKvpKPjALz#i^|2f@R0(jJE26ROtQbJzOyGmp?IyF~c8=xPL`2q1fLS&fc$s3~ z`V6}W?geE7Ul!&s|2<$waN4rTUer~#fXXb$pX%62EZg~r4{O?%+ndg$EU#)NQ5iTtUl@#j_SEMC ziS|_%LI(bwtoco1tSnX&39WJ+KtkcAxKdfbyKZ1NCc1yd}Rc5S|! zG!XF1FXI>?j}-GP?H$~bxaBOs)ZBU_WpdG83}4@2Rm}WNV3i=#@nt%^+Pn2ymVpz} znscr)P&$Ep4NMTfpzh9fzm-p2{_)vsj!>I#0u5~;lBhAiCrfKMU5^RE@;Jv}Dr6D2 z-)3_|&e3=e>N{!qcAD`DAy&%94Z9jE-`#4xwrF_g?5UG**74ZceojRD9p~wQ7D2o;hLkjGOdJ@r{-J^v_Zvf_g*dExDinrkImMc zQ)D^}r}$_A@7poj40N;q#*L{@J|ROUEu*N8<=@DJ+WJ?_Q*SMX-5j~&rINog;Wy}z zdM?e$4^)M9;wMWf?9frTZ2a)hO<%?^QZgnoxVJ31DbZa9^&k<#u;}==9cAWJTdhCj ztMr)PAgRU#&jd|*Lt$>G^a1vXOM0_*cHJa+@2k~2UVfPg(k}{nIwihPk{pOURlg}K z@UdY5`ek>R*oZZ?;+fBHT9~L7Dho&qe5DgS$q5QW;M1 z!SY$WIZ3-t*$d$|het9tVEBQk!PJrXBVvkjM|qVwmj^sep(7<^`@Sa{A&i)7KTd#x zcZC`LN2apf+2f8+Z(v`Y-*(|wbU%A{94f|J89E0%x5s+ZT9exGy536&bD+P!iA zme$M>WF=ei2aeW2n%*8M@=0+Br%xa4()EfYb)CYa(Yry?j#w09-PO?AU(OWY?Tu;$ z$Sv(gEIH-Up;sa~ojaAPG2^)xIk>#i&Ckc)3dKOO6DZX%bNpsSR1xnmNXSVl!V$GH zo{uxTV=H_}u&dabNED)D@cA99*-rH34RinMLn(4M&OAkGcy#h1qj_T=KTW_+7$*R% zw+^oTBz@cJ+bK=VfNS+Mfek`x&O%YCunOwox38DtPq)o~cSAr8=j5SIWX|Rue~R$1 zQ|(2_1w$sa$+18$;cJLYN2Jh%Bg0nm?3zC$pWkxpWcTpoErZ3lB=meWkIWNS-U4nC zGQz{S&-dL;hc-6TJnTk*4Uqv{wcu7U6M;$SVcT7>acmQNFXPfUF_e#AJ~+Lny%x=2 zK*35gd5x;vmV920We)9>NdeC1`TLp-r4DUT+=YrBD=@B0>+O}+5?wg_OLYTZt@i*a-t%MQ@5JXzKYg2;%47<1pk)!OCNcH;_3Oe}u4lPCGuR=gQX=*%(u>>*1y}J-r${5PzuqX(g zX`l%$l>)CWon?*OgA^MFbX;n}-we9-G+BgVaEeH!eK{Ax6({ zwUCd2xqnm%Sl&jwSjSykg`(rue8dQ)3}oq|W7FVXpo%1AygG=Hcvmola5Hg#_4S}J zm?sc9$VI5ToNqkZZW3CcJFnGRiR~ltor;G7MP4LCzBr>pNMQ{nQblM)uUk73qRMb# zK_tVKX5L#8F5i{{I>e)x3(e7u^v1a8qiRpYIbLh+|*f~mgAp)vLC_}(CM>umWCS< zd&eva#=*j=g#NQ&3f6<^kVbzYKw z=yb${bjC7i=Hx1sl4<4GVN<|@+H$=n5{2=a>oGL6_xwtA1W>TO8?{idAh?n^8+1aM z_2gGTBk9~?+992Uvp4JMGZGf!PC*!9cQ5UGY)=cu23K!c9UWV$n9LvB#y9KH+EvYtEakLk*F6^t&NvEo9w|V{rD(q4!y_URSJvXFq zOq3ZH|4sJ)$_b2j-C3+2kE(^P)5H69HnBllLLY2zMw~Sp17jR29M5sjGO9crclajD zepV!X)SK?AMnxz{)EzqBAV-Px;pZ~J+@ys%E=H0#w;Z;uvHZNhp1CLEoIC1rT2aeO z+3>y-{9q)OxnCQQRz zf2P-86VmnEcXhjMiPoPA7|ags*7qvf;ojmuXMvN$Y^7K6#9N$k_+QIlJM}2<{HLy8}OPn+DxDM1wobFwM)`1Q5oUZW3%)PXRI>I*J%eb(Cd7+&Wn~~2U4@-LyMXR{CcnL z3(D_ngy^64eNIHjB>UPo8{V)I0gEyktctW)`StK>lf-Y8@jp$wE)L{SY6LUuOP$I)uE);$(@~1FoC1LH2Dx7!AG%m80p!=;>b|*_jBs3=R!4 zn&jfpxv<@F&1oi_T8R7hG9fz zF>Sw>_$@Y*vgnwae%JCBV}~6%H5uka+wu7%|BT zjq0|?p+eN#(`fX#9gc6K)V-t4NgIy>xnT$wrv2?OWuRbv>4LPj4<1%n53oZuDzAvD z2}q$df;Fjo`p2VgnJs}`qLL{vRmdv=gv9FY$#CI4YIJYXH3W8AAr4tOmec%M`=*_b z81)zvh^Ak%fGN>PGnJZ2DD25M<@5ao^s7v%+7eGQ>c`}j@CR}fhvH8}9G)LtLFNTc zIAw*KtCgPp6fD5ZG$)kE34^{Fj$`KKJp_69#ID9H86aZ-Wx01$QhH{iRcg+gGa9fn zWhmc=3Yw0?oPvW*{#$Qff-u;bo#cSOLOWgG!tQguRYx3Y;(5&1FP{*CxLs&LG5nR= zlq5zm0n%26IU=lA8&zeddfRD0USEl7WkP2)HiqSHA<#>we6?mM(YBE{?AkS9T|#5C zt%e2c?bSxn!H|wc0`O1bB%0ig3Lyf~?Xtr9q~w)WBPVPAbwrmxjgBB4 zuNG8jOR%Y9xWc#j$^as1?WE*DZeHnT=u?8^>}v2*%ZVY*EU;r8|&SjVJ#EN_YMfM zYO8CX*Q-~mEQtgXg! z16O||UMWJX4_Mtj5bIj-IejqS)b>ZKw@_3Ywg}U=^C zk*2TMxW{_llg8O{awb^p5a5hti5bYN3=XsdMFWve3fMJX$#or$sRa z*rgzgGUfg-oO|x=B%r3gIIGg3Eea#5whMGf`Lk`75fZ$>pSH$us0%slQY2ZP7=P37 z@Vep3*wlh#_=a~hY=;8qqQfBEcT2kGDur=GVzy@JOMklORZ~o2O@3Wup{1a5^0O(F zi+Z}~2UjGbG$JplX1Kv4S=jC$r>-;^CjE9*z1-e-4c)n=@)6jO_>H%Y$V3-)tpK&q z=qY8HP1`N7F zjnrc1tfe80N9K^%N;-mp(mK5~@LGDDi0!qS_O|<)c?9?CK(|=<7D<7cOOdaoM2@2}1BPRZ-unh?O_U7dZR&#DQ z*|1=c2{&?+T8-3Ns)Q6e@z<5|Z4;FPD1IGEbx6-Gl|>s?DQ2ltJ1X^K>C=xa^A>X- z(}ChYAfE0BDH9F^zq9mp$Y=E#5gvJ%vff9F~;l zt#jWly+Qa~4lm7nPW}+ph$dnq#-b^dy~U3^xBHLe(spL+EtfUf0_%t{Z;2zRvm^Zj@lrLjLX6G~ zB6EJOd=3k%EJE)R1fuSNsjJke<{?+`(FILzCn#F%Llo-)^_(-s{q4z*8$s~PeL}|t zVj_1O&JRYIv}nYdkg#3^_fBr80~_mbQ;Jz%HyzlS9MA00?`LZTVMxQ5p^J+XtGcWY zlzV;kW`=TWV;34;+%spy-sS|dm~C%RsL?t|-~gW8rp+DY513j!&JX$omck)cJ69}; z-WdBNzsqor6_&WY(8!laj$tZS0%pZ>CE7I+{VhOopKG>V0-&P~!imIA2YFQB&b@8B z!yc0pha;|vcgLr%4%GkJ^jha8~!9!n$&N<_InCooTIW zIZ?_N;QH8a<3Ik|@EUM?Df!oXto0=k0L&>5YqPZq`g86AN2@z?X_G8&Gh)xsJHo=z@RbG8EWhwiyeG3_#N{!*pu`A zc-B7I#QsSb&_b&3G*d;H6;NwF<3ib1;|_cDQ5qawOf#6$4L;7h9r7r8Qu!DC`_ls+ zE{Q7JDGC$tB|1p`L`h-Anf5(3D3;0mR+tRKAFaj7*K$^?KqrGA#m5%q?kxl1{R3a2 z_`;Ff?xq_BC~DwvHe>>=YC66Lv$b-%j^`yT=VRfKV60Jr+s|FkdRXYF6)q<& z$=hugrt?Y*?~#urDh+~XBzi?rJk{jfXT}R}b?44@{j5y`NxEv|P7P1sv8DvcxK~!X zsleyPlxy8wl71R}@;t2qTQbn!>VtS}6PS{vH-^>U@uU_dq%O45nY$_RkjsyVdjxPe z&23vXm3x<0O9XIOZco4C_OWMKHlp@?RwkIhUH^_fvw|qKgHfcOh)Uws(tXXlkgZG` za;nD-p0zyQj6P@#7dgv1B1eJGt$X-{chQWe*!F2z(-e#!N zZYZ9%^a;`L)YD*rA=8AsMD&TogOIxI!E4fHs|THTYe?Alq#W(e58LM&=`~;3i<4By zcQ~7_c31>fZN?K|yypb{{Z?+4NBV2}ZL8u0s;^QW%Y6f6vV`r~`z|t8cD2_QRNsJ(Embc%xqq$mYaboh z^Tst2lt#g$>r>hp5PgzrF7jPtpR6Is){z!$YPqe(4%C+$m$}O_C~t|SVeI;Ejqb)* z#>CgcLms5Kz6(^kaYlRLnnh*ccSp1wRjklnj(CGTV6VBcFzW62`n0+H7kNE`HF>?1 zLG>#rR}|1K8}CRbnkM&e%C0~a(Xbz~jOudwS44dj&#w%k-q;$aMOi+F_#9JMNn&HF%yr~G66rBpwGGa%_qsP@RvvuHbyR%(rpzeK#z~ zvt{3l_?@>Ahpm(HKaI6^o_x!B4~rA>For6EFpAuk7C_toKB3*-SYG?_#bc7-u_gir& zP%x{Twh>;AApSBr5ic{;tiyL4jHsD%a7dI*%`~Q6QYoaufXgS55|cPVsob7~pX;Up z$Nm+BNX(JqTX$*1-4U5Tjmb+p5~k0ncz)qEC1=1zXq_W0kz>AR= zogdGX1wn-8#ThWifhlO-in6?)i}haXQzOCSID1wj6Zec#r++fGM+2N!`S;n}G~CzQ z7aOzI0cx4@-+vA9_el_|0^~QxpEP-Y5017(>G@9JBK7XMgP%F#_CeJ%QFCB_Uj!Uf z$wGm^NT=9z0v6Vdb)I3opMj`AA4SSrL^torY!q~I< zjCH-$X1^8tZZ2x;foB$VIJ15C;uAX3E1zXoa%#4uxa0>B(z!zK$MdgUlD!1rGsSXu ziv};J-h0G^m!FX&`zqZ|q*7haw44=wfKrli|Jv^$zTo&a$3|hjP9PRAy;%^=QPNxtCHieCW*=CK$>l8XBYNWdZ5h4k zSz4lx!wg`tIF}z6_}A&h#Kf{?T?&c%iSI+?A|X%#7<^gWQcFE%EI77Yb2JjacULQt z&D*1Vab7E<`UMnNxh@S@UVdi6b>o3$HZ*lqliNmvZ2*(hvg#v?nz0FAk%zFWd>{>d zZB=eZI~^`}`A1;No!uoPt=fOZcCR0F4hg<|s*YrQM;zFpnYUGP#I#>z>N%%O8_Wa; z^X0;_grukW+?bOo#$NZW(;Twh_-Aw2!j@9wHSM)lITVKwm%^%Dx8*laBUx4nYg($< zVh1<514Ij{ocU$VDT5`)hWp+(VRc_9yE278JE&qyVYFWRNyo36Dz5m%RkT~@t^c)c zg15Ci8~CZUnGkI2HSOO1jtD=pLo0>T$4DzIWf%Z2Hp%$8}`JQm_tOEPt_ zIt_b7#6UFVZE#6;pdJ*X0U@dds`tMmpKy$PjB-}Cx%D=r++u^Wt>~wWFb~;%#K$-z zuM&qjr&zBgv~stfY~5Bc(Vi&gVKIr=Y*YfGhX%jITt^**TJ7k5a(T( zUj0`5v`){wLLhz&^Lj1x=8*yE1TGgg0!F%Gb$6ZLsERH3q>R9N-hTnZ>45?OE+RU+ z21nunSq6@2ejm$Uxq>WQB4|N6D>R1H2N*P|J~o0`Fpg{!fY*Yaasa!6y~={atA?zf zSGD`)@9szUz3$4v==i(D5v4b~`n4RtBC}h`4{ZTG3zJU(gA%06jD`dl6QxH#y7zoM zIwLU^QBk`BS#6t=H|g1+qcd-b-KfEp8;Q@$h_@=AWybnL{0i(hD1A0j#cm(JNc-q4 zH&Y^rButAT#Q8804KnwTFDKaG!S7$2cursUtw0W`eh2i;R$;AFLJ3a{d)%7CSNI>x z-nxT~w5;~$W+YC{PLJeX02ENFS0p}9CAA;OXJ8F-XUJrHa{KDr>2)@X-)_}4?;Q7H z)BqGJSV~aoe2xT?VEDG5z#l+yw{|4R;c=N=G5U-_eMxeD=z8Ey;Qe3?!Nw$P%xyJ- za7m}2`BC@y6J=>58ERhZ%aI}nnOzXAR6xf}a72}ZzJ)WKmzQ}6xSXZx?>L^@@c@9q zu(+?$A-^~Z8$uZiNV+R4snLb)0Mg+YqgZ{HZ=?$4l?G~lCpmO9b0Tx>5K3D6K zn7coXR^4%GV6y&4buX`(Yh3Hdyq5P$(X7BgTV4_hLxj!3s>P%U%y#Z^>)}yvZze^O zxMn-TTqsCvS0aT{t?Z1!7)KVvc1o&NGW+dUL9GNP2VCHA?ao8~&KBfy_cY3l^w2+= zwVFER7{kisqTshC-n$vlV+V4x!rPl^)szOS$W=kBV1~dP^w9V0Kl9rsyUVu6`&yjk z%dYZN#h&&7oZ!%I-mZcdQ^vxT7y>9evlbYJGjJqP)!)@rz6vK;??I}h-6&!OR!%NkZKtWvek^Q+aqIh^yI6@0uCUsD$QuNXC0ClTU zG(-1fukp&;>wPDCu|bouq_ePO&wTkT$)3>RqUsYmP#nAS;P=2{#(pAQ0ju&fSv%+( zfd3L6(cWFKwST17lj9`(oq_h_bUn->*H6Ff>a<@iHZh0=E*ha2BWVzRg>qa0yqL z<8Acs9~RaCx<55?H}5*fh#-jM4WM}WfGCJmr>f@WZaLGI9`^xBH4iG0PM!#Rnan#r6jz%aLyi- z(bo}eT=&)E<_1YFIy{hqeD)g759*@p;4G7`& zM%&35t<Rj1P7vaSOHPbi?-TPgSLCBfUS5mvvf$gWjNxMJ~teh>I$|$Gd&moK2 zHgB2M5zVi2+)g_gr-%X0Sn#%$hk;i5zYlF@A3wWJ$fBf*`O8kAt$*V0%!C9s&~5nF72gn@Ztl$=fe zz-zTP>_AGvre>fc)R-P5#8?0npeF$6G)JYAjl%3O?IMY%?6m|aEvxfIlN~q*3|k1b zyteXvkw@Iki$LG!Ml3Q z5ue*UIlZJts?0c+kC~gNum2q4pIOZ-lCki3VW+_6d!-g!m8sgS$O_ZDyHEL6s%q#U`_B*@=xicb2%;og5IP!3-tL? z9`c)cv6y`N^FF*Ha}-a1;rH4(T(%0L8zUv>p_Mailksx||0B0O8NHhkqWjj}jbwB! zjU#1wmojoZUGfpHJrnN&w6{kJz>KTxUj>W5Q2QOMm2x}$6vy%JAV!&l z!z4e(C9u`6Nx&m(^`qsj=%=o<;tF%kA`5Cik-Z<8) z=hs*=jjrLkDnd-frat)P$A;WO1nPWrzVZ}eu7Rs35(i;bb`7I+&-gLzR8ilna~ zTqeoChV%P?HrkWw8I)S@DnhjJn158{X1kTOWjRwv8RsKD_>%{G%(FXN13!nI# z(U(aXJ!Ws{k}cb)v2bdbxvlPn1QzQHIDrhKEkcv>l6`h=OcszmEYf@rr}DU-s@4F&R}Zxx{+?((T#SUuwqpxbVqVxQvtP_|)qr46A);arjI z@;M=sNOH90X!GaF!5U0VaiNvvo+1%182-5)tFU6Vu=E&L+O6NwC<{@%yL`0Ej}8{65)i2rfV zY-vUxzVeF$)t1iX5iT7l7yVxN0Bd63M(Sh8jf`V#QkqysdNH1Zp(iakoQTsKGn3tQ zoPzU~7z(D6g8ur7=0h3LO=vwqvxCr3F$%p)%&t)r1|D24pdSMb@_n2AQe)$YP!_+J zazn^BZ^2n|2+OKF{c(vzjYVl z$64wy$+9nMaMYff(5gJz)wo@FN;iJ?(?z;DM&8{Awm=CHj-+F?8M%~PBcj$eK$N1xnO#>mYAS>Bazy! z2|B#prIouDyGcU}5I8AOQTy%CmfJrzwY%P6Bv|>8f3~Lvda?hR2|0&LqRO1rFsdb) zYt%19m2O=zEm>ye1Kkw?OSx@`Nn`SB_kfOE;zN42<%}8GmqXQALmMG3CFEaBhtFd7 z>nM+Wz3xGX-IW=|KAMLrg$++!iJeygi_yr&|eXy1)ETSgX54Lc7B!k@ zj(u%9&AjLs1VN=rU;+O)$sHhwVaI-musI{1cvbI-Fu<(Mk=O^4k_Kqry4bcA_T5s& z;DCp0ywRg;DQIC8c0CTLB8?hkkIIH}SoiDphNVB6>e)-h-}kSNRvMVi_a!EHY$atU z$L=rKaZTAqpYnr35e>;6N40Io0u=QLG451hDKE=kNoZv!8l%N8l z#4&8wan^fKi;gEM5`&j&y#VUKF9ITr&D3f(|=V6dGk zU&a1Er{XV>OAVtq_x<5XZTX$n4GD@RjummQOi3v|+dmINla&Zf!oOY3oA>v{@cRHC zj4kp+mCWB5giw=__`Vqs&}LuKfzKyl*5Eqq61AiEe&gSGaEpLfO&47r6*}P@^{^LQ zWCDuSgB(xeAd+O002e|(g7ceqXuep@7D3oLxa`Qt8xdAg0vj6v0akML^mX=|g(xU^ z%7MTeYd^#oiXd5-9k#UK(9k_ZO5N!3Uk5%Pe-E4-kg5^2d{Vi!a{pXCDv&=%YkE6(Ph|C=kBt=m`T3`h$QGs2U5oG4n7 zTt_l-;yHx>^_>6pQAtbHt$0AJfa)({O6!Ylib9X%=KuxI(#Pph3c47iySSIG2yNc} z`Q%k+qpjyShYd)S=`;vfwIgRCupMxYvLS?Bb<4900w%*` zELKkGB`t}p7(e!~Ontfz%pPLwyY`hNh$sJ_Gkr6Tk~fwSa%wmy!7gMFC~8*;b6zLE zv2#BDjrq1U@ARK%OQ!=kdB~TkzTTrpF_6esINC1!?ZU4K05e3mU)W0tTJNi|ENoVe zVr^<@fcuEWrggI3lLCQl%_86%S#KgzWt7VbEbJ~(3s$uxzoSpvs-cNW8LR^ahNGTlgR!Hw{n6!qh3r zzn9{_R^3_O57Qy;kxCKl*LZ zmgvPBH9b1v3blSi-d|=P#@2(JrPx(Se@uDb(Xx!6HDynRyk#E&Eh5nmM*TAx{Ld}< zM-BnLT=fM!Wnk4bdiwgDBDrH&89Gd3IX*ODb7I=X$!W~s<`*t?zmpV9^t$Hzp;mdF zn;fkM8mAm+SM^mz~x29Azgs&8&5ciMe^H)Irub1DB z3Ja`(!oSq?bGfixt&h<>kQS7a+;P++e!HdHKrZn2`-|&`^P``VA2ehZ02&AW(R>_$ zmbMjLQJA{=fe8Kfm--Lje+=M5y!^%L=7+M7jw1rX3L}s0Cf;9l<)iNIG58 z|NU-B488_3So@jTIQw zWKma$|HON_|NF|4z_ynHP8f!zD4c-RRV9w?&C4)C#?_bgk(pffESyD?U_gUg#3?VD zXp;x%#Pw!-nwWLP>GkA+mVf^z6lI`|22NNVDY|dZ^k>16nK)(>6I}r3E19iZLZGq z^3*9yTN&~FKioqESWY0rpk~JvTa4!(oaBZP0LD(>w4Ep|pA#1rC&lvYI7Vk%SpXwM zRRFp5*{#$6cV;WU*(KGx-aC`DtfKu7dE>u>q=6a;PM8-F5C?d)U4|F5R!|7_rYDoyJ4jO+g z)~z(%=4f{`83HzwVo@W&RLWPKPT$?iNPfhdoX~mjc?lZaeRtkl^~*k26ZXd8+^sS% z;QLmf@!dbjpFHiSVt8mXbqr(0i(m{Q=>2IUlM5QeC1@`Ms z-uM-Kp>Z6cB%@u1K;nmGFGV%ILUN-}BBq$yA)}+pjKov87z7R0$fjVd}_=l-< zUO9O{;ZAyg=4UeB7hG8fqra{D?2xdvyW0U-^7Ip8{6;t$&qXgq676a0lG7HAY|+DS z!FU#BJ-sVMqtqu)yOqI2|5!}F+bkbB*?HIBpiDsre^-?(1z@M%JaXt@9qTo~p$3}< ztD*h7#P2sm_MG=QePy8*j)((Py2q4`mj~}2r~9gF-P5l$_p%}gKA}UNz4!DmvS54z zR`nORwFn#!&a!#RGYqtVDiApfWw2^}^2*{UR#wsyEDY4BzwA=WWdIyC@&S;xKG_45! zv%g-=<7^hW3DZ;+2Jd|_C*?xDCu-Yv)C+pRjW$A#;foaR4&! zrjGHCq8n9N7P=_3Y?HKpumi(}do$h3;?lt6vb6T`)&M1D&22L$-iKrAe82@S@YoK; zoDVR;6Y@GQ#L5S+%QE4f?bZ6Z2w>Xi$^lMxZqT(U%SrV^F-ncPm*$qccXlVKRDWMm z%r{TjPoj=5XR&gyad5}&fL6dxCST;=ZL1B7*w6K4cR(nS@UA}_0Q%oqzVAr?KnyZf&bIZ&o6|OTQRo`55pblGm#(Kd4+}TbK*@AIu_rrhk{V0SiSS zN+=p+p*!2<(viDfagYw~cN?;_cn@~K%&X|et_wBCNy%?}DAsKylIbAXy>+|pv+G~n zhjVW}zXFg58-vkg$|bx0!Mi{*B^d;CILXi?6nj2+miI3!$$awm)3vRgv z2_@>!b3DMe%Gu&UZ(h`n&xTmQcQnI@A2o;yL3=mNcEiP|SoDe|$-{G2<=IhfhWC+N zC{*QO!RpWqo??a( z!{V0!5Tl(Lx157VX?u zES_X2xg%z;e~!MGBpV82z#-l$nT;XJ9MgazbX5O2Uz5IvV%q7dk|I4wh49-bsqq{m z{b?+I%V>;WuoqG5=zG^uYc-WB=w&$jD*U(T1d$40{s&Aq6-2kI;%nc&Xx%z_a-CfJ zvOn!1%(Hq@(5asq+i1aU+g#P1lsCa&Y$uB<^~HvqKfL~eANAk_ovOs=I@KrR@jd&y z)DtV(?6!qX+mZXj3&YF@e$_AY@g<*JRF(zLRD~)& z=Zi)h{JRC|OBIug^Bk(zZ0m@b>{NytB|#C?pACs7HxPHLdO>Q(a)T>RC|ceJFZw#O zSHWkK{Lt_H0}p_EgW2n78KwzE0~gVR#(W}k7Gkn_rK~zYN4b+V#>rIT(sYkR>nqzb z`C+hIVJC-o2$B4t$(W$Wd`$B0>7B}ddHzUt?9q7;juyOVv8@TkXR>Yvyr1Hy|Ka^~ z&YoL4zr3gj5ZIFVXr$UL7^|(6~4wmAVJkMne(8 zZ`{YkM&Bcy1_dl6YhxrIOL@l_vulNl_Y>wkRcz|FrsTY{_{>_1*tY(yhMjt`P>mQii zF7*Cv7k}n_I``6hJZaXZ2qZmt>DE|#R0DhJHsE15@t4~a*?>o29H`b>n%8JIj%qmf z-Em#m#&b3Gb54_JdEsBpR?3`zon#rt5A~?ZzE{5Y;MX`GkUA_gjboPqs)goP7fSt* zZ`9ypuT^2c;m@lo^SN($`7QtDTsx4WuKbCcdn-|A;(wr#e|ARC&C{E(=SmRr2{n`` zhV$AEmm@W>gZVkFH%X)FHjl}nc1G=%P@xl-9?U-8!yoFm$}oC7Zk6f=wJ?Rd?EQK7 z2U@PxD8tkuFC%L>r`OCAgGZ>>%(M+ zONrKvaKicn;PJA|035jWZ1VEW+Y6zs=3Uyi6 zN7TE`1yvcEZ8+Eb9;ah+FONoV^#*R8>&RV|ar(v2skG0ok$f7Ey_V)w_P9HXM)k>_s4Tmt0-CMtH*JyuAtg$gJZ2r-KyL|7ibbukY2= zZdZt9?-IWe&pIN7;34CP3C($1+tYf*7X$ePN>6z95QKhlh=HFk0nRhx_Wxg2f5UJZ z($8Hpo(mn=zMoEi*oGQ>|AdbnT)3tq{#nm|qxjfgFt-zt8vW;*GN4PF$Y}^X<#ZZf zkC%NIdt1mAYlx^Y1Sr#3teP5V;*TW+xBtWWU0x zK{-4RZx9sBX_KslsIW0l;G{O~2r#X>j$p9}J-92bLpH_VpH64&wB0yyzUM|k0LHwT zgc%>$X&}t2LIC64$*>P`f28Kct1lHZ$nW>Qi26eb0HDXDeoMsD4SUWpN28;AXiL2d zf6hr2d)FWOoxdx#-Uy_Z^*TxGB!{tZy{pCDZJu36uBH_=gh0P4szpYENBLm>HPMh| zYDIV=gc}tPau#W`6r)mfp`MOl6<0&Sn<8qon!=Ntsn@mT39cq9jeB{RXk{=k5;aN0 zW#V}GTmJT&=?Oxzkl{jR@3QJxTkinMIAS?g8zKeC!H>N8sK2cT0JdEMg~wm&4;_rP zoeHstw7+bg;Ku+fZ=gFg!=lLG7sTT{9<&5{79AI0ZcetPI!oH7TU~f|KtD*!M(ejD zmCRkQX0he|e*p9UCmbrF@OLCS(Sen65$Dduq+-JQ6xUn#LZ6Iw!#+-}kFk5UV3%Ge zwOkP%>Q_$9I&vm;0>)z5HI(XY#jJD$6p%<3QIg}C>;1|*f%CWoL4*^3H6>+litag_ za8xinSYv%}e_Du((h=~leJqtq6E!iPMRS4_M7~8c4n%Rno7^x5x-Fc3qGo)H#dMOV zV-RCA4ySHt%a#@F5jM7{?wck2KsHujP9LAIE8<~7rsE=1XV#21&KuXYR!e@zh(}O( z1^`l=>7P~!*-uPy;Uktk!?b;_HiJ&d>sEijl@p+ZGL;s<1GW)?Ski!w*mC{|3(Se! zC&@*&(7422V)gmVk5*uc^kt;gO1$)F;|EtkUwaEk@0>!C`Zb}s>1N?+Xu#EAZ$}$W zMc9!mZ)7;|m$+POaf6OT_1v8Bmpp zQ5@&o0$6SJdw0^>W|5bMOzqiBs|K^oQ6AivH1+x6ce%x{q%ci#oCCj}R=tcaJ{~%t z6Aw*tZ241AtlHM!Z?fj0+pBMijRI(%bdOtRNROOc*^r`SJ6h;;ruU{Ck99|@oO*dS zy>QerX(d^QrEz5YNeNFT3YmEyPx#*#&>yu*vbNm^){lsPcsNA606brmPDIOitC4NG zsu6MuR|nu<=(0QoZ6MhK&ao&3K^1y2_E3js*8*0$#6|%Rx^Bg9N4J_lwSSXJOFC`L ziLxBFstVX#GMhcZ1-iH+>97I!IbDSwklqf!1d=)7Lf)rqFN^F>&9lT5vAkd6AZSui zY&cTCWA@?BL2^XR6a?cI%*dIRizitAEpGLTu@+!##Nz~Dh&%v}=&P^4-*9s$r&?C` znUBmI+()QnRP7>xW=4rIwEer*oC?K2;jj89)dY|8cI~4To-V$@Q9;d0JOJ(*6#xf2`qy~3A<(=eK0RaSnLKM77OKR|s z0Q>k=WQHUek7QwLZaWaNrHfVSld^g=pgE<-{OSh9Kh-WnqW6Ol4}qGhMUPV2-JCh! zXKVfB8E|5ms$wt4`)1b;I2HiaWFf$#Hn_i5VgI!tZ3L*_WybakFBd3JsIlRxP^jdU zp*wE46pDcB|8JqdJ4TPj(HcZzgB|fAveey3 z(~+x};(uDm^nW+NB!nlqEr#~tfh5h>D^kD&Ly$}}*b{c>X`|WoG?o4HkFW@%F2!;r zy#X)BCvOtHYJ;B`!HVy@*H1M5YL~xBpp?2i*nozSrx_~XRg0eeL51}hBXd%&7C&vG z)wc>zSB52hXv3t1xJhoc9n<|FJ;t+3^Qq8Q1`+h4?k`B(Gk_(4*UR`f1Zi#rY(Kr- zeIPS*7?XyET*S`YUt`!Y@}5lCuCop5<>DK8yt(-Q*n8`!DA%@qSP4N9NkM58q#0?X z5fG4)5F}<$kuIeh0Rd^GMq24cx`vXHc4!!2=#GJ*^LL}${XEb6Z2i68`u_R;_}1Es zwP&3BzUny7^SF-lisB135Y2b})F<2#*BwXlKybVQJhhBLaN}K-kF)};^cHWNjaH$& zEWdS%Cl&1T+VJ4<@y*NreD0+Tjx*T1?6&Acjnj02$_`-p_oY+eImaAe5VHu7$DoMb&f(=yn%7$0A|-)Hkx@~+Z4I)0L%Zv@8DWv zUoN`h&7qfl-mNi=`n)@(bfXUzQ zy_V093LY6c7Q9CTl8~IUk-D(R23^o(h-D#mwXJ4W-Z!rzGjLStJA0u=eAzck{p19% zz0$*s7@+~hJ&}~l05)$3F#?-6fa!i}#;JeS7p>TXCxlxmYSq9o59wOwK2s3?K~5Fa z_cDG#MhoZ>ztSh)+@ZPAEMPh57=mANkRlml)U!F{E*?kHCNFqU2v*gLy8q-qFU@Ie+|>fV8+gYK^=wH>-%R@Y^! z+(esa99^Pzvjh3*s=v68F_h)=d+68vF;yRs=bU$lZuc3*slCGP1mEUZwoOH_r#fg#tVy6PzA+?mi9^Rl2$1x$_V_;7&VH z1bzVx%{7pEoaw4k#g$RX5BEG*!DsjYibzD>PF+pIZl;8} z?YKNU(Bx-+m=A2L7gPX7gSm3UHCgqIjJMevU0Iwq9&(n))EU?t_N`z6IIx~!*Ypq3 zO(O6If4-~mwDR?|ZJY%>iBk~Enj9Af?%G+iOrF|_I+A@4jXIj+w5pB7+rl87+ESaH zugH3W9>NN{QnLmweh(a|e`P)4_A`=J50M8%pe)_JVlBd!9GC9)20tAllkJ&;l-Dm_eB45?>+B*#h$=uW=>-( z-^P2Kvm-s!(+P2ODyEiyCUC?*V7WrdtRWzE<`2@AVpF8??5otO7SB-5^L|&q<;S1a3z$2+JUGbwKlo z+pc{Sb!|STi=N`b24$xr%D>mmD~y)hoAFK&xlF_NG}$AdSFF^7BgAx&t|MZO_xD~} zjqC?2ASVH3$Oi3sT)u4(*mJizC?L?{Z@HJ8@a?b?Vv8sLyC8-PwRLZ(nEjDkGh(JJVqQMWHM*93Na(gb`6Yd0uf|0 zj4h(v*`8 zmyh(@pPI+m#y*!UH6i%OW88!C7%MepF+lsP?bOgWD+GGDsX6}`w}_h<+5H)*7)tT# z3twB9-3#>WUacC9J#c5Go~Yx{9#m)j{UQSiwTpE>m*zFn6`*1`-ZHK=&neF(i-9|m zz53D>Wa%KUsp@gqAd#fKOz;Ar)D%fJ?7s*8-v{+SQ~i3aKZf`qyCa&d4Y;CW`Y=Tl zGBY!CkpQ?a=&&-tG6t?T5A?7EmT1AlR9Hd3ot6GA9)v6Y$RRvu4^#UE_u;^L^QBF!3GTU%Y#ON0h;LkK{>K3ne3 zJPfuA*~CkTeRzItE8-z-f`;yIqwL@6C7t$r$<$| z?(LrD$zqC2gXH-v6lVfw-$9hQ5sb-kTHohY!CJ)4jmc#npZy zLHat|8{HZOvz!khrP}>FmUPKUi$Ut`&(>WNDfF@`q86D za;~K&wv9o`W&1(q1;atqn0_>%P+yi`KmFH3fB)YaF`ZMk-+MU)g%SgpNmh!eKCj)I z^fo&^@(M`PZ7?m5lSAs+-IO+k)H*jeCoDpVOPBxQkJlAe36z@q3ky`rbf7t>9o!IK z*DhWeT=;RJX|W1SIUhBZt_tB7HAFL%QbjKRzBZRI@D-mMOQ($s9gJPs%f7KTYvDe71_s@Cmf!V!Vf}?o zYLq(tBls(sol1p5h1JAEimb{nEww?byD6O%)s;gdKF}&!QHFqY>#Z`#LS8R4=Mp)NJEAzERh2a^Cs=0pbjh+8Xow_!~ z!9y*MV$F`(NGNU06eDansHbK=Q8>3v8b03&F;fIl)&-SfPo8otf0Ps!quEFst%eE7;gkUBbf0MBe z8w9R#z&AzBwAzj80)IVC`PVx9GT&TE&QgB~tJwdNS26c-ybxw+^c$RBpyc^ER*d}; zM`7mmJ%^rl(B1;&Z184d&=t;&HedE@vo5eDp$Qu3VQTBry!!%bN=ECR2B<=Yl)E~{X2(Jy{nSfCB! z`!fG%^FNFEgnK{+v)i1UVB^aWq$o8xNNEh>Pjq~7y)lS!n*0xgi={aA1q;Oa{Ea$a z{}-8fUD+`5&PLEb_?BPYgB#ueAo^=(ps%j4KL`sn&E54|^wGVQAjG->K*XhdNduEy z%SI7yN8PAEc;+UE^QR)n4+^h<3YdcZ?ko9sT|KAzQwf(aLLgILa6qhcE;W^q`(v1X zQ|a*Y_1AxBGu;z~hKeahK0dy=NnO|SN@4>mJ@Sc+)p3=Q7h2U5v43zCmoU5tQ5;Uo z@Ko7vzU;1ekZ~7${WyYTa$E^zj9*>!Pk4BZ0hkToRr#IZs1|H?q0O(iL_ZY_XEfr8 zLfEnE|6nL|5*Lq7)Hv>YlWQsGIiOOktaSAj!Z4b@W&f8e`*&2`0UiVJL!LKq18i5z zUy(TFD=z-0ZjXCw-KcPI3uI4U)gaRuV#+LqQiBq&{-JK4xbOhnrKP7obu=AKpLVG< z`8Km)9~o~g^h(*lVYcKC$hd^zdV$%r%uECqWSmH^VI~HADOD6w+HyTZ|wkq=W(CR_7M}GhR1%Lkk~x(Hk0gS==u7e=&p)&|N&1*d2ZFYpY4_ldp5PZe>6MVmqV7uW# zuH2xyWs}}aD$^NI^*uc&r$eZvxp_p*fTGUgapK6x`oYQnEb?FV2MiPcq6KeeTYbx| zk(?C8CR4=Zsx^9x&qvEZ9u&pRG}Gqtp9bDb;wr#QOnPJ9y~8p^ zl;?A>#6Y3OKG3u@1_XjpSXehOFwmk9IE75&l==<#AMpJAM<*#K-0CBKDHN(uFKS`2{o_=7Hh7XD3w=`=aTR%*B5p*UkE34q_ zTy+X3enrtt2*X-e2|)h|MS!&z8MOKFK575WFz?CVDot1B9EwYOMR8!`em~yR87rP%jnD%Fc0C7cLQ!@sfIp2CMOpL_+ z53x&v?#V@z9GjIfR6KgwW_JO{^j14X~Q$9&z2j&e(c#Vz%|#f1M&g}!~bE7ct@ z0KITzuVqYAQ&TOM)KpdJk5Wa!rBt!yfJ<}e_!CKzpkuzMPLn?Yf$4)Hz&v!7^GZtx zLRSINf;>AXCt@&H3qf;#j3mQ$v1i+~|FR_4oXDRHo?JMIy@sPj2!(hC4qfyt#@EDTSiJFS$ zmX=W(PTg_~A`bDGq$JMy`T1gtQEuTng)kb?xyX-aUfy%B{;Hw`!)L>UH2cS;q{3Z- z*2#HYe%SxbeFRf3Y*JbLbmxhoVLISU`(kdfv9XoRR=?{KuLc-u|IExwU8_8qAhP1R z)up@F;v#XH$MreA)O=8{gO$~A&<{g9UYD7&BI={3!qzM^ z>{lc>skrd^kHToE`?kQP#zCRW#6(2&9~Q2>TT`h_%n3+dc#X{alIib`vRT)o>Cx&mS`1A(qpW1IUJ^l;jCLb>lq@JO8)qZ{K zDZkY?GvI*uUtM@f1_lNv!?q}i&R|nr;)!16L*E}oNQ7g}#J6MfMZ2+Io>MiyZ+!8qe!-K^wMa+x+d=p;=kX?HwJ((?Kz$3V?8dX4B03 zBKpEE*=nM?9ce>MQBPz1b66xeyx5qM??6L@+jVOUR~@vEP9Gie3-<|wKDYGYGq^$>NZJZiH_D%S_PUk_n}j_+28c0Kz!HCDPft&GI0e{d8W5g}bKH%jxTb7>29BxthWgDU7R&Bi zpfMVkt-FWaUmXb!Y7wRHBX3;gV91bAs7HRAW`PBA3leLpImqEDD zq<+<3HjWD+6gw$=b?Z$rYo@M zyz6s!W>f3JVJ_0EkQ-gmwLi$q$`3lYvjqQ~lfw#sE)##{zK(;%@!mS%gI_d}Pi*L@ z7M6^&tN*kVjJv2s^WG>D7l)$75*zoVgg2}DX=bwBG$8xLwKo|jBV9#I9dCDfQdFe; zDyW5}jGhb{ZXYj-f1y`Yd#Ir8)^;6zKD1J6<+k%w`=Cc_8dQYtjb~!*7iJne)QZWA z%B69F_sGgT>hMiH>Wq?fXQ+}ghZDAx^=esu!K_@NE3oG~RTD9uY3JUl9H78#H0$0H z5YuPuRMaj*fNmS=KL#dIbiXE1Q*t+*=E=$BhxhW=mp!Y5w0aH?BU21p_bRB9;o3CE z%Nw2w%i^nbqBL>vNiK9@>`LuC7j)9xRUhdvjT`G?Mq6_hAW#=>++8~#c`%yBNwV1u*4UOYLNk#qA7C?FV%@2Ju49Ij-Q+2Z6Os$WeV)v?kCo#knpn6md-+l^LDH#GmcNxxrr6 zg2~UGhgGPLba}TVw}X;Sv_>e5ezMIh&kMKE3928z0x}=UE1FhtbAvJ5yVnuJq07L; zBwQH7kRa^R+{)pM>s!{r;$%*J*u_tjlIxq82+r-N9#e7wamG zwbbDb?7K&u_KVl|AX>x0ev}5*2a!>6NeuPL!i|2k)krOKoB1x?tF1da8@EK507fY!|KnVG(&eraPG&JGSpQR`P7K;;ZiZRQhI@>$;T0bYsw@ zx*t@yf4F`J9w_P!t=>CEVizK&<^!*a6P{l6e9LrVy9B#(A3A|faN9b)Qj-l#-DA~9 z(BftKoW`doR}Z<_v>s6>)9-gt)U-KNcu%#+|I~O)V z^KD{vF$>)g%jzj_at`_}uyS1r&Ydi?nYm~NWjwA>_R{tqMO7W)0L^SNlWET zZY?OoswEK`Ld2o)*)rO>eoH{qXp#1G>$XiF9J~(m7(IP{sH0o`FpQ5bKXRWmW8;$w zZ;z*Gz=T$3;OVLH;_y;P>gR|X7CE9OI|_As%~!1ft%%~6lGE^k{X25U%;ThbqV}nu z9{P&~>$r;qg9kQf8fTD3z(pmK{`+Z=SQdPi(M^24@f7S(H@<&ztX7(z*IH%beBZr+ zslIYxuYBnEVXgQ;#&ma@F4@TNzzv994UMPv&?9X#7p47;Ny($wH-z9@fUMwQLPOIx zIX5<|<7!r64Hgv(^%G(nnqSuama9+~T@Tx;N?iO)C&QPyn7xfxzWF>bpwZsjTOqFV zGS8qb^de?l#Jd+kdoBQp4mawKYoD=X!Ebrn`_p5;EyPg$KxA`TC1r_kw%-D$mT-M{ z(&P5ReP>?9EGlMcv@DV3rYeiM4cL_|8?>{s5KH?FteF4 zFoK^k_pyA4r-QIvcAV`#h0kfn;;P%FnC-;sj&>P-^mn9+r0 z8B50WdG4hgob>~40p-ppG6W4P&Y4YOnNsiJ$@J-5rt#)RnG|Z~Z$Z4_ z1Lyq|&$w}6S6JJ3*H%$J7cy7MJuX}3#?D?4g=t6E-rgiwA#viYIevRLPKnROuztHU z$dbUcB6ZSW#YZZ)TQt>=K}c-Mwn7=YK|MACPVz9%9^X5l%t(lJPBGT%e?2!E--~V) zg`s0B=84cWWv-{}`Ze+kXB)H;k@{;8*5M@gI6Xm|w_wiPEMkt#1quV0;MI&D&LQMN zT`-*c_JMwVBEgi=Yp`Zv8}s+LwQxi=Jq~*zvXri{L`CImA(~=7BJYk z%DtDC%D|r?AF}Vf*vYpLv~Wi^PC=kF*qn9o`Z`-vH*}jbgX-f@)lj&Mx!!6RrJTk- zwbMN9tInZy?g=dF;bdWHtx-^y&%&u>sc}f?O&;qGi5du0rRGRd_gq&Y7=IicXR9zrBCq*WWP5tse!It-6N=T(_6Wgq4!Kux;#`zic*-X7 z36P=lo49|mv1|;?t^;0Yh*JTkaSh67z6EZTsEMGz_iM$G5&< zZA{jJZ3W!tb9dW%Crid-0mkE;Fn-@MYeJ5;7Et^PZlkIvlp z4Ix?R&iXn=oxrs+Va}}%58q*!N2`eQ2m;v981B$?x3EK8se7~c?EbLpXr60wWJQdT zbLTYAv`;cI>|N*mUz1STVhLz@{@kEGc#Wv5()=^W=t}-bSgh1lh~4#v)Im=WYzmqk zPYGbp7K!wa2O0aSEMXHFqS{Gr=pc$?{0HU!jJGh$z+>>%mYpe zJ_!$-A=63VUiGpVD)T{+A-63{!^eKH6whCDV}q(!VwRic*67{WHP>&aP6r)x=k-2J zI1{g_&!bU9rEKo+JJv@KY}R}|#yV4b27StWBeD}kreAS@tBr ztUFww94$5sGPzw`=YBkP-w61iHekO0$tHyQ!(VD3{}@oMZqfQ$(r|zN&2ro&;jLu?Jxu^eAii~n7+OlQC@MII!gnG{dDf^0r4>J*oNkCf7r&Zy2|?93b5c;&c4}}?0=;{ zqzeER!%1!HEz7leMm{&FQnwqk&)Bv^BX#=gEy+SR0`Y0C-otjz8jea``uKo-s2~kEqgTRUHx9v9<}3a z^87JA_M}Y|%jVf?Z0h_D2{+8%0|#`}s?de`pxZ$-+!kKg?erFzhYqbMjFrNN6bKuC z(Yv2gFWOApe|&_|j~DOvbKWU+^FpEGw|FMk_8Lwm*3+qse&rjwT5QmELwHc)k*-H8 zsqp+?!BvvT1d&s9+tx6H)QW?IgLcc(Aqj~6_jDgWUKcc;RT1mR&Cg#vSy;?{wdWo* z*VEbh?IVe+j-QgR?)){9k4w;{?GDxl^r=B74n0l*)?}+(gEt@mi+bVG9lTq<+STe! zeA{82w);HNu}~Rs#dT}?bUNFL2xzYDd|`&wJ~DLbv`x@1I@n!MrP2AcGXN4nC^L@uf1IkyoeNt;iFE88EQab`%yDmb7_TwtH zKw<20w>hm#drbP^afPiv4V%w##?l5vn5wb!CW!}~?Y$(6u+O4aNk_wKw!H_59MLsZ zCh-@s>$FdJ^mv3u-g51?>xoBZQpj0{9Nl>@x^dU}^q)yeCY9Pmxbsq7#9+w3vuEgocVv71*T_N+70 z@_;K#rC3DJI`GhQ=?vBf9F%tD_TZMDUVkPf5@zeSv<0rY2x^N zl1V=yqXp6D9r_=+4GK&vQ|Wup_`RX0(Jz1Hp9CYYcqJ;&VD!XQ^#Yz(7RUVcBgn-L z9$5)mXDL!TjC-z4lc2VZNLP|%Ojs>;Ztv2gZjAOttNW<&vopm%?ZCSt(!c@1t zp%e-1e+#=w4FMVc9hT%FQ3dNd&Z{eN?EeNTj)-P_LTF_co~^uG?khjySvS`cr&fQ`#tF0Q3Ya|b zp5B~YXacnKcQM2eR!i8`SDLZU@4@Uhzdt&2KK7l=Q5_b&v#MxKHf+Z(Nv;0HAs&!` zw5!Al_snAcn$-zh_J+EoE;jr?ktC@J@lDfCE9!~-M5>AWT9aEP{ciF@TY5V|=wWmI z_B-lrx;PK=Cw5pGO8j@CU#Xu9-xGSQnTKFkD6yHJ0BLnz=ON5peR^~-)4PZJlvwF@ zk*%WhRm(9-BkQuSO<~yvZ94#CSBoUht>1~K5zv`gV^jB5>0>^(beRO>(i#ULK^NkG!JknLS)RFJy#||F;nN$;wNNh58kWi)AnAF>NW_ zHTxkN6)YxEGKqBqP-MDdtnod|9HL@h+klp#F$~m*(kMZm$&M@PMti2}+X@O+%cp7P z1nfr*p`ss6Hzsx_H4u&&#_#<=_GQaW$MUc$&%wQ+zRh_BTTpdj2BU?_a-zis6Ukcb z3p{nByvkC&n8FDL{k$={WViVB5WFnLZ=AQZMIQy#Ek;_qabhzf%wg`UWJL?~$sUu{ z*oE#!lZ6XS(qovquECC0l-3=2GJ$@=j^f9m7HqjFNZa+FY;l(ZSmA@zdOQ1v)T+dD zEL;eNEz1LNeh2<=3U~rG>FsNw%?y>*QL1EmLKoNgbXb<=sxqoqvUvew(QNkUM z5H_%XbL!x~|LvFbNk@1KD6K*7u`<>lN?Xx=JC$Bnc&SbHziaZV4PFhnK(b>&&F0P@ zN_&FDzyj^MV+)G?lH~razQ5{(_2}&s<9%oZ$=_PmuQL8sMXw_=U?tNgTf^2LvTAhq zfzrIHq7rcbP})GnrA7sJ{mY@hxa~hx-wRkbb+s#fPWr!V@^_s+)dB0wR*tW|cKgHN z;syhyJ?CU(^8VG@e;C03S5P|UdBcC{(q$QWX-SQLugL#LVKq-zD3RHG;N!*!lKKO< zYOl`Ck#Ab6r#@3b*@Qy_rsnCUoo@erSdR$-c(evAiM>|Kav4%|=w1#^oH*^w%Yh8T zv=+pkjlTOs|KswCU9NY5orqt$bm{#3syn9oufrAACUD-8w9vF|)qj$M-tlIp8)11V zt4buPO4Q<8K0F*lDSgXjk&!cFi%T*FoQSP=Y4^8(;s>JIr@6 zf+jcXjZ}tsIuAX+7+ZOF#Q7&=HU>@A?&8AaeEtNodF{6i3eI9jYr?gk1 z(7yGD-$WT-#sJM9E|qNlljZ#NUAQXnqucYZUi{%VPm-{4VNr{zy>)+bp^tzcy^4zT z{X4Pr-*1#~CZj{CC54F{hyG!dZ{MUtMW`y1{p8C3{KNmhll~ufl0?AGCD(;U&HU{v z{MK9I4&AexQ6uZ@9e&YK?&iqqSn7#_bfm8_@_b0_^vy$6hc?fJ9UsTC#0s;eWaQ4y zF~9pp${kP;!GEpwl32bN)xa?1y|NrcY@#FD71cKIU~e1;NmeP~S~320Z{l-yvh@;q z{YZtUA_t16>ql&PBIp%Vvu^p6)iN9<#io^CY-&q3`tCM*4I02>v6A3>b@6!SEJ?G( z%rKtI`a@a$+=qAQsG$HxL!|P!CsR$et81^*X#)|z)7-wyz1o^ZdWWe3#6hoPmBXiH zn4V5&hP~Oy3(I(f6~f90-)#8HQCTjc&ydYxrt6Tu-QC(VksIOXcH-0RC@J~4olwv$ zIi?((>f&K=rH*IlUT>WKl;3hq{iMt4s5fKh+L@L(+iMS_AGu&=F)uQu6~weF-+ul4 z?y5#bh`DBoHXd0GxKntZO8wHsX#yTxHGn{X=g$>JKJ6H7~*J)&EnT+3>0djI*ZSxNsU z)l2;o5iX>t(Bc=-HCTb`k#m9THrR8P0ZD+mci{viK4YgeJd~u>AY4fQAU=Xw=x$X) z&fd=FT6!G=RP~Je$h$$oswYGs$4Fpj$zN8E@**-kj*#fg z*j-;x7m6)d$78*gBfith?7Ci(tYk0OQGN6M%F0+E&cqv*ETX0YgoTk$fnclk4khQ3 zO-rhEK7yKg+Ptme9W5O{!DTEpV!-l=)!P$TuER|52FD#Y)L0@qzUT_?4 zCPFZCo?hA5SzJubqEtHm(7q@xYrZ~L`B&48{bS&^${u@6VVx^p&|B)Q$%IbY3S;HY zB&)6qlA4)DgCos1&kJ@$9i#Xy(`$l|&1C}`=H0t&n(w>O+f3qPWhznm8cs!tY%(fe z8-n`4?F$k7}^^L&HjwMx5lcZ3fyN&i}PRa zJmZj+!Qx2ab&H9yvf^R!c4!4oX$TTSCA;dE zeL$YZqDrtJ#KrfCfC&37OTzARI6I0sKTmVFV=qVHb~aay#@@H_yhz0uW9UfrE(>Toa-FTQF zGy2pWTFS}+zG`{L5qp*S$J!(u{tXHYjdualed2}z_kAeoMQ$mXtS&rC{HB&d*n7dzxo!3oK ziZ>UAH7LO3&I-4>k^YWE5})jFfr6>qSf(}oyr7P4XGY@Hj}gAI>+_3B{LgeHy`ZcG z^Q$xnf%0+=3d91X^(%XDfg`rk>+`M5j^ibtU*o=~a>-}?lbNolXO9Hk?>bN7MBz_>I=F!dg z&Ax}GQ-k6eJw@c=N0X&zCxI@)b|a<==8G}?-%n|*HS&wQA(aCeHON(3rminq;-@Uj zA#d$G{Ac%-4E(6(Jovlq1Pj771LlnNDFR9=Xv+k4*(`j2N1mucpE#Q*@f_KAufIh7C(wkR zkUp1cJ>l=PKGLfL+@-bMdOdp?_$woU(QII!fEKYSezyS-e;bFe>eb$&UQd)Idx&qJ zkLiPM{(Q@(M!VYCCWdb)WYXG9?a$v#XeMuzHE54gu`n?uVBQ;s=V1nO*%o@f2dCNb~ALRKta zCF)V9#iG^0DaGc_d7jqwigC;0g`Tnj9S$L@qZ59zLLQTF!A*7gX8!G(+ za#2^m{}!%))n>@}?&c?}ZnGYbBBhUFy_ubqJRZf2%R3}0U(J8IIgQK%R1Z)7OW$kd z1G{>on|-p8LuG0cw-P;d1P}wmi#v#X`+=b%}-n!~dk z2VNX-*WoJzk6Z5*-()-GJ2^(4Y{c+%d+OPTNsU=7_Rp7_s3CbdyOTE(4(EgoEN9|u zU!J(643B2vq|Xvr8ncF}x@+z>*lv1GTmio+t;b2>O@6$8I}w>;c$3sg-nd4g^Gz_j znsZmFb!kt^z`2IFX>o?*!F?_L1G{TEVFr)Bq-IKo!- zL({U`BIh%U0S>#fn+K1z4~(4P^=*d))j?-ImYXrUK>B1c=RK8UC%W#ABjPsBQP9>w ztlejiHIClHj+ZB{x>b0q@p@w8)D`2rXZa)MPY>*7B|EPw#IIA1l0Y5Mk({1$O0-zl zkc$rhPZ)mH3-yp5ehV}$Wc5ZAVyCV@KOn3Z22HkAla=n2BXxpbT1p;wcc}a*(tFdb z@_1fFNnn}eCis)64gAB|j0pTVE(5O>a*F&CR)5Ym%)Web!(4K@&XlgNM(_JWf$PN4 z))U>{wj1soG2R>rve{!ab*T3v&LB6C3#Wh5eyx##XCkpuplAlM(`e=(nZvoWzc%AA zF1;$;dEuI)*z)9O`#Qi)uNt;@Kg%bGFT6sSK zZ#rA{RLb+}#=6q4PIN($1F@dc9Lo2`CI2`0H!&$vc(#Kgr zBL_C<{>@|CgYHb4=ZSjXIaHme%6jw9SM}$d6$EN{KNYP=!z=lnjciCZXto1Hx!vrN zD!y)ptms@L1eQ#3b__m~kwKcfJN9pVE17Y-_YN5bocYkfpR3z{1pYqg`4IEe%#{~q z{cIZ#mR2(Xuiq+6=*Cy6H9qYX@1n>zO(3yq(oJnc7-ITe@c0VbnvG>E>FOB1H!_z? zc{V5_P&L_~;#UfG%@@XrFw?dZo-^Wmc9 z=zQtHCc_MK-`sd5e1U=&Ik;IZDS;{I%tWKG39{H#gI}t?gyO(jviQG-YD}fjSQ2Q&yj{$Cs?IfHgXfa9xp$sn~6j_w`TY%AbSZ z)!9gejVLwMg4~#gX6bbvc>wG{uP};MkKod&Cg}C$E4zCmrk#F8NXfEovGty^#sm{# z2gmwIf&}DXj#l;@lj;2@*!Ol2;K4E)>t_{y+1RNr58u_k=C!S^Z_;^GYF&LFE)(D~ z#{BlP+kEwCUDay9_rXMhfxEJXU(B~WfVtS2^Nwu&VHm_FjRiL??w9y?WK=n~nolIj^kCwQpXD=k&yyENgOr7P>*Y?cr`%ec9 z(tT=TX{kG1{oKqj{XAn=(bM}2)1OoGI%yCHBg*06?$jfw6(l5CgpJIJB~aGFi$&yW zJ?%A^$%MPIt?Bh)tfLLjT^{xOZ0y-skihB-L)0!9%)~Ih_B!Nr*V>bPP->o;++xU4 zM&|s+z>&r-AGY?6YufPR##@8?obFDQo3+60vMyC8`@udZ4CxN4?&_j&QsDZbL9YGR z0t7epG*o-j@Qw)>4`%odfW`K!YEylw`$hdX#s;mwGHz6GsCFKFwMs7NKTdM~LXeYH zk+BlWb_O<#A1E+7E}QI27B2%(Dw?-X7f(_;M9^yr=YxqAt`Q26Z^E8RsfQyxC*76n zm!tW!Obl9;int0kDmxOx%0gq5R*#(rnu^UgGi`P?x*SBAsR`;ySk3}^>{X{^7TG6) z;8n8rC6UKs(OdPB>` zURG1*dUq<`j5p?+W<>6xn7`CX{Ga;pEDBU(m=gTk@bBrYf%<;W`hDVTtZFV51%`$zormReUadZY9E1aA7lxzjV!N9TK z#*FY;s90tjC+DdYvgF2Iq}^qj$#7&lSVH`bwg9c-lNNnZoG3MRRUuHik;atX<&CVg zW8u7c>Enz=A^q{AHJrV!W8{)y-qO7qZ?&V^p>h^xzTR{-b=9Nm;1Slhh1*N63Y>!ZV&cijNNB_mrhYsxuz6h^B-QMy036x=MIE_ z{=#Ts?;5sB&G-D-#wDp2(9FXh(T#$`JOPg;VS(bwJ0E=7lFb_qP4W*oeEC$w9rcb{ zsL9LZG&-fD4`wMQcMj(KuR6@9TDN*9o?&i;)#(c)!aVbE)ZI{ACzDG&*D&y1_RVS8 z)d}TT?xjS8%9aLe&@^qzk~(Eid%F}O-69CqR*pS)x_gfrj7niA7@%b<#{+A*ml!?@(A;dgvig{tv#!eT~C22)NBInJy#v1EYE!(e_po4*^e?tC>+Ly;+b#b_OAw>=%th1zgg0KB9R( z3_?ulB@^lMf*CUu-I4Oh?{!(b_2h-3lQ_4YW||>Z8};lrFLMSpOcqFLYRpg)`PX(u zlbwqU^8^FJ^Sl%=>t+$_nZ^&ik4gy)+YVy&%z1o^4xrjo#Rz?>+sATF zaO7evOaRVnFw!BB-ORh7;O4x&oeJLA=|1hQOgyvIUwag1b!o*f`Eg22{IpGVjh*Rm z)c^^r*>sj$84y_|=yZX(tvAM%$O##(X9KPeXUVf_Ts27b9?TqN+D<$VjrqWgB6jDj zZ(Ev?@CupeT{WgSP?r(dAFO$pzKM4iEVfa2g4Q^Dwc;o^CUCgpFgwOP_$Vc1Xw7V} zz$T^U0oTy33#xZQX*YMG+x}*mjTXU&SLwPnF&p=eE}vPZi>^%fy^>~x$%WKQ(h9Lm zMD-~%vVrwfRLh%fvE`I`ZTVGd~}htp_a}34FFUwW!=5PP2J( z4OX)0%-DM`YjIUV3;IO$zPx05mWca2SDi=NP#w5{@)q8L%%*IZkX7NtKoidXfNMpr zIXzW0$~85}IvsM=Clc8X~y9gP=iVt&5d*IGYN zZ+ePQ)=b%gmY(cEMI!d<<6o`55W3*rffAn3D{8al*-II2Zr=r?4M`nn_&!lhY>LpX zX&$v3j91aIPCrlz;U8?eU&p09(uC@Pij}ubQjxfe>^T)EAhV-Buo{ma7E`90dwW8N zS0xXf4?>i;RO|`>1>|VSS9ZhDm^vb|faAKIufRD8HsqR)r3V766KWuNe5)>59;rBR z-XrKFP*aJR^dM<+wGiS=o*3>IFza_`N^f`yIy~icXDAoWq=lL1(SM5$tDA2l4z6t{ z0SH|G4+1xhZ~f$*7x{XGnjteIROec5dX`$~@)adOTEVuAGE;Q!7>sykYGT*-BzI+B zk2O?Wk2O-jT68eC1&P819qm^wO}`^A7gAk*mmUE~PURS8j$4=1L1?(RHoI~pL5D?}*ue(a-XWZNh;+T0awLVg(*Ij%-OenkyQ14J6COk4NY ziehGi89^(rWLBSSCYXdD0R|prX@;GXBC^r$tq3n3l#*QTKeJ=$zfrZ&ZemkFxf;+% z-fYC)Oi~7U%BC6JhNLiXyna?mn5-;ju38tbqw}m#KITZVZDG~FXP+&s&|g}Yw461# z5Hongv4CZ8aJ4|Dkkbv#_W1Va0V38H?hGfB%>obQOJON43_6;{rZ1@30V(&4Qh5wn zW@j}oeiW_{;(%mJK3v4chV+dB_;qp%6Rw}(1NtDNhW4X&V{D@9ByHVI*RvwZ&c{B| zZRf7x-*9`HK!tSj7cF+IA-g`zh znZ51eHb6l{MP&d1N2DrXp-2hfC@@l`*8~yiOd2}q{dUY_tJS7s$bMtH{gcdb(sXS zmCW{1U7^0?3N?y!rXJM=EZLk{&aIJ2f>CuUn&s5fhWku>&`z>~m@5+*^C%Ft>&U&6wAgHVvOqJ%j)m-r+pP~|-cY~#hH>rkQ~CKbpjqM_rkf-L zto17$Omyu82fWlyeXz@4n9%vbbX-9|pzjZzqr!YwmDkSBK)6UvUYb{%GGDMzz8w)^ zL6u5%KlJOaE9u6kDy21R#(}V*7)YBBY1QS`_393d?57zO>Z{IP&%BwVEJS6vw?xak z{hl5&a)-NV)`%o1ap6m;WQecEhZRSeXZ#fjcD$RHjT8a?>X-s^-9zk42=BXk=S2sH zK(D%_scK0!QuOTX^Ov9fzArJ_Wl)!_N;!oucbeekr$f1X%Hbz9+9gw_ll?vMv4}V4 zNqAuhSIaHWv}A#;wdI#egR*&L%i8s&oD&MRzj>ZW>{A(k&7O2BI(o~dFB`T5%=Ruc zJnbKI%Fxx8gZ;S|`fm9mdvZNDdS+%bsizY%^~^vpR!aW@xhl)y zI8h92hE#$7?lMgrHd1ghx5{**t3hsJ1%w*5r2Xj)^a=06{z zwPSNFiKDAlWFlYTU;x1MPE|7Vp(fniVyCp?n)Z|(VxHmapyewi{1us(xT*VXpnrsL z;uGf?!Pp%&`sQ`zQd8wAgD>REZ+bGs>@bx9vl@Y52Ly9dieOh&NbxD3Tyf@D={{VWQ|j!!htBNzIfHsbTVRQYh! zlLgNqbA&Har%b3@X5LoAtsg4?^V9 zZC~W-WNvT;j=lH&Q5H?4Z8XP6k=A)f5Ua#dbhH= zRB-52wTWBb7~B$%^$llX{965Jrd7;1>Y$;0TZP`9G4|lBCzUF}55|aD=(DZ~87caX z&+Ijf?A%dCzL7v*v_e$`ixB2rmL#F7=Ea%!0%E*{$zPQgC*^tilP*%f>Lyt_!5&xd zKJQgr*S2h|Q6xmbY?LgKw2TE46%jL)c3~w09pdDY%+25pD5&)qkBY?iWjos16r_kI z+NwTyaKgzq5dZzjo6rm;Uk7w${I#s;FT#w_zRFuBh;(p#JcU#bCD7PDady2v?wCEo z+7Z*~q1^^zOye0(%^lse;oc5Day07=aq2CK$=qvSRSPt;GWaju>yHdA|+x zUeV{Q&a*#b+{2TNzVI?m=7k8SEe*GY+NDOa3;swc-JxFO zWAEMv8>MFJ+7_qm&2+*1?5~lHL9*$JXKTan>$^5#{w&LV+}q%4&kGuHG`F`<%#Ylk zXCh(6q}R#$I}KakO7^DRK&>NhP#_Ri7cy`LyP(COz}O0ljG#Jx?mv$I?%HyS|523T zNA@SSCpeIZFtFQydppmLU+>Z&Cw_DDploez0z&O4TsgsiJpW-u>*W}>jSAVWScHhS zKz5r$r482LZde!g;~2Yc&H_;!MQd7|9tOT>ZZBhg2$)S3XJo!owegSW4~j_HDzc?J zDQ%2zOX`uQ2(K(PKmGHFXYs6HPR1{F$zO_$w%$##pmsLs)S_e`Y^J+~3ko__++Z(v zGZ)`*W_;EEM6IT63Li8(16r%CWz^8`>)XJ7ZW~x{$WdXbo<8N@ubGYW$h>Q!)2Z*e zSZ-=Z1Z@C00YvR`3i|dDk=72$_2~D0ONmPd36>c+$*=l44Wz4cl}3ryA4dhF#FwXp z=XfvvC^|~z1zG56@@`Sxod-3M*`;(iYRf|4;qqtp5|!tr&0QYOJ*pBCx;Iw<%5h~xqJ|~`6Fpn`x#2fGHOZ)ra(fVwY7|Iz5qirZ6N~AM!ZTR#1~cEKS;beusJQVOjUHhPsgS z`Dey?9LP|<%6Q7lc``6IkP>b#r_9(bh=qPhPZ{tcFghnQoVGdi{c)NZHV(1Jk!C@3 zYn(!qxuN6DYSJr?h{SM>bgIvnhA_#PY_}MTyY-2DgWs56->a3F2<#yrkJ0_Uw!BNV z6$|U{V|Vm9nHf;lMqn41M>r_#BKdVHgGZ%@JQQ{nsWeLEl&1tfHh=Z!13CO#F1@`= zv9t@F1#=R6*;6AUTlY&A;`qi^N)#mm+&jm}qlgn-SSfv`>ILiMbX~4i%W(x_n@Ik_-Kj_EM%C+vFPwV9Aqc58oz64sA@2 z{I=ZOqJ!sxWfNUiWHByofXPad|U4LGAbdseh@T;pN@{ zvk*6EPW8zOsXZUf@!f0|CH5bL8qj|RWQ}EWXPdXp{O4n48IFqDo|gnA{3CO?A7umw z&tQMDV_bgC{k^`Xw{j?5ulYfu{WEqVaf3x^XMX4X;!5t-k}b+G)2nB1Vd?%EOgM&1HF(O=$~?qDQ;s@2{**}d@Q6U z&-^1hofPj*EqZxk6Om+^(H@-U-rL@vqf?wX$|xKfn(`&QAp*C_n;-%We_}`jVM23J zV?e_7%uLKmK#Z!r$GTHBu=L?Y>+8l4eW*s(UhNYh^;FyqHOyvOCHr`VLr9ab*p%n4 z-HwSGNEQHNHu(q$8jhzI%_-ab!@p4!=U?rK2p6Wf77)y(mI&49oY|;a-EMd9bDrBc zR=QZ)Lj7*ZC4Z4OZ^#S%_z}|gJ`8(9(LphX=eHjQ%@jMCJZGZ+U|fM!DXEfh8*pBp z4@Q9c8^C%75(2=Bc*D$3UV6zFyWVk+A~HPvF-s_e2Mvp|;Mc(GsY`sW;oO32`!Z0ZdKy zMj5Y?#k;XjdqaO`w5=8f+wnT5s=Ry(y1Brw@G3p4I5pl-3|m2q%+?P|Q?0aW$q;|I z6%*GO1BLF7+!1EVS1zUpLe+9qG6vg`EExZEd9XF>N&pMA8ZvJrq_|yu0Ih7@PY}mM zS91CqJHaq+w@hxVtt=`QcQOl_jVlz8+4FBaOo@(;OP^77XE`ZmQg=tAtj{;GHn1BO4#oGSGuVSvzZZ|&vtXxlig+jA*Ocme1`1&f6O?OeQH!S>VpqH5tF zV}fJtQch95dCbL`=MTK|QW!D>7Ds=}H~(BUU*)zXR4xjJd{aVHym$aZ6%1L{Yauc4U zwpqnGU>AIKImK_NOcO%%*f&duNo#7Vn9TzQ`3%e;pd**j=@z%3$ zkd&FvtG^-Sr~yaf(Q9H_8auz>KPGwms0ixQ)`NlubM(t$7Rqkl2Mq=&aRnuoQ{g=^ zj4PgU@*AV_dMs0^Cdu=MJh{jY+FHcD;rMQKLp8DFdwBE4M7jS~SLVcYn?!;&5-V2N zI_V$1d&xD8jPb|{BW&4Os`VmWQoY%?y?`xtE0^ekimTyh+7_P_26W)NC*3;xEA{aY zqky0PD8D1H_`w_nW}oTF1kNd2)%8E0-RP+oCC8wguLM@DTxp0{bUsN<3937`(D{Lb zdXnGL#;t28rH!_)vGD0ojXH(PZf zvzSKr0`8GGqx7pU9~qqUd~o$own}iiq^VOyT7d= zOzP85|LEg;AMbG+?Z<%827bH7Iq#^KFppZz5wrHy?20rKj?yv3nDc4cep|jQ1{y+b z+JZ$yZ@1<7)=0R}HPm;`>kBG!6|TWp($?^q@nsUOssNo-X=1s1@+>eC>=$RgTjycoLT^K{?l17gDC*tkryw zdl%m3?kYRVl7?UkL_JK9-~do*qUI?ZMOZT0qikzw{Z`6WS3Jm zd$Cl6%9$2cnkY!<@O`%{)awLGN%^?y;jfC!;q-6j<=GNaS!eyx`W`y>U`oD!K9WuM z%ZGakhgs5&_^qTat$k+hy?t4q6En79KX$uIso#}MXdZ)S8* zZnyfwEgv++QX2XDv$SAYRB%Wrk#ve!+Q{nJ4NrHyNZ!^_N%upJxe@#);HEQdM{~YJ zD5EjxLPUWdXDuli_e4uc+7idH=ZaO*4)>tua5*XmeCY#AMKda>JSwMpepV$d_&iC1 zrEbeL+fI$tQyy8G5^Q6Ramjec&aWp_ibt`_?`U94r<`b`N*%0xsQ8*2joU;j&JH=6 zJmENal_vFw*h_((4t=Ad9rx^A*z*#+$V$z1-u4giJ-3Z`W;_hC8v7zj78P}&UC}dR z6M^V-e5Iu3Z}CrHX$L*Gg#a1%2|k8Ln6X8b>&glIeRAb9SiFNtuY;42-S{Z7#uaY-!R}K|2XD_;UXc3JYU3!#K zXSY|o%0>lkFh^`JX1Y2Z^;pCXl52ICWD`B2Uj9+@m_ZPQ&_9h*56u?;0%bZNbeh|~ z(CSeJk1VZ`dw(l3n$$Vq{ATmpSE7CY!Ofz)Yezv%R}M<+9>2XoZ*U6u57PlZS;Tj! znDzHB54HdO8ojVW&c9;VV-W_i~oGQD4WLHBxTCj25^$ z>Zw%Je_t~%bMyHk8n8I>Hu2vq`-jP22667)z2CXm z2l5PCG_L<@cIMob<;?{enhvcL9N)6m*M_^}X|JF7p8Qwe3GfB?K0ThRlwIUo%TxVR zI_y6`+?hX~a*E7MUN3q7i@kiy2-Z6Ez>?z^*E|rW?srH-yZZk&Zt-8=EH4f&dVDw5 z{a4SVl4?i7r*26H{nsDmW%sO zD~n{H=A{3(N&la0QY1X!mAf5al9z8*-S8eg=d+qvpu8(wMENgcWIg>c>BHfB7k(Op z{445Q*KeZ6AtTvlQ0X$tDFq{Ja_{V5$&$bE=dRV?sXiU>j7E5|tXwy%^v;)C`LX6R z*}5AzyxeL5!9k~kIvLUQCfPnmzX1BREZ)h!V05rS<2NY+OBJA9*x{}n?gI3)$8?LR zQ1`*2*!f8`g2bj*RPQZrGwU0F+dS!D3E71xmdof6I&9p=`;SQtu?&9JbC)hzb9`yE z!ljKLbmf{hLB|YuPyR2XKPDVS2oj;pZHPX8ju7Pj}lm4+qHYa?Y{WWq7kuI%mTOKol zBNMqk4ke*>!^Y)_gd-QuFEobNmax;-uox@eXRNj_L?{s5?-@(iHiS_}GKxrQ>yKx$ z`^DR7LOFe>7~-${!BPxA{4?qnX&6u_8$(b>Z1f(Jp6ZNIv4A+6V?NHk;^fGyvHPHH zRzqIJ&M2tFjA(P$mIW-mLDHxkubU2OjQ_E?G^&qg-B$IIaM^T_C?~2fyv2vM=D$Qb zj%H;}-t=3nms#`OZ5FNC2=Z7}wfdn_EN^)XRN6-v{VQRwXrlbFzDgzsk)-me=z*oZ zhP?$jwGU=kM{nMZ?&UvfKCgQY`A&r{EV`a50y9v}W!f5GRs@sYVQ9^O^|E&LP`A}W zm+4}kI51rzKa*T;ZFcp0#qzgl$s4j9C%T3l7%mc3Xh>@qv>I~kC{DH z#ZqE9O>pN%^i?&8XL=X(@l_~hkvG1txM>mn&zO!2`f~ag(DVmZ*K_S{QC%A=i|G_| zN-msFgOah@ypUGrxs8^Tbu=O?pU-p7W26v8V(jB?C8Al+4?4H0k*I9vHs7^2XZW{< zhFd7#pL2!}3gypvYNB31L_7<}nQ~+AvLu!#41X)LH)vk;+t%I%?4+WuS1bgc-Z33@8xEP6L{KOH^#8{yDHmEe;}ifPLx@f`O=06D}Bch-RqkkC~f# zvZtQraN(^*?;*sNt2d%*95?b`GdJKMLiO4-=q2-jn5#ax3f|>M!iB}HRc{ij>t;ou z@64wiTl=z5wMgp+*p7!Av+bxfZ2mn*xqz6nUIv5wVBJmZF$F zHFXrW6$c{uNgvYZ{dds&*YbtcLX{&>j62cXXB(XD}tl{E+LUCdU4bI$Mcg6+C{x1Rm$9ZeaRxi&!5$cqXSng=u!PZx_qHQ^}>F8UcFH7m(H++9Ym)O12 zmt73YvlX{#^4(p?2wF7RtjVI&DAv-!-NScTbCB)yC6LPr$cOhAn(j$)cDs1}uvp-* z5j?;H=-EBL-GdZq)`aHv<{R(sXlmPniM36M+5@{dbioRsP?*POIJ0&}LA5nGcK{tdoG$3{N3d-Zw zNdI}=V8Vo4JJ*i@lY0Wp)Umn4^>hF@AW@>Y4#Co0Lx9Oq)COmyTSNVwq$t_hodE7@ zx%{$#m+rGY#kJ6RaPe&03KzO?#&NltI#MCKzhAIb{-^+%G{y(Nj`dX5liiy2s9OGF zmi}d{-UUo0<>5a$?5PzW74~mWM}0{U01vzlbpbqZg)fIf;{ko}2Iu}hFCgu&`566H z622rmLerA7gM)?kuYyYU<+f*%m)IPE&oOp8>ZMBb5Y}-t9xt~g-ev!8Q-3OB@E?kQ zWk}!F>cHFzeCX)}wP8yd1%sp^Lt9>Mcl?^5chA!9_O397CwC_MnQpbXozgxUNYEAB z?x^r-;oE3g?nay*b_1vBAk1F@{lU#+^*i#u(1MRbsu@WJMSsvplk1=h2@M;sL#raJ z{WPIhfQE>ww*136A--M1^D?)=BF_$FX&LH?YDkg4e&78fp*VD#EWTMM90Ok8(<4DYo&Koj1xvdl2aL=8Xk1Jq(UR7(1)AZT;v&4ITI%RXAV zfOxK6W&YZ4#dT7Torx?pI$SwWC#Zy5&!yZp^UkkpbMo(kKOc9PHfFv0dhHvN|Mr*= zVH=k-p9?Py^-=l9j2(%QArKrgIK_&m-A3_4e+KhOmU6v z3?Yc6y398;P{s?W!0!CcE0%pQH&zmg-6(a&S7ct>x2nW$j0VbPc%eAEZ~iY1O;^n7 zS=op^dfTM~^7N%j%+Tv1^!CEp9?kIJQ~5U@=MkbH(cU+6lw37~7rEwSpS3b@A*>`& zv^VCX-3SVw%Dvx9fJ7H9Y&t=FjjQ0iqDH_Jb8pz1(K~`c-&XRzp?&;7)`ZU`e@Vv( zf2=o1;ZGCGSF1kxu!G^bn;NO9Zhj4QZ4Gyo3}YZ=9-DVnDwp`bh}Vz%<20mS>r&S_-4`YL<+!=}p3nrJI-aCEd;+FKIM8Si;RS;n|Y z&(2y=WXu|QcD@UBRXcT6UT9f~HSCMqGQp%MDx8n(b@cz%M4Qzio~<|ZiY(cf!K-a& zIDO`lxfOD~qDVg1L< z5U;j46=Ijw-1dF(Ii{ozk>;v(&Rf2=m2)z2`AVIz)xR|@l;h+LxE_cHD&$Wn6ua~s z(2gwS7n$n>8)@jY=HAi2IK={7fq9`-30Eq~;EK_()4_gsl=AZb(LV6SK(_N4ori?z zjU)HTJDePp=0#^n6y3?IMu+%JoTSJp-;LY)D74s^?}N8AB>`Ny@anxwnPKlvC8rR@ zq$|46WX3yn{Yj0MPUMLzxoE3;2|yv__(=fA{i!!K)qb+4JY(vU#ZTm{7=YwFJ_Ck^ z+JXQ~ZFw3JR$5~$zGCy}6kJF=_K0+<_ytkx(#d1f z?e3GU+ZDZ5hNto@dUs@7(7Rp~Rmi=R zvtD+4(O}3?Jk;!h>Dc~~O>IUSn7#KCxss?+pCW%C!L+$L-yC^&_r(b8bxq<4+}0YN zBobE2H?}WW7FI9&tt+*#?Gb{SmO%B_5+?8KcL|N;bf#!mvhiL(CT*=pHE*q`&Q`#f z0mImOZS*(qpkQxCG+di$WYi*wpI^u;rOPg^Cl(4uXN{aMYvnH9+&=`sbROMy7!Ac{`*-@W^b^P6`oXQRfh2)1hMeBrR#`V#8?+!m)o z`_+gh@H`8$c79gtt&s7G(|Wf|I9vPTd!PL&V^$(BrW3;TI*p#_e@CAxP9cC*0R+&F zwV@}^Xb)9qSh2_nXwrXp0!#YwP>e3oAG_uZ5zO!6yG@xgy|qvLLj zR%yCZR4x;9wc@N7AAynCp>qx6R?abcD2u*xVRUUDaA%vX7vkiwhq41r)*dg^sBXQ& zYgBTK;D=-&3g%bcGb7+=k;k3oDeLec*xg2W>B$0LQ)IqS*Iu1?T#?(H5(m zKQiGg&CLs*mD|y>!k>bN`nFXZ+COg>2|+n#z&Q9$@_vC_h@Cx0d>~&e^PghNDPpzW z=1e1&YoTgiqNoh)0q=@lVc`~Mb@jJ*1-^>5nCR38tN02=TPJNPrHN^K-#X7&FXN>L z2JA>9>g4BK8Xgh@^vcY7Rf%HUZ&7yAj5fNo9 znbg3tMbZ{5D_QJ}SJXHEQtd^|LL^;Zju60IUp|}MdW}<Q$7-yL>jarS*ONF_`FUljL5hZ4!Oe;T*m<-d{5>E}|st4wYxVI3J?} z_^c)x&lj>TIydx+JNBp^_yS&`L8zdlMEBl{a|bfhwDDC-QC(UI@k7)j@dCrWfT#8} zuwshO&Sw>5;cndFB@yo@AHd|a@4I*XhsGO;Vdct*2fh6pt$cDjz5{GI7Pn#ukE#^e zcMmJ(pw?M5zrg`lr8X-`?$*Q^$(7fCfrUIOmvWgNb1xS|r@S{-$$S@1Oq5E$+LAIf zlg-^3ZmH@LhX_t7G`DfO9_s!XjUC6z{$<^7IsfCEZK)koy{>$jKp&E$VQRbY5e&Qzs^?rQ5WG8iMd-JK6+t%Dx zIIkb2_XTTyTIc%br8Qb$5rz3QRJy^&lFjWwN|*3?gH744-J~lD&T56S+uYoGJmez z8a19B|I7zANF{!;X5h*hS0+vG8|4nifP|y`ONyJ>5fP&e!@vbc7S75T(+){6v|MFh z6Pt)w&fh142_uIBzm50)oRkw+g>6Ht4`#w=TBX@LSRjr>lpxyWt~x{fR*^{xeQZzd zf-}ND*+XvUVmP%rwz<#(9{UJ7qxB_a!(W4JQ|XpK8@@L-gW^1sw7&-NZB>DIOlbA~ zc6&3)CzGRaO%JiZ^;Egytu>dJ5TdrFszNJNfvAr6J)a~89P@EKx7&}h_J4A_x{wVM zf#OI(V$Ot$2ko9get4d>~Kn)^d)wVx}yA}2BFY^h33j%AT z?$4jwm#+WlQphV(Yxx&N)7L&12C$ItX?E%(`+g&>&NvMf=Jz{KWnD8^4JY}maF^LP zqATITxfOGaX)%@S6B2$BlP0%NEbg{?NInswrE#T2_PRfX!3WG)Q(P%jkq@HB9sL6- zLmqx{*9bnN=KFLDkI@H^=CLQwX{eAxK*XifG)Ib~Y_Bn+GhVunSj2biIr%oypWjmw z`)$5I9PI#9ckZJy1%*jp4HG>|v`>vTZWbpL9k9+%gtvtL-67#O1PSAkaX?I4xPw)O+i;_(UxR?DLi)WdUD+BvB(XQJIh8 z)7&jBrJe{2_N(O54GZ?2zV;a9nif4n+78z(ja*nP9=XY{$6rI#{_Bm+abOokpnz_}_w3^q+f@&hyYYlwRWmh^X_Omj&bP^t@Wj79 zIK=THlssn)hsTJ+T{05$6r&hj{S<9l$Jiiaj$X6RU)+g#VmY&kZXv%tVJsTBL{uF8 zhyBsm z{?UTK_r2cvD;6kHZ|fWcar!HDab);t@2X5?>8NiUkngh%g<`qg4Z#0$#b z-E$AUPu^Ldf6uIS;)qD{-VMy`HN*F?;5wBc3fs%PtCp4dO&rixVRsRA z9U!@JB`*0db?JXvSbqU&KawOLwJSPr%{QpeSh!h_#Hv*ibsc>c@A|YdK1t3!?RlTK z0RZ^_fZqS@r*=?a+Vs|7;;uYW=9^9S#sO$s(b<*6s=Yz@fMu29{&g{@;`{dT zO=@vA&1A1JQE`>xKgM}tPxk)1Rx7o6j6N!n(AOO{b&2@>t%KHDXofZb55pS_IUTpV2 zZSjA1<95UzqsZBwfz}6@w_enSGtyPYL65XkNnj&tW=f6S4_fH|1|sl`+9&G z3{hnrp-uz8x(3`^oeHaL#lo*%LH$@CTm-K%WdHX)Iv!~T?*ISyn{=jz${G2pv3lcQ zZ4mI%d8wR{Z)1YzdrwrKTe*J5Q{eJNu74NCy~G8!R`NCxIX`BHOv;BJl=Sas`CGZK zk3wdvV{Tz4*^GBLw}1H}%*gYHy{jXmxW6I(gPr_sv2{``mzIk=nGUm4W5~Zw1im&w>r?5|X9 zk4HWVXs3Z0k!r-hp1o&mGG`&AalJ+_J{6;mXZ`n;gKwn$@r|Y0bX;cNPL$-HC_AS8 z7%6qUx^Fbij&GJ-T`G5o6M zuRQH|I8*q#ujS+!wW-^cKePJ9CO?&Dr4p&qNS`!ycr>z$kg?69*AT)io;J?%|7Uk> z-@Q=?G}ZcpOTUhFyUI1vz&1>)&ddC}y@GnI6$nm(#kz;S)IVqPO+fNabY@IQ@&$1F z9@mcgF8u0^#+M59p4PP)F(myW{vA4E1JJ?yA>m9vj=2A3s&+ItfAf^|RYTkeojRL$ z39Vz!krM0qSO4%oXNlGqfNpuy`M04Hzjzk>C#dv}dd-LIzpxiTK?49Lb70ZqrF**r z9Sd`CA&R2x?tb~kd^of625rgDS0>QVFOR@3ow@bTJb!gg>qesp9O$S< z{h7`vVSpP$Pn{geG_r^nxBBFcnshc!d#>`2Ry+Og526X@`j}l$`PyW4U6{0M&HZ76 zFR28vL&&pKkStf zTfo+47{4SBl!!E|m1*ys5?<83FtQr5TTV%T&s6AW=dF^okf11C5Mh8?C`u$l)*b@+ z3E1xFPR+i;{ZZAjzhB0pTp@3mt^GiweY-d+ddL36LB^L^swt%bvr@@|xLKNwTdc^n z`KgRN@yOO6`cCN2o^@JQ=#|^rV3OXf#iYd8KnS!cf`Ni^8VNSZd&@EYoCg^dSD`D! zDKYR!9%#{Y5>Xk6u7jM2HDUJaqpw2Q^e4rUSN6)N(yfYP?$NqKPmb=o4x30%$MLP* zR)EOjMfRIvd)8R;=Zio-sEjBcKh&z5<8aW%g`9U~nHkdiFCr4niO5${G~}<(!X}3| zwX?eN6XSonw}mEHzkqDE+4u~$2yFAH>RL-F?n!Tq-;TdN=gWyih zLJ~*-j&{105CEAf56JX(8!I5Loruc6>?FfQ_15BRg{DNyfu(2ph&+wjwJ5Tm+2iQ) zOUVAH7r2cW@8pLa@%EEPwdo%SJUAa6an`dE)TnUf4Cr2ZmPD3!)IaQwfO`7KXzJ$n zh1=gD5B0@-P580aG+nT@HV_xbDh6iHZpYd+bg%tds6;XKC<^WLs?+-{IiPYs(=BSU zp&4{;yMOgrMsC^`*q;H0GNCINLrTq9mowNcf7KnIFjeaj~Dd-1P%C6a5&8D zsECHiaL2Gcu4QQ@Kp$fE-m-mddu?;Dwg~CaJxFIk7|69%*4Wt0-4?ePII=reB}eMz z;+xjeT260JH#P!-jk&vsJc$^9x(2q<6;R^)FTxB+FP$Xt7^kXtTcHLk8TKFA@Ha3R3xQ4wZPB zOFxXs%L8NZdLF6SWlz4{^jGipTKu7sn!3&4z0hMR{iF9;hA8ki1F=K~7p~(z)jv0y zQ}qqhsj4l>smBkR2p;-^oJSsU}vg z0C9j3?cH2Syn$BaDxttfd%_KSQHDoz=Bf`|4%bteD6$7OkL;7~X|MqVT8e~1irGDA zjzcY(%mBg+t{m`H){`-kvYPkTYcRgUn@xbMCIt1HAmaARh8Td%#Y+l|&xntzQUYv; z|NfDzK7rw?q+ThJY?-C}*qAECNK~{Q*4am2Y1F$U)Ztt4%)XHkqrTf13@PRO{B-Ci zeYVBJSELlv(vm*l;Jm{kX_xhax1i-iqvFm}>yC3o%@8QW{gdBp*i2P^QZ{X=+5L>9 z-$2)bE@_sK%2x6uSx?O&CXam>=#i4Bg5y+0(tP&x?S8%d(prv50$RF4>QM+U*6N-Ir)uPxH^J@`P_DYJ=Re8b0mt~C3QA5OA`u!sOuiVL zCx)FkSq{O_Rsr(oWECz<7-$fSUo%&S!p87LxCZzSgM z)^2S1<+JM$D5|gst$u=!&rcTgP93O9jx{EyDkh5tC2w}qxjFB)C@Ae5GDz7JQ@d08 zw_d5Zie{Mk`b1&a@;G~{eFDSNQTR?k?H2`6jdf3;3p(;$1W^>P0jZO!tkX$Zeadi+ z>~T1KOY3ji&Baa1fWnhvm(8~t3-2aU*Qz-VYPfD8g0a4>hig3ybTsDv;l#9*Jo+np zJ^168R+jdt$Kt25gHGdZA;%Ho9qH|-iKORavpHjOVcXhCg)w;P9_7p_HLD8NwQ5$){hD zA|ue{GqG9Qu}yK%#(3T*4>_>+ui^Y?E_ul8${tj@$*ksnI6=C^6zd8c9y@^WQvK+?+-vpNsLy!LVwW&?-xL; zB5%u*H@@uCeu(ZTw$#{jZzehNW@Vmtj}*7spY&e<%pHmw<%9--ke4!WQQ0*;nmM&u zqbw?arYT7%Zm`o>Y(2UA+uCM;w-2=0HzOIL!cMj@{_TarlyC-YuL8G;(1Y!RGWJ;emVMfPmoL*qor}pTDpPKV-P^E${(5^Ovua*QFDbr`^;;AQa~+VFrh?q zAR<9hD38if)T&V<{{a=rgyndrE_P(Hlm_QB_o-y}(4Kc_uMiM#>NnS~M5X2n7>VaC z;kzN}`8CO{{cXy)27Sld-DKsgDZHi=g2u`%IRj;9klqeR2>G0(?B~f-Z1P#%P6qW$ zl)NrKYZfk~NA9O^HYLCY^#M9wfIp`>K*YIJI+CODa&Hz5~lYa^nXA4p=b-?!@0%>L9l z$L}*)>{xr}xluy4Rgl&v9%ag>NUnp5y4PCI6nGM+ej7MbTJ0?S#Cez`GBm1Sr!6@r z{iNYOM{2)eN~DdxyOR@S1NW`V6=>d8Y6S`Myd<0uv^Der@|ClamQu75mFv!QDAa3Z z-zNh5J_VP)fAm0au#BNrK3+)Dyx+`iL`&_tQupdgfDZB81f#VBn(a!07pASU^L<=? z6N3f}?v{Jzc~39l72JRtcb~+Qt4sTswXy0n(8v?_6d;2I@X)}%HHliF#_Q(B<#&+5 z^z7bJhPFs>fq%_JPiyvymVr{u)I#R~;EqrT=YFef5mVQC$Sa6S|6VJ|Q{4JRU+#>Z zZz=}Dtn@-D3?|=1Q(hc`}JZPQ~Y+_TAYPtOsBg-aH8XcLm;YRAWKth!26G0H}h#g zCF+bq%^Z-hG@}H_W4|fLDA&mqSk2I?ceLT zo*6rPc$~Ph-Q}?echYmxNWxe8tg?DS%5O?n?T)o!NB7~Dr7~BuM0Q-^A`oaUUpV=g z%UeRFWJZRo&YeDO+{$Oi?|mF`5j&szne(YaeIKzjou$xQr^=wBg7ZPSxkbX0a!)rP zIQV_bDt~1a+t|$fl4s6UVPye?HitTtwbnzw>DVgNQeey&rQQC?SKWzpD0wKqHibN; zHZMFPu?@qIv2tqrrdW?RN~l$>jK}2Ep*asd@E+cu!;Zpp-bOz@7!Mk$x}ntKWY=kB-kGu4WctDv#u$Z4TKr^O==y|*3-jkF5> zxi6;mT?K2n^(Ety={t-}_~nuJKf7)Lo#!&s)F*IH2O1=aTnLN7se5}L`k#>rMut>0C%4xhksyL@)j&Ic2CO{j*2RiUQxtonf7MyLf{1T#ef^g zN8L3X=-r1iCnAjeaLWZ9qXr0l+2w@o%_t_?oXY_$$PYu)b9SQ@{${V(cvod?`Cn0i z3VAgE;Mh*u=C$vuMcFE)%QtVA`Gn_iddl{6D=4diR+xbEzEr zvf3fuam>AMAb)F1E!NwyvoSfE9B$maI$G)Pp{CYfO)fa79yINsqBh^*M+iom*f&{K zMb+`!Qa29hzN>M=#OYwZ8jIW644K*v{y1fCDRqfl%4gvt1FWKTp`Lub4< zXdAD>Pw(b_zPVHmq@9na%`6yLtkAKQnrQ6LpOEJXO?27m2(O&q;zFwSc#5JnyrupJ zd+!<6)Yi5EDhMcuSP&EhDAi>0 zOG1YbAc4$|dd~aK_nqVXnIAKA%^xn!UVE>-_IlQ{o^s#MvWfPL3*Gk-tjh!IuRHEw zP7XiV@fKa#!XLgwmIiH(+B@0zZ?5lMD?#{H9)9ORu9VT$8=R@lRqgsN=xj^pI$@p| zGC}mN_EA*TryFzlF#77dw{?7r7mZHs!8(4AoYjnC5c64+q5YS;vLxq~>`2X$0u*j* zf2+&t#)j*mn|M_?>hSKJ9&2E4deNBoK+s=uBHTlG=az@zeX6<6)`)F$%d3FS4cG4! zhO)vwW*AZK2rjM`mFvb`bQyiU503V|r;gLKsdNcrGd9xsR<5!LhNFOhgK`a&z?_pDwF2q%b=_zh#Szk83Zw#M$1% zDLZSm=a82g*L;E`13_d=uib~Y)C};W%>CvqiQ$B+l7kZ58t-HJgYOw}XvKNYGZDF- zFeM4voRu#NxzbH}!eJI-c4Vb|Mr1Xl+ezGOcjKv8W$Yf>1U5*{*F~#JPh0cgm2Ucy znX-6e#ZsZ*4La7h94m^M7kiVu4ktnsS1&krj}@uRJcamj-b)kE8pA!rB|Ur)yfEna zaAWEr0WZkoIaVx_pQ11O9Vm%m*1ot(PA6x6uKL>#5c`>LU^?(da#C`_fI4hBzPm%d zyxq4(sDkB$2KarrNFnlxDRY|6BredUGJf;70$@0QTPLIEIv$iX3%Q>b-`69(D3GyI zgV0U87U(T3x9UQd1VQ_iU0FP6KO^Kjn*Th!4*_%J&L)_plIF9Rj8A^t)}c)Bt3wJO%C0p;t3UXxW;?#_93Am_ z6p0KK!wC@9qhsRrB0Sa75;ATDpFYh|1H(2Qf^em#jZ&wP9Zty3j@L>E9Q_rzF zLK|D9R<_CcXM~12&sRsd6YOUCWo@d9wJoytku&itYL4G(;kjjnsMBh(V!>l=dEMsM zXEevaoGf`-+fzrg5b@swu<01vecYPf62RO_)}{%jB>!Y~`h|kE1q;;E-B*vyPz)-%sp)dQr!jOnd)@Cf$PYwN)3NSu}N~%NZ3oB)~q5j;kw|E z7M+18|FTpWj5Pc(=O!7SZf@y^QO}flbJ4WB>kX^Q{3)#gj@!~Gz;k;mW&(Vuv!=yB z;EvtL$=DXqnmWKCQ*GGjl0k|#m$gqNEi65iCzui?{TloYr$`(Ll_!#rdkGNMo0wv^ zME+L7;`GESumaEwa-jC@z6a$Ljf%bz*6#KDn_9-5KJv51de&58`U7WR`C%GC-WaV> z>q?k%Z~r_7_@rd?)as@UosH%5K?vz~d1-P!>X4DWVzk~-=~2(& z@z>5}pu4PvAc5jOhjKSi*~~N5dNfx-#K00s#j%`oiGG!=s%1_+l~vZ^QKVVnx|nT! zV<0apgjm;2b58{Q+4({4ugpeL359u<+R_MtxktMmd1yc4-u$i;41!Mbs5;NeLigX8 z4Z9s%RaMTNzlS}R>un&%l<{m#~n!DsW=DT%H#rt%1|_i`eQCKPq*CnmQv7I$N4E zq1$HD?%PeiXdk|+VU$qZZvDWvb+#$FPR(0O1z5VW?7V{m)n`vPeU6up7clQsJ zY^Vk%23TZ!Bd)`zq{*%F#hkYeqrIJHTFpk&BK-7~l6KEuQ_y>zYW<7( zEMr<6wDP+rYH{!!6ZWL@caqiwv@+z5ibecGUkvIEZ=dksa&^9$=JQH*y1{ja!R4_{ zR>|st3l`#CRmKS|6LxzHYw?*8%YgNv@$xmkrot=*d!znn@SGPTQ9^Yx>VxZIrsEM_ zf^VZQQ?_i@K%69(1%MF4=5-9jetmAD|J`*;l#CCfkgugkQ@quKL`rb~HB&iP;>RLL7?9GBZ(8aryUz^ddkrSK&fY8;gqh;&oD|5>*dyXkcIKnwi3zp?Xm8LPHsq#%Sl#N{#?KGWwhbDo6EO!|p&8 zUc$Sv5&YwMTP78Hc@Kncn?hs0m&<5;lF91DEDfK#&$Us!{=PjX?>#R%zwu}hWo7L- zGg#9v4_T~V-$tJdgr%;UapIwgCXH}m4#BeF72XCVDVyFyx7kB4? zn_bBq!2>dUjwx84b5h)kvUuQ4gdEf9!x4-3zC57P&f;>K(wpTvKLTlI1xCT}sWd_G zxbRWi>v5LIAbG=pWvcKx<&UY{mRe?w2CL{6MPwDH;-E#y-OA)QZCD$55Wclc4cyxqX^Fe?Wy%WOA0gRAzZx|`h!7Pm}uA+sFbr@n z9?Ak=1Q`Wa$0cS}h$ULE!g^~LC-;`xzdNeGc|9$Pzf=}B7)Sx$U&q(nf0)90BoY0K zwVcFFfzDFf10^}GP-mJJ+B@D%=RZ_mjJ8-X>*VrG7+5v>v9qDQElUOuEk>cJJpfzCb^yL)POwo znM90oRmgFv&8x`2^om9o5KU*y0%E22K^o{&fJRSB6vbV&sFsU40qlFe`tWsceneG9 zD)Wnj8|p?kSb-{1K2{b{fmS(}*pLBziafMCgr031W=Bl&oM+Y|QvKOvZbN%BeuNpi z`@VBL(cNkwgNKy3G}SmB=xV!e3!E3|2S3SIvADm+?pZdA1#_>v%m|n4)s$3r>sw_E zT|pnoHQIr*y5~~z;otS=wkAwl;m<72vWZXct(l;r{Me%!I(joIdN<9Y;m11fBg1%u zf$Cn~T?dx>&OOH%PxMJBBj9hVrt&|>+zA_a7lk-a6VmeTnZ>!mdzyu_O?yx2&aD&= zg-qX|9m#6&t3&M=-hE;oFSJss+d&5=GTgB%K!>b$dD^Vj@yXWg_sAna>h^zu35K=BlTJ>j*xU?7W) zDrB8g{9wy%ZJGn5b~FoUK%E*P^z?eD8EM~+CR3!T>3D!y@mu;>k>t=}EoHVG_Q=_0 z!8IV%=$F8pRGg(-DQQf4y)k`E6_jRuWiy2N^a1PmVr|{oelosL<@-g|W+Dzns<=Ci zyA=<1<#hg1 zjK{QXKZ_#iEIh?16xGWSHFEN35R4cY;hbkUgGq!P-n4&18?auq)+Ymj+-@f4i^q<_ zJEfSbhptgSzEh9emuU>u3GwC>%P+5tHXv+%?UdL*@C7VQ?%^V&hIKu9X1Y>jn$qc^ zSA>`)NV|1(h@JX%b3YVAD=?m49HmRZ3EGs9|ERy*9U@jRt5#v?scY`_B#CY034TB= zh!J^M>Na)#`Q-PX#urd{tO(r_JXtT6yK9odP++#)sxMQuw&5f;JMh)U zC~kZ8n`0BtsbUj<15U1ks+F}A9>~N$7gwL<5YKhlqP^L1*d3uGyN3}%^8WN10p7fl z#Z}d3xHa?ed<>H^Oj464c7SQlSD%ZHN?4U|3!~2hyg=0wGz3QW+_{IWydq349tj3= zAUP2S=9{w_dw7W@iiYkB3ZR*DVU64*AI{P%odRkcZPjHL*SxNh>s|?MNQ?WSP&Jd^ zDZ$v5qb8{jw;zjjfQ`LO-fRWgz_-F(7ej5R#lNtu*qs^I@UL4MSRKJ9dM+m92Z8yo z%*|f}*1F_1&MD%ttwh4Gi9`M63=zcV{HsIeS(`J}iD^N|^L!eKm_y^JF{c+j{Z3lD zfv&T&1?TfbXU6xoS2srUIVOaXvUK*`_vW4Rb<15CDUU?6EcnZIqK(@UhF*rb$?c?h zC%{Fq3K*Si-J;7dT=DUbew|vV!<7V6_w{X?0J00(z+NAvVOM_h{i=7dRQ=v?>QjA!;N ziy5o5qf3fM`@u#Wyhe>*^AvNG=1J8R@LvjJ zf57AdnCz9@pDwywc9y>P7aI8 z5jHeIKdUkUX8p+;hw^*)zwt|Bq%uQpdK^LLNt1KzxPFqKS7a5}bVOSiQp*T9zVEX9 zRC7J`&yc~%fNdah)Usc3?AR|O2r$000fSPVf#FwerJg>LR@jO6SbP3fdNIB{vov>@ zTC76oG!^N{U!b)Ka3u4xg4OQdm7hw3f%|u>G_P=yt{)@w0{$!Mt@ZO&P9Ri(cVnC> zAss3C3o!5wc>U6i=INeaKYTw63^&cwi-9k^u0^5Xda28gO7=THx7$lp6fnT}j5aTR zij4N$p5mV><<3m{R1jNSVxo#!@_R_Z&EXm3M(C< zn121c^Pg|cxCVqkpZBf091nH-yhI9w_3Q#@v-Zi832W-kXf3uKlTz7y#>AKBM*7{tq2`MF2Rs zzVne@K7VSob`6MJiRnpq9si|x{#xVzr!nY|01)zelxIj0n16d3Fg&lwwbvI#ss6pq zS<_R%*WP`C};>r~*Ubggr z#bQU+&Ie!?>Q|0A>uHH^)VS`<<8;<8iC+7A&b_)AlM+Vu7gk6m(j}9yB$=NS=5&9& z-64>tZ8Pe{OEfH~v0-&z%gY`Q8cy-uUu zopp=I!OztxmM2=CdX+d6V=oI8CgR=o4wK|N+!8&;BhJL;RThdS5j?gE=OJ@n}wt*e3S_ES>QZoH3f;eP7r= z((c!ixnyzzp+xrOm>crrs+h`!QaN${Tz&7*2a2 z@ubcJ_ugz39ROO z%lT_}5Zd(wz}QW~o^7=2DVR(rQ)zQLI$Z#&sgj6++lL!g%7_cBbeN_#n8t zvmU>!#Y`{nDG=WvfAg!QzoerVWLT$frDj22uLW?t`X@Gc05#?d{Ds+Ey$vW&mI9sqDBYrFf1QCV zRag~4*~H0(0p_b^pp~U!X=lqgnQlHi}JXO*XvR&0lpQOFm!`-1= zA4L5z3o|I8X9KM>psQG|PV_L;6rTziusd0kT3mS6EB#~u7)oc4vK^1UoW5pMx4+3K z=u)uVnF*EwrL7n<6gSnB#Q5X1yDw&4Tm2G=jMQ6c9PuG<4oA_RZeFmar4?*cZa&|r=InnG$goVHM zuK?i3$!1CjYiT3n`M(TCm7L#iS6@7cE@_s(!SU0ktp;pbvte$N;8?(rhSVf`F~$$- z$amTVO*$Dldz*}Il64i%QVNB9oJ_s7(f2`M{KhA~*Sl+;g6)T9PLWR`CRsFjnhKCZ zADCqQ<&H8cn;FwJ_buTPT$M9>)JJ$an~3F%w;%f@)B}f^GsfA_(8{&ufzBud^Uc3G z0%a#le=hJMZrxM~-P~JtKd+RQNIvpn#2dgr!FE=`&hyrf?p;*61k%_ygwc+QjzkRK zr-)&3iLO|8Fy3@Ec9c!Ya02fUbjOWGgp5bM4p%~31*1f*a4$&8&lMk9&^bsaVKa$e z8E^WmEGVs9GIl<#==fyCcn&7KG}S8&ICV^RQqJ`VFP$VThR+#Bi$h5s)G|71_#RoM>x4ZkOtiLRteNe0AGq z5By^j9TA+JJsDG7MCY1kJTCGhI{ z@JHi%+DLo<`lD$^`$-mMO6`u$;JTM}#Hvz7ovE~n+H`Infeg0;_qw|NSbaDiiM(64 zm<8$pb_&Lb3kplV-$=PX8_$EX-g{sG9dXxKM$Ed+qt(h{XEZ}~xabNz$HU~U7>@nSxSe##Q876(Brmr=bO`Nz zD1pLBj`V_WqNlx7sH{G`yX?+@dv7V?Fkj5tS3_@C(CQ7LgX{QKf>RCCep^OxZN8e4 zh~Iu2oYiv|OSfQz*IxEyplVg=c064^==`e3DlNYvKMhf$XVxp)dBeVQrS1_ROlmmz zz@qCXA zH8J@6SOe`}Wi%vdPSIzn-LcVC!ni$K2Jco>B62i5CyG9MA!~ zYriXYv~+dg;-)_FK}DWV=gag&a{Z_Zfc^O9rp7!-NYh~gF1b&37jn?JBfeVKR zk+9*tfgxE9Vt;L@^dj02j`t|7cHU~Rw;4szrn%ilfK%MWJ&PTiC{_-?T!rs<))=nS zLhQN)WpMDV5OhMeFRlV-VqAgKgI^UNJL28{fy7sB`)LKPJxfh1#no;tKUY^GMyH=? z?XYaRX@$B&a^hpI1G@3@M~J#i2|3@9VkwaB97K)~0jq@>`6M_4wbHObtV2uLA8th6 z$RTiut$8dcmf)i+q=zhI^g~QW*PPTx<>j-lC3uWqScvh3zV_kf?uL|aRYu|lwiSJ? ztm$v5Fcl&>qr=+i)i4r;4yR3-sTH> zf!baZs2IO`X_KCKIspjbbx!N%nX)H3%(!TR3XXMXwnEm)3N}w4Ogr@{G~1>)_F*`IV?stDD)erw?BTXXLI2xJb}GJRpG(x_K!k zu={f;!Az_m&u#rY)vm+VG2^KfK}!Gg1qXyH#?>@#3xUDsF?|eri1mYo?(L2lovPeY z)Vnn*3mplb{^0R#-1AoC$oICCYh!CBNMlylP2^p9@nQav5#TIg+;@vzDYCNEfzAk* z`!gS@I#!9eY|)pPaJ{JqbU)E`Np2^{5rDv(jh9jDbhR2d7*B9nq^9XwL4@|yG=ReSDnT>7yO7GpPmD0waAgxJA$DeBuuiaaeP-T?&2Fg)7Jh8r$Com zP90<`Cfqg;UmE@i5EqwR%ylG<2)vo(el=T zKD@$A$0VK%lJQYnXI8TaKhspb%r~le8_~PvfB1Efu}Vj4$+*3J-D4pkRizGy$dhcR zk}iQXxi<+TmEDy7-VqOA$)+DXwzR@2($uUAy<)| zX;9@wvi2NGTJ^;y^a!X7AC0xLp>827p+oiB4hpwCLtU!~_-(Y`gR)$8`7>o#25=E% zx8($mT1P8nb)F+G7Jd!h81NB1y4EbXt1u?Q$ckW zurW!sL^F2h#2ou^-&1Gm=Aic9ZiZ7ap{s%#6AruW^eXmrk>3QmRuLR?s1@)f@n^?pgg4`f4USK zGu22jc->k2aOg3O83j}m-(Hii5uj7K$t;?vcnlqahT;FwAmzwar zCgFLW1g8E_NHdA-0)i@ue&^^53Tf^)U=qWrCr>|UqII;`oUaw4s?@JS%GhKnWy8Lp z53`4}Co|n7%qj9xQKw+9O_EQwf|P4_KfAUK8MclfQs8Q*qdX`h7kTikdYDh`H|d(t z9xnY~Vyp0SZKpNVrao-8A9-Rhje3|#PsR{vn=;JX$ zS`)b3UPgmY*%Z(&0N_+oN;`RbnMMowy-D}+(!v}7Z)1i_aofnAfDVN179YwXU6=im z4*4p%dz&;M+gGfsYo8@aal+L)c<$`A76<_$Zu*rmvp}|hm{{%~GOpNL{hdb)qTUJSTS?n5* zjO||XNnNv7A9dfJE$H+qHxoGJWeaKWe7K=HPEQ=MU{zw<^gPDtlW=Ez_bu}cFI66` zVe*W1M7p-IEA)M=`|S^4{38|-(k zD9>9IyE$UA0YhGot-SV@?4A!!0=yZ0WsdtGI=y>?`KT-lBlBn+`g-_@eM@IB2bn(i z$W;$ntCC_&kRtNl?N1@Q1JFXxLrG1Gr)iKC+Q8iI`xI@wlP2QMf{&ErvW@%@^zxX4 zM|qN-WnSkTPcfv*Ook4eP18ei7lSv;!L9KnbQ%i4Tet$R( zCyj`;Xu+8hJOD_w5l#XFci{$VWj*j2_#mr7S@6rtE)9|Fz5kA=tJ+#Xbsk8ew|vK? zMqsAj$?s}|-9Jb{JTdRf6CDKgL8G$}EzV#aMhvJJ!LK&99VhnH+C*4cya*;g>G118Lf@t!=NYm*A42c+7~Ui{PY@Uy|~=4}7&S*MJK z@2tDiwOwWhZ;3naiL@qCL<_ew2mfz zWaE3zgw4lm%D}K-EBnp?LTFyCyedzEk@}}Wp_y|GUw>i~UjdOoMatEVnft(Tg&C&m zpZohqH&fvgM7ItR>!O38!O%>pHkz6}%#Op346$wun|IX`Q;+`fiZ=g>0};U2L~`$< z8nE^S9QQQAdwm1;gZ#_OLAqy96UfT`z~-`*{%P#3`o1LQGt`shR>qLP6W` zwN56gWYY@J*ut2Ph^=z`(sFRKvv@yY$0F;7>JEDvAhE;H_2adSeSL?mHj4>CL!p}f zD-N*KkcfyxqmuzSWF}*4)s*AbHDOyiUd^7zR^94WLpq#@VG%p($%ro1ieqxJq zMb1KnmSwR3RMk;x^goDeEFmc$Cw6lpD_+Io{-KN7N6&@ocaw>L=UZns7D!d_1Sjdm zdgmW7*E^8%nL5VGZcJ&-!SyVT{V>3ju3RM-8}sI{iq(mjhsYAQ^&0m8jIGFdhhDhQ z`yTS$61}ItP}kOD#FQaPG@0~Mq+|AY*EQi;w}E;Y#PQU%JA^5@p7QZui9A`p_CsJoTcL*CU$APsJb0P475+_-wJM_`Q}9|GlDJTugDujzPUQ!C z3I8c-jbT*EBa;*~J3T+xWg(%WtX2m47z-##ahg47t+lFHgZD_|x2nP5%>&tvch2JB z_fGr`u5NjK`Z@BE>&ig<1i7JkbF!NZ9M=e!GRJy+s~5319MaowuwOuFNnFa`Md8f( zOMdhYSK1Q4o)%V^a~)7QtxbZ(!~g-sfu=#7Xfc6}^Pbs*V0-b=jh`Uthl8iF1?4|1 zJ`twm+yf##bE_RjY%;ASmf6*zsyQ)J?9U18dV(!3mt7ZlWey9>d!`QCeTGd~x}{>z z6!{E9QpOHlqT1Ay)E?h&Ka}&Se_*A<^IECO_VLTtF!9FHQEHlTj)$;n<5ucicXJy; z?E&1(V4=RCHjD(ggnVXZb#;91$_)$ctACcke|sSCxhBG89s4!54kiErU3+@++S!XL zG!l-2>1!=p)(aNg{{`DFEgXqMyt(ffDLkPn&XU1A1XpD|jycU_P#qQ1=a`jttwe%P zX3RQu4M1zyW6tSTPGte6#H*3z>Gb~+xptbe29>dcx2n#5*6j1jz1^ih@!R4H0Dk)& z!n{L{Ya8yCM<1Y~(*+;G=ka*2?#v}798;%mnW7%rFEEczzlj?!?aB*Ee;yzvT5J1x%G9oXRUd!6x3 z$HytKu+;EofnPykgldv${KM8IVubp?L9LKRDsQ-qhRZ+TApvM?g3FLI01W1R zJMjm>Vp|nsMq#sdCvui5=}d9GnRRKs)m8{Ra%o!E(KeT#)n~4Leeed-#`eP8ralI{ z(QZJhf@zu#Y{ACnPIlU`kDAK;T+7Sk9+x%c(ctZO+fL4-GkG8aAF3wSbnGWIJ5O-n zmJ<*ZeplT|Q)Bwcjn=6kY*<)cB`PL%(zyOjI1mHs?Nkwek-XC-uUe?=w6b3D{X5rcl1Jh>iV zkO3oGoep(+-S`?SSc~>zT%_a#VrAk0LOfI1(nEsx{z|~Wabq9Do*bQXv`i!2JYxeA z&v3acG;9e2j#1Y4Gdsd}YwvECC_^|-fOurax?h$Vt+nF_uMi2=p=Opv-KgYqE%g%9WLB;mtpyTsSaK9d+B zZ2*SL-^KA_!C!8*!j<R`^u&dJN&n1URAbqhk{6$&KI`ig}xJxvo zFgQCVvW4LyXZm!I&etajL8wAf^#qp38yuHXO9*ZD{W=Z}vmn?=hMGFGRWB zi1}*{ygKrA!Bva-RnWJAg|3uxyV&N$V~#Yn;3M1@#A}tS%K+B9z)+S78iN(r+3`SS z%JS^aN&n0>CZ+s@IzK0%LZr#~n0EA#D%{I0IBSy$bo!z1b!-D_&?y&;efcHf+JO={ z{Bp61r{L?|%Mj?H*}DdL5+GMpDez+Erbn32P;!f2E}O8Frq#~* z&XvmAQ*I>CrWfat!aCjcGhrKZ2Z-JLNQ&2vYXQ3++@pGIzcaXAz=G91x*cA{a@Mi8%EYN(dw$6mt5MFJKdH9ku#dRE zk=#&Bc998hUT9U7V%@u?+S}moeG5_arL==}QIkjO@C)CFCwn9~5A5K1Yyz@M8$h)Z z7?3N33=6H&e4tYRAJl;I0C1dJMA>0n&BS_e@=7s+OQBR}ittoH$U!F&h$Kun5V~6c z05+A4NE6S{n+B#!_nx51WFVR9%+A-pqn2{?%`$=7(Y9BF5`03gs`yTjdhVA zvZqm|>5ei-w(@7s-mdtCXu9?{QF267(zot0;K!9Db z7Im3x#HLoe)aVJYXNUUc8EZlIdZQbfnnmy^}1O1|GVbd=GA_7nb zYT)L?^$UP5mkgyKH2ANbd#vW_RZ-*X*YS4Ljg&OuOiq@bR=+nbaNgxqZH!3Ke2;Vo zoSApAO|5CB_#%O3L zVjBX(*#{sbK5`IcAhlkM;!^d^ax~+y9r}wwCg)I~?UN21#{)fW6In7LE&7FlCK z=1T<;gl>cR!B86*881(k#`^=kHR0vQ*4Uv|Acv-Z*q}%S`ZfrARRrmB$a^wll!^C~ z$7!P+zoj_>Y>C9{OjD|y1!?a+Yp`$=)2mFM)Vy5NbP#rTwxY`i2qn=pyIkT{8MdWE z_x4m%;O(Jbdi~02e!a(j^ERI-}H0&cN;2A6z#m45v>5fP^w-oa^d&e7a!Jb zv8-rIL~gm@68t)xybz)4zwr8=3C`+3=o^(Hjgk$7-BUmMRYaJnG9x#|f^v)GaH{Uz_k;*<%+> zWo>yhP(P42erj0!B`*TcNffx19;>aq1E46+x%4*bdwx$hJ{nDTc3kHPsx42~4Yo-#006I<3Ii@?o|Cls16Jffb;~X?n@@-hS=dV(LCV!+8a?6@bAgi3kC-z$ z4R`L2pMJ4iJ#O$$Cw1=!aVrnUt^@UFT$NWe4<5C?=q#w(7+GS22d512nZvSO#nWm5 zTR+-rH8A_yQu68yFu%1a87^S}mffvnSkyUY5p~qmnM1=OY=v|?G`eZjM9#;hAMSM| zh;>rt(ckXz7dgA*?K+#n_bok-O9dptm{1bTte|}{85a6e)fBHK9bfp6r)gIWpI%k& z1me{UPR=5Yd$Uz=7vU(qp0pr=7IHqV5$kshMT=ijd4mVApF=2>PFp`d0HM*eHCHNs z7?fnyzL&FLv5UsunamxrYPxy?;q?YVsm|ynhaZo)T`|VMIT%8`d}VIXMQIVapZd%I zVwOG`8q2o0jzI*e=ugOPuAK@(t`*3T>u@a#uKs2V1R~-F7X85NVOL$EUB0Sn1suS8 z7q<>%^~|6EYJNCxo?e{elu!B5<`6#q%cj=*#8MxOmfoR1hAMnl`_{#M-~gTZ2F3T6 zkZ)A_9#P4Tby>)ho)n%3>Dae%H8ssK+( zkG1SB3j!s*R?YD|5}UnVy1n~cY=!$!dz=gV7%#q6b9jYLr+q1AsalOEYO;iq6b-#N z46uH{-C|rDeF5ve$?GXH;>G#r+J9jMmn^+tX!;|Yrz{0zTudu^$PZ=;;6c}g7+0N= zw!}pdv3w{xS;sN3w!60daPmyoX5)o&5KQt3mPhVB?d5UFI8vB+{*`j6 z%a??xT#g~##6j^Zj;(1_w;fMedk`+VdCr}}Ut6ts;qe@^bFEj?N#RnN18k#86;u&8 z=sfp9byw_%V)Mu$r}_ZKYw;2ZeWYT`2o*&&Fvh0?R?>l8#(eT{mYG&w1^<4)0?1i zmM*;#1w-}YnntUR%tF+YR6t*d@n;ocQhk@GsRy!R^76li5ttpZlu)Pgi&zq*1E~&_ z3Bd;V&YpP>K3SUerX>i0tF(fAdYt&Eebu!NuaM((|Hx#6MY+b9A<;QvV_PBdGeAiI zhaIL$ga#uHu6urNw@+cgOY=;G4HR!8yX%VbIN9&o?<}vjl=lf79*Y68*$`HMXi9-j zeg+ZdT5hd8V!@Pbd|5<^po`^yfG1(~f`p{4r^CT_87GAM!Xb0YpSw$wt{^2xn&G?@ zW;;Lp5CpvPmzhHOj<@r;#$!;)FTlHct{kVk+$!ooC{IbD4SX$dk`mmCrmhZXJyH zFwu1C%u`U8Ox?j3(XDJM!Pd(gKiwY9TN}xSs?NOC(}Mj!^B9tk=3qWvjmLJ{_;zA+fuhpuM8l?7s^gUcJGyk$f?`Fgt)n6JOHXKk*C4 zZ|&|>;=?%{OOSg6uozd>K+l}@O*qG4W^cq%eQ!QA7G(~0doiMBb!sxBOH?0hBpV?% zD^plNvU#t(cYX|mg#Z)Jf*HYQ6h9?oS1i?K3-|`x4 zsZ}~Fwrt;~OdXSH>F63BF<`R;xESj?txdyV?1AjUG3E!OhQJX$2!zTW{Y-}i#&V7oiL!dSe|odfx*Pl<}#`!ao8ju!Ga%GrAdX$S|q~SHj}Fpoj_vV zR?JmF@jxN+B9Sd|CQp=w7a>L+EGx$@HG z3IY*xK2#J1$(SDr(yTnAk zi#wJ(R~&e-Z@!+cbsLo=HZA0=!=03c>TvrYnd3*f0E4)Lt75brC>d7@5F=LQU4I5Z zX7eS7Xidu;o-rEQk3jDZB=39RtMv_cG~}~Gmq2NCY8*_S?kT95b@!KU>V@LU^oj!) z{N*mTXYh6nir45cE1K&1xWCX9;Jmh(ziRiq*5*~3Qx@a0RBCia{MVsx83KZ1h(h!< zim*{q?HekhWIMF4sXNKbI@sld1-2n^Alm8>j2YqS2I_{S=_Wkj0FY#}agv%-MsYq< zZ~ueIzd@$$75RjnM0NX#`%EL@J_qKf4BUZ@td6oDcovexjKFbs?Ej6b!U9p0tnR?P zUpFnu0Zk!U-F5ar!?~?O0HKG71|-JXNlKLEFMR3mT=i4_-{GNTpn+18u~r%BQJwx1 zKtGc}HhTKaSmSvB)~Ffj@AIn( zFoyez05Ce^S;@^`J;$&EZ2_3&fTh=|maE+z_po#MBZ;zy)^$fmi^l8TTcoH^#JMHF zqBqX|!S2|)4Y>DF06le3ptZ&8m*EWfyeA#vCD%D&F$otGm(EOu7I@wTXzFr zMIG5k-r(Z86-UjX*J}+NYU3UKJDT=C@BaD3zb5&+_CH?!)vF}UNr%@{(k9Q%un+ws z87gP4{He&ULzJWw5J!{EEygodGxfhe0p)U6_sPSLO z(BGo`Q=b3&gYY8>q}_E<+P?(yuPgu6dI?4nWKY_AByhz)T>tso5<3YA|Kr`9(7(5l zOu~@X%%Skq$v-uUJ?ZdlsyPb!=)L2Ghf05_PY+ZQJ4M)Q7)|qIZ5bif&UH$&-xPdt z^o#Him!mK$9ex?4k-)Zb-kkqW$EzbB18W0R^(l^YG|@jvCFwVZTHsUV*HZ$dia#{E z;1zVL<|N0;i#u_*d6ILAtha`y|MW$!@u~=K%+M|;TeLQq! z8Bs6e1poc@XM-er8|0xN!#+F18dL8EfBGkX_=I3t3HS z*`+R7uW~KLfN9rrFtQZ=J~OoE;U8W?>3_23trJj5;~y0GZ}kc~can^+_c=95ySV;Y zyC`@qoPe&Jyju#CbZBp>``7OV0J|;%qFOqmF&*`%Mm(fO^G35t|Jlv|S99P=F#!Gi zX;2xlN*&%Ca*aZ*mXeN!VUt92_}6hc(0Bngvc$aQck~QPTJq^yU7jhC@jc^P_+QWe z&(s@CoLw4e@IMW?5SbJ&pSDWF18oTeT{7|e*Nz%0Z+*J#vZ+%xfSQpG0S+T8{Ls)| zxg#>G_wNI`1UfK`!iYz4PkT?wogFg$UOh)-GBd<#7v_O9P#4KTm0e7@mVrK zabpZv+2|}|EC;|~jtIXKO3Ru~L8?LbpIP}I|4JG^N!Xbhova!Vtdq}@R=BZ|ta`JN zkg*;F$+l#IA+Gq2*6&1=Sc3T2KQlQy6 zhd*>~5O?v?w(tJ(^mcoO{u;OgBXj4R%jS?qhg_BUnHmK|PmFO*mPvltH~K$(xNAKv zWQKM7-w9h2dGms%GE>sh?|5`yLIS0S0);Q^Mh`0pbx&<|x&Be_j_DcuKi!nRC@_AT=1)R$*3``_QC9C&%h6G+ zc<`$!HUQ`mEdr!61+T$cS7i8*tD`o^!M}SZB`Wg~?Y_MKg%yB+u#H^PM_6X?=3U$i-PcPUefc^n97c z^#Q^>Mfc_>bY?35ov-M%a8f<_SSM$}avHr@!+>5hV}#C^N&+YIsB~J|4@YrWQ-tew zudq}8PCbWu*R)Z<2}oGKE@SK|Eu(Um-d$kh>0>(7$Zk^Qdgk>yySO+Egz(bUJW!id ztNc>Y=3kSV@1$Ka{FZI>4u##j(GrdrH94pK+<%w2B<>S8p1nhyX$V)zjM`C{?#uOF z*-}loYchY&>JwX0=@l10UcSh)+Dn~}*=sMaati21XDN){De2@_77Cf_1ahxjcl8*R z!WgPX+lozxMz)^cm2s8l zsz=A<8|vp#gqwVNFrUlcI=`KYmw(mL84=MG5veSeQzkD^0Z~0bk#jG8Gzxla_Yy;x z-PRJm;?ny}<0WUWq<3si?rCKM%eLY^Ic9f1hI7`l(jF7VEABe++8?x_w4sjlTCMED zSI&}vKmQ_jx7nwtC_Y-fupcaY23;PdfYo}1(>&?cZHp}9HFDLViQ4irS`*Y%i1&(g zwF+ne3h;;C|0bhT8&(KLCVV5zByoAJN;uz zW=pjU0(C=J{$<>Nx4Fysf$|bsH1Wx)QNb+f#WK5I$}FkKzK>7trm9y0cu!)V$+!gsCP#7^KJ~b5LkRW|0!1R0N{(w8h%= z^|{_!eWv&4y+6)5>+JiTy}!NBw^gHbOxuKIb(gq=8?T;AJRqj#k^5jy$-=P{!Qb|C z>g2+)qX)`HlT-+QkxO6OgOU=P<5;(t+TsYV(LFOSeI_)potl%vH1+k02N66b{F}-{ zv$%jtc^s!_ANa|Ty0qvb(_z&p=U|%JFxmyytNJS2^jwo|#l){hgS(wef5=Ei`7yDY z1G;RNS0Pe0>aSy!l!SO-W7w;At&4oY(n^PRt`N_E8!U+Zwx@uX!2LPrSYv3P*ed$G z@0c;^7UnmlZ_FncT8XR1)9$p-@r2dK%kcdco>sXWT%NZevzYzJGW_UI8@2o%#*s!+ zi{%%Eg0Cz%)S-<66`gYxDu@KO^=6MdzH^Nfdf@$(YYf+?LZ2cZ+i$BL^twk5DnGEw z5q8Wv88*AI9L=&}+_Xfv9L(%uce6yF;oosL(>!!VEjymDPWOg$`ZNc=qbr3zFMwS?5=1zReQuqjBLh_;Gxjl8MPKtMx@J zq41<axdoF`lAPIM_GfQbSz5}%==kZH!nl$&)7XeiTI2%fk zqvwbn+!#(BBW6XM6_ZdniyBT@le}H%^uP%gvA@%)^$F3t!RcRG_s_u{)jMq+bPd44W*mrw1^C4m7wYn@UEP1%K>&-^P zQkYoa(`OZGKFh)W91_mB1a0YyZJ$w%=6m4-ZAm(x%V_)Q2l-F*E=m&=>18oCXWaAz zmZ~XP)d1ACL>l%cT9t4;UlFR>N=PTt)%}$+^qN5q?8>Jc}MkJ@gyea~*g2kr)WpE}%#x-LXAHr~AIXMd(6w z$&|R|W2#ngPP(pYEl**>4vYo5(&)ccl8vY^DpSw?0}DNQYI9x}FWp}FUp2ENr({_y7zluSmQj#i`v+*XcfQw zqU)wx6V)(4=GsNA`So0VRztqNRUx|;NrpG|6dgCB%Q{M=oN=BF$nB|H*p3Jwpyq?o zv&0LW$R0FF4ovOa-eQsr zPue9N?->H+vZIx@Ene*NJK=R>{+(5?A5kDT&#~g1ukGDm#$xg`K+nihLg>{;dp-%T zsvE09Ib)~&uMb`vP^!EnlO)BKx}T*#gz_cgp>2OG9x+0^yKe@MNxR53smX{b4` zp-o>l?r`bMTKsj-t3BrWAtCa?u`y_w;QKT_)mY)&NG^0&j>CXg0;Y*ZPA?0gm|hny zsldN6D=P%sYnvLvwU~Xdws}Q-9R{vP#pdTbvYTmpQifR$2dK=E4Bn$AtEv7eAaA5O zQE)l8F8t=$Fm>=r)Q4FCrSq34O61^o8k+E@U(9Wy?^Oj3;i%Gkk{}Oll|Ip4w#o>{{i!|~> zmtDbkfaS&Bx5$hE_B(i50kawhZ>X#)cP^w~ zo&`^D5F53|`G{5lA#{XPJ{$(ec!f^JjG^Yko18hvQS#sv>^fDD>p$)QosiN8+E^w01 zAb$s5Wnl=Tg2T~y-fmR!&E{Ir7CT*8D@qlp^zPhr=)L-dDevp!LDyKkgzmY3pF~$F zK0f2F+Of5UKE|5z*Jk_Iq+RND0dif$PSeg}D{T*HlV$(lNxe9bU!ZMX?NazBzX^`c zMB~yOs%#yd)KQh*T&S0It0JO4xJQsHBrYF665&ywGgYm2jmFoDMNi?zbw@+C^v~Y!zyLztIhh}t{?7w*IIiuauRWMY29WbTEDB;#tb+evj-p2lgBFOl*;0i)?hu6XiPic$GE}1{= zG+yr{;i>z5|A6lm_#f;UIxr=;rpdvEV$rgvmSXbu$zMw4@wEL$DS3Po)v_~R#&0Xi{Uxtb!ZW}B+Yy3}s?C+SHcV+U?vy=*8WZ|>0kOCc(wIk)e ziQv;jfk=Z3`1Au^&K%*lCZ+I5D1u(IiL{NfW~&co?>tnLZ`=!P(S$s7yH{fOr#`Ao zUm(xs{jA*>tkjKE<}6fhEEkCkTyVRAp>O&v7CBR&cjjqn5KdA}{5DA+N2IG=&8YzL EAC09@w*UYD literal 0 HcmV?d00001 diff --git a/docs/source/docs/quick-start/images/camera-matching/deactivated-camera.png b/docs/source/docs/quick-start/images/camera-matching/deactivated-camera.png new file mode 100644 index 0000000000000000000000000000000000000000..85d750f7ce42a5f039936ed034cdef80a6af8745 GIT binary patch literal 216740 zcmeFYV|ZrGvH%)Sj5iZc@Wz;6V%xTDzp-r_6Hjd0wli@i=EQa~cfP&%Is3!8|L)Jb z*0Y}O)m>FxT~*y(t#El+F(i0gcrY+9Bnfe0MKCZ(A}}xrSy-6gDRNIn_h4X%QWio& z@)ANqMDh+GQwwVoFfj4(WVH|KN~4(BT8cm@SYdw2BN^0q0KX(Gt=}zin4~yF5Wq-K zzBWG+zDh^9Ca;_*0w1;3Kn-*7ToV(4n&!l?x2gjU+-XIvi*1w5_5Ec!&3B5!^+j2HL-tWw-T#IRM| zVaDj1GegJf4}OFLGj`_HO9A&2W!uwu3P3Co3Y~?Z2$%otzl>s-^W(>;VA!FcHKff} zrc)s=*V%`xsBViQB+Kh3oIrI9DLvqau>HAD@3+60@PD=M9Z(vZRi-<{eO=4GJ_q4w<^#r*^aZ{u$O%KC9fg7OW z31-rbhQnSoQ%Pfept8|_pJB8ophq_32`d-A?pgN9K(8D90(r9`oodhV_UhPGG5w+N zolV4rTdXkF!Ysn=?fI*bfT=d|fN~h*^&lJ?sulky;B*YqNwWmi$et+T^2o<8W9pxY zQo>1l->JPTm~}8eeg}0ksqvz6xezN&L>>*R-7xM7D!2A!!#;Yy_p8^~#s{JEeIrST zMIa0lp@fH39*jv8NqAJph&_?Gc{NftvgfjpRqp0Fryqk;y*5Q19=$R8Fm!O(J6Jk5 z99iJ5U{B3=b^Y1LJZX&3iyroaHY%7pKe!d{SHwEMmd5ffgpE><05HN4ei&5nP#;r$ zVMD!GC|x4~@JDoFv^bQQn~M_+f3Fc={61=qE282yPQTlC-a<)MH+XwGSV)db-PvMN zoLeGrZvUu9LV_y;j2>(UeUjo{-c6*NX&fAcRPG# zg@fne*Ag!oya_hf8ndIOA@e!?iFK&|GB$fi&k5 zn-O?lX^W_|Yx zkf=||PE~k!Uwz9?dvGH;246lz)`JV}c4W1Fv`~QD zdNuGDOsU?n+YbiY{N&W~a_j$v;R7oJf!P*JhaVv%_9eHsTENgnyHst z9!j#up#~-?P)47o1fspyM;;};N5T$M8$zuI$quV38~GB#DbRI`DS(JHD1-skdjP6d z_!P}7DEg7eUz{BfND3?!handDI3jJ#s~AurJQhzY&QgcM5tS)SM`SaCzXzNP?-1q9 z#V(6E{w7+2!3i+Q|HOdbi^8rg zSczd812_X@14sir1Ly;+J4S{m;lgtiD~TNv@ua*|vC6`lVyhyYvTc&bMBYT@@iHS* zdqfV58iI7BsR^zLvGLUjIq`f-%v32K^CZA$t>d`sqsY z@pnsK%oUhxS~##grPs62Fr!#)%$?2}nn%w?%#ST-<~1sv1S~q*Bs3+vd~1^T^uJd< zQ(BG1!S2uOHG##x!CAvL!^YBl5*dm}u)?zZzT7LGaFHoAuB;O)GP;?q+o#8n-vNLkTB!ApSE#yRfDY$B~N^kwgy0LAe zZPq#FdFlDdI;hrpS>crI^o9Tm#W$9NK!$*jXPx_o`@!>le}60atnvHF6ZXlMyf14* z-1n?E2cDoS+XsWEf@kY{iwBmw{TJ0|-fN}@^kmbt(oZCXjx%|V7 zMs9Kce7|A;SU*AVTJU%u-f*6g&~O#5Cw(8IAV7f-j@UiEocKaaLrf-|6Ce{66HyiB zgUdv1YC6%XE_zz9oK<_V^SYZdxE|dct~S6%F@vrMC_~?%fFZ4twkBkA_)%e>nt+%v zAb~Vmuotv97MF&w4*7R+1A|dt9z`aoekovyn~Ko=~U}=3@a`i z#5qKuk?;O|&$RG(gK`m}PrOeUPlQF}(mV_@R_Vr?<4)~ABa8WHV5uKXV0eWX^4*Jm zPPj7>PVG#rGUBCWv9`O%JY_;Vavs1;SEh?)rSe=X2^RMy2ZIhNra;>I4f^K+!+g-c zl$8n;NNL&{XRNl1L>`H+@)ig4v8uIRE7jG#Y6nUS8urEky$O+gvCplihZ}`IrLSOJMEaBtReRMb^76X;iF~^W zilf}9ZjD;)L#%h{i|ske+NPJE_qY3R`@MIe*r5?8acw`H*YDEq&X6RKY(j-l*w{Q+ z2sn4#jKvZylm->n^T%TpVrkhIJv+ACrr~~uS0&<55VFZxc6nO@^kWIv3_dEni2>b>dPjy#RLOZ`E&(Ad)S>3QL9NvP7c(m8dVo=y9zWp0_Z=xkYK zvz($DTARx=%k^z8ItK;=os<1<9hg!k5gA% z&+DA}S?Of@j^0L>;C1|>I_2Dc9lzSR+Cz`tJ^z>KuvTjGB##0Q%Eo@z%WKzT;CpCU z>}l*FFPV?Wz56lNTxwl)lOA4ouy^}X#@ZUq{`jMJHw3mkfz2GaTPGx#CIAf4&9)#$ zEequZK9BSJJ@7K8<`{8B?FU#%@UPohoy&^@Ofb)8aDC{zpHyJNvtVI2U`I!@fzDf> zmt4=4F^ReHtYepB0f6p%5Ow=VzWn{pp zf5&0LpuquPkiTQ#zh5wLTrlW=#lgTN!SVh#t_V)~9~cNQuuuyysQdruC8>hOmrXz zGx{$a931ovjP#6*w7(%}9o=o64BTjK9ZCL8ZRdSlBsPfNY8Wple_Va(3b& zCjO(K|9$?=r;~;0e@n7;{7ba{80p{;iaMrT*3mFFZH>|7w^Q9#=V)2@H%MOhQ;d*$w=( z6E3q*P363EO5139;U<&ddzO0;Vi4+(HjF@=#7B9kP6vA8upBkCYGRLzJC8x|yN6OQ z2;?yBc%bE2o)9z!vD`f_6MlCX(7T{k$+}E#PGw$xuO0Q{`cROyATo7 z$PJ9M)5pJ4g8=gH;QS-e{}9O^m1r7oepcZhr38V6oBbmZDw_>T(2pA=FDCXEX8*+s z1Znm^6WumYVZpCE1n}{p|H1FOF)A~osq^@CwQZW{Dud2&X+gedh$K?XlV!5C73ePN z+$t;j;?F|)7m3GMVgA?mw1~$p#~0IJ#7}yb`fc3F%Q*$LKQp>^j|w1!ck;Kd^KCh7 zoq=YTw)y;H#-ybBP!=OUnC3H(h#^arPbM-QvFGBTtn~ILiJ$Rht7>&j( zRiXg@ko2Z2RMC8ogeE!X&$KG))lv73y5ERa$}i(h3Jjvr&D@!?QW9o40MY1cQf5_o z>26w9vB##49ycD5ENf5;=0Bt$7u(Y?yt7CDuGA^5R6to5?iEQD|7G1}=Nv$~d19#a zn`&iDfo+jYDnU9XE>d}#uqZwaZdztR*aAa`fqQkTcgS+B>e?0lKPXQl`43DLlO)fl z)5Eg_MlNN|OdH=Zy;yIIo5+>Np$ZrrolZ=|r@*^8$T6)woeyt{_{}t|jkp51D(MO1 zj76oMnC%wkN3csxu2n_Cj=1#bwYn4(Xg|9b_4>GyxuP{BX)aD03mkgz+Xp5bMz7cS)(CvbjRMt6;wP-Sv|hoiKR^;W;O;xqYd7l4!#Mxx501iA|gG>Cl_B0^1Lgr46gnWklmtS)*@wPwx`Y z;#P?Q){=v2%{w19s~jFPCJ(FuO5;eKEnEw?(za@72q8Hkc=;)muMx=UO#0(si8@O?%VDUCas z(5${csk^YWNH$F|1Z!{`+xCm!xHkurT0Z@gB?Jfwn1&9RhM9;`2Z9{U3S#1~n6!!AKmXQ4f7f z$@^!c?8bv&Di~HKq%CFG&)*UbX(?TN5*?GIAdhrRb2&NJ01suu3pz>t@KUkPLteVC zO|UH}R9RDAD%%wrmUllm#>x#}Hp|bky)NJPMA}LK-=5y=ROn2rX=*Z+I?f{e zp$xuSnl4rz?rk>UOV{5muZo-^{YQN?dy> zJErsoE0I2sM8d|ahySyq`y~KNN!b20de|WTFSIJaZa85f z-AU$}5q^OhC82hQ9x?w4_Vjv%XXwYke87(+f2ij4YYoPso6P` z(pOcYZXC7pT)o~~{a&4TYvKpB2xhaXae#UxZtQf*J4 zhgTna>R}+On5Wr21y`)q2AU=NN{Nm+VvGO4{hJZK_7MA#Y>heyiA#$y{8TH{zG9-P zpmt{!zPzi3h@U=Kt7O#h|7EuQ=y(ccpaEsQ9VI?`vQlKU&Gn*iGToJ_?MKO@tBbly z@;vUy)nO4ush+0(WnLbSMpvaUq>SoN$O;B4!g!$`Xb_#z4|#oRMq&x`w*hq%0U|7z zVm$i7nlxjYPoiL?ewI2LbB-ti4yZJqXlf8-6%QHU2|f+W`K@fvx!}W&@H=#PoNDYZ zRp0*K5(w38Rk7stzEzUCqMnGD_{dGDK@%63w@{UI4Q!6;tNL-Xy|deDNya5!9elD>c^nZ)%ewdVQfuHM8DEe+wf@)b%St-t z@zx44#@*j4@!N~xAVG!L;}F6|`e!lqBEKD+dJ*d5e>fArN5S7&jv)+xSIloBW|6=B zC9_E7d4zvZJdFCCb%E%>MGWuySTJbg(n6g7BIFJ>tvGXz&lW26jU8w{JDET8hyB zcX}(KzqwptGc&ON+c?Bvg$4`GXjM#yi1N3pnG*hX`Aj!6g9rcCOnNH*kYPnu8w2;> z>ipFkHV7=u+YuAx(--ekp=5-yA}; zJ+(Nx;vu;)VjoXM)0X){$;O9etrn5TLBhdDcDM5sDNof8hpI&^*e`3rKi*}S^f=@bNWz@$!jTou0VU8%pJDb6gfU2OBtt1 zzRsltCUb>)wOvymD4M}4F)hzXqsIOcgA@AmjJh#YVK_;NW)q!OP{zRwF60+TNl0u-|-BLp+=LWLPBQ`GghaY)n zLLxlJp#H-|+`ed5fTCcc)$4*6?2~2Fmb2s?WB1q43Ofn)GS|sQ$#sh0MGLvRpvLCR zJ3Xa4<8dV^OQFV$Xm{xI2Y0DPtvBwwjmJNGl0DXQoJKNrIrX}o_xI|g43fj|9t+Xzk;6vPRI6lQIjR;qihr2s5;XmPx-V2elk9c{iI9 z-^Gux)0PwV%>7ebnXH~-ae%|d|j_>H?T%;=*$q0s&%BOL}EOMJ%M6&XJuu6ho-S z#q9tcTnRxzn-g^?F96!M85$O@QF)k~+(AT~wO!(jMFcbs34M61K+xB&;J{tU3%Um3 zbBy{YpQ)y9&|wL z_epuIOgBJFB8QD(Ddt>#0u;O`^V)zcL!x@J-JJ_gY%^hglnrhvmLzD(SctdeD8c6v!Jv1gmKYC=G!=U;r;=QGfKDOGomQy$_mJa9_L9AU z4IBA2cn&2ZO}Iqn0A}6j(akYWPu%7(*2Ol(IR4#$<}~ZL(0tJkw6TFz<$R6w3dF$N zbh=HVb-4PJQ9&)2BQ`-9R*4B%n)6Ga*D~bXgQ)SfJIq!Iv#f!3?j5tb(U*K0EF$

p!4D?=NwX^5dd139 z)2MyUHxGCNbY6)b4}^5W6-%CHCB1YtLe250B9^~Qa(Ym3A?ii_ z8r(7*FaVQ@gx@5dIr6>W;=4W~i=5#MbPm;SXlJ1BW+K1`vzst^Xwj`!M262lLxTA; zUx@9s+`(vpT9katXvfmRx_rWt%E@?TJDjCyr|IL_gm_xO=TQyrx|hF-R|mz=y{tL2 z6bN?z%<2pZEGvth4;cs{jZM_m*bxi@b;d8Xs3h+GJgGwrhoSqZk!BW`8cLj(>ngf*fHOoCt4{etKBKm z`g%2eJIEjPV^s`)V8C_`mi$(VcCV_G!74*C6$H#{#Qdp^4B2Y7rs@bj24EO zkBfB>jB4H@&TbD zLzA_UMxd_Fd`_r*JzT#k-dBnHCdo=6m?K!JEWqL%I8@+M)19`tJ+Qjw$1OEtr-L2g zrG{p5O|+MuCrK7QHSzUZnzW_Jso{0b=Ei_UKi=n_QMjm-bbcs zo>eeNs-{Smwa89NO7=;a`8b^qz4A#qx($PuZb9yTl%T53o7SG>lKbu;qwW zp}YK?JAA3pYgswo*F%_AlJ}?)NWpdvI951*92~O0IAB{6u$k8o1EWA;*=+^@;L`t^OD`)F~UD8+(}GDCP{v!^pea5;Gaah zdGt@ln&v{oA+w10Td>fPx!*uK&~hoZAXi>JYZJs&M53&xbbKi*RI*%iM0lke`FuZ? z(Qn>Lo}14|>t-Aqo0zc=9+#=8(7qA7WD`yttqc+N5{z(P+T>u08)xCpPwGK>svTyh zA|%fnsfpezw=I0VL;9Ma#;<-7b-wu4CwJC-`Y}cV)%=s?_wwQ~pAx0Y9g@qd5rQ{K z7x7y-vFIfp1>}~Yf&>rwfOZdnZP~@nboIFC{>}&}SCuS1;e%AU=9A-2NFfm`4&`*L z=F;On+~``+bo9{S*YDl=)0t&F;ktx8jwMWjs$!)WJ~ufHDG^oVL{9wM9a9$KOtqI* zR}_Di>v!xwI!Dp~u4vyxbuLe<1j%JBT?k=gbXE$W;v{)q=}V^3^%lJn8&qhTy2={GRRUlY)qEC*)lvMq)<~I|Z;Po48ui4P7{n3`{tL ziFmY4j*wzvlvv?4L{&@h6D6s5pKxD)xI^M#8FXX(!+?9d&$;s)edas_lsW;?U2!@< zRzHuG`CS#@mVA@9<TTqPUgsxi3?4rRtkdF4aDyNTerlz4s5ES(O*)h^p(iIdSEZa2Y?1S)<#FdYi z7;ShdQDXiBK%<@C)kO+x*+7Ak2BjZ(pWgYX4rS$GN*y&DzfZ77dS@cko4TERnXI3y z5tNx7`MG<+OD6zk4V|v+ke4Jbp^|EV1{i-TduOax-#{>BY<*(w_2-F#ohFH$BtjgO z&wUaVYFaYoj5FFYghYRTe!nC~2pD>L@O3xMjt4vOpbnkuuA_^@5kr5yWY zkfuj#!p*^9kgU1Dd6dtT+GyzSQ{&sAS)c3BKNeK({4pYBl1Ww%u%zX3^)2qpC{Z%0 z+?;wG;cY>dl<^bG!b4S%CmCzT%1zpS@LK@ zSY!gl(4M4$5U}WKa1BpqYIj{4eg)xk@S4APgxXw;lwjPPeRc|-A2|g6*j3%)LJ)0~ zNP@qIEyac4rwjc2X6dzmjZJL-qv^ACGmBK}>ds)K^=v>et8XtvIfGtj=bKAI^Ahqs z%1VA{sLe0+mDSpEKR11N#S9h93y~UF#_+G!y!#d-o{XHleKpig7P7M`4^FFjF#)t1 z4KtYEmwr4UU|UUQv#)|eUtrF{H-Mg}!js6+OO*(p5MZ-m1S@*A_iH$YU*(jqUTZ2G z<2P9@Q;+647Ey6=6Zwz;QJ;Rc?oriWg`=%8&>QiLA28zRPtFYuQc8i7P;z0Bfa|FWRh^E0BS0*$B=4prhI%quJpsu#V(zRRs2@RCFLMnyXYkHfq+ zoblr7y*F*+bqfXRC{4yp+mXCB37d;R#oP)vS_sK%tugL?jl5{ah+GSQW@|s|HSp{Y z^4QSVVl?UAs;uADCcOHAaTyp7MJW$hYZRFPJJn#Bi(rYgo z>>8mrHG>8=?4LC5<57OG3l3NZz;HYJw|zCW@nSzSRu1}TYu$;u#2e-d+O%KmbWJ^5 zw$I^lGMba2b)}(arwOpQ9 ztSVjI0v2+}D|CRe$pTt^MgAF!cgqWEog-Ck*Th;-cDSjhY8Gfl1wlxct!GtYr@!7# zu_|2)41|*FB#c`4doCq0;#FoSFH@4nQ^Y8fz+8t?IGe@34Dpgrl# z7H@f0;sfA_AU~%y`*z)dx1VRYt_FH~o(;J5bFQvlMs2)$>T11o19d>WOTI-)7u_KRUDV80Y*Nb9ONGFCWd8GL#PHc%I|$LqLYi+{@K?JtPL(XrariIi&}}KT)}aQhAnRFU(gF*PdXG6|GY#oiOU z^B;LOy6rG%eiV?`W7#`RhgV;c24Rhz=}6H*qByZo1fi^mBTLka$WI?pCIJzoee|_N zePyUb3j4%+O`ZZ9i}XjeLm>p?+HET#dcPQ7Zo1nyf_sE0hANRRda$#RgCC6zhEz_i z%4O6)&_>Da&{ASva+(YAis}hDF`TkSWq!h`i@vG9zhCNHtm--y%ve$w5b`T=c#s0P zUXL7gcB{INUH{}i?bz#^bUD9AS<87lleurLUe{mOfyM))caLJ+lcwA&k$zNC^TZ+u zw$J#4ms_u}*5r}<_S){VOvmjADTEg|fHI4fjp$wkAC=vjfK}`-W+u=yx#703;xdR~ zw&u*nZQcD;I{m1Pg|n;f4iV`P)oi>Ql;+&pY&9{}vwOMA_sZG+x>GrUU-Mmea9HpW zLtX!?kyHha&Vmivwh5@+qg==1o%3b4`?c+Doz`_F0Xp&$21tkIh~utP0}VzQ#uX$M zoV6>4R;ICdM!Tg!y^ry%YEXo$YAD@&x@zM4TF+;gYQ5?AwSdsJdIyI%59vY~Qi0Xt zENeX|G`?K;DD7UdbUQg7)@BsZ`y}7C)2b`~Pg7SSJ5FMv4NrJ12^g}_8!VR;!(EJ~ zxz|e=_op8mF2?%H=e|b*6s|}kZmv|I)a?4+m}qq3y$M+$1JwXr)2X5G=&`eKZ;@?1 z(urF8VL{k3s)Y@O@Ua;EnzZgnOEcAWt~5maQ^Oj|b+C)r@Q{t8Tt-%-vr%81adhuh zg!jvPR#O;i9w+E{7?_z1D8Q`l32I@5Y7X!#v-9!0%=Y08&B%F|%-$5?8hH59=N4j+ zmq3ak=nKCB_d*ZyE__=R^9jg|t6ktrip_@qs zbQ|>C_soKO_C6i1(&#=5(lnUZWZs(?(Su#|$8^HB@nE-gXV$;t=0OO+FoiNK*?`~q z-rmvIEa^Iz-sK$CbF|P#fK|LEQQIPh=az+PMWbo57^;DE4ZE+IK#o^m1WHsmBE=}# zhCQBm1APjQSTv=|nwC!?1EEhhU|~ zcPfuy*4javCVaQo<7equw)^0v&+4K$c7*JNxf^IhKYH_o(>F^r+hwoQH zt2!riUG@uEi!0adCFMT%1Ux|zS5`(NVnD_5Y77)da8m+EzI*08{(MCL({g){MXX;p zDX)qc2L=L)yYc}<1A{krEbvSP2wganh0jG$!`8h6fBeL$*kmI!N{(|3N>4!DIY<%- zWuT=}XU+yMb*h${7>rfcM{tGLyI-ft!v_l}jGoOUAN&I_vHP;FLUfG5el#-@^fs7! zQ7^GkMpMo2gGn}Xa^_jv+3$f#TPH)qX*0fRn;{e<`5`Y~a$;dDSm!<*rDI(8DmQkm z5bt0W3T{Co>C8bZDa z^#RIXNz0D`E&=h8;L_(P*0eBrcyx^AYMm*y~H*Zwy%ev%3}mS&WI5hYW8nQAg=Ie)+53C%XREBdY(nn-D|^Do;R5E zbH7ACboTrFoPHmg(rtn#j+EJ>E#UdG_r<>l{l|VEf}H=5vH*8<f$z2T_oV{82St?K1UCKs zIf9q{htAQBSA<{qa^G3GVoI)p9Y%|{OuF&0aT;RvoGY^&4^)YBhHNqi?ik zpN4rsT9r$ytA{Ozd-9-#t_Igw@7o7nBSP=P#`~$}cM9PgyD<%lhs<_o|IU|2wN<1| zpB~NwI+2drGAtu1bWyV>GFCqZcEQe2g5TcE>n-2f-NUBYI49;7(85fFHXH5ooQu;u zme;=ct$EsOf%g{;pJ{dXE4SU^jlRp!^W8n4-Y>(Kr_DDmu9t~u(be#M*yQU@1NA2> zfW4aX)CZuR3E4xS0hfV3l4?iWuPvXK@>uVgsnv$59J+0tVb27TB$T>tB|%KR|-p-zhaU2v*LuzZ#cy5L@UW2->q(p|gIM+32m^ zE<1C(MB7ljF~zl931QnAOwBa&3|03JXS)F~SV-tdpse;~d^0gqt5&ymv`3nUOP$5D zK$CVW50&rSI*krP5vMrYC%U_?8mT9W9Yj<0<}^~EAoV2KORNt9%E+>w#=OMVxV7@t#9(I12G+h{VE6cZ-92s%^>evxh@NO-_48VFRG`jZPr=N^x6iyE3Gaa znl;?f0XvA-Pl^XWnLW6f?8@d-`;&IJWV0AC7gL!HWsFkc%4UHj4jy~(B6 z{NloU8fbxfFyA{ewYg!`UtzfKPBbGH+f0Ea+$SnkSw)^{{xWpu1|OyzfEYXLlZK50 zmu-8Eqx&9ka|SEbXIV(KS^G&a8U!IHx)L(nSfsDurApuEdRH3oERu09IARfkjeVZCmfVL(5s!c3@BhL#m1D531 zR6@93f7hNV&2d1>WANp2%P^Q>)u$*LI__asx|1ufXvDmO?ZCkMaK6^wsSE6;c-&S7 zjD)GQKu*VR`+>n)7e_6fadwrz-U_u&+k870uB?km?ix$XO5YBfyXOebO;l*PC7}~~ zqB)kQ9Dd(dbZ%aEf2njCU37MfF8eIUZD2%NI)1W$6XN-qjnzEuI?mapab*g`XAS9n zoi+pIm_N6;XySsCYv?xM;HGNnRxf(#rHls05|nXIL8S&4PeNEkt5zSM8+e~RzO>S~ z*Z2AK7($4fp~C4tRIkJT(B>Nl-|ck0vKp6L2(xN<1FPWd@n>XtgDDqp(P5P+yyV}Z}sMM`aqhbVgE_^H$@ns zY!f4lvBFqqmz`w&##%-PRER25sUP(=ca|9yj@1sVE#Ah46S|!yt+X1SA7G)U(X9+t zdX2pAE7x2#OC7uD9Z&EusS%MgSWL;RtonP<_w*|?ne}JhFYQ>5o8{WW&H>1YjLPH#D2A8s4@S%>dE3==xQN)(QGb}_}IXqPFJb{(M zlOuw6&S#|TR~ zE}>U?UC_FypMHO4qh0ES`P!D%-Wpl^r8#OcM+FXWI#+^W$)-bEK*pWK7jSgoE}j7# zi~GwFs7zhh31flcjgd=LQpt_y4C#4|B|`BJ@lM_;Jy$WvG0ShUXCw{KV@PSA1sSS4 z_O!2Az9pdQl7V{$unK3I6977~mXG(xe?Tfyd^&u_vu*r9;Ik}YPe9yeK_+O}%Z>E` zU6U=9270w(iXTNxPbHpmpm<`H!2=Jgv5hqhdw7YwcOln=~0t^E*jTt^#l?vuQZn%(PEW` zl~`EnT!v4p*2nXti1U=352Za*8y@Al!TfS{nWx4nDDy4S=hBfMPYAHoepJ~X_7=nX z;ONn**^s=bE3(lj#+n@KaggC}X`opYbGakCWV0KXWz{Y(R_cgM!xGVbI>l?Ot}Qq( zW6A20VmBS5UXAN~E+U}F{XqwXwOjajJIQr=HB6X~>3qe#l~ZFPRU7D)g-Z}qko*{} zCeX^oazLmfnv3C^x4=mgipE)}(nftP?;p)7udLX0kkDY44HPbY-pYxob0c?%3XNC} z!R`@CP&!A}p`z-dV6)|l`P882ez9hK(p1Sh1UB|0`;w~VvO4YitY^J|hv^tg%24EA z%dMlSQNB9Edj|OKMOsG6d>el>qhBLpsDN!8%rafZIw387h4GgSr0=kQ__$yV*W8Nn zrA(89=shfG?z#<$SPBjOkohhTF`U{intg!B;k=9~Z_{ z$~!F@HA7y1?cO!7R`Gb|`iCctDP8uPfqLq5Goc`Ih{jaL9Mp6WEW3JPe ztEae~9TRA=7DLJIZk%uF=XgI`HQQH>3l$WgdqMKr#UE0xWumxKG~~C9v~IZ_%~Di= z%;z7NwlOo7ST?J;T{}UDrK}BWZK~@D`ZE!x#FqgA*- z*pt&X@d$V=yWfI6&mw|F5-#8#^1C7&{DLY9jPacdjDoL9b>IY18WS`VW+!)up%_%O zrp^D_^NT?Z@W`#~1Wo*;<(6r1NH2fV=pW{I`C5kKB;OSJ4at)HGSnD^UREZCTBhN45dg!1EsRjy+9(p)El_{_6l1JadYpmekSakKp$AQdAA_bP?z zM3&%|b{^>Zipvn|BF>Qdnk>VTBpif?+?90wnRkn8nnri;2WITGxU2hB(XR_SN#{2y z1#-%_JAY&DUBKJ%k8Q&b6UQQ1!zAL z_wnDcfnsV^=JkU&D^r<@BJ)%gmS2sXJuguSfE!0bzmE_nPF`GId5Wwi;qQ{_)=$w3 z5(n2<2o1xGDbTo%8j-{%^=0qn0)Apj@EP@LuZ5bQk|>@3)cBb_Odiz6Hk)nTk$^K+foJ`1Qa zfM;Y13an9iR8u7u1!~Zlrqftkba1y{D;08BdhlS2Ssk#4{rR|Uk45Modo{unw{)5! zps0*1me+)pAja^H<7g(~hN+BqPThz%u~66-;7?pZ+5`<^sDlO4#MoLX*Nlxtp~X;f zuSFl+wP|gU6IjUfmTlyesr9xI0zO8=hxkCEX<>?W?GERz=om{8nlRd;u!$;D+8?x5 zYC_ahVF0+Voo_0h0otLQy6BaeA~k$_nh`>bemqhm8Z$^^Z!=*@549e2!q~Y$K$XsN zd7NcqYT-rO#yR@CV`jlYeH((yxyIVE5`;kjgJLAfe5ct18Va11U3b$aW;h4~|ECOR zbi1A7s}qd86K|-EcwG?vLIZjmRN%(@xTv3DFm2!JGSYjUjg|EY&dHDS-y4FU7F)fx zt2o+C&QxJ{&0Squl8&@XDjVz)Vg;bKNADEoj=RM{+ha%=V?g$TO!Q59Ie^Adp= zI;z+-EOw>qHj-*-NuZ$sk0pYWn;*xtIfD|FSS?0tp?v-lm+gQbNA^Pok`CQvL6p#y z@MmMQZq4jsh4!{lvfJvCTBC1Q;7n7cPBuz@;nzl~_SG3x5|8)eL?eC0+8ocN*k#oN z9XFcHM9U}(8WfoorfU>vY_U4YKOt^=4jXiillHPRpCfQP`chTEwoR78 z-+8^`cmN3vtWI~mQ+wXg z=)sQ$Bc`sdL)JbptUce|wZ>l?i(eLW_zPQ*@dFx@S%^CTctPKQ%GYkjNx56P5SDOj z)J@dF<&9(NXyDAet5zqRdyk^CWkh2?Jj4>cHgqK& z$9D&^S^f;LwTenw-zA$R|552RBW-RWh>wJ@2rqN(IrLAt8 zP_1o_;AX-d&w4nkk@Nj2+8)-CY>@I+No1G67V@UKTw~{xYv9V$wB~b1v0;6f*`C#b ze@qktdS48@_n&@?%Y8~r?!mvpmamwGLtH)KkXCCQi#yLF>Mx1Rrz4_l zcmpqi4zLcSG*b?8^DyzbrkQUAmBqlP05n3 zd+po#rY@+QYx!4TWS~C}ICpplcrU(zNMZFxTR-Mh#xR}-Gx%p^P$LZ`c`%O! zA#!68Wg#~~6l-4VDscMOUBo1Tq%yIFCTO^vRKRLwaq3<+@H4q-gbF4q^N&0dyJm=uzebl$ zg%a&SzaX3VHCo#BzQ zWEVcd?}~sM@MmI6TX-5S*1#BL$-yJA=@GK=LTG(UKk3aRrsMj8cTtwl0tnuR37Df* z)D14!;NhKQJOc7$2ey=mf=~6^IT>hRYOc`g$owg0Ig>#x<-Wz3U%&!z19of}6FEI`7P+_qVM3canw>eyoC zbo_XTd^)J^0zH0$1{j)~xqlhV(i-fCxzu?ZVI`=+!9DX*cfw}A7u=j`>;^5dtc$D% zw+uG?`Qs=&B>%#MK>4rxh67&G`UM374Z~adhRbuh@1b#?JyYqLVK=pj%!h!>Ar2o- z(Jz~2)8G8!!Mvtrpo35ta={jbMAp3Ft*tt?Pu`uETN<1dW~>sv3E9wLdnN8-ec4)j z`F!yS})Uum?whT8PItw5RQ>|D>wC<^ZPZ7n?cVBiFf{I7=upx zkaS5|v~Os-&T+{|6R@7b|}HQpmq8qES!~ z{s^6s)MDN=qmcavZmM->(-N%&sdbaqQVKfo0@+aIi4@wW<}0*aJRe7c`9>m0|n07b0T%b7Ono^sWb40TX8w zgIi{Vxf#x@Rok8ib$zp^XLe|$$DQ800!WAGrtJNDG7v;1x0o46k+1|1(Nt;%+!|hZ z+VK-T=_(%)WGi5t=+V!8a3vW>UDw&?Bg0zVaO9?`Em6`!k*8!9?~fKFaxOI|*Atvi zqxcn!9ECzCe=;q&uoFg$AbOn;a@H&&P zs6Q7c;oREd2Ahrn7E&Mtcm>fQM$Sd9e7dsR{MaYx)zgzJb$_n$JzD>CEYR&VKf1c*X7d1vVXP9vV}L)59=0qSyE|>at@m>p45`QLT`1MY(3>QRiIm zTyv>*o@LhRJw-@ov5OHdE<2z6QnoJqlN#(HMRi~cVaKZLV#SN(c3qmXKai;y73!g3 zH?NHC1vVj8nS1qT)iz(8lb(zZNMsg9q;99{*Duq2U$5+Ie|8<&t<^hJUmfLTHv&BT zL=Vpl3^Y^r{w^RiiX!w#`q0Fs&SLLH^9!1Kh%gya8V(R{TpM<|&?HRW?MmXqn0~@gu0Y&TUdA zU}PjBerx)j7=*$BPrl=gI-5`7f#F7>(?pui1Oi-+4q|u26=*(6JiG5*{P+ZCP_PUH-<8<_1J#^FNufu+9=nb3xcDNC{ zY7bf!SS@bzeH@HO+rRfOI7}~!zSBh2LnJht!G0NJj_wBH885Lot`HLO8fAy&8LMdW zm#n2SR@a`83No`!;mp(%IuS^vIj9Lx6#lC!+DRP7;gGxf+@(2;J(W-zXv(WPp-~hz zJtJ4FQX};qr&eA@?ZVF3)q-nLn~be7Ic(m>DVm|>ydTroO25t?G(34sJ;wj;b~td- zn*%_T_g5`8#?%7m$L+Kz^|!^2Y#RkYdsOEeHErXVbwuLH6uPU#Yr`7CXKXE-##l_6 zf~>6MxJu<3q+0~p@6cVKW+_EuQ7AV6{c$u1r4zj8woH5F1Rq>KV3#bZzA`_FLf<3{ zhcr1zwZle6kBBPXAZdtql2~R_UKu=*l><513dm zr67W7XAgKMSamYU%6>fG^pt^+gpyDC-C?-@%L1s&Lt9}r>-m_sZ&~iThoy6>4p5i; zh{C(_SlUVt*dVgN|uIjZq zetm0G8ND%NV9tqW5iX6e4TBhVIvzEA`%}Tx0$^O3uJ5lWp2#6bYySDf=skAZ&Y;r+9UQ8Lo(LUp4j_$&3X=bKHbL}1Q|VWVz%tH3*l0_Ps$+7L{FY(%(TvB$ zzei?^5UMb9ys=67`@7wb8UJkEPwRH?3_zrqf43cj;Ctm6i| z6lF7+RNdmORDiG1hCynuDau3YI;I^J$c`pEd?2}R*`-cjQEFzUki(i_7}IV$rjH!u zd&VuiO!$1pIeIc_IF1jrA8Sw1`b&gw@OwexPI)QfDTlnfU!dncwY={W3pQ80PEkAA zw5v}N51gWLl#H@AT=|4{on`3RHc zUj;Dn&yVo;DNWw)`n=#ht-SGnAh{hhQ@Fw3Co=Qvp z+7{8nuuI;%a1U>pfD&J!3ZhUGgKLPpN9@E_*Y(M%I!-s&{Z1VJyXAEGr!^E{{#n zrUzL0ST)+35L}lK3I?K__&arHeD2m_IQ0%Lc~_uCxfPkPP42es2XZm>&Wp#_ zo&HljEkdkr_&l?HpNSJPCq{B!l~B1v_yR zDY@9S`d(LS7omDyG;gXZ$gcN)(Q{kfYkHqMJ+&3nT4ug0v*OsO(@4VOy*agI9Gjq%yi{pmv!(u3`NHA`8^w=o)_{@xuQ@ZFt;B{#)gpOaeWH>Cg~`99sn`&_l3KW|w8^_o0KC z=WR{8`YzXhW{X#2ducAfP&yeRQew2cq@s|VuHeS&4RfJsQulQQ)sVqd8~L~}-1x8k zR{@Ov__UDJ#@aV}Nn;2KnWRkxHVW>0(;IFl32wJ&85Qb6)Oh6Z@+!`52A^P0PGQI? z$WY7OyH?ubN=@GE3url!Oq))j55(lJo@h14bn(_WB6P?KZmjC`2s||{J39*B)EH^XqLorD$ zrp#P5T32(;_+7DWH6ldbR2rm(mI-w?csMZwpPwn9DejZUTt@z8gVU`gM2s-X>l;t>pV z+!VQgc0&uK}~45? zCJr<(Kr^;*xh!-f^NLJ#E!FEDUkBQyR!GaC2MVi)AvrfKx%NB+=5|ppo+2@e4q%>E zwCo#8@==J2-R1C|KUN?)>{aM8D7@22Y>++P)UR@`Phf?0C?ZPa36>*rJNzpdSGz3M)cqNZu)fxI% z1h0UMO!l5q*~BIHigjr0JsY^>52C5%< z9l&Zm(gb^|u7S21)7@8a^j+8IYk%FRDQ{#7z;*XA39_O54+dC@wdFNybHo0=01=;P1;rQS(StleU*kM>_n>bWRPXq@Vz$4)gmtMaYjJ0#B ztw$~G5Xoc+)1ytWw?zR^`^NKVL9@dpc&C=Dwwyp_3O$t;LYYu&Dkk0NiJ{T36E4=4 zSB$H)-uEfff0f2x|JxCa6`|=k2WusrBX2%JUT$FQr4$X7oIT$sPV1Whgs>4t1}B29 z^STRY zatOtQtCHB5r9}2B|8BzU$of~&S?UUldh1yjAjmB_dq}X7vy)-#h{jF)ZpR6y+*|^v zlvN*%AZJk2#6)z`k@mWbu%fE=1Z#&^< zdmmbOjjmoE1ZwFxE1L>L$hreHf=td>f1q8QC*~~{?ZeO*!ZCh3myV5dvWN&vV$b$` zE9rP#Nk2kd5wkwbqZ_uJ-?e+Yj_v&82Rde4lLdDJgGX0Vqp#mh9o9;b9Z;)?TDj^z zDso%>y2gx8^6N}U8-?F#I}9|ydD#FrqZwM|k&@|?R1)VxKq#MQ$KIf%jLb9m z#vdyeqpiHkkY*DeT-}os6>pqfcr1XYzE_np5Djc)Ozy0xKW)m`J{3HZW!z1FBf`^S zFTJf0?k50m;+54sk(a>KWo~%GrPJEi z8NMem1l_Po*>McM3s6}o{bM=UaTg=MZXC{e&Ik4KtH1|NEqB)nvnE&#tMpRLML9KJfjGu70*=cNu}{#es`< z8a^RK0jmRqfHkYEb5i{8hpCDCzEuyCXM)Jcm_uoVD?j`FK5MQTFYvr=l6;6ROqin8 zAiKiz3fwMF+a9+zpD?|_c13uy=$?XAlP>Igyh?npKYf;}f!)(+duu2*T*}wmah$?e z7tjl0`;m=z>-(d1V>B+XJ0$TWu|TfP2t)Kf=0Ni=*_;Z~E65el@X2_S<}vb1a=)pE zJ(l*9->m}#ym&indJu`@*L`l^>xiYK`?tv;#Z@liKxexa~XEy&` zP3F$d<}F31>Lf+sWmL{@e7$|xOHkh&8!?WA$2GgcxxHgm&ao%ftB;45!C0R1IX94n zV4~nR!%%JU`MF0UG!V3VzVwf>mTPXhB@%AqLHO-#hF;`{z}blMxQLLs>W?D{632Ha z6fjlksM1>zA$Mu2ub~o-3ysy@qUU_+QU1Bm;#WqTqN5{8|JUy>jL17J;C?Oc9dy2p zsQnDPEJIV7== z%X~p(q~X5VF=DsT$2y|Tks!iiNkBid_D!zfZ$zvQr{W^WgTFbuE`q{QLc>CEVh4BP znBQ)*8QT9Yy=9~eY}oDQKw(! zsbUuMa1#;rD|@=ctfYsWe}$W%x<;y*u#xBtco!>SC$EPItpUwBEWN|;DYoQK(pdFz zoc#KyzNbW_`S54Ff1>5Vy_R%>gU8ZwJwYSG=kdM+ZjTvuj{^WhxxKhyyepqxj+tB$ zi=?o!HwiPDid$)9=)pGur_$W)>8q9|ChoPTL~6m6k+y>yP$wo4PQ8^p(thSU+%!cF z?G=0>W>b8K0j9$Y^`L}(51op_vFfe;cgdt0AgV3usKAX@*B$1JYGG_evWwX-UG6Ni z@^PH9S+{VG1&ic5Nsm&dgS6JrVEgzj-kg9A#8{yBreqk}u5lWLIS+Ke9BQX3->~hN*SHV3!OrGj0S$b*4Q^XBNN@yCc#o;Rmlyl+i5hdb98!AFig`|IUeiaM#i8c zQh~Y6{Iz11Kpo6Rfe6T&foVGUJ8LRL<)>m*t>1P!#E)}hoVROq=NLvJbfAT&Y9eK- z7jMF3NEITYv;$|WwsGQ!=P$3=02LeQNB^EA<`Duczjy~JB;<d}R5#=%Du_ys>TTEcX~q8Y zMZea31e1p&kX}fJHfjoOc@0|XEW^AYjMo#NmLi4bP}{gTyzJ4$7*(-ez2`oi@m8r3 z5;_t^yNC-42@yb>C?PtGSW8_fCwV3ZO5XmHz7WGprj=bOBsYC?@UsE7(VTh5Yq&`bSVv!`C30G@bOR6K{*>yNS2P>WO2pOdW@ug;F14 zLWjeAS4U+wAI&e4o%{kX?+wznKeE#nJ@z1DB-G$P)GrVcV>C325>>;)?jukd=S$9r zO0{zNjq8U+VlUb~uBt~1>bFkMYff_3RCXvkykpY?9x5@U;^hMcY9?@3@j~m+1aYpV zE=SAb2bj6I0 z^)@zTC@0re%MF(t*hE}J2-onqwqPl(Yd(j$J9qlL6>l&J9If5~6Q{pu7`_JFh- z1VmMvgrnjHV?=QBk(iT$;7by;zQ;jiz=x3zp@is79! z0d#5;7WP6{?X@9w=Zy4XZM7Fgx&whit+gz3s;egdp(Yz@f`E2RAJ}^)j zJotgjzWF;*8eS;(TUEcbGCOo(O7+w$KQaR9FxZ;9w~;9wr1&SK{j_JMZh>sPb(PNn zNQgq$|4+FOHEiqLCJ{yO4fepnI^KSkK$mjdCiqvv9Or`YJ(5p1Qfrlqp6M%61P(xUt3ww-zPt~2Ko*z9FP`0 z0GcKJsYi-O8x)Mze{h7_EI;>oXHEXBic=lJj21F9`Fe0>psWc8Wsv4w+o`E#3q0`s zBYHa35hd`S%(wRrQsVA=9~k5=4*qDkLEL&O`+<0rgfxQG}Z*2Nz-3%_2s zc7WU#%M-5}>naC(T3Wd~vvupqq`fR<{hPgLk4v_EgEa_v-Qm`wsM;WwKpKUP>kPA26b$l@7& zW9Z|p69_#wP{JTB2A~R7bv*x2eOD8u)8=tPEQ>Iwn=tRB-RbiU!+yefy$iTbc!~n< z?a?!xYuvpnQsFQ!+WbT4bpVn%c)=kHrwr2PB_ms^(W3rTpR1Lx;Kc=s;iJNgB|(vo zAV#jPc^pJ#6P#69kz;NpZy+=z*8_D7%X`$}n zgJ4%M=};5e$?k!>51aIiqJ}d}SJ6b9{?w-qkbB0t$^@v)u@MiFGqYP<*ygv%r#L<* z?W)b&sY)FL`<%FIR`>@5917-33I7QwVe=ech!0IF zjC6@$E+L&I*2kZK!rmEKONCzdE)H)&V5kiiRM^eEX`F5 zpmm-45gd=^^m%g8LO+MvUa!>EAqbJIZ&EBv0(yd+9It zl-KI{fc=PbNjB29xKpJ?KtnqbPxHHwQd{caQEatKjaNc+)g$OvF~Nx?z&z(w-FEVP zuWWhG{hwWY2=KoJSqf4?G^fl-KENW6Ukblf(qXs+mNd6aF9na!=bIZHYB?WYmKBGT zQ+qB?#?z^Faj2kux7eX-r&NzXyt1dsoaY8bV5Ws9DpK4f3^lsnVLK zt#%3HIhS(2rj%jYz?=-!hliBJ4cWI&2CD1!TwzlzfZX5#f>ch{_XM-Av}LZI>ZrQQ zTrRflt-s?^LzOLqSw%5RAucmd_1%6fy5HtnO`uwx0)D=CEH(qBN)l2d_RKo!C7kn@ z7K%C0l1kI+6+bG<+SiwD^s!GELy{La%%Tys$9|@#kd;@?xXh*{N*40FQ5vS67CBbf z+xxs0{}-AHKVV+V|2vI9A(}MoiKq;T%qB zwXk4z0H+k2dswTNHY(y&0wkRMrC4t!!_5I`QMFBTu6l#?Vao47FHc5w=ji*6I$zTm zw832X^C>^U7+b=$2gIh#M9xx+zNHtfS%N7^0&0<~nlDwwBDC#kFdj)`f{zoMs-|%C z8EoHpK_{gDt>E`lHN{em{vOX5@5S=hJu?9%y!I*YJ(u?CU}wz&eO#Jg{T7Ex zxYz8%;?-|G^H!$)BY1n-UC?k_c-iy)kz4hPYkBPUiSttlzY6$|)%DlU#x7+$68~16 zn3{jNom3cnN`;Zt{I@P=8hqi z+s9+hD?*r>xD4L}f+^)GCc~x9bA~Y^PLNcqN33#HYiiLCS|UT%shT%v>{9U)Iv>Tq zDLB_d!Awfn4z3V4bobps;Lwu z_R;Ey&F+dAiz?wbofS!BV!t_%UbKFhoDvGRnquT@siPDeXimS059ElqPS$TJT<=mO zcDX@Gwf#37&u&u~60@-;+)>T?`ywX(*t_`|CYi&|WMDwayA+Ps2X-t%+>d10n z61QULs#ta`zgj9CPwHB)LR=i3N6&s-huWwnf`)B2-1pNGb~#R(xBo?vzd_nkW&g0x zS0N8W8II5m^1~u*+}?Hi$E-`0pm>m8K1~9D-3*WEY4GrcV%G&Y zQ{cTHmaPBo{$A}OJ9S#1-!Df>di2&{p|-yQG< z6xC$B!|P*UT)WhJDi7BI#SQ%G>+$1K-!>{y^#4&wzlj}yaL80a$_*#?PN&NY0iEE} zD4C*)^y!~2_G^>8xnWvMus;xDs-r5u!bwrf#>VIso`0CfE!_ij7%+-{<0KO6#ze+D^+xnWjK7j6J zi`^RY3f7hyXPiyG>yKI4D_}SGZ*R1G1klD>YXZpT9FDlK;Y|OXYAI6tw zRX&qFO^WcXRyi{K=S*BPq}P&BP|Ku?ok|{*Jxw*8N!^p1ZWISw?s+)3Kd!Q!{kp(c z^;%YQ!p;4eeevVy-rM|sU(X*WYKf+*KU@p`fhL=eeR*(|xxcr9uc%r()5iNWx#T0I ztLnC}yW~8MkHL$7s874)`&;hoi!M@5RC0OAWA4YWd3Ophe$;A*eM4AU_;Whm3qb&M zf58tkQG)Zy*2uMS)4=sQeIpQ=ng37cZ-5W5{Pkl39?AK?LCJ#uKL!$i3V7RN+E}_3 zoBMiiniD$bSdC{?s8E!BZ(clY?y!B@&Vz9eh9UKbV{G;3xojg2gsb*v4rYPG4(h|^ zVcvfHb1Gyd#gME*o2-&pPD{r|cf?CI(|Htrr1|+HSrfOxQJAQ0ITvVt1^Tr1Sq2t8 z>25t$C8LZ&n?SOH;{-$rif$^}vOk#nb#wpra|6Ykh zd2SOUhKtKx%bP%$`QN({|IaPn-$|}(qQ9iSi=IbP3B0^?;Q)MY9zGXc?dklK_@0VA znJ;Pw$0S}=*I#z#A~!#!PCsuB))}4(nt&0zuAD=;=gPCqxqQ-45BQy*g<27}eslA& zn?3HGm!S7q6(W!u=SFPB$>n@Uo1ad5hy16i0EnK~PbaeS?nBF!Gx^}T-Frmo@~Guu z7M}>DmUL6_6R_}*sP$1$c9;G4mH*E}nm~RuqLhAEa&CW|G6|XfJ=4ipx*+XPhipkx zp z3g;wR=hB=Ik5evii`0^31`8C62t`gSZi?_BfW!g2S82`h!){TQBYrcJ3Dpo zjocJ$kiJ*gUL^X-$d#aA7jt{c%`Fh|%N);_+K^32y)-s`x4TV8FCttCyGhc-&g3u^ zzaNhg`GGrNl{8X>t@c(}$Fx9WSAct!jGaQ03*XO;(o)ZmUFatxxmJQ*R~5rh(o4HR zQq%fS!8cAXX1lV_WT6~-K<<-9MK*Dy9hJ_LGVs2Gxpl^JI8Zuw0LNa$p)j2W%#w(z zYy~dE*y1KfvcyO+6y^GBC!0r;?8$6$w1~ZYS%r!nkv;^?H4E`zdX~GRRp-C(Cr5PV=c& zG7%^rz78RDN;6KBD1Xk-!(A=bARzleve%qCtb7hJ325Xgs&G^87=OFK5BM=KInf5q zxMzefn5I>}u(7@2hA=up;ExmEtZk-K*1=jTI`m2Df5+9-a;!M!b@v~?M{l0U_McAy z7gC?_YC%3?nv<^>@zpO0$I;?@rNXDa8iDAl6tySW=y8`yMd$|^|`lG-!UemBT z$mo(j^-<;*;xmWCQZ4nqm=}X?Z+(*l0>bZMvF=Png&EW>&r}mBVd@kuXpn+MxFC`T z;I#L60IG1mrvkcSV|3^JT*{qpptetQjOeEgRx0G`(Z@_u^K!SRNPC*(jgS_!?bie< zoF*c0O@Q)>ByAjo{JtX^pb`;6ft)Y9 zo-4FT^nD6Sg8W>{V9;YSc}KG)yk@9mEM04}hdKyF}V|-<$yUC+6!@}CH-Gx)8 zr{%X9g5t`AhTAwB+opt$RD3fduz38b7O}w{$C;o9QyjD1ZbUSz}0Qr~|4*`HGI{G^jhf6ji_&E$LfLqj!~xFPc*wrEg=dREC`2 z5^*#5y(JtC*^?EMUxuCw?I)4Eg*8=!3-(fQYkxAaYpsI_w3{zVz>o6#M^-ZjC;V_> z_d5C~+5*3Wb*4`f7yr5sC@lMHcKJw;-R1sAg+Rmt4_yZb&kH7>7$xsO1u!vSR)-eP z#3lb)Z)(9~t8E*rg?OPCYgznt8I#X*F3|!uRuyd=ag+>;-WvSHpI()OnL^UOfjbJ< z#9Sl3TUuI^uf^f)&^f<3t~zMqJ1TRyYCE}=4|B`l$c!F@WHOC)6ZcO|m{2ZR;w9g3 zw=P28K}9hqI+miSI?*_O#Brc_?Vy6VP?@shNv15V)j<%(jTl|8#-TXlkm~HWp)a|? zQOTC-aTQ~8hB<+ifZMrKU#*>-+CT=dMI#e=V$ZlESd&Z@6Pj1?z`ujSUhzKtaD9RR z6c)}EGuJMF07YD4>3l3Ksr8?1e|OOmZiD1*%q~%mvoLXbl3gBf+pzs$$8MhpFh|uJMVDzcgf5A<^VqH{HC&EFKUM%W=M;%USxoJD-0xU1(>TG8yD) z@|de-xy$ZnyVFh<(e0BhqL616iUiRPN%nQY)RJUBz6&4^p)r41h7s-$%o3;J(^6OnJi{xIYDYaB}yeD=LIqP|(ZLw^Aue~Tu{JyAZ#Os72 z5%W(vvO}7aX99{Oi`eH^9)hLiHVMb(!a?2|Bh5SpS!Q|Lqx9w0N%u-xQ+gxSh%85b zrQ#I4HTC?S>55zINO;@mF?t8reEqZG-QO5g+8~dxm&fDBrdIBs-@DsAxV0KP^A-43159K(G+XuVkL0$FZiJ_ky zzMpiFnVAxSwXU1E;L{PgZ0x9;P0o&kanccXNcyJaJNj6v949OJdqE1Q8UTtRj`^D0 z&f}nj8@|0!@$4h`A#1;uH%Pva9kFOUPJ<8{XXg!pQ%%bH4OvdA@;mY_1~MZ>q#Ddd zE%_?yj(3f>brYdwiVXY4QNbX9fmE)$Q5sS$Y=2X@d>@!7iu6?VW5)_1L5x+Y<>ew^ zu!Z;vicysRDgBC;C0$gVz7xgP9g~_NfesDw zXM#?&jRZ+r!Wqs3eyiR|gb5zps)5Ke0*Q;uBCg*~yyBI+wv zHH62J8Khbm`NN@=65N$mmn2t*%xRJ_Zlqnka{)#&c!N?u;s{GvYkLLX5!DiNWabdz6FxcsF!o ze~elZu&(x@vJ@jo#)`U}bu_}z4NQ#>wJPSsOejya0@EU+%N8v-%@QLsTGdM>Zfzo6 zL9-jfGa{Z$pi-ejioWEX?;uw*7i7Bj*jWrcE!FYr%h=+viBVPGm^3gdCSxpEcj}P{ zZsczXhU!NbJt>G{64qM?mBrpjpI*>V62<*&dz!@RIH|LI_ zZPNOuL3Z@_PuQG(RP4a14m(X?G;XVwrPMizhXtuAP+?@se#riJzfW%Q#t?yDg-;su z6I^6Q+6%xkG5sZ2Y}Abdy(+4rj${m2W;zXC9;PiSZ^=tAwL{o?IjGczM>kowT5n|j z%Z>DMa)h`3>1F(XmHzfMiNomEFdH#arZ$?vFl0=~5pM-PwWZ9?7}=RYCf^&loA-Hn z)H5Em4)5$^*EM9tu`_Blye5zPkdnQSJ9Dz`cPAU)CtFNM5{0-~+;=lGFU$AE z6 zTB>;Pdv3;H?l|ifyNKPdK^m9T;-__b_Cr;N!kv6Mk({-HU8Z8X zV4l_DLur%pu3!<%>cr^05Lq{&;z_ooB!0X8VP<-YBRo!VpMOYS7agsLXUGxe%%=n9 zxtU`WLxPCkkU$Ey+{8_4>b4M}y!Y^|@+objs=jNT?5AU7L)%WENqJ&hu*d%G8O%{S zLgz@`NeqB0Y$L1PT2a*fC&uUl-FcDs+fvEeV_Ns~%%-x~srJo+=TIbA*?e;YNOw-f zD3b+9`u7V_UGWvF@FIvFd{6 zox)z=Thg*ftrewo3_FmnP>C`}c3VulY;x$Z3DSpxLp6rWS+N#{v8ijORvXQ&`7aHo z<9|L+63#X_VGl*Fg@p}~!&9}vRi_fW^>NmNBN3Auk-f>>><+xyaIYDh%3QAHjxzGI z<1ov7@HoD|Nz1ex{ssoa19F_)0ap$r=6ADV=YM&hubYy7;7P3+sj$~27KLabRZk(| zgyMfpa8!?QRgOn3j=W0X>;WLd2@kO?MnWPnE{-&rxpw2^dhMiZWaUO{KL>;EYW%2h z!{emBpk)`>SBi!-et-&kN_+SgyW zUd){ONgl=jROTKXejSOwE=O?*h~V$Q^qgOTgvqaCJ+z5I#?|=Bok$bB2EXr>q52WB zlBE^KPzhc$$%}sGQ!U#}(?O&h7VYVVtxaG*cw34k|G>GsZopamJK7#G#i*)I_~V6o zF>15!X}Ibd5hb-;`r@GYf_6TID^8rWQsfmusOjXR&h-2G_N|{S)~reHs;e{;scsZ9 zxE3=02)C^?e5!6WYC9q(i0D=)FJ5Q2SJXO`0E>!&AV>-YLaBdWDa@bGqJ{(Flrml| zlDiHD5Y)uAwGl1Q(}uzmR@ro7Zj5xJP$Hu{=atM+nDdNg6wD|`5NW?aRVVRjzstSS z2U|!Xh}9;Hi;G7tRRRt?L3bPg-{@N3m~4JspWrAGDrB)FOuD(r2WhQEozNgS*5zYM z?`5|IV&s9(=U!rTuG+`T^~B!^B#2Slzp>j$1Nk6fB$9jOtTcm zLDO!tMvOVvkrLzRIhaO+j?pp6a$2+CR`5`y01-w(*xo|LF)`80 z8~y7{jGi4Lx1#+H6Ra=ahIxjbFi8EdYFw?08NL!^UjRo7Y)r|JCxosaQ8 z)n-IGDY;7(Rf#i&zipSuU}UWK)>#r;YrPOH0SVFK(tWP%Yx-_-FG|jdaj3czjY#*5 zi^^eqH;byp#PRJT*lfQ`op{v48J7^QPj^0c3Dw)-qgSKP5iv`jChl&U4#Pdr6j_K` z`-Ld2l|ft_>tY`Fdu4WXImhS2KYZGjvO|z})UCp>aCmbuP})`65bS~Csc))bk8#~i zo^j2SAzaqJ3R#kF@rZ8Z2ktuX-%~s5p@dM0FTp8T!_NcL*Scu?*ZtI1iyZ)a0D(d7 zsXCVuY^%!*LiVgjU03IKT`t~{k zq%bO1nu6E8dFG2J2F|0_g`~^4vZHqV0EZ3xVYcvZD|$GiiK?F0nH%fS7j``~jo$bbL(Jx5@R4gjh7 zIK5pQ%MrvzuQs$!w>f?>f@&#sbm{`<^owlAw8BurPCAKn9<$BPULGTjAI#^v)Sm5> z$NiekXno05f|s3!M`qk9nY|Ftr+L1_KTu3Dwe}d{WkuX z`-2qrzq|7DSLi{ppLQ^+M(V7UAo*`$@*wdL?6KWx{d$W>HFeM8(9G}GO&sMH;y_UmG3bKfAlksck;^52zy`U958FV9_e z-|xQ%94F;fAf3EZ#p5Zv-5!PRw42r(1u3X_opc++2d*uq)RM|r%&*)LJH(bLJYiSz zqUDjm6lD8?dwAb>hMfEclTub#B#C7Q0!yZb;iyf>&#QG~r3736#*k@i#gz3IDMMi- z?wU%|*k>2x?ZN5^R5%261FAu~Ic5$tK<9@XH#v50$I8_ZY*s`ajOpBC#G_sB1M^+A z2N{)etlhC&J>Kz4%@z6Gx%>21QFU{84l|7I!SSwr)kx7qw<#3S9_(>7Pq&cfYJ47|{qP-!YMwDzB81@(K&@=E9q?H1$ z;nF{T&pwBzq)t`2@5mzN{*CsL* z_4>zWk{5dR>mvB&oKW~;smT^bPM#rQ@?rgo)19h0W1y@oWBQ^!5qG1Mx@rBk;%FhGt5yYPeL#^9QIh%4>ARCS(LNRKe82S)^KW;U!V4K?gQi#9uwdQrG4H+^ZgORD&<4L^ zJnx}ItD>|=&sG0!{fU}MKy%d^5jN3uqxCG=V403opoy|SKfG3BC+}+3h@Ip-z~%0e z*~Cr$;|2_>r4k!G@KDY>9Hs@m>(x~xmCIt9AX(ZM9T%x2O6aDXr^>d%YT&Z!(9CWY z_o%_0>xBy%z^c6H&e^xM^}4M7R?&seCRE!%hV1t~f@E^!zD&k>mBk(glhI;*7a=^Y z7(?Kw1QAh92rHX}J@GX(g9cW%zh4xADiyyED!HAwL7{4>RWc`97sM* zY@~2Ee6+16=L_^7%N2o*wq!|Opo(Bt7k^qr_;>w3hRgr`v5SAe z8uASy;Dew;wZxcmWPz!3kJzI~tc9q{ZB0$l6!?;xa-e*PAW{1J32v+q?pmP<3JZIZV^>$7hP*1sl~A~q+bh*WJ%z`O>>`LYr;rB8k5fXvS(i?KIrT@Q!i z67vve|3r^Vp9i=i`065B-0Krt8U+Or>g>Y)Wx@2}Kx4K8_%^KKbak7%Za(C_JQ{_K z4Wf85KuU{etX6}fVzclNn8RkX%^#4qQADs2w6+VNCEi`psr135&+<`E;9hKSsKm5xD_%{bpAV(hSWE?MpMd*yLKD9DK-UJqJ4hX6X1eX$ z@)v`^T1)=*oTKXh%L3@Gm14Mj(v|8ul^?U(04jaTiKhce0R)rA-mqS&`LoD$dW8YM zI=?QdouiaQ-k34AMOKhj;(>?0HxHKz3fQoN=deE^iGHqB!VK-g`}%k=mwigv?!hY@ zMSW4PpWA1o8#6$@JizSp#(%u!LuLYh6>Z|EaI8+LOMo(7Lm)EI_07(>&rfej`UIL3 zK?~D>uU91eA&fLv0RIM^=6W%eT`PPcX^XC0TfRW*zNhyTr;Hzu2sTM1#Sm!DHcmTR z=!m4Qw%U}XHi0&h-D@udf7Mz{?!V$2^F(R7bifZ5lQHth?1pC*9{EbKm&G*m742H} zL8~B~6VBsCdV|}TvGg%<4H$&KAw_0rqYXt@d%CmZ+W|P`ciyVxz?j`Do1!jpB`KWd zr9XT192sC$%7pHrYzI1&ku*C@*G-$me1s1^EgfZF__O3r3d*5LPx*2f9EcTc^qsZd z=pHhuR8YCENbt}Fgs-Ydbu`oGueB37asy~PP_?{>B=M{y`|I)1HZg&6s}>z*rZS@@ zy~Pz>gLrOS;{&?a1iStw34>+N5uM9GaU!dSCTU4)0cYXext?6#Xnl7=hi$3SMKLUZ zeeHJ5{XA!Ew2h@ZW=VND>wi?SH)w$bXpk)m5R+o>I2s*tnPtQq!8Dw?FddVJbrtxM z-N1;6umQ#Hrpv>fIV9cu$*ZG&F2);JC5`g&xX}xgrXTRQUXfJGw|qwb(KMdI{K4m) zmkYC;D^19jw3nMio>V8LBGz*sO#JCQ=(N$t(U+?UK&7h1J6Q7!bAjS1gRA}j$7B&MKyapk61D^i%!M@+~coVzYLTh*mHVa zqI)oUt}R29?(8&h9QddYInNMJ*U2%;iSE9u=%!={x>8S2Ufdjur>cA{ehr8=wQa7o z;&wkhsGl4d**}KKKDs>1f4SSz9n&0#+R8j;`aCV#A`b575ka?eL3H^N5fKxs1Sh!`7}$A~5bLi7oxJSKeryeyj{JXi-F5ynZSUB^Pr z-AVO6`E=6X=eiN zJndl(p_HDA<-r{K5;qa=h2(z@lNK65Gg8P+OJLUAIulb2K)vNty7s?%%)1qMukOiq z&C8zO;~zlbUQd)2q!>(~k8fUUC)MuoX5y=I8WfR=c>}~yX=%N1MK2#88@LxcX5H`q z_t9W_k{-9k#-z22Tx_lh!f6L(pNmdz(R1>YVvJ92EyUJeE5acjbn(jL=$pM;1&u*3?+8hJ?A_9q&CK3#q zjjbnCqgz@BWK`hC_$7>y2op318a4#yX*fkGky@Ts1DkKxPZf9?*>w%}a!~?U{p~5& zR?VM4<+!ci$qi(B81jTfDpjXa^5jsV-~8Gmd7RCEXQV35i*F)~(-BfAHDT79%a@rq z^peUeJ&kH$yG2TM1XcxtpP-spaVmBaUj|Z`?Tw(pEiJ^)b6=mAfB(hlcK9Yl(t#<* z4}!xiT)QKXPcGS_>@>)K2nw-me9(K81WMhVstPA^#4bip6#Jw&Maa%}XNXGPtd6*k z6;i=}mVoA`+oR}xhW2FU^4&-b-RXBiVp^U$JCXg8 zqRURHkD9fP5sxN9aguYrCNOAq5>@-l{Awxq!)|2?dFWy=WxoTSL%ys(_VZh+LLLD885MJ$+gVc{0@9IIE>^wr)fkN?@1&x09iC z1lZIz>toviIG&{a!LSKDgvW4TEj&LQseAy8tciQES2M<~6?YljZD>QVseUCJanh^O zN_Pij`u4%l@Jd3--A&(U6lorO4Q+*qj{lRT_?Mpi{Qu=|UOYe`Kpc*Omcm-`FSMm3 z@hL=KjfWMA;Y#E4cxkwnKnGbce~j&h8nokw_c(qzDyG<+W_Sj6Tulu4?C0X1(x-i+ zX|JqS1hk`7cLhCqJ@oFoz`Cy&IS_x6yT_dMi+z%3pS$miU6hI?(hWuvLDE#rq~tqk zh{wj1Y1udq!_v*Q+r#eA-x5^DG?J(JPsh(f^bwaEawv;z7TJt;-i%ZF_B~!bBH`b5 zQ~oM{BhY7w2P3oWRme3#aC+}Ra1~A)#%j7sW>2+S5@0Ynlsa7<~U+bdU1!wxZ|9j2q!DhDM+1S;?ckYDu+H4@dm9Nl zrS;P18||}W?~>I1{rb=ZART(nKcH&@QeM^T!E9&^m79ukjEcvYxY`4I-784NkIrmD zAAh6+jgq zl}7yaH0mH3cjzW931V$fOFVE5^P8VajzqmnwoOe4soqs*9@nVcSs6JVlafSD0XL2H zSO~~TfEPaa7N|?gFeFG2{8H+-csw~Vkka~oLjs*|$ZYS9jrbfd1Lvwg*RLQ6$`wzL zw->CQPk>#29zD&?w1Td^CPIzR=xcO{8-@3|a?5o3^R~ruAg*ajH&ge%-UOcGkyp6A zY3zu!yQm%3W`yJ~`p4J(8*oRfBczP-F4Y1l@4?Eha(x===_Z-q@Vf&x_k~Ll?O4st zbpl=)&v~q}8a*G}e=8MT+eucZ;DBn~ylWc@sgA99QrOUA_bDc3|6{8E{J*9;lq_Jl zoEC)jReiqqUM9}D-k9yDw=-w;=8(1dDLp&}Z)@`dM-X_W50mI?u;PpX2))SL%C>y3x0X)1^SRu6nYH>22T! zZ4$e$)M7gd)yp=+GvqXc_Cog(ggF2GwP zjlou$$*m}mIaZ_)b*Ii8`9QH3Z-thEnFoBjdf$<2&;!tsJ{)tCNrB5wZYL~LtthCBSNO;O_d z?twkfClu7J&6eQSUDSyBVfR*5Jf zW0Wae^{y>iZpx$TtOJ#+cq}l6U&rUdba((o7*tv%bObb#k39IRT$p@Wh+|*PTy*uO zQepGySFESSCVB|*47(b^BV;oVyvLUrP+nPGw|UAAM)KY&>q+c^Lt&uW0)8} zPiZWhFD-9GycCAyZ=jf|Z-b6{g*vsTQmg^AjQI2G$6vLV6%i-;bMb(o99vit%+zU} z5tVNJS3xxPr!hOAP3Zv!$dT4Y!z}#tm{FXML1qXDagMKCUL@Y~pjI&LmDZprdLu|D zjMYe8t=gj@@LK*#QCYM7Eq&27w@oM z8**Y)6d85j{1xC2ZuCw0Y;?NtS5zT6x4#xZ_0%~*>y=(X%w+%Q2iq99!RWOhcv5}-^6UgBMBs1)Iyez?%~Llj2N$HlFMy1WWTbuZiuX9 zsm85Xesg3?A@T70`=xRTn@s$AKiqp)yprFz(|024W3)sd{Vo{eyaRw<_ojGN&qOG{ zSK>ck78x{xR-`|^s@3>~8#O8O6*tCTrlAqbK*MDLXfPkDtm zB*2OhY8I+i^{ee}K)Z|5{HBk8J(2LwHPlm$0*|LWr~2vUPx5IWhYXb|;vMUmGrr?u zp4gA`3>3xKiD1zt#+mk{pG3}5u4A7 zYD2b^QAN5TO^YXB%>~4gqUvrg!Y!y#(b5X`=zBL>NSUbT7pR*sz-HmKd7z37RRBXi zjfoBB&(9`#(hM$Y&NOX@AFR5}Hyx7Jy#~LN>1>kj=6O*8^PNyqe;PU=O z8Pwq;x(f21Y?KSIP2FcB!OjdYuTf57oke@(+y`Jq>A z4Kn}o`FA3PQW>n|OV`tCOZ)L9RPv}=N3J_9RRznDvG(C5YOe^a7Ai;|-GwP^&=WEO z8^U=(rqYIx+PzA~;4#Biv9Aq?CA|XPJk_aic>9?n9PKqeXcSgBUiSA-8kbTan*BpA zfA`pt(fkzlajE!YK%OY?dn;OGnt?-@VgIC!$L1`JAZWLq;0_uZLlY zPBu`=_cV62mgm8D{???CVT9d=ip&4DYt^;;^_3@{j8k2hoYQokaR^(IL2!u2Ln zoZf0?6+d8uilbo;;&W}zJ6AdsxhZB>#(jOX+^r?)A=)&0lmj}HZimA78+4PBk#&!> z?-$BwGdg!IVIo^7r&PxP7OO6HzEAEg&AGu3vV#e_itve5%k1W6hgfi3YfJ_WloTwy zTPMeRsZm!{9Dil+ISoqo;?@A6>F8$_nnF8HYDR9-Z|YdRrIbQ!kK+IUvf4i)HP|<* zMDEjA*660_V(l-QqqVmJ&EKX7U~XQlCOb4kaJd(y&vj9w)|Fmx?NDH?k(F7W5_NPi zM(L!(wj2*2BeFwLRV3Xd)sy_?X>Mqb&#~-Xqw9Zs6b~#~H)Is1urG2O#2c5UIr&E21EP=opSvjU*a?dKJq#{#@#Hlhxr>uDG96AZFL|0&2jM``aCef`1I5~B1IT|B*c(aw0*m&dew8#J()S?|o4 zC5Y@()HCxH;^wyc}j5X;d8F;y@3r4QxEJwRy?gEA;z6LnRl%CXdV`c;3AA}4YyAvkHUdS* zKL*R9iK*&*e8b1`Ej0iNFzJTwayywVRr=(yiB_L~dc9&b@p=HRWi9?yKrIld*t#ig zj`;PsxLMf*%y2>T0Hqz&npqVku&T0^cALv%;F^juqDsjSnRKOabE|2mep)-ow;NTo zK&@0LD9!7&MJ-5Q|HuYQZ_>r!_yTQNjEUcQ_drA=XJX4ywIT%mAjM6y8)9+xkcZPU z|E)W#iFxF@;fiS)Xf;k9x4?u)o8aAy5VsatnDe%f3(Acre$Zs$vALmRtw=H!_Fj!E zjA0G8qCz&*6X#TMz2MTxe|A!P8{Yh%cfQa6NJ%I^mcN0R!Pu+E#5ghwU|=TME{1$F3j$RIu*es(bGJ8-KeS^; zrm)a64qYjIlY(3mUFHknuW0ng%5({Q#ys5`!Qp<^11utgsnL2Tc@^%QxSw{7m>K0T zhG^ESk{CayXAoAs{w+JSMOy(CG5EKFu0EJY%=alfsh%8jj*1bk^noh;)E$Hsw&3^u^$(QTxno`C!U#wM9NtUYq3Nj@aPi(lWOM7L4@WHToCTL%m<0?M3%u}<=Pjo9>c{z==mZFJtVEzx ziis`UgVg7rQt<-~d)>(Tg2L-9nxyx`&Ofjo{8V~saUeq^KDGKH4Hb3mxxskWIhn)i z`QAdJIV+jnfv8z+c7hCdEx!c|a!?332T?wF&kL*FA?cKjrt)dwxU%9{=_l+@kD}#R zA^&xA#_2tt)G^DJ%FRS4u*lg2^ir4RvltDRahvD*FmLkj37jHtn<->;#qO_x_vWVr zd(mr+_W?aFnl0CVYK@p#V?4GHO#lC-ZxPCs3{6TaskAA|XDZJ(3o*CGr=>CY38)(^?iui8 zcDesoZ?QkPXM>y(P_Q+MKYa2HetQ;l2j3^q8_a)*7@SaYap8A%sWs(#I`Ib>gA(+l zU{a%VxM+)huhvFR_5N6+n<36;apw^aaD@Xv$4VbVX?(0&L~e0jz=O#{Rrm8XB4TXFn7!H9+{w-XI^T9;ibnl+RlRUo$RALet<(UY5R1y+0r? z`HjNug_ct@VtO*A+1E#J`DJ{$0&m^(*JnJMmsd7ekG#HoK}L*>fU9I6iMeKdD8J(? z&~p?q zMguR#rcUuWn$11b=mF~Q0<`1&&}%UF9qggiCv3W|nTVJTW;<5yS0zMZZv1h8>sM^{ zZ*pVAY7EPz12|rk|9^#d~9fDh-nFrkqB&cBQx!wk%B@cy_Dj(2${P+m@R;m#}D zU2bmkc4hxSZQGar`?&oj?89qpQZbCu$lpL!+I$NWhUMk$=4s}@G795yr@ahzLfh^X za`DUnGNxOBe;B96IoxMcCpI0cExnJvO^8czrCDUjIYA*@V6s>3lBpA|e38H|n5IK; z-)sKCYXRHAx385odF4h-j1N{ke0YN_f9?;wFoI(7T1rbD`o0=VrfNc`CnB7E8N5i% z=clt&_@&bOA|5r>i=Q7l$Pn@k?F0HZ&hYmvZs3s5na8 zla``Ma-5$KgCHRkt^`x~nR(V6(kpfd?tODwa|F56j(`>6Ms=k}4H3PYg*{2E&ql6Qujan}$0DmcZ*=OLd7hapve2uAQ z#dZa5J+0Zz7pe0Z5*_1CqVDG%%oa#5CYb1L6ydLTRcvoZqaJX# zGDfRD4t^BUa!n+}Zi0DMX(lz_d3H6xMB5?KL(TGsZIEL3j}1GFDzX`p^o3f|d7Iz+ z28leh)0#KMD-P@9_A&a#svI1~%92;;QJe*@Y9~xA0=q_kMA20WlE5=W#o4~pOT`BN z8|;T{vR@v8cr)a;;B)$;nF>~IC)=W*x+hHpj|S;_a?Xt~<6P9DUQG>3LXu*~(GP?a zLB;^HluMb%4!Jm0V?8?l&2SIBr2%V)pVnsm;;hmg}^JNJmA=<-yo zDhDY50~N#KO(Zleajl&7I#g`1zQYJxD@o_6UQ>935#AhgiMQ zzB6C=MZ#BG0&p`rMt0mNPUwjsBGSfH@t_!$|0OCC(fdmuHtW>q(v!hv+V!8@;)c@t zdt3n1GzxQS($9?yy)VHNKKd5@rds!_y=P!VUDReW!#yQyo@v-8XMmJ<;nbr#MW*PB zCL(Cs9w_`&|H5xYfSZ0EZsyfPnQR#@{W3_{g@^GUelsz#(LC#von;zyoGdfDv&@n@p{fk$JBYC zQKV^afY|+0jD?dIosfkw%EzlpLhL$}-^UHsD98*7Ue^Fs2A(R{E38s~VNf3FR3xo8 z(>`5zf6}$X=nfNyiGHLAPb9@D79uC)Vdz}6ay%W0k;0^*Hgu127hHXLz30ykZoYo?`eg*4 zHDdxs-1tvFE@vS(3b6heJedqcBT7VUTFD9P`(U@}Y{m6dGaw9RUpi$q$W_KVeW{Ly zsS`T>$=5Mf`C@T-^L@gX4shMM$Jg#Bcr0%DgcEQxf=~ogBkT3I3E)QOsaoilh%Y1o zBk)gXTuTO2>d9q+pag`LXOysgQ)7x?iL=TJ0wP1rwHRSSy>!cd$gqPMEAj$_8 zSby_)bs{bH$~Ak7;PQAQ;ri~A$kXuIptx^NZWrSn!m!XKz?J3~%bW;&i7zQI#w*7r zVKqmZsM8)4U3)j~7W2SIo>0RhO(6#1@a-BUABwxrWGyH11@i6{sw{Cj5T^eU+tG#| zu6mgC{Avkrv?6fyG_9~YRoi^Kc5kuVzfvvKKGHI-OC5`L;n3$YBiJ6jaQpW5UrUT@ zr_q{9<+?MhqRb)3|A5%g4ZPvAgzuDo+ZDXMN$b8x4%Q-pY0OvfF{>JiqVD{sk-wq% z{g>OtOwhx0cItu@socIi_?8d+``UkFtN+U;XVF$aZd#T}@l?G3QBcNupsbpA%r~B5 z@r+u=o;*JjEPTijU-c^>863MpRnCW@VCJv^L?hJQ%lXG?=supt;WR4fA@|0=`@Yd9 zZuW^hR0%htRMi`--TLKHW$YKI6RT`#8O|D6NZQ;ac}mVv=whjVs&v9VU#(0-BrF?i zY%u8LFCQA{;&}M&#b!)=9z2GU?}kX7UI>Hlulzdv|9yVRP8Q8BPPFWk6~Z8*&rVz4%e;q{h_U|z6TzUn#c18 zoiCpbwYuxrHs0*y9{OBXU7uiBq0^~+*@UIqS)!NwBr$FIInZbzBN0T)FD@)a=Uy=e zK3A;8Js+7r>Ez_^p2&K6D!4$s*E&hf10GjyMy}Tq+z+y>zi7O9mZ#t`I|?X50y|iG zzmPm_R_GkmvUBM)LBw|gx4Z^t%?ktexR$?^yIq)ZTx$KE<$Wbq`v?AcPBi)y)=?jC zaCws8CRv%-Y%d)KSpFH#XZQy(9w%+L(j2^GKT=8&jzEvPxyb1IrmL#tGZDu9=v2wK zKa|G})R{|>soYAm>!%NIQZ#{*%hU0~*KKN9S!kS1hfs^=ckv?)!u20vw4u=V_{G zhOWy6(9qpW+c9oi#N$IE8CvmyM2vG%;*Sapz$_zCM|TQN4x==F2*kj$B7_&Iz&c`Z z>D<2^Psm0bzjpT->i8>k+oYGBF3xER7K<<@pCddn@15O84gVY5`g35S7?-eb?0+|x zuA_rLWosPMnJU|?d$x=5oh?3_r%tfzA(_ZISEmzRw;bF0#^fJebL9qI73Y6lDqzbS zj?KPmIsfX+!uD{OIGCyZAaw099dbiE!xas8as1N|h8gthn)&8I?q)%-O|{jl`|q2I zlbNN#ZF>^243VMj{&V3vA+azGa(OsZ!?FJH2-DjOfngA$TI*-0|JNNOVm*OTw=EM7 zo88NQk^U1lJ-v30luE6iSalur&HB3-36Q7?gmi97&*C$VJ=dLU) z*$)mTtdlDnuXeeTrM<*Q6Bx9QnC!nZR>LCVz%>4-A*ULNQl$7=mt74_11~KBEl1Ux z1}|)knqLk?Rlz)6?bFf9OOF0{7SD6>l2{pDQi{@=&=C zTD!EuB=BrnspyVY&F`I0}q$e<3wEzn46*-iCXx1c*KImwbcYHzD0 z3j2;k^*2Vb6(6gk+U5I>8Y2oV5y~zRB@5P$ju*SpdO)b>fQ1!ZG&^8}ykaH~VaB2& z{|(M|(t*2iHHIJ7*!Zc~U93mVe;#s!6J5PLZ;jN>k@`Z}AekrXWJS{SKcbNFqy=Tf2kIi>$l}5Bpzc0)v<6$HcWO&uyf=qT ze%X+3L|dkRb{5Il;Ng2?@xEH7E*8F=daA_4|I(2}A*lokAVT7`ffrn|TwHe=2BHwT zOQVHPWLUP5p{V+1u`s{^f*GNTDpt&XUfxT%VsYXGxeQOopk zSM0S^YhdlPi${FGdPlVP3X}vA*eegJ5KsFX1_oFqrg(PFKB5G<^V_o4WkAkZ!ED9ne#9VLGK3_!_zf!D>%A63pNXZ&Jg=MdabaSM z#iNMLB0l7u1eDhi^lpk*azQg(f z6A2kfUQl_@YB){ykAY7}f?fm0oXMX{GPtg39NR0bl@&gV1d`JX+vwz@%lUzEX@tnt zzn?%;og=;)b0lXSPX+CTz+*ewIX=#j+C&Q#u;;!f@X}d)d&o(cz>4Bj8FScBgJU{r z1jgi0j+T9^{);1o1zoobf#$A4{)1^lnmc;D$M~yMuJ}dI0sPorM$; zyPNlS^)q7&5tgvD68_Qz>Dx^3W?aG|LHm21HFlJ@V%4qm^O=K$QuHZV0dW+X^!AyQ96rZ5tD<6#DF?J zN3ASYhQU8F(iTC*nH=_>E5CjKx3;m1hR?b2O!(_!B;8W;j@ua2Pw6fSq#ME#jqF$* ztLgnO0piZfd)r(MrR9X28bUU5Ee(dhxIa$ozrq$gDki&sl%b*!RjLc8E*6 zAX44CgCFAyTe*6d;k{#s=R;YzjJ>=ebg1`g762S0h8b#5@Gh=JevIA_?O}r{fPwOM zC+M_8+KbkvTLAgIwh8>5kVgTT@He-%D|T2s3UMUvHk8g<>&jFXBK>dU+(E(F=J6f) zUIOm);@PXG)0Lzz}0tK78gIPxnunDQ8n5d2Bi* z^&jibD!;iQscA^7x2xgr)kmDt)Bo|X&8A_ov3hkAe)tGq3p(OzOJn#eqEu~HO!_)E zA4EO1&$nCA!qe!p*nJ^Ew2r6`Z}^Kj#LUbZtiNO>$@bMKP3pWL1uYj!z8c-b9m65b znthl*WNYqmA&8AO?e*KG4vfjJ4z})IRS4u%U@b_%w}179$hKC~0CP#8=-uCgCm*Bo zbO`r*0A4WKOoQehJ5Km^&=q{Tq1}kxPOblHss=fYY?ZYt}_pYpox zbj*{>Iy5#LmpY5@v?7}PL~hd{dq#(_1#EOf2Fn5nvYPO^g8oI&7CeNH!^Cdo74|z` z){E7;t<)uFD<4kL7+?J{<0`a&zFFR7!wsYU3GFS}3CFKtzrG-zrN-VwxIxcP$h!k!MC`uv*Fox?V(M@-6XMnUI#NH~c1# z2%X0g%nI!%ld=$a`_G;bW%3HYm!~mJVrL_Ln<<<8y_V}qVH(dTKHe)hgPv)%DsKKMGN+YY@>A zwr_CJXMb~JdiLf&&mJ_X{!Y#ro9eydz%x8+Jxw;L+xqL52i*sgB9Cn#^P%a#b@_7U zDiP8xU^C_DS0i;CaGv_@yL1y^%c#|o6({b&vWo z$&o%|inW>p?^kmK#X^E1Gk@>=Qo((qQ{Q{}WLlz#h|SN(tj#7kM8mxNt!297y9sfi zcOX+LO{Ui-A?Z_k%bu;6V^@X+O zxYa2Xm-%3tW0+0NXuVhKGSRPpMfg|#-j7u6d>xlw{T`_1LAJ^5@Z9kVnaDy`kHOar z7BTKe=PA6v;b1r@E^4Gz*{ve+Rwz-q0ZyGJvD!jR-61hZrd~o}RjJ#7BLCfb0F`Ch zC4AhaN*lWU+k4JBU1t0ArG#u4+U?jZX>Z?Hq^JQ_Kelt=YFH^yCe3FwKJFpg$Vc|-bu>%qeThi=F|jOm zwgH-KF?s2+a(O{ebwcUWne%GjTV}KOYG_b-No8o@D?eJo`djLkYX4b5>Riq%;eR-> zLm{JSyOBkH!`#?u7DmC&hHegp7PMmOc1#B`7iA9@V|YbBQUqD+TWUtrZ(|y+3cneg zvn>+4-T!{eo2B-bZ47O$NLUlVGCVLQ^WH5cH@KE7fpwyc<4QO{#xDI*E&Q-X;cL(Z zQ){*5a9x1%qCrGPaYuRYx_uIq%~N33c)*WUzDcQ>L-f@OG0&*X8^h_*Gv9As?n3@| zsz%Fc)Po0g&p?51+hLAnY$=C8ag{U`!fEq}%4-fIKG%NT)okY3e5Iu8+~X4NJKM3i zI(Dx5E>N)0KGejAtyya6YbEQ1<%qCt#8Y&4wMhxpt1KU~P*kQEO3gX4z1n~)hwjp{ zFDsQV1A*q7KClOP6vcRaDR~}#j2p*~X{{d3Ih;lG!%2eL)BZzkVM9Sr7EjUCn0Zyj zMe$m_Z^u)vjMe^&79MQ!8$Wi^{FAp3X;I72KMC@-%fIFB09y+_?SE-w)Ny8&yex#e zf9@{o%W;Q)d1-uQ+{Z!S1hw@_Ykg4L-t%Bv)C;8~IkQAL)4(9C&gx?wMnQ)lH|&T7 z&naPgR9d{RuH@D-acNSDKF8XRe|!TFs}`pS;D_W~s?B%k3RF)r+5GzkpkN?I7P0+I z9aPjEaZlkHrW&KO?kpdtshU5Wx6~W;1B8t*0+>t}4@M&?7*a)wE`(@LDO?tG0YLy0!ivMra47g)t!Wneeyz6{FfPoEf2718tWtX4l7_q+B_1Oguydc0 zLGg#yoiUGrJx4^hp+G%RuHpkUMZADrt>R(p>s@IVz}PaIHYjFOxLxvVLp_616_8{a zJB>B^CL=X~S}rcSg~>QKY^xkh9@SUrQb(%v3PVJk9$UFfQfo%({t=(GE_+EkxVZ)V z6!SRa$u*FhWXR)LMlH-|b;g}sHF%{(sYqi3ha8JonYn7$AC|ox@v8O#S`()j1wO>T zPYrF^@u4)2*iZG%K~2Fh%dyd#b*?#ZSvZW&y^eVY&c9jl3XSE9Qe0wcieVPM^H+1X z7Ettyx%B$a-S9v89p>nyjG<4gOb8CDvoKcuonG(!(uyRcz>9>MEv*5}Xp;gRVxJcm zl)o(TljfOjtz2|%G0n%|ncxSF(lHn8VG*3OQrB9PbN`!<%o`o83VCp!Ay*4)^^Z6fg6@~y-!=l7;4cFx_$9NV41%T$C0&wv7TuHXM*?=73+(3ZC0gh24%lHl$Z2=1=I z-GaM2GeB?x!8Q2c?(XhRaCdi?foJxSySALF_Yb^ZDP~Q3_v+PibvpV*@KdkqHr=9L zoH5e}X}SS(#b7Qa*UQi!YhDzelMv_*Z_0`vVSd$;pDpcf>RX~gHnF2&J^d6|r)mp< zhbw7N7@V z8pm0>Z^3Olxx7MX$ zi7&oUIn+rU&0QX)0R~ksu@j5vMl9CJm^?SqiM$z;aRHK(igo=AkJhU- zC*?M~`a-s0l`8XcNUN0Lvy?I=cF0!%MMMowXs-Ghp=Nc5T@1Wn3ezE4(CW zORQaX`wILx#nC_NnaXgT(obV6<{(*Bqm1oA-)ngHMfPF=`suEg`(Xz6Bb%mW@sCgk zX4T0Lv{#7gzGft^_eIoM-``@RFLC#ZZilyF8*M}mU@N^V&sx3y@;dk@R5%3^`vRDd z0P@KYqD}OtRLZwBs$7|L0v{Ft83df>VEZP(8P4zWb^W|)@$>G);wmjJeoum^jL206 zEjNXtaZK{K2ZL^%ckNH$)i#1SXS=6Rzz^Zei|(5ZaL&`6fb~*j9XL~V&8KF$8O$%K zJ~8BP*V}B^Gt8lD`Jrr+-9{2xsmQzD+YXBcter#uczCxtDAcAxSpQ)=DW_U;14Fm! z){1tu!O2cYxR>L2JBuMA<(zoS~S%K2kQ?)RhyZ;{+IM8#LCg6 zy}D7&A-U_PEaa*ITF0_vT?r3C~o28hjB6?jXS- z4*pQSoGBmzCmDC;!UP2i{kjV9@yxioe?BnCup0ZXo;unQpxhD*UR9+BJy`z@1O8u3 z?0Cy=)Pf{F8^4nP+12o6d83GCv( zVB@g<5HN9+_x(E3e?rgt&wPPB5uEW`M+DOG)A_Yd2b9hiG@_t-Dnx7K2>Bs5BX~aDm_!dS0tlFNoPxFZ~u1>E20$}@< zJAOJX&A8jiCjqdw;;zKg{j}3|{@>K(uF%tm9}*JfRu z^<^j|;?j78M_<}YN!}1wx#f_Bk%nt%`xxt>Z--h=Qj;*>@q?C1y29`am_@TsacgHn za+d+mAl6wz=rl|%&H|-2nn{uA(fuoj<3Cez4uS`v3rBN`k2~Q0 z4PZk>6N+yvX|k$pOWS`Yh8QLf1pi8;5zzV?z0;lSZ3@pN^jAf8jQ`>1&%YgLLoPJB z^gdyer?m&(5HG-?zA>WaG6drSNN;*AGBsGpQUkV! zuYaSv{lg!jL|Fn&n4aS+_B(#T)7WN}CYZsmqId?1vor8-H|Z$+8{}&=21Y2hU=9+` z6Uh$_^e@=3%FQJM(zkVXjN=7s?kC=pANgk>0%RZQuJ$w?-8PM+lhbiXjbGoRgi^uM z(C50V!NqSDn_$_k~uf=3~P6HL$LA>-7Lr45pr;4P<@n109D;h8q=gfc^{A!_ol z2YydYI}&3_Ga_n{BPm5wlJwBq(=d3#2NfhGdL#=(kRtDd=jPQrw3tQPaV70hHv#p@ z{N{ux0ma>?LgM_t12#DfbSb2RAQQ4>gbpPL0ZKa3eALV@?kxX z@U^Ojb{-)b>x?%C2HeIE z1a_by^NFPd$I97HX8Mqr$*l5^)jp z)k1eupA}#T>e-Rb_npZ$ae;nhe-Z>P#2~JPtT7hI{16hILo^6oIrpe1#Wgd=s>qA0 z5YEg*{fdn(mUv#?N};5>yts~yK+%bJu%8}_zF{DOd-Bf0LjDK-!+4!r>@q$h0Q1HHgB6LgwItHpr zw6y7RT@5AR?5AvrL}Dd;=C4;^wq?JmX^HBmnwP2X$O)Bb>-pik=)WoQGL#rG+g55! zZTj+#km;~P)o?W;q(mjo9F6U?@uqSequwtJjdHjFxEXJ=oxeppP>3c(A=yl!UH5-! z#~-FamPWRC?);OWKo|Ch8)M_fQBc5fn&r|3xBlxl*5*s|x(cI;uQJ00 zHOqx!sZa^11pQ&*Vzls~Z*588O+>|`pdR+2ODR3J;g>8eh!DoJ^anRjW$HpwsEBCZ zD}_30$UG)L7$>gUp&|hFdT$$*6Rpt;M$+bsBq}@ zZ_rZPWfG3=!D>HYqqQ5#|9&9-FWdP)4Y@QNo>?q|3KaZuz%WjQEpeEYpmzzahP&`|)28?o_T17wZFMMJNI?QSJSLQ^$gNHH9Y2?zaveb7`zOhULp zlq)P#e|dr(>d*Ee4!(p=x_ir>=|Znu{X&ApkCH}tNG4H*0Ll;;-6h5~D1i`R#X*gr z)T;8xUPHY?>cOU%>^PwsFzcD7+^mB!b;+d2kSlsEW1!?A>0gsOAvqj<8C~{w( zDFHX)pXgei(V-RQO<(B4_PU>|G+Fx$f7oss@ z)i$1p>ef5_E}L)b3(d_^%|XcGmF!^3EZipxR^oNG zwo~llIoOwawQ=&P=HdwRQ!J;#(%Va?kC(K){Ud`BSX=^f0Kkj zG+(1POueikK=M&A+tcqZ$mJ6Qp7{RjM*WKE@FQ&LPpBz%#zsMXVf*sgnw8XCHTo3G z@zE^9OzCf2)Q&o~X}KCO^zbGnh_#RS($HPpp_0W1Ak_H>P7)RbQt|77(C?ooM?m(( z&v-snUnHX^2+_QdD#X3DOjU{PXz*`>BHr&3UFhCRY?y=KL}79vdqbkor&I-pq=}kL ziTY@5%RCQ$gi($m* z2~07nnoL=R-Fa^G=h>jF*BL~A4YK$4bfBcTQk4S<8leNB({d0TrhT!>kij%h=vRnx zx?-5XwKX`mPf~;jTu%RT}N6 z%{+2{!K1AyjkE(PDD(&Agpip)QxvFCm8VXVno#ThpKt#=O)$|zPZ35@9P()K)yPT- z*PMl~&(*TWefaTP^7=I2MA0UJbO!BKJpsXWD_;9VeeLnn)3iKrl0CA#eo(W72=4wJ z_1nfWVCt`4T1X;$0S;nn~XcIsMg^l5LKoHnHla?npIl30`P zyI1z%U(PwUdMN@8HKjt;56A?;Va%(Yq~A@yDbweBI={x*5U^^qHZ89{B&aW$wOM$IwJnQ&)PUD zS1y2$-D4`9pWn*uWWlOm+oRd}M2kn$h%0vAa(v;J&fYAnVMuFUX`D@ zyqE@Kj)|fpqO@eXiDH$sWYTP|7pgq3S4Z2;Litkr!>_yfd;3-Ill)avfpeMH1-&Yh z?_yH)c1k+*B#ZcEGT45djsn6@so~!UEV46^s+JFCnA)anfs>TY-@umI{Jhq~LBVk0 zP>#GMthjNib10N%*ymai(2ufWTTU{TAZKO0(&R!98d`|X z?mtd=r+mA>v}W?UmUvbzGh0^I7VB+s^V8D<;#}mw*z^xc2W@!B>9W7J3@C(B_ba)CMo30mjO8 z>ff`{)jQvu@AQh1+`DSR_NbASO2pK`$^{i_>zy2*jSZV^RIC>dw$U zkf4a5Ht{FY(v7;lEsxsGQqvcsTOywwzT57zrqL^IUY5~%ap^jzY1-z{b_Qy!qen#7 z;gmJwB?Z*HdFIdk-tnN#?>1{Si?8gUIN;@hRK8HY&5h96Z&3cR91df>8+f4kIMmAZ zUM~S$(!$N9T8lC5G~56F8RrDQ?#MM+*Jsd`ZX~^;y%{b`NZ_HB>soiS4bZql zEi!z*3KXh)w|T_ZI=*^S;dMEEx3t%GkIXZ2S%O8Eu!OroyOVW;LSKynywt7>%vGs& zQq^AKwiLKqbz2yn)3;^CpLq(Gh+L#dK54@AASkIpV-VrYP>(_tjoC*Qj;Bm|lk} z^gNdXb-K_xMxq)!fu^;Wr8VH7_pXFpbv&+=_mza6LHXm%>r9z0-x!TTk6FT+D%%wP zx<;v?74}`wO{Fiu(zNU4is+?~?=lf3d8I(Kmaf%^PF&*TUiazbmZ+ukrQ7b=s@WJ^ zVWUyMxa!>;x>xIdLNhxYcwh609bxbZbCt=?-BG4oW;l`U6{wOw^gvjfhhwC`kI zrxH-&kMDJcU!G&{=F7pw0`+P25$Ex@E#L#6XS}BypVzNXGZ|j_;ZDc1s(7#?g#4y- zu1HH9k*8G|9#6wIRB8#Wn74Fyr`2vReZeD-pIjd#+jlCDf#71++xu>blRNK&+FPSD z&sG~RY@s#`SC68%F5 zsVH#dFx&K&ihh+J=8^kPNUL$abpKYfE8cMT-7dXT zt+%NKzsR>NcppUa8{$~wT^f1h_U-!vUD(a;Kt}s?8)E3ih9>UY^DKZPrZsE4zJBX( zAz&hEdI@=zlY1Ac<8FO$!pe1JvZ%zhWp+bZt2MOG z*6XbW;6P*b6JFW%bOB?FF`imjDqka@e8qjxl*j!%6TIm2007MJ=o!Zz3($N^({MV< zrSJdD({Pq!qZ_Hz72VO-`i0ekhfCf4sIIimFA|Br;wY;13gvZ`@zdG7tjBVCa(cyE zw%zC#wC2-8{--n)VApK5FF4rNr?3=v{phS-$5i5$NYH}>4Yn(|-SZA>?lT95jW>wf0yHeJT^<7tnwv};JQ zo68`q;SR>umFZyM4Jb#Z=+<>cR1WI0Cw2oVD9gK~w1y@}S|X|}oq5*S6o7rg<9 zDuhrUvH^q+OW}oo-ghzM;a6b*N4=IXYYZkxMpmA~TXOu(F$iTU8Qw|9G#h?^E3RR9fHU$1GC; z4vu(CoV+3F47XBS{GzRQq~b)0g&n1H&kxHreu0dtiFys=qRaIQTN;di7WTz=^x_h4 zv#0cHanNc&Z6LGQX)tHnq2JE%{U(A{ ztvlI5{7wWOn!a_*c$ENn8osCN`mS5+QQP{GcjEey2yY?8Pg&5`j^lpyJ>QIfQkge?`4MWv6~Gwtu)7OFAVy0gXI^U zo2@1CBons+QZy_Oa$@hc!gDL4a99?BtUWYj8JQVUG*W*rMIQnLl>`$CC38nk=m0F3rBRr!yGBG(pM=LJW69sDFmFQj31z0nd)K6(nw{H3eA@iB6&WSWi>nT0tumLC^j9-h0D))%k|jS6B>-U_s01mAk?rS-Z3*6QgI(gS86mH)Az{5OsvUWK z9I~#Jg*iwoV(eucHDzI~L{)@XaBJil-^mdO7U0{l=cPQR0GU(OG6H`p82{B?efviT z(1^lPz%MSs{%%K-5LP{4AHnCOLbEH8w>DSO{;MORRnX?lP4Af_kuY$$?Q-;NJ{*|6 zwKJ#ZSNm=T+C+rZ8`(-oF<)ncok!QD{za*uy^Ow^rqv{v(9>^a(;q(<5TmLK^VGX! zSCP2t7`p^(JUZ}H*~Ud@bl>sv_Q%H4N5+<;;w`0^Pa2fW@#c-{c!)pRszJkvzvA7g zWQC+*smv`%;`X_*#JOs%j=vn#FUk%RdfF$hICg)j^F<+Od(yS5eJ|7YvT-3&cNE>- z7p-aP57v6^^+wrWX_>X1ub5nP`jV2I?kYyxPwBBU5fexO``+3ct<=_{Q@1FE&c_jx z%qUXh<)#@ELs(zK;huY?C5(jEKF43~zAkp=gHaw!a~fp%9gPH7!8eTVCb=n{od zP^8H!sA^&cE;J5PSO5;VfYa_l)p^H?WK6|WXUvKOqr#D!Q>8Mfv)MxJVm3=2aq(lY zzUTbooY#!^b}3V}m0MZ8>X}zc>qD8HmWyLo(M&SI*49rlYs<5I7Y6<6vAi(46FdG_ zg66vkTRNxYgxef<{wfmCJQk>W-A4<1Hji4%4=XO_y9f2xN4dYYSvl{}ATmRDp-zFl zY%C^tbRh^Jq9H<$yeTJx$^6}q;m13i5(<206d|`var<56p-jB83rPS$2&40b^wtMx zJ15or+?`RQe_u$%Opv2pq*4(Sz>{%N-R@)DZu3}-vN+zhN5I~bII!mZBzJt(Fjy4c zbQ7EBD#Ht0&+*zg?LUd1vyRm=X!J$1z+w+akD)`ZB;rlwRoy3pZG4zwrWUQR%Ob7~ z)lhyE=PkuII3!??Hu@6XMk*tV)?277s<@80-xLbIFGkXkcP^Sm9j<&itiG$Vw(8LH z=oYIpxGB)RepL6+0Ly}|k)jgKXKq%ET%MN3mwO#rv^E1>B%kCne`K8M_i$<01~C23 zyoRO=pOXAXMECtyMDOR_Z0#}D-6$!XEn6Oa8QesA3^j9wX?w7#Q9% zcAz5Wheapi`cwD(E^5p*eB9i8pOv0(%B`gNY7@W$ z#V_II-i2}8P=+E3wM0K&-UQygz#PU)Hfl!>mc;1`o~X?;mWm|MwS(y|}&wjz>3f;2Tu z^&;;JX6R^Z+`(d~Zne#C(>(=+d7afDHU4Yc;fkLsTwm{fpKjlxtHlh@F5MJ!hT{CZ zO;4@$XN^01(KWSFEa?-MCDNt82#>+OW>e@{q=!+~5^9`g+B2B6z4pRl@ZhOE6aV%P zfpdunULD6=A;uhNjfycihS1*} zn~UFezAyAME6*^_JW1^6Ss?$A27R`yoMIV!%E=%>VD<`n#N#Co#}~^_6`xvNi_Eup zGDJbXTfw9$fA53s5&HT_!;mv{YGv_zr9k;r$PC-U{1`tCVJtV@ns%5ARh;<`6f@0-y9%STjV3n{6o_h(XZA806Tws`QO zex{ynXuVtrn2YNDKI<7B;JO}j;TD*a<9GbbR?y(i4;SK zZEIVd#lcpzwy%Qs&Y9mD54n? z+4++|jK)CL>irq(WR7ajKN={n|4t#~23%CEn2ug|!LabFA%ih-jcfpY)1mgs5(D%N zQ7ZUpp!2w#2KBprBn`5f9LdjoRPqjIBE*S~-@V?Me77^Ww@~vqGRlz5|5B{N=l$cJ zAc58Z*zq_qPHB(rdtl_B17cWpiNhf1Op!34-nmv3xFoiXee)2*9~P4J-7zz^;kiLK z4qaU~gvrgeC)o7Xu!dM+_)v@cCDh%cO? z%+x3bnVQb;(x)>~$m%L;wlzE{pF^SiizBL(Rrurju2i_G$!Y!H?SiJ{|JHQ=ccot< zr;hfO22aRVob$t_QwYsQx{+(Gov?IpfUPc<4~h`Eo)t>a@AupGg)nUk+MOO0C9|Z1 z>bG!HP8_Kf(vkrZDfSe?v%$*VWh!w|4`^%fSw^lr)YQ_Tfxi1X^gHJ`%ZAj?dc4Rd zTn=Wd3gUk8qG;FTy<$UO%?ZCM*7I`FGhqInK0k}34v&hWTAoz;Y(U)mo(V+?TWko` za4?!#N6Fmp6DIopAqB$v%RjmV&mxd6!CEADy!{K(v?e{!8RgDnke^pY2_xq!1!4zWoHBk1im5L-BufQMm-BmUrI@aGx zV#u>N^dCnGsW{OZ|5ZnV!s`!zWbbsMo2Y_+KRo^E!!5*r9Eq5ftW1LO=f>k0bpGc2x%c_VOFh z@vkmBufQRRV)Q?b6e3pO<&at6vZ``2BlryS56L`V5m(eW1H7eb_DY}}>t>=LYe#s~ zsCSb8dJ+WYq^4QOsWH`sTS?-6OY^f`ez%>v$mCX|cUm?A+zn`Gy?n*?>8cBBvMymx zslM+k47c(q4G<~Ti$7j)*MR0V_c^Xd_(ik+*oksjj0gu|?P&Ii5F@s^Oyl(YcElS; z1^`kqoOeG%j?FbIWFAjg?VbARYz(d*pY*AGGBg0J0M?8=5gW}`u1k&<5_o#NUE4Le z$JhgLsaCP8-=<_4F(!`-I*7HB}B-`Yrtp3xM*BRhQoDn^ffLC?EC_ zLxXImz^r^#};lAO%AEzv*!gopPcFBl=VDEU)aNBDdJ3g3wOs(34PYjkncI<+r?X{I`bUs8|Uw@+2nidZCh@w$!a@u|?XTMM_F>JCmuwOb=of+>4Mx(ki%trk5~;ExC6Zl>)zjd{Jhz|Hh}x(48x-OsC5{?46WIk~tjt?v5tEBkF44S~xzj$x4LpqshsvJj!`Ft-Pj zjGOeTq0+K27SMn@qce(|Y^q;jvy35PRJOw9x4Q$5xG=^^&nD^)v+<5BTyxcew09VYU~1 zcxv7YM+^5ieFvigk9Vup54ZgN6^@Yy2V4n4;}@YXlXf7thhDbq_RW4y&xjXKy?yT3 zS7C?kI)xTVk&$)|+1d6vrrqi!z_tFNcb&sHWop;{kRiTKm)-Rla<#%@s{s~OkoLYe zy9Mpfveo-emlux5@#fSA3lOJcn0m?D{R_B-Demr$6}(zA#@>$0xLSQczl{yv$)~H! zzApjTwcHb)AqGaLlvy`j@a;}23k=jg09Uahh1>R7j&8Ue%UpvoF&|nQ|F8n&oE3|O zi@`y$+D?U?%FXcUl#UQ zbIU85MBUi+ZZ%&n_*QpZ>*jRn27nEd+#?SdoX7Lfy88i08D5d&h$~p$ELz+33aPkyFAFjT)#`Q) zNoq*d3itciTeod=wszbL*M=?ovw+BhL9na=VC&Ee)MAtj`C~)iGq$uFOMTLq(#s@M zijVU&UyAsx2T41wyv0pWxHpR)F!F)6rR*3WOVyM?Gm6{Bf!rJEu%&C;7kGLg77NrZolm5*E05{fb#QxyTWpbHgHx~-R_s)(Lwt{#pPfg+R^$o?#7Ar z7DJq#^YHH6Q>xc^P-LT9NyjRRz+I?FT+JRnL(k&!Qrremkss1BnTI01RAqfst{u^L z{MDY5Z0xn?h3zwx7v-h)^L`Z&StxdAJzssnqnu>j#A0nnh!}YAA4Rff1g0A`tOD4r zuZNosxSIN(3}0GL%`n_RoUOKDJ9ynD|4s`4_G82GP(1LaSLHRfqdxVRur14}k~hoG zQ!@lN%GbcD5Qj}K5HrNy*>#*D4C0)HHA=j?M{aC-k=*TLpRriCKwK8=G9L6}y!Fod z{@4jA(PjEd_;iwC6$cS#dgu>NZA)4cJ~eYZx`{k%y-T_izQa}XzTjFlx<3X0^^RBZ zAYMidF46yqb0+g(GOa}mwENV0hL~He;t7dXIMPgyX`^1CdznUtZ8!FZ9%i#pA4;Fx zSmanQZ%XgzboVp4e2&s%2&=bTd01zVk5pS2XH>sv-X)D0+G@TAb{S8P@-t!Eftbx4 zwFd-JUX)%CA52y@om!Yw`mFU3A)CD~R`K}T?j9l0{|q_NMIdF5-e%#PM3;u}m?z(& zdN~xMQcE{1xGp0DGO-nZi?1#y9QXs?L=~xMaF+qHFC3SD<(~x%6ZG>F(LQC29>ut{ zoCC)x#7m!x=v1Xp#EPo^Ud59`kC8xYxM7*h7ufeaajAr|#(1V{2zm~4>3g*DAMpL7 zPy>n*(-MuRve(D+UYWnjvW#iNY-hla$JzX&SjxbK%nv+cyi2c=`D-|lglj=X+g}N? zxBX_Ht|d5ze2x+Smz?uQ0c951(OCF>gb4fQSSH;t{R@;O`JSl=*AZ#ncgX*Cu!<62 z1en3idl2&024A)KDPN#Ntx-Xb+5GyfDL7X2k-n8;00lfciON~dg`bLzfgJ9yoTkXr zlp#hg85}txiROSa<}r4Vx`*2fUJzx1OlxDpt~QV+M&VFxyV{; zv6GZIWmyK6z4+p%@(>7=B%_l2G{=UPz5p1R(4^drHZg+n&5;bME)uiaQ?mRrLcKkI z@rp*iK3lP8*lHalpmNGU8!`=ybF?YT=ikjvME?HF7vcURofLzUp*_jco_D4M{AEdR zuX{B3$IC^TWTn7JFanL4kJ0@q^M-EQ6+eshPojOe7hz%fXl;`%f64k~ge=s2&)b8K z0WDt<@!ZFN5gQi#T1;}6C?4a%Nb*;h2f7zM%`T%`2j!<(`PPe`A879F++;&s(vUw= zM=&A~I7M7!>kp9a@}Cvid&bIduOr}<;WFk>a_9)3+lH(z0S9muIzjr*ke@kJz(%D~E0t}t8q2F4ZJwnd}w5Nhl%d|DIL$rSi4 z6wI+B1H7EBmd^Vv>O-wt;2*)iy_L9$NC!zkLh~D6u+t@SbC_wHQ-#)yE@I0dhAk{; zlb@Eo=B#ynvRl}&T4rAF5zAx4A|bF@ZbNZ)wTURVxpU4`SnZLb;_QiBj!ysk@kT$f zEdo!c`R)`zsFy83>W%;!FC4#;$aqbc@oGCN02;nu!)U`}luf42yc4~gpg0sJd>M+I z_GQZ5Nfd}k#AFv^9&|e-q(_mH1G^jybtXcUTX#EY&5}fzV{qII;@!(*=vs@a@8q zs`tYgxC{m)>hY0%r_aBql^&ymCa^`V<^p+Gj8b}AJCll3cFLH)?iK3GH$83rfF|-i z@QCK0KfG+106B*EB}^~Zy^J9h*5gi62TLFA7}MV>*tlImV?QfuBf8fPNQ7XSlQqS) z?Zu*;kfP|&+6dkB@Bv2`{V&Nr-B8g6rVxr~(?J?@t0U?SfMF_mcfZBpMCIP#FlqsV z6P17_OglyIF4=?N$Mwnb5O;UwMUvB&^65!rJe}#YD;(d4MbDS122K-DBI9WW5a0KW z^6~DK8_S`+3%RDfn1IWZ{U8i>hxvMUL3=1XH04282aWhiNfuu0L^>s!^PW5nZ4Z!9 znuQs)@$fRUX$zw}2sgbMMLOD4e&RqWG~kdDJrJ?7mGoUw86|>5F${+)Gw!z^z@3?( zNvT}w?e30gV%fJr`xkIj2Bdnr2$_{Biq{&~W%exCZf{U29XOGJoD~WbpsHY8-MZ7a znL-ztiWg8?(y$V5i*Q5T4-v*S6P5K2NJ#AK;0h)^nh{53gm-~!an!d~A!WYody*BwsDN_i)~G#4G#LF*QM?U8U%3|HA<4IWSrCIK zZAmg|ey)nx4ozh2Qt3dAhrDe`MR0&@Pv9B#4Bd%?S|1lxA=u|S4?A56^n?#V?^4b1 z&36BlrR0Wy7|*NYo4oE&^i@jiTGIV^*0LVg@|}>i%Hd-bd-qM=iC#`L0#i^P;dk#C=D$`!P5s$g~;i|&xNkEas?pS}SRWd${c2DPe3 z2&V4EDMjZr*a4YB`4<*xf>Inj9AYEDm=WAubr)oo5gpZgoe2QlIW#^1^ zA^DPeLTQ<@D>ZTAXB744R2ht7dOj_#TZ0myoS)n~sMyMmZjF5i2$Q@mm+G&m6b7Vn zG&C?9C4dl|DFs65FV8UPoz-*Y`Rf+w9o-%p91xtXvOFW&0Wz$t-ajy$xu6@-K3BXC(%&-}(j(~|zs8xjXrRl%O@9A=5}h#@ zolz0Q>s7$n8~9C;zaS8R-w`TmXSq&Q`I%M!!4r84wz@`7t)NSu)gfMK@RJ5V+m^Pl zpgEZe9M)uBYMO_eREXwnlf>ipnfEjFBM6%#{uf>$0&?Iw6J?)MroOi?XxKRW{83pW zvNNn`+>FVq@AJJhwF+)OE5>kkUIrw>3JSIgWS~?>G1ysI8d=sJ9vL<#?=U@#6q}FWu5Lg&QxD=h;}xIK6rI`M6NcMu7RcIuKb-OqsAXf zfSDs;UFs_;a6@lbJP8Fpx|bD_^zpvx7cUr*&S<8;)ml^^!ulN`H*Jr0E?hosNkfaJR4? zE%X5;U^u*IwsQbEY>AP{<&CSL^@Y+xH0e7e$)Z)b->sr%ome2|Y57}SeZm&zB7a8G zGHV*c5F$qk6cz!fW{NyK@f+;JhzWi*8ol-SPsMCcM16eEG}%*A^evYN_b?peg)$N& z9H@D-IWgY@D&{DTds15U{9?WR%ZCKrb9-}%rJ1gwNytP+#D(5YCY7{FKIpK7coD~` zR?4?SQA#uYgeROH&NfyJt^!KFy?N}BQ=`t!dqMV86Dpk54trk&U!TW2xHQALSSMZV zvq~99d0}Ev%;sNPqgH^LQipO|hU+w^I(|n(;-j_@s#o^ybxQjkViB{A!Q_vPxZ14} zb0|dET)gu6z8gYmP(G@RJmdkHR~<5WW=vz;oW}N95e91-j*nARg=0omy7O1N=%XdV| zm7R%GDySykUVmO^_w)Hnq*cRaXw*{98a5uO21g%(;v(F8so7s<{$^#o!^CXnHSlwt zkCXb0+GT3h;-$8YLlvCG!P(5qH~A^2oqWWsu)dCsbac74s0GoTn>tEZf&W!z@YW127 zBNz85Ke~({70!S351_D%9mDud-iij04#o4#6mZu9<$7A(0)_V($KgAl=a#DL!IH9> zlzD^;@$GI;z8ISXVdO25&`Z4kzF6iNOhJAqUKn4*y0ivx3vp@>7Kh z^SgYXirqq{o-i?>ME@*vy--ETUeR~Rr;i}>9jXF-Q`L0iQ;&)|bW1y6P@b%Ncz-9F z^nEVruNFSa@gj;wDd+eu5M4+(D2V*{fJv0RWG?NHCvGuuHQF0<-vy-*_QjDlJsGrzai5UKc1)Mt=>?zl9RyHLe%>PTC@sISyP zL+D%4#XO{%?)dA72@0@q|pM)qENyEDL*f8Ffz=}-Gu{ULC;t{zibmhoS^*vIaDmz0b-qXV*XM` z5&tZ6(%cUQweQbzg^IJ>>AR;CX>06poC3T9{GhO-wY(DUxQ--fqJ^i-zo1fft)DFG zU2_LE9U+{RnWwQUD1I2iqZi2{i|aQEX{2S}(B(W2xMp032Zh>mj5=DpnFCPEgfRUK z;Pl1CY{I;+-iOCAAte~y4D>wV&es-Rr$>WZk;IlKo$%2)_l0$?fOmD&sw+tNNJ*w} zaiI>t;ZR6XUP2-f4*O})`URjp_rh}X7G=*DGu?-Gc!BHf!Nbgr8%%e6+Iq>_#A|o6 z(th9dM>iiTmfXF>yUI+JA2EV*n61Lc>#JBzDvXgtkJ{T`5DLHC^&%udL)Uz|cdiLg z7A64fkhkDyrc=;KP6vLrH?aE^y6l)9Q{Cn`Xt`*%%NAydR`@~>5;#|R7@QLPydpz$ z-VaE66H|T5fx5)g)Zn)n5T}BzS=^PL>ZkMpC^E?_7yiBzO2JQk7@@4i#p3mAdP_=+ zm8&*x(Jf?OEp3(Zp@9=)9BGnkmp9@=4W_6=YMBO|UNoVEz*skCi021srFvk`cr_K7 z1W&gJ1u2_}N~3Wpv8l5g(FO%KNCc!RU&I1Q6Jm&*`x9uIyvvczi^{0B@gg0n>+rFp zE$XDsxJ+0XqQ9}5B0p5M4+yE_s{cO#l|X90-GW8TFt!DsXZ7nehq5azX|$mo1X{Ik zQ)N?rq3tMwp2DA^IIiw5+;AXBw!8`{EaY}-TqcZ0&${+Pl1PR2N|&P@XpdJ83x;4& z2;51s)b`c~Z2|kbW)J!AYX=}ubtO{dsJwiy4bfe}@wVZFdj2YBnf{}Cly%Nqv*`8| zVk*>#KYAi~i6A9U>Yg6?kZ-7C<(saAz;lN{Qb3l#R_t88Q;f#hfS3`TQ*6K)Ccim$ znQ6AFNJrNaD>2+)GKGsMrUo2wIy$i9Kl0;aT2dHGUThgaJDf5Zi$}@T?gM zy@h9g^7r7XF#3-_={jfgXZeOJJjM9j71V#6J!jsPV;oEvTzQt2qt0w4bCtgKI^Sjq z7UdeMR8X=CR;`gIvy$ZsRuUAHmYz!$ga;>!d?Foz!jM^a_;fFRoSr~y_?1V97k=g1 zOTXND>DRjwBYkdR_Q)S_(?AhxRbj+vb=O5M%7|CRS6%tL`=y_Rz%xU@Tb7!TgcEON z{7M**0)TL;B^(k+)P6%7W|@r(CYpl|LVgsZy)Am1bZ$Tzq1}4A@Q=`vm09TfN>Q%j zMY>{(7oX7;6&&#rV#vi)k4v`n9x33ldx>^EO1Rafm^eVQR&j-3Jh*GTciqWHa+PAZ zk8r@P!6b!vsV|w*l1~10B)H>V!Mf2wQks!v6~3DHeyd!FgVNGzQbG~pg(6-Tlc3}% z7vU{$q0r?K!Ij@`xt(Z!2&WPYZ^cwZCy__dCQFC-c-*`nLJ56QAB1g3o5;dF){7_N zd^^yhG=i||+}^43CP5sp6JAsfQ6oCE!FV1urF#0Mca=`5xvv1xI3o{!{7@4@ge%ms zKPzzu#~(s&JZ95(vh~BCXj4e9ClnZk3(NR;a(dN5BgUtwA(Ue2S24POisFTi~MMMzgd z;5k7cDIiP0st)cmV`3KcM=|^P8AE)Q;f6w>>D=4Okfu7D^irHv$aqt zF}UodkQy)o8_qHNAg54j zHnhyvEgQGl25XiXFms&XHP@^olxQAIIfy|*2U!QUDUt)7a&ide)pLa*<#b1}>`>lN zE{_j=fqs7@C*1?H_Q6>+c`}L<;_2?8phMWjcLkF$rS#+<;>k5#34v#bfEp1q3KCwl zeqZ~d!n%6RnA7GExP2YDl2xCi9c!mRk^Wpla>?Ug^mW`p8BqVPF)iMd@GWlOeMo|! z1P%mYgj=1YCs9YexIx@Hr|s!dZxA1oZ*0>cI&ai~5bb&iAc6Gw@;egM7ly7pD&1;5kyx980h|luJvhiflU90T$J{s(ttHAsd38 zwWFg}8W@5dQ6?rqDp*FeNxi0%_PBd)gwuqLuAoTZ)t!MCt>Urr7XJ``);&wzi}xsiU=tG5WRU+8sASEBx{X-Q5HOt<-T4x`VURNRXgFQa9cGn4;h5 z)wlrO+P|s(rheMuy`v3Vq!li&2^aDMmO?Z1i=r%EP}85|Bsbc{OpeJn>fA>?5$TFS zm}rnP(kPah$g2>Z)dSE~B5a2?zVIOMp(cK7RF>p%nK~qG~P=|5$&?3svJ%o zZB3X3`qW=_nwnNzXfH{?mx!LG%A|PuuOE>a4h$e&rSBec5C1%vf~G4W@EjqK6p$r= z^&up1JnyUu8fMAV(ZdXfj)2THs&-_0!lpPfPn*ERzUE+NVovh6;;=0*4Ot&c4z%XE z!TO0dBaE1k7_3+#ThtkV5#AA0O2vv*>tY8=NyAHE9ASn+45Z6EaM!>qHWOH;Lc&OR z5d+qnGZ8)LiFlzPiqZ8Ww*CiBADB>78uBc0&^qJ-OfIkU1W9LdX4bA9AF?;S+!a$3+Y4sNMndr)c`lNUTom4H| zIRg)hqm9rK#MM_M`gng+I#I}VM#H=ORoljh+v>hP8y-NB5D7|;Kjkbtot89( zE7S+}ePsQrP0da+F@SPBu*xcZBMAOfBoSrt;DOU1JG6zI9j;aFkz*&#W=Z_S9BZ^@ z%tmNM^yiJshiuirfXxwA`=GQG$`u{eJt=8YLYQbNU|nrvz99yZ@E1D5L|CieivpEg zSj4`oFv8Vcl_c#h_{Z8;I-yM|xpXB2o@)e>0WpHn>bRlPb{T`rurPsOUTxZ@ zO4TmjvdU`35r)rx1`TF0Q6}=uDVRaiW@|;;eRR&gc=UwTPtMu4^~~z^57}Iuc^SeE zb*8L2J!N+vo3x>oV>UgNv&%PJU^Rqz4YtlGU~Jl)NzPm_DJ@mtNxVs?$mm&vm6($b zlMxdX&7vj8teghLmQJV=Q{^wrxJpQYWvPs$FL@)(EWwyaQ)!8z6-zL0{Q6lI@$lY5 z_AhR}#(wCXZ$<&h+uip*VIThV7i`NVTgansj~+R0#~EucUeO1iow4y{EBxq8Z5++B zSH#!4Yv~2Fs$5XwOT2U!ty*5eIxhk4CvW8;PW0o&>=bEq>E{K?814bUXM~6stQQ0j z8pM$>puvPdgrWSxOz|D3AoyuGm7DU{ZFNP-A`OQ+Z=D8i5qi}1cc zKT|)KHKxh3N-ZzVtKYysN?0#SC`Fp7SDy%7M862jOe!c&hd=chQpF#BA!eli{CW4m zM@y>2L)GsCKSFRLx=z-UONp7{8WvOLWx%CwgZZl6c=?s~raNw9Pg&Fc>xVvThrj(@ z$_jSS=KWb|7Ewm%#|6sXYy=vm=oI4$ zWbb_0PP^)si*3coAlBo4#)py}o}9K_lQnyA-;{lh`dqzoz}AfpQ^(?ISe?C@kdLfp zV5rF?3Bo@4<@kyxis#EB7Rss0wDVH&?nRb?^T;nS#VLA$s>#< zN=S7m!JA1kPIBwRx<=u6M{#3ZYqqp7SK|r}G!~tBD1lzep%f?Q*R&mlQRS;D6gE%0 zY*W`d=}cwx`ognKSS{}jZH+p1MZyWgRgv|_j~Wtp(XD||tUY+@H(;co)Oc`Koe@4q zU28L=`aqdBroJ)C9-_&q6IQEE*mW0evC;93cHr0vdwAbLEB6g}d+;$90%Vob3I!!9 zrC4=TXiV8?U*0ZUzs5>~E9|kkLEFXnUaZ%>jW+XT>x0Ib6G!b^PwussTycfH?j;x4 zre*!MX89m1CK`79#0lFs)3&=G-ESYc??JnC!&>qlvl?`Jk7`w|Tsv-urfRke8Deax zY%7PC(|I@vOAt_w3S+MCm7<5Z(hA11l9s4gs>F}ZFR^D+M_s$(f}8reD|lWa>XC}~ zu1h)b4sC&Zx)K7+Xnk4;S4j^Sn2MhU4iJF;bL#D4BQ zZ?}<=ihbdpgZ9_|@Euz-Bx?z2iM^6e8wH{WGtmZbXHYOWw{&Pwg&z2axChVNc-97R zT&*s_U26ec(iZcPt2hx%i?qTqm%NJGi)qVOg%?92SX~1=Oxy>QYTZ`A2se-9ZIU2+ zM;S>b*m%xBwd?4l{qT+3?6%upf@NgRKKPmM+TJ6_*f6S%oFwN%1`oo{2P!9+fd@tj z9X?7C%9Q}o&p!z+buf@%q*+>}qB1)D#5qMj&LrdhfqwGfj7>4tCd)fI!phU56y)!C zQQnU5bw3mk1~xzL(!aqV8kJ~B)ss#?34yajfNn% zy#h;9^l?@lt*gCsh4!4SsB~=82urcRX@FC(eAb#YYphi%GMOM&K_Y<zlfWb^K>N0 zgRg3~2}r63E$fx#Lil^VszQVv{|YR5lfu-J0!SLlOUj9=M%(*!I$5DTYb~sDvSjB7 zU+f>D?Xt9wWHcrTAKhIc0)z&6$ztAu7S($}jf=Fx@+RR0FIOEvH#x}5;}=w~;I4Zf zt3jO=0y)wVP5#ka+^9AWui7ITf2uV-ImzDsH7?6Z?%u|DB}p%r+QML=X~WdfKkPnW z*REe-zw~2ovx~QFvHbE?_N{L}V1M@qe{0unT}FAeiC+n;rD$wYa}5@Wl}&1{tX$Vz49(Nm}A1rmvZ?FdGIJBfJ<r@ZouslqPi!Mh&f<~VNjhr1r(Yp2JH`yDmxy<(9 zKb0G^fBWy>Z`bbFY;C@p-a<%dp$te^DM7zxV#P#TC`d|6Yr7?w`Fe2ZDD&PV4r3(c zgf{Y)G9kL1fxH~L)bcqoILAst90yIg@n5$jpP-wLQS(Z0Od5K+kO7TbNYs}aQW=Vhd zNA9p6c=bzcYq!^U>Yce6DBWar~MQyMyUKUDy%{-u?o~R|A zn!Q%vD%c$Ss8AY!9)wd_0O+@!dev!aW8NvdbcA>Wuh1lj#7cetLl#?2Y*ab!yIkyt z4*8KUaZ4<9odZREGeHVo6Z$k0j_%~VN0u5*$`r9KN%NYk)~vq|)oCtrS}{pj0XYd7xPK>d*((T=R8%u``((K1|DNXb_i zO2L&_zY<;dOHb^ze|N|A_U1Rdl8LxM&wqElU`Oc>!%|$pWTdZc58Z#*Uio9Muy@>k zJ<7D%K2~5odSue>tI}7&d)dfxTfchLu3Ir`mtK6KEl2UV^8=r^b$q40Lpwaqvb~q@ z*lD-F=2p85<#b?dgZ;xUv)xZT!X#iH z>zZN7zytdx?9qqzdY8^I(5qvwf=7+P+t#dEXIs~g+bgc#Vnaj2_KnAO`JlLry%NW# z=j`dJh7Gd3;^3aA2s~&t2G@?8`!RDPuq)RFr%d_GmIMU{)|-F;Wd?KA>^;<8u)Lf&w7+$^hidUxP1cNbz8>mWf{Jxn%;zjA+AO7yvZ; z3TJcWU@gq~z|kq&4Kc@0u!Q~SA+zNxV0N1AVSHi0*9Qz`?a)`%H5)5ZH4v(N8kEFT zeQ^PFH!x>Q{wQmvSM+NT@_*zhdZc{8Y`t6v1ESxR4=~f_)+QDw(O**eAp+K`h%Ssd z{fuG~!c;ERt!R>^M0olPFf^nqA@J-FP#=^UD;~f<8kh!mwPzfIz=dF3&avlV+Xnj~ zW=S^;VO6A`eD~qU?Hk|SXHV}v$}DQtMutahJ-p+Bt$ns;eBAaOM){yk>re=7pe@jU z)GLh>d88+}RaBD+^yQ{z#l3GKn5sY12O9{V>e3Qc%cP^WE&ixi-V5LWIVpubAk)I^A8=@pI0&Qk~mHn30n8j1>i z82!uzOaCw;G%Kc*2ah5?MgsaEqV~#2sqv*p%<5`lN6UI7kn0c(DO!r8i3mdoYcb2L z^7bM5%K{}nq8VZ>8&X*$h?P`I2@L;8_Qx9c% zDzi+hI(^(mD=quQAAgIz_7yjK*(SmFu|3CaV&a%Raky#w56{{lbd0m7=Yp}04a3*Q z*Q~b7x2&*Q-%IS@zW)RElGPiGWwkGwQF0(P1#kz%3mrNH={KdW5gUE!#6co<%? z7Ry$xNaE|R<`G;LAkj*aC^eKz{){1-8TYnC+Z2zMpsFxZE~Z&Rd*Mjg-umhr?3!z? zzCRY5a#jH0QDGbt&q98nK$WuX;$bENgDMd^~YCp@WNs9oVl zJ(R$V-av@F{qhgK+TO;Bg&pI|S)ow3W_8MP{i9?{Od6DM*BBt2WV!Lf5orGdSlf0V z+Gn?I-(+uk^BZgf%12AeE#sf)8>NtWjXPjnDp79afdcjY#EDt^^4FfQyPr5|dk^oj z{Sy;5gW~$)P3!H}Yqr^~H(YENE*rL2-g>qD%H)*2?=Qb#H{f>!3rYip`rxrS8$tm& zGQng4N8S4ejVZH_UG!(25~pwG2nMxLjj!q>niQ;}?DT^*qo*rvv=(nuzUqOtL+F;i*==}5>Z?pgT&;HuBtzK{c z*8{UQ^XFg2Z;k!Q$G>iuuPoRkaXF*IXYMt~*O+N4V#UxvBxXM_#K0-(o_7rd8hmRo zZRQ|hK)!F)MIdcz^VvI?m6l}4GNRL0O1Q&UeMZ#3Tn;1Ci5%J#sihnxm}`j{Qq7oX zsf7=0Afc_Z7F`=y+rp9jIvOBJD=}iV z?sPpf1dv7$z+FfnqK@e<(T=0Yq&8KgpQ%sZ{)*ddq`!^zG;eo3a@bz~TYrW2e%Ll5 zbPTiHX9_`P&%~F^o+8#OudpkMbEHF?*Rj{?3+z$Q=}?j!>-0780>li~hx5ngb?sM> zK-wnE9BsN-VV0kM;IbifNFbEZsaf(4{YOHcmeh!cR1lyl2Ss;%h*2n{w5mNrI!6wy3M;psmQ#&%cmEXTEdXc-r- zu%CGS4fclDyx1mK<8LEttlEKRv2<5UrzE^fag${Ul&B95DiF^k&$t8F%qtSrY10Xbvk>&1Z?=v6QaF}_9iu_e&cKrQ zIXKYl6~P9uyxhJ2n7!}ySK51j@~t)mUEg^8u=O8*!YB`q;m=vDs0!VMgYc zT(iZde|OUQHf*pB4B&tKkx!ZJVQ{dT_5g3vhHV=W*N(# zrcWNXT`V7%X5jWIDF%q`D@SdVlRUI$S2H-GNwZGA(GnW9*;30IG#galSsxZW!kXkG zY;M=C(_qEJXb(!8!9Zh(kKC{}sV5p3B<2VLv<9NKYz6u5J$TT5`8R*h zYbF>gs-M+Kr}nX$yyKW#Xc>qfmx-k17%yzG6gYL zZLHM>O3^RzO#_kWXZtM!f1TrhSw{=AKRFHkk}5b&WDPT0Yhd)MvMStJ=JXPRSg@cl zFoWq3>wufhIeYjhrqy!1YPgg?VSs@UbP7tb;fD{s6 zUP9k4qX;~8c*?eJT;sh;J3c=9=}*{|tA;H7(x3uOFN}FXnnnA z!^OkuSPZr7MDJRDsiS=laEjAGnKLEjz{BWxwsRSZ(cqxXA=J##C1sUWz7nt{xM>oh zg|H^2Vb9E*9h+bm3vOgW;F@h>6Yk2PA(W#5CRv&&40$XM^l$h=lRg~!X%}wtkfl}= zF3P@)1X|L!7Z6xySnky+LgP%wwyj+cKb&Je1}=d>l}7>UM+h5%#~eK|VY^tadXgnb zb{twp2W=e1?t;*+x zJu#C#IdjrpeDPX)^BuRlAgT$VuYGryz3Gp>VpmM>wi~yvbIYpo(5$?s_RCkJA~I9{ zp|3w+fBKDG_ST!Ounnun?c_`yzKB%{-dyOOq*X?NJI*PKkFb2lC!B<3U&SuMy1W8Q z`biWhu}-f~G>Qg%UsiIZKf{s666BY0e0qsv;XAaG<5<>r9fjXYn_R{Qc<^0CokAVs z1{P=-ULSRN;^dUoiyV+r4Ho_uv+2$0qgI&=ln_H!@s5NOID~CqxtM@-hu^M*mwHKlY(63l3*;c)P_3-F`-SnQaeg0eb z+Rc}2wPjm2GENQJ<=fV=L4FpvN?1k)?e9MKc{})lzp)|YgzaM+eR53J7#%7z1-@Dd z0CLC}E#wOI;~9HuYMODCF;P}X6q{>TuX5|>6d1xaTp1B!(PAXNL~-fk{u`e4p00$z zbBI7vK$ZkoVm9Liyh|cP=&G-_|e-_@WnWw#rpo?Er(@A((%qbb?J ztUSw1iuR27Aj@E@O_!ViY1OF-J9uK!uHCfOUUlKPU9e%?DhS{wr(j~Ynu*s#W4zhjMUS~t$XQM5^LdwkD9``CByx8~3)+djV9 zCfPWzqb$X+wMLeMFYW8Q582h6Nb-|6Tw?22j-dDSF@V%%$t5fUx!DuUzE0V99^Ykm zT(rtwcIg`1df_&BP{j_j>G^Aq?6EtUNxgpidITbbe<>gcymk79_*zA?<_LlZSSm6E zuX){$Eq3AcJF&JRX~6-Haw6Avo;qwF|MpXM&4nmVC=pc&Ys42<(2}4!g52D({dOUn z-)_C+B3nInkyQpcS%?x&&Cc0=4y(BHk$v{?!J~H7W={J9mj*M*%&E}NnRGyCR$7ve zwY)@qPZL01{?;^`qG#+deC^VW8*H*(w##;o+r1C%LJ;d?c?uYi#&GAP6>2B#>-Ros zZ@=Xl+c37q#yIYD<=86QO}fVywm*Z=WOj#*yC1Px2pw6CR5BneX)Sx*&W-kC*KfB`mg-0sJVHI(^Voj-*!_>&rE5oRkY##R(xp1V0fi0)Y=lEh z1_xIj$5TN@{UV4+1l|@Tf1t^ zW>H=g{vT<7Uwn9%-Eh$bj7`LYVBt_Cp1!3uzKZ2SITX_-OY^F;HpzJK$P>pH%SLSM z0{A>Tv*%_e*bF~Jzd+$|z8rXS5TQ|m>1D1A(bwA26d5ySbPCFjmG zH0w>)zBFsIvhr+;8dqtpUHx_(I7UIw;{zmqL5Y@}hQc8MK7(i9(b8zgjx|{+N`^&~ zOD#Vir3KHahOBE(uHS8kTI+4vuq^995SRO;T%yI-XkSY#5trlfHQq6e$8SCaK1c}o z0?7M7S5ZPBY2%A~_)tnliC;w#nyK znj&p>*8_c^#b{}@*%LjkT+2M*Z%PrQtY7$GKwB7qPciBEEe zNDYSVU~MhLHPycNxeIJWafW4+0&*A{5}9T@34Cj$2-pQR&GyQc8oTw0^)_cjo>g}a zfbi&mv3p1htrc^SH3rqI(@H96?xIE0Z1Lh*&QJKc)jRCTS65jvTAaOP_xQ?^sdmQV z)9mn(YWuH;pS8RR>2~qCiy^#N910385h0)*WZBlxV7p+TZhvmO)it&|A8p-JE?nu1 z|Meq>?d;*DcJ&1dt*jso!6nsl5W*CY-vPm@!wPc|FnnfBmEHN`2Afk^2&01Vfz}MY zovo>?^MCfuefH}&_S+=f=VXadJ1K~W zUT7J3bVEN4wYMM834Z%fLV&%meIfoxyFIchB56^jR_#S2ngw&WVe4+2J$g-R*K8c zI}__ow&gQ6J&P39;wP^-8(}I;!jYi8wEBSk{)Oe#vB&{OhoBv;cCfX{ZaQbKEtoyQ zvY;`;5LnWAmm5_RbncwG286`}cI#uWTPkA>BA_XQS0{LPG(z!ZXV13^lwlk99<}Q} z^)p*``DymKPh8B}?t|9l*&$LJ|HDrnvl$gBl+@7b5Ij9p%p0FY>G;mx&~GloA%Z-P z#5TGl!|r)*ht+khw<#o!*;HA9D--U3tS?zK+#Y3|vLq@IiZ)GZY{06U8tfc|?T=n~ zmK7qT9fFp<@WM*7y$29B^t3otdx#s$TBmr!Fs2(l_jas`@qAX4R00Z#RGy235G95f z#45Mx58Le8hi@-h?clJl2Xd1bk6tg5!VpWSG!#1tvf zL{es&ed?lxHUe7s>Z&*G$M-yApS|jAn?8B84db^g1X|6Z4h!Zvi>KL3D>m5utE$Md z73bjLieR!=1v5@`#w5ff=Hk9-T7L5(@PR_W7eL+zywM;cq9WMr(hF#VO4|dW1erNQ zCPWu(V|~${hDaz(h4>Q1=u>2>yPxyW1VurZ2eFK7qd-PV5~lxLOtjp$hu?|XwwA&; z5KWTJC?DoV)0c+oP|>Jp7i$NTY*>2G=72m0EW--8r`oaynXriucGnlglSQ261g4q+gga$$4BSd4cC6$DnR(@+_9c%9K|Hx z1rkky(HK!)W)pZ-R*tlojvD*nYsYM2S&7S712%>4ftwLL`0J21LzRE{HZ*6YrFqmb z7-lv3SiBFn*}>j`mBl6ECedJH^HXdxHBj;qNcu=MRmnI;Kve7Lq^SYH0RgLISgH+2 zQ#p2cnT6ug?31@XOuED*YsWQ08Avu)AGNP798D16WmZ{1@h8Smjiq^CJ+2juCKXNV z_z{&hWdz2h(n_>w9roKd(C(FCc^T-iwKX;NZ|6+4tFQSOX^s=TRKi@^iM1vUCM=nN zy^4x58_ugPlw!ZW_f3nNQ-=0h^Of0Krhop4+Gz4aChMU$4hS*;geHBGzWMD#2!SDM zhumM}Myb`~M0aUd!69Pi9S%Wj|M=P}JL8rm_d(bB2rh&0!-Gre*s~T!KV)xy6woRUWx{WE!Hk_~Q z0G>bnwYXHFfXGfsw1wk`6Z18ktUW1q&A;DgdEqYH$rO*mJYkID(acVny})Kn$+miD z&BcO)JC59P5)X9W|+)kqp(uke8Ux1F%BHY9BS|) zYQ%NuNK>aJr=(kXVWLfBeq%|Kn$*)wdef~ovZ%ra5O9?JE(hzt7#P%YaANhIz4nuj zpKfPea1M1^Qn3=49p|-vH;98E;Y`vcmlt?(D^2axb=bDa=E&MjWjPErp4OW*smMlH z%VD}p*UA%EafYVH23Hn73j0?SFFFG&|?Q3!oS2h?!=GoBOP`rpdVz z<)y~ktWhPz43t1S$ToQAQx@z+hy=bJF!KpX(J9#L_^mM!6yhTo_)x>$VWX-BUnUl!%IS9OS5d^1V6-(e5 z{NUcFIS!2sCfT0O7F(K`Ym>)TS~;{Zj90a_ThO> z86+lJXgGptb&iVv2C?30@Ab2OL~CW$kSj6J#dR&-Sx5{QyZD<T%~-DAa_+WnL0~ zkHInpeNVwV;W%z*H(qlE<1Vv9Sh)V{l`VGbqbn?WbOEQUcka)%QLKG;x!m8d;z=>t z7mP<>!%{)rkex@c+EZu5;(IJLFU{tb7T9g~e8SFJJcE4@XM1qjUcafzjQd4r4Pz|0 zO~AG0~eLELiKv@D`nzYLiA5+wg*H3r-znMH$f7vlf{0a@DflRhJ|K z8duJ}Ch{7Ai&t;>Pj=gjTW$IebG*`*67 z*g5zKYiswi`8RAoZiPkoA!B}quRtpyL`p~=goGRMiF=_%kzcLaV0Vv|%M49g+r4#d zw(`y0wrXp$HT5*vxbgzDLYV}y=fF7R*}OS3>>s02>}z*FZ&@HfnS9%EyIPF7{;JC_ zwRs31NASmfa`O?}v!|XSXNRm4O;J9YwuO}$wvg-`qcOjK`r6B_J$Z%wYSn(UGN3kM zI-+pH(!4Zl@G)Z*LuHoBVfnu5P@nvg(bPe;m>+PG#uh(XH6i>Zr%!~anLV;{n;ow0 zv+dkp0qJMYth95dmRSLDD5uRBXJ0D5Por%+c-;9Bms6#E-UzOpKGJ3sQ}FTnE37;AX6xKyuq3YVM&xVw3ofq+tX#gzW+tL?&A42sXWg{SCnD> z$hXmBM%#twwb-B5ov?>q-fFQq0UMv00KE=m8Qqqxo1tY-(xZP@jXvEOH3SVIDnF5ctxe1 zf8M#4i0j6d6D_uW=TTd=z0Hnc@kk<&cVcn8Et)jU#*H0Eor`gH*VnJK@Bivq1fqWY z^P^q1DWwG7wR?|+VBYo|Ach2sYd!8ua-k{(hs>E$X^W?fvHZ+9yYzwu_QIz9FtXqk zDQj@ck?V`Mqhuw3!9^%h{e~`re*g8Ge`m8Mjxn5a?DcKLS$y*zo01oYPd#xH{Od>f z$P4z^r?3C4O&(Wf)u7IG+xB2>IRYbG0~3d<3~pGnCKTJ0vBPXM^;SN4)rEGPxSH)) zo;0plX|AGL=?WLWwF_A3cFPF0M8% zPatln&WbKvj!+Y$?0ldG)ge&=0=dB`>z9&U1PLPMFyDJ^H&)zb;|uNDD=xNpguMNY z-B`(X*qd8xiKl6DLEV#w#n}9*nccs9qis7pXa^7Nruuf!&Y4kZv!{$gKuxv8cdlK2`7*aoHq~|k z_nr2}mRhp(Hd_)jXkux$Eto#m#*Hbn3zkyp9$Jd)nvuLQ8YQ;?HpIi~U zpfic0!blx*(NgMX2_Wv_s6r-J>3N@+)b6atf!tIZ9v=)Uy`dDxD#=28X2l#~ku{R={g9l`(p_PL#N=6R1Ee##E zV#9vhf2bW{wc19Ie)FQ!C)*^RUs+0mEm=4l*TWk6#EnxiU@SUWZ(I>kN5=#+DN7=7 zb=~`adjZAD2%sf`(q7J_rDYTE4=kG@FYVUfLg_^_+ADpcYe5QGB} zI)eCBW0M6z3jJ^h!lFWXRZV^N_qRP_udUo^6(>?>C;wF)$3S1p@ucRaG(GINShg|>pwg{~Er336mSGV>BOiT^K}P)MGJ z@A9xaoh+^w$|38_ubov{id9PN0vb_L2LJw^N9>{3H{1NlXp9k> zHXJyCy9K&Cv`XWKCD@o8+$h8(z(BZ4x@Z9Hc?Z-4O3jdq~E)xLPy94jduZey`(Oc_6xmmxUR+ZBsT z>`%+r+4I|vSVmGI%z6wAKZzW$zV;yK^s*0?IVc(7W8J|9yW;zgSTp|p`H2L(!jC?% z`Ji?FqRYPhxw9yYwuBrJLAwAYz>0O-Y~|iY#p=33f7gEMYTS#G>==CDoe#Wfw?DGR zGH|2HB4}G0)5mc;`qxK#?cOh6Z5N(C%@!eqtlf0jo>{p8Mk*Z(4frrN)1F+u(l)Q$ z0fIR0DIX9nTm@&C9{XdO{psI7ZRgJ&VHsF$r_35}FTC^`I0O6!Bi;?(@YpJ9W{}e_ zvFilFQH$O3l^bp5j0si?9M|oxwF_^1!KTB|wIcWgP^Ki3@rtN7I}3NV=@YPE!koRd z?x z002M$NklUCc^l}5G3B$+inZc(4V>F zbSht`*mhF0-}T^X`^DXl6AO@qr3obv4Cn*vP;k9?$bS2o0M7v-WY!q_Vr`H8{N6uW zI*hHXZg8p&M~9h1b<2R={ot#1>#a{%%H#sef$|?{X|}tbebMg!$LsClC9^p{#^%kM z4t&TAm6~aHyt2*4zw(Ox$3I+eqhMeg5lX)C(DT+*v3B~Bc{a_( zaz@7Nz1Ou3+UgZm_N|}YZ-s@!tt&Q%kz>8F4)!&cGy0YwsSIL$>=AJuinVI)MWEud z@Jb)CWZU*P+du#MIeY1$*KODY;&)OL?8%o8+K#HNcH7O@S#o)yW#tvyg_B3y1MJT+ zd3a(-0O5LxZGyuPw&HyVMtt&{4}lK~0=@w9o{;qrnY1Uaim}_KA|BEf2wl;n;XpHk z!PR|@2kA{6Q*L8;=?v&TFQJE_^Z9gweZ8ZK;KAkF(4w{AK9Ns9AYG8DkjzPhDrBhZ zaFvjjLdFCMA9ZA`y8qcX?KQMZ^QVn;!IW`ipUUPw=}Xh?u2*(iA=x#)a?@o-SpgX9 z3K$)#q|(PEe7Vc=vj}W6J679dSN+>PHYqz~P2nWlg$6R3V9Pj&Ratqu-FnYUHidw| zt1msz@aD2B&zNFIckjlM13bverCF&dKwn~$(3ec#&>7bRClOvDc_%+PIC{UeA-TM` zYKMLA)<^Bkg(JyIiK_zRla|Ovx7zVz#{hpofWMd*KEDJtro;kUGPQJfwA#Y5LRb6dT8I^ZX@DNNJ$oim-&L zxLl~G%Z8%>NhwaU?-C{WlSP2B7GOC{$0G5CAKYqZ%)Z+KX#eNVonz0fT1OxKFw)9Eg{JzzAzQF? z49wy(l03jrv40xSptrQP+k=~T*w5~|-7c8>6ZWE6d1*d-3&s!TQdvQ0-CGdLQ^a*Yb$|!a1SAS?D zEAzpfiMGFmWEo^`%D{~*3U{+RUVhQ0kIW-|?i_@WBwJ8fMphwQ&A_Ls0iq`-L2*w* zuU&u36V_6D!phM2SCnR1fE2nt1R1yW$bE|Rr<|>E2j#kh)n<@m5&+}|q-U>pv5Sh@ zQIjC5I0IQe$dD-I zQx7nb=KlcN`_ImqV3S7;w+2pJyQRwR|LR>f{>GWMy%Wetl3>Ooa3$Njf0sS|>`S=G zmf{W;Z%by5upj=uhd_E%Zz%A*Vv|u;jo|gWM_1a9zW)cCJ-^as5epGmG6Hud1(XXX zYdMN#*6#9z3%ASk14ram=u+i7L_Ks4zj(V*XRx~1Gai-q1Q2(C%T+I>lVlF#DH3?a zN6xZQR7~GV(EpP!uCUcxHnOIR*>~&*mtjl$nz3--3|tSRV#8#Ilj|L0;}(i1Vw-utM%v}uPeICm_G50n&Gzj_)>#{YZKE@XIkUL% zO9agbxj1A1sZyFl3!w2LHJ{EA(yu}DcFVu~-WFXjiNaQB+aPjLq$pIOsctk)6(E@A z#wM$-ZnZH*R8NK8O~#euAh9Nka`P-N3$C0d0(AX|6#R1YaC>OPj7~wOXtezZL(#zu zt1l&8CkRz7kxU*FG4HNhw+U4X#0lmGvI~4jlPJyyWIM=MyV1}H>8eSG8H)wTcts5$ z!Jy%DS+w}AgOtC=s#|PiIe~UCM{;+NJ6rz%+EIvL7Xg;NotTIbK*aPAJqn|NFD${N zacD5r6wr5RS%Ot!dXDaEb7pj9A8|#^5{m2~zVz`BcC}bi8jmQmZf>jbYx?=wZb38Ik=|v4PNLZ`%z+Iw#}|Ed;I0~cK0K1 z*hfzvZ_5^pwUIFBV~7D$#OT$bUO#}MvMNu-;rt~qSKxZyIJIHtme z5l4_mJrm6qKG=GQSG(?vQFel0cyexuM~5NG2G5F7M+pH_n*iVhJ7oq+Bb(I^Ke5!# zTsjX$$)Ih=H1maDF1MoIM(~X{{|v0qU1Vlz2Y*F{n_-;OnHl%O-|9e=hU|t# zif3Dg)g5=)&MvYrrg*{sf`%*v%4Vh1zF{(_^(z)oI2M?urNkk865|8y%OZIG%l|kU zWmd>Of;Aupcy|&z2l}+W;z|;K;Ck3_+~TtrHe6=@`rVzmr-cn)+&qI!Nz9$@n>k|^a~(*Z~`m>h=YpW{pLg9gM)xC zfV>ZEA>9r+Yh!9ddWcGYh03&1sbhg(vu9FA41s`b*m2bECWB2($}mUZ!tC%a^2F~s zR%bg2$fFFZO&nWjAu@V2k!CQRw12_^QBVaTdAIk~IUhi!d{Amd{7c;@G%9irC{kt| z5E8-du^?n+&WJ%7G`~JUt(IHC-I~u=y>ZSGS1Nrt5R8ydQ!!+U@EtC2vH3)|@%QEe^&u>AS z7j5%rk$a!CgmY(1a_1duX|s8AkJ;6AJ@(YfDtm0>PJ%eIt)1tgRKP0qsA7qOAahxz zTrCC(U2ZkFF8JfkKl06g|FA-UMdS8ygf-GvaEQ1inwUPVr9Ns|MB|F3{VNxzPBJm& zV=<^07Qhwes6F`dI=gVe1pCtE^N4LK!737K7m$r-J1&>?9bK-VSrp8$c9wc>#~mh$ zqz{S-Ny2*Cg|;;Yw?QdKR0X`B``0KPt2PnaGBX1)L`#-e0Txo>6As(C%NC%$g#lu3 zM#1p7l)#MH)%jq&@;u4RATb7WP-s|~eJuC+AO-op@)0UcUv!R38UdSzhP{UDSJVRn zSIRwT!ldywlb2VgD8^N4R{f9IcrYpb$h|~E(wN7M9b;!MnuW^?v2nPZUH>E8sYqzi zCFTyrfTy_yhk;Xi7?c9^^YROw(3O{!XrI6NCM>p`$16_oMiA=-UU5i>%mRIfNFeMe z$_`}HiZVD-us)u`YxW269QFk%Ie^9*^p|%$YmUCQKRb z<~PW_#9Zq-NfD}N6pzJ8?m_A=4!7U2g($V!YAlbK3f&A=6&y@jVrqu$BD+#N(p?ao zEF3Ew#-ae%dV`WojEsXzYznb`ZnZkiy>jpqaa0x)` zM1@$V%%cxsK>J2k3IIlr8s|_G=geV!_jVoo0vL&Ydv4Qu3hLjn+MLUokp~j#0|NRQ z7V+wbY3kTTx(teCeCGL+ObEYu15c7E4Nt-M%X&4g5pjxD@(>MF{um zM_=9Ps*nd+kE%}JGZ<^b5Y~zzNrTL-lQ}h$4etAER@;3mUbd(H={gc347V8*%I*3^ z)9u!$S78M~iTSqqIRT32!Xm`#$y!DjR54vO714~sJ+G6r&_S}nN!h7A8i+>Xz&(q> zy7L4ZL_#KjfW{i|<{yC}7pUnLLvZpA_0})p8Knu6>p6Rq8LVb=|=mLSFnF}$FP7uuiOt5fiR1^XN z$Ss~+>Cspcq?PLcDfffypsEmjxojvQA^3>nb+{;qSyApT5hD>8AvZY+h~a2K^Ry4k zO%nl{he&IilR?HRStkPWkM^>Qs1mO}JHK{E($%}%L2yii*t^dvuZ|`b$94C;4=o-k zJO~gCTMnQ5aYN8mF$h$Ww89)ydP664iP)l9>`>4g!L4D4uwbNkk47?Sg(+c6*(@fc zz)pTa2vNwMs?qLkMsTaIwT3>jU6Hy_2~^}x6-R*P7k=}UoxARcopss-t0+h%7AKqc z44Y4t+3EB@eq^PUlVg6IQbX&LwM6tdmIc;58vH)T^Mm|$>MA}%AUIGu&- zp|%SD39LqQ&wlGg8PF!2!ck>o>cpbZNG%4rQ^^7h?~hhl_=lGi3G`QoGNqGgbTUyw z$Q=$6V|L|vXSui&g%dyg(r&x+$(6QN8WW1LUR1*V!iWESimgt>tt>7o)$vAy0kpJK z#_kztLEA0ss+e6e^dZ5lrRLE@V%=o*{NDMM_NBY_;!@V>s)qN|XA?|nG84+8Mo5@> zcQAIb{k_y#X#iIa!2AWVmbl9EvR=RlijQ*u=)uJbSJ)Qj+=jbQA8=2BsSl|lIgRN# zfhCbL=urb?6ht(L23M<4qkvw9z);iFYnwM6w58L_EsgQ~>Jy9X)4zJqW{etdt@sN` zh?8q-v>0UiRV;$ozyaKe5IqU7kL9^^x&Gp?mPeCRKp0lAZ6XD8n=Hee8^gTh$R!*U z;@LVToRqnPSW5b^{M0mekY*j_HrEQ}_i;b5ox)M|U0er#RdBQFC50qy2p{uOm28bj zytspwy@q{BVn|RpP!-;W(S0)!G{WUuKXaxJH+R*I(fmCj(Lo^^s=24# zX54&^6_Ghk0(1$5ZHsfJyR{&i#4X(O;mtK=q$@$eRe_+aww{cRk8Y{6z7vOt(c%hV zu7oTBlx|wns+dDH55^E{XHOny&po@!4(;1#BZrf9EiGu1sLM5Yg1wrpmGhQTPjl>t zu7$X6K>L!o5`f_DDZ#oA7wUeVKDIe0IBTTQD)G)9a3(&^)MM9k(}EO;C6GDT>bdY= zbJHI_`pt*H2Mz&m^?u;D`P;sM5SbVTmnnkJ(y4$>Kz!b&mG)0fSv`ViAu`bNWoKnu z5|#-OYMD~|K^D#Rzf{=`wIg>yr6V`U7E zW=L>Rb12Ng2MWZ5fR|2&7sbY~GlBf>+7@Rg`NpVU!xqTxhqgCGZh}B?x2D zC+3B*$r7S;yl#vdq~Cl9ybA(af7-|rRJB1|CLZ2}H{1@;o`-P}4j^MH@fgykqv>U@ zyEE960ho$T)^=`6njPA|**e+V@$p$O+bD-&dE}_t8xUUoDRIIX? zP43NoC`062H{wu4Ec zm8h{g#Irw>z&WbuoJD4;W*E6{(uJ$2SwF&1E_g2=hD{aH>&O)K%{%U~tfVv>k9IrE zTvu$~ZjY~8ZQEXnvHS1%j$_Q_{se#T#;M6Ww8k(1iEY?@*nafr8+OMxE+_L{p`E+r zG{%=`pZv*hY$jIR4qy~UXwYn8=%|f=^z8?0$beN!CGS4_*w=n#xw*ycSEUC=k%2Nq zR*ybl)bZ#tnxLADh+gcl7>|mN1yO>!u;o}%I@4Ya*DJeWpl3%zuFqpp(a7_e1 z?l{q8>(;KZGZ8=%V2;mOILVg2vDseOf5he&P>2w#HRyu*@Ss74vJ|Ombu>6!Z9S=V zd04iX)WGXcP{EqI98w-BKzPNvL-wx^FSki~nWTe->E?JcT6NEbpJ$8fPbOM>6}?rQ zK_3;R znzQt9N!#`<@P6<}CX6RvP<^ z%QX`=wLSocAzsFP8oH1F=0o7G1OZ`gzr7a(*vrzeNU)H_Kv*k+*z_Jm%i`i8K!|Gc zkqr)lVEYMV#5Ws?><~mR$UFv&84`m*KO)v*NF;W|z<{@h(TwPK`Vey-a)<@ZhqN0I z0BPQJb0wNo+QaYObcTKVw~yL_iIX5MF!2h81L3qaov?f==+2%p3HKwAK3CPZ1+0;D zk(0(1QF)l^=k3xk5g=jhyUAmUO6 z(d0?{sh~}#hhiQB_}327UyvL)()p1l24CS++jQ^%)rd)OPRqbe<A9?qf%b^LoQTcy-2zU^PhS3bN z?+0LbMo?=@bB(nU zhk>b-&OHT4h%7)o6#h&?dI?6UYPJOK0b4w^0*z|6J-Bn9O)0>oi1W2VRm88Uq1H~Y zzrXXDk2^+1$bZLabqcD1tJR;c#3cl ziv6J!!AjGC6}O255^0h>oG*YX`3aa~KLHwheQipheJ3Z6*^Fr8gg z^TzKeIw^y35q!=wA@Tth&)e4u^u?HrkVahxV&a6-2C=L-Xp^C+ofx(h3NdcpdC)fQ zsj<^W=37!~jQz`vm)OWhR@l$~@Qh_q$h9Oh7v`J_TCVT4Z(X{~ zMv(FBKYsfZik5WS-xY0pD4;SvCl+NgE#;@ZN z1oV`Y1VC=V(&a}30Jq|y11@#CAjU}&MjThqwfN2fEi`!urBVRMN~!fG_cBtz*=Ys& z_MMmaTF+x!9qn<8G(L^-K>vD}ugp`VrCv6(#D4sl3rT8_Y`bdO?5v+GN20IA4=>%u zA>@X7V{HSmF6AUqQ9(gbaaTWzF{uU&IW{fK-ovlVa`Fq9WNmaJ!*P|8oRzd z*~No2cXH?Ze|!jhkPvYD{DZu~|AoG_J!PgA3h;C(L&$({6gEBCB3cGdg8@+k!G^S} zL2%$|-aJjEP$XD@1N7^DCs!8lLQs0Sy$_~vKDr>%0g#6fq%<07xMh6u%5(6k4cYHr z+GIz!k`gkRt03M}Cl0gkUU{X>r_Kd^)8a_ zs*BG=un5>at2SH9>U~6~aS=Ye_&b4(A!rcs)5eW()y3-x9u>huW#f>jW}>M(YYhT| zi@^|lhVYgamitYrGUnhSA3Yq%FCq~@3nVSAl!#&grXvdNFH(dfE`phZg@D1S((JTR zDR|@dgEnE}L@O@Lvd>(3zGbGR+nuY|nQc4<(uOify~tQ~{kRFGHnJcOSF=H@Cj(Cx zTEQX-a7!-0($j0Vys*w%*X#z%<0DJTU5W`<4RIhY!->Yv$Yg;LnRD4jK>DKDUWOcI z0kMt^|xfSUWe!$whF7IZ~|)+!L3e)R;6X&vqSaWKXb*VQP=pH8__Y z6+SI1#dVapvz426a&0DaVqb>Z?S?Za*!5SR?*t475B6*bt#}+lj_{(i%-Z|HwTiEZ zO-i+1YJhx+%yxHv^%9#w7NVt#rrEDxY(MdX|FXGQ8D!;5Btb<3N{1D1ZnY)zq=bpJ zn{K?+vi`K(9^0_ps#hH(z5yJO#!H1unbI)oIm{U|!cGwE-HwltvH-RcEw8HVY6@5$ z!1AeT)&nrf4kyXtjABDt>mWhPs#CJFuGM~i=RKDHjn7&+wS*?%M)SFA&b3*SbFt!_ zu&1^k1KvCfTtLgyqHO-?LMzH1MIDGS)NUDTaU|OK?GO(zlct{I^u38#tf#;HO>%PCg*KF}9 z#t^jeV>4|yu1YU%r6T;sD!cTI={6C(d&f^dXZJn7!B%eL+2bnfd<}II)x_et%$YvQ z@{;3i8`Z>fStCiJE%L$QnX3uUYAr~3_h!NG8XHZ_w`hv!ql#O~6-|#LVr>*omW{z# z6QqrTHii*Uqxmd{CT@gqFCe(5N&k)-c`&1|UO4|s;uaIg_!i)KsXu2$SFb3t6hG7) z-)Gs(+uPeLC4f2x;VUJ!i!4|qS0RhnNHQv3LI$t8`WpM~%Khv`*1s$lN$f`{0txh= zK6bd>^Y1rVUa^;+zplQ8`Zh;wcs}lk(84GzSE6NV5|rd-tn7K3tKyzK*Z>oLlNc!w zyT{C$m5ZAMG6jqdVqx;2r)AH)H80MUB2@2M=X`U}(fu6l=7`^X2z-zb5TEF`_ke)6 z?IDOF?b3d*wT0-kIlZm#`I#yhT}>J#;aBDNm)TldU4Nba#(fvMfKcQ6t+4HW5J`*> zB!TE5ke<7gzT>2=33Z}{g4mlc3 z@pMJatinEODOiLp3&a{aYPP@FjzQ=xf|5`gpkcDCq z$TZ<%2Cl#7Su2IXpF_IPOG!~ZCNJ4OwRjwEqXe(hmx|hDrD1J^2~W$+vi+Tjw(Zvs zIN_rYro9EN?CaDQnm?_aG^?rhpEq4$yQ>bkB7&(DmrF%ETues2QNu`vf$$WfM$iD3 zRoOq4F;EC3p1m(<^|Q~Ebxs=dC|QCz|At#0v0HDxl6p(Ib{_FtfBf1Tg z${e|^t=V(T?tlDMyWz5hHn%*}O0QgGm&}5}`y{SHRIqEqs+&PTm>BFJ87h*|;Q!07 z9>XY#HX3}VYVKn8)D%E0zSsrf^WBSe176?(r-29WwZo)mU@hHpqSL-}*PraBtIo2? z#kn?`H0Gn1&bL`(kJ=UU>%r3~q?l7|JouGl8p)}tWC-&zcCFmkYQyp&LtnS~vx|cA;0o%|Su=`Nxoy{ z4lY%*RkgTx4Pp;w-sQPfivRwEzNE7gk2adT56zhEO`HXbA$i5W1K` z)>nYcZb}ScflgONT?#?f=!ub4LAw}>g_`0Qh4=fRXHmF42k1{t{q&IrI)tzjhf=Sz zv)1y6E4<{~`MAgp+D8{2aGnD_(Adtl7Gz-T`^o97g8~~ho@`(w4G_&<^~P?B10S*( z6cB79omv=cTSOSvbJG)5W=?@dGgRUg*WeYRaf<}&ur9G$L6@B?vuH1ZY6y5~2C_JE z0t1%Vg%Af{qEAY$AhFHsl{dfn5cn%Vz!yN?56B=Pw@sb!ApIiy)@@P{6`v${w320F z03T?zSgM@|QgSH}G+?C=Rk;NSr|CRT6!GjQZlez&2)E&T`5hl@X9yP#h?gc15+MQs zM)l0gLVf`|c)Z=7f9@H(>SO2I>9ePRkc4u;)x6YXz~0^vw%1m#wC~*hlFc1I%$nQU zLAtO$u_=~Ml;Uy2Wzn2U8&!tTGSkZfC1NFXsxT7`L-XC%L;&3YS-m6_>4law zj9J}-0OzH0cD=swA~-#2C{1pdAlVoQsw$^jINAL+NG2JzSgbfP6lZMhCX)<^FG>^v zq!?1AbiNP9Wde^hH;!mByvXJq#{93~_e6pOAA9i)MRnNxnG>x7x0QjiOcukN%Jt2P=G)WTUw z5NVzz|Dt&YVn!mC56NGG)mu$ai?nzC5;^L>|KEpz!xh3GPWI3uVKsVRyvehU`rvF! zvXgC7)e##}QDW1_l>fJYLFGW@X)G2;8*J6C27BbSb+8c6JRE)<|EQ;Uy#iRE1D;5&? zU1?)RRiLG>;3|~woQJ2rho|_CKG%+IgE)OEtqj$ZIC#y*8UQ zFnb(X*sv5AoxjAmATpO zJpDn1$Ma)+L#>|o4Y+WvShLN3`owmdh;Xa~GomehG0;$GwOTYvLB;Io`3;C3ktiUF zEMjUwWkLg1{kU_*A;@X2sxzY+W7fjFnVZ%-hERgxSv|6NG7dy6j(Vbp`T>}{xUqZb zyWe~Wd~gtW3nP4R_xPLbS#DQeZYZZC5ZXauq|GT!1Plb`*fg?&>^RSlX-+dgX|v(=tM=w!#|lkRiCRqowVbrfq%BL2+-{8ob% zCDqzMf^i_~4SP;lV%8ozOtq?ghfY`_sUd}o<##QH9w!0PSmI+0JYQP9-STpSq#HfX zJ+Xj*SbMRQq|#3-?>F7{q%E0KZI_=p+4At0jlvZoO0g=yD2$e=kMTE<;bznBdi;|K z*2M%ZpZgFlWZ!#it!+NuW3$H$vlIwb6myS*;poK|yb~>JbNisZ@ah(OWc?PKObvq` zgg`F_i07xrCxMjl$|54FLeFQ05lbxkxfcp}7K!9_Hy|QYj zEnmByqI!AocDQH2*y)}sFsi`pcq}j%eeHg`@rtE3cS-?5KYIkBMlLw2Y1G-pJ-K%S zn)>A%jiCW?VzHzr*ws;1`8b^`5LkuCVJHnx?i*Denp!hbP?W(O*BY*f+i_ZvK zMS2eDT1g-PZb?hcux-SFocHxV*fk$pVrNb+CRUlaB9uBYig%-*ekzlPiNC9D?zMG0 z>#Z;sH&v`7u~^Pp>0|9~o(-wU8*n#kByJ<5l&l;VXFCYf-otzo^K&U;*J96ZtzukZ z+b%%{%S$_^H(B&2WoOyLduy%lHxJt4qbXJ zxMqv(FHW$n2bv&U35-L+fT%5QzPu9A=r^@D+qol)?DS78BEbP`6Dye%L$dC8shyc4 z4LQ+zpbH16SM#UkTk*O>;RUYmhHiI7!OUmH*tX+cmW9!*VN*Lcyl$^S}Pn>sD3W zh{c^M_6Ud&8gDaf4?2;-<+(-($YPu3j1at2%qP7Rs6V_Qs|?(DQC< zL)p3S;89D?Ny2TCy^rYS)U2!t(JkRBzxfdOYe66|V*HH%VZ})z#-mi5n@{pR)VpFA zT4RS<@wC%9CL*iNI@HkiIdi7_s_XwYo7|`z6DfSg932t_4%(>t)(awo^CwW7VCR)J z#A2W|8<}Dgshrx|*=mCj9clG+zM9fl20;2j=YmBx7005WJ49P?5Tf1t?0%B#bK>w} zHk{x|p}K8HPuTa*rNZqOu0sQ9wqKag2E65(Q3t_O6sB7Yt@ooe=cv?V+f7E2FafMoN+dUZoRttf+XHcv1xk!bMBvbOI40IT z>wqD8X*KnP)jVM}@`+#FQUA|}3j)d*M`u-gvRqs?uD zkXsvSeP@1df&HL`ywZkjS8o4AvVlY)6P2{CNIix=Cv z9sE>KWN|sUR)ovR{)4sLzt##Tr&u0B!^Sl*eDX0HOQBHw=f!3!<4`RwQjMFqcXE_v z4^Ofz0^3zBT$Ch;Yia^DB~(3r)9b)238s2;w^e+i!1?&c%dG}0iLBDGSXFw_`tL?F zPenE(I@*S_*E5*&x<)kJ;79Vnf~y9p#GQgrh4q8`NLZ)?2i2}&p2REI$W-DSaMuFf zvW`T7ucVBUI$kwWBrvpLu@0b-4&rv2fQCI5Mt2X2kEY|?oBLT|9);)9a5V~B6;^Dk zV}2)EEM`WwP0!15aVLWaa4|8xFzIbD?kTJm+;p&vuNPk5OFzVWSP?Ee#IZGVzq)#k zA3p+@-E7GeUM&M3cjNmfK}|J9_O^h(*MbL!MceQ(nee_?uYoU1)2%o}Hzi zc)BD6t#yYFfxlUQMG&;S43ej0TQ$$MkCeyO$l7c^VdVtar=@4RgiJ~q+`+o5J50X^ zcsAp6Z34wN+sRrOkC`tD3xr-N!LY44aKOHE<;C{tYtOd)zW}YQZ|$+~-10b?6L(`# z6O71)h5(}CfJYjtEhHLp6yaccnoX|Apgt98a)G1Vqvg6L!6%0Orv2NCg-`Q^av_X& zTh%_syMeVef0&gQ5x7q`qWAqM=VB4uyGg}=U?1y#02&J{QVB*c$w;w!nE%>FJwMrk zx~&9v=v0LK0j?9BVJo6AV|}uhb{_<08@b1vWS$M{lyxFYh?D_)_8rEg$Zs?Au<~H> zf(FYvGsqky@JP^2VNB}}GRIA<=e%gkACqlGR3z*`5z>W)MSCtm1%sI(;;UGlchR)J z0LcC+|7Ree=Px{=lMLp z&KL4hKQ2A2Y{}Z_^x8#zjzl!@>Eu)oqaEr+`=OxF7*a!St!}dKA%Oh-=dN*X7~4UX zXWsCiHg{YhNRjJVAno|L_Ta0Ul$;48fax5hrGiMZvJ0C8AS80<0&NkB5wZ@YPsCgt z4O-8V=McP0Jo ziXjUN{VElun3*oF>%)2@m?75?dxsko_fvlU9{LS{oK&!Eh@PwZaobK> zBkfGryfvba`s6)f_k;iELj(Z@iw8VP?)Lu4?}7o#BC=d$m5bpOfKf;wt)~S25Xlxo ztarsq1#p`T^9qq2C>)KZ8A~Iq4KH>o>owR_ZC5OrXxD!H3RjfyhxaeHpFX$6aueeC zE?hvyC0re4eGOpYNFb|J3z@41#5l7b`oR|=_HmF*RPivGVKFw&YJ*D>2u7(`gPhj~ zbJ&aaRqj$zxa_DJcaXi_N^0O3`Vi9-598Sd!xmr<#W0T~2-P6>=|b}wCPQ8d1=1)y zL@HM1iv>j~aC^y;*F1o#g?k5JFyqiY$5U4#0gZVW1y2i>AJsW>Sp(V2$}*VDb;^>L zN=%w?hupqeG&c65bk{M&m&wIOZZt}Bo~-PBG%16-yF5lK2_=lqk5V=#`t1cj2p1>? z`2Ye;JOWb+%(<(zB;TZ7V#L6sy^LR$5NV3_3LP4~Ajj|`ibBjZ<6A*qRV_-7H1|e}+@G5-VL*f#Fv>SM?yif5GpTtp|j5CB@S=4gL->CR^;_OcR%!sHP@n?V{K~u zy~LVm4`zfrc}CCy#wPc-PGB449%8)2kc)P!_+w{ODoh!1C#*krOuw;@MYChrhpmBB z(%G};ds|7?A_k51$GhAJrR>824*m@~1>F1Sn@Kww8Y}uNiyUjIhdoa|7vRW0)``Or z(3u4K5HFyh^f3Jk&b_QBr9n=ms=5NxJEvw?X=b^0#hSJXQ+lL7Pdj5Yc0YqH2-~L+&$oo?$OqL(9 zk|2$DG%*5D#h0rB#CBc)x>$b)K&GG@@QVZ?UE#Vz_gG6dNEQpe>N8 z(&%v=F9ivT<&Z4lt`vigi;x0GyFk!R%774oGp(8LgCH(xNd z#Db8NliU>?1L<~kqh*3&iAH_n0{I{SDwe2Xf67^|rU1A&G;4xKH)HLPX&j;@OIMte zh|#w2S*aPjaN}?(5S^A5WXzbAB2Yv~!WJZhBpmp40~Jkb5X7qVfi7?mSoLsknZU#C z5LZr!2L@uy5K$bFR26e&%3jIpv4fwE!fB+v}7 z4<+o2c~+Og4`RAieYuUky5X#2*n3g9Y=|lCr$$CoH+V{YfER=_6yU0>W3|TFJIe4D zjf;(fYUKvf&;E*Y=feo%N)zIK9b)+8W6u6$h;F~Al6y$Z4>G&v)zyU+0>J@J5P$w8 zZr6)D4ax)%llHD$#+tCe^rIvYe=j5zD=UncUvN$n*E2M95eO~dGS%Erq0(?aZY9h& z01Q;qLlxHh!9P*J!%GSwtnJ|+#g_>#N-`lAG%;q;)M*kP?sfYXyi0~B!NXPHX1qdo zL5Cm1)+i=jFoID|bWA0^ah+2-fUlGS)n&;O4EQeG>EaBqq(*@oC0I1OXNnR^j5Gp= z@QE^pg*jIi7Z*^?yqt9wxQLmSJ6r%ImdAoZQ+Uq8!vTEq1X~4NtM4vesz@%Jt9V1z zU3cked4@a%mykouu5gvCwZgGd^n^5bU?HWH){&H5Qq*vmW3n_bK3=LN63cnQt*r>f z-3XX5z(~&ovDQ5ktvS`U64T8m=7Tn#d-OqY^eF~9qf`? z^e%eWMPEJ8qX6qmbkVJ9#xAR&tlx60%1=$VT?dX@{R7WKTSz`FVV&E%_&m)?=Ti$O z3TswxTsHHgT75fK1mN7m8sGAE>i_^i07*naRE-4=u}Y7v_076c_OreLXbWTTXpmf_ z847lb(TaKm7wt_8RMt0fkw!U8KSe0|Qx2MDL^7T#6NHLt&t?bt6>9X#KIb zVn}%{(SW7l?LYPbH74D4T1O1S35a^OF8iZsEo(;oCh*dllolFLKvQ{6977W2rHBrG zEl0Tv~-kI48(G#0RKB{kX!zQtCyk+YLZJ`pt*H2MhsLyWidm05Ot(QGI9v{YV(HBW`xjsDb=51D5TjDBOHKO3pschvApf=2`nHKY0&kL^Mt#@ zx*ntfkzyZVu22reh4eStJ-Y95gaiQAZQT)7?6G#{U{K4 zlq3zbedew=dKVQ z{IR)bAKD}_4PnOVRZbRS6X{T&yz7ktsG_Zy2@!6lj5Za4VTeE?HZVSZ7ZG=ZwdLVR=9rrvWNa&tQjmT5L&m9p?!~q6JE?8U! zQNWc8!l5Runfg%^1E%{pW``4<@Tf<^m^CbSu?QSr!h(-Gs2|>H8in6J+z@cs3F=2z?6eJ9esqT*UHq2l+ z4Q3SPkDkN?rQ%K@1{E%t{>2Q%SUXHz0@~+6>W7G@*KvmA7?Lv`YMUv2y~Pz{YrVj_|4x{}DvFBm5e}eI$5^8H-hhBJEYT zk71}JsPNqhfWTM6-5~fYilF@fpL?Wr=Um}7b>Pyb0}scLJD`B)^qps+cWI;hfkzJv zrBImgr{ZO#*wFYiG%0#C2Vs;!=B2n0-Z;+v1vh@z3J{IZ+@ruvgAkWE@S1RmgCWmW zf{9}uH3vOH{ixa)S{K4unvd?QA2~zwkYzx?iUL3PlkrSqmxL{^Nf_f-zB5epS+cI^ zJAd49z0nWzP}6bsrspZ8kAm~1LC3R=>`O50!jHg1r+cnw;9t%WMt81-x-I>3sd~f3 z)*Gv6kuo7_;IXV3ZUAkRMT2=UK-HkqMb1SL;af0|D0kemq_4=>twxScwk!+DB3YPwr$(CZKGq`PRDk~wr$(CZJRfJ=FHr8zxR7D6;{40DZ_&`?#{`9(FG^fO#fW>rw6$);)kxPh<}wKEsEh+Jc9C zuWeH%6VodWN_G?Q$`HqHp{H%uOva2I;o_H{Xj)^Nxz?Nh4ha;v-JZCy&6)OfU+k!A(a@H2f7Jp}1aOsFH@BnYH z0>Ni^@MfLFL1DO#!$^M9X=Z#f7&k)r_$jXqHK%^TB!lG*bT}-0PUKnyez;h>x}!R# zVu6L)>5!e!W;eHC?GN{+JG~-WL9ph?m^=zPQMi(`5okHO8|#ZGyDT#Bs5&8A?TA1; zxK^erjEeA~A17_~0hb|Bf?|#ik*Zrk;GuH_cDfsiLk~D+o9`#OpL34qkUEuQS#{725@lw z+2Fk3Yo_`^daFQoM7n&Xz6E?^GVK84VUM{1LfzgG?uJk`_e6F z@9PE|va~7ypau4h+8)DHTKk|{LDzFX;C`Lk+uT3a1_Cm@o7O2O_h{#MOk;f&z^a+7 zPtHYS@OsS9A8xZRpv`uo&;TM?pI4%~(A?Q`OTaTY@9!nE^!_; zpDw_l190lW>r-`9E=*0ow4bn>n!fHut_2V_1*qR2Qe%;y7r#NEHha6uAc(DZ=mTzW z!3$u0PPdpF9I_A5*J|zC)}N`-72vXZ_wes#EID$!BMzCGOGSxXw=KCcybhzyR{^W_ z2u-D@wJ4^`W!nfQrz?FnkJ#bBDlZA8A~pwgvfT$K~)eSQCE0 zP9#|qJ^{IT``)H+glsand(oAk|nYt8b6s3RWIM^3s0_mB+{G$od zx_QRe;o1c?BWr`*+J}W|wa@V>nXLqCP2DDoV9oy6XtKNErw)V`DRg~(9J^TgRJP>s z>(ZU0J}2@Bne^Ux?_&X)dq?8Z_EO2khBbe0Q?<$;P|4 z#LH=V^?qX8{FL19++?>AHN`>~u*K=c6p-VHog?r%4jWe9tQls_c;39gZocb~-4n6N z`50y+c#4YHow|BnM2~flfw|ou{(3Kr{ruXk`EW!1gvSN^`Uwto!PDfsrBP?_WaKrs zx{!v3(8RLQyRW+WW``TmQ|fl!524xM4JP4_#_74w=KV=$Y|tDek|XI@f!MBXVgo&u z!C1fC!F?}dX={IFEB-55cyih!5Wszid-L>DJBxrY3~TXeSbK{DrA2msSo5mdT98*{ z^I@&c!|TlRYHscAZt#sqwf$qi$!Q;^?dYa4z>{kQ5s2gEWxvS9PFHf!tV@`28A&jt3z%0%RnC};)q>@EGh@oe+Ot{9aj^4{eZ z|Fl1cM)rGF_}7|EtI(Ocb^lk{;pM|6XUE%Hn@7a^=cLKgqI&Gs7RPOrtc_-|prY5& zH@;Zrmwa3dfaNaVzjiXOjvY)hI?k5YG6%Chc5$!qub2G4rQUl3-bYtwG*cYFn7Bke ztMk%ohi(gI18hoY_q5r5l1*Q-CJi7CDC*#Ciet2hJI3Ubz@M+PoM+T$xW7yM{(-r& z)|DA_OC7}Tk%0;cPA>jtx1b?eGp^fJ3!Ota8deAHS%?zN)GtxE{hgl41MCU@ccv}H z-x|L%14Rr>Bt~0toXUXw7IhR5KZX{m!=1wYv1U9us^p8%h1X7A*x4mRsBrB~V)%a@ zUz2l5`k4M*q#Y9wfrqOpDo1y-A-2YWV~Kz`FNE;mES-U&JI6{{`Zo>3HE<6mkG&78 z(#O^Rwk_rBE|M=AjdxvQm#Z7 zICLu59qbDWfD4FA@V8n#`A4-r!}PDPNLzB8fkeHVkUY8+N!1ZmT5tvgDAKf$p<*E_ z0tC@-MbsVKy+s17rIw7@`jhftF6KvX8x@WM1DQiyl*Er6!mN(1b$*wMuc7~}{uiip z4Y&}w21N^{Pt$Z{LD-?+@rag1sYtc1WL}0LR0K4L37mfA=ycdRG|=o;uHzx3&dQfgK`gCJRm`Xt_EX%FB=XotE=Y)@UU^iaqm4)^pxpm}zWon4eu_wd zogn*2UUV2qw{w&o223qi13Jy^hme4NLottvL-)eH!Au1RJW3FjVzlm%Q{%X)e{paH z1^|I)X(!vPSLBfdeGA{R?YP3-E`(Sa6%rVYZxk3-M2_7=7w{dx{>vAC_v$Wz{H{>S zuABw67l*e~I;&7E;Y5?bxn59*yGtWLGsWe-{i|Qzj)-^@Yc}{5YMA_8>m%noKqHB_ zjRd*6G&!0>nE_HyFW9in^&5EWyEMSR)Zqb^Vg5^>l1HIU z794tvS=Unc>Xe_%Lk>caP(A6xTbkz~DTvYfJ5Wz;llN(Vf$>R$oAx%Qlzi69%Cc-$ z6K*kg!P=?zw&Uc+>k(3s-+b|cOV8PM{D05}52%pxa*+_|Ycg@Y3O{rzgps5dkO;h^V)5L*O&X_*!BSD?FZv~F|b zZIk0cjRh@j7RJbBx9Bi^U_kc6J@Cgtn%rE=w*p1{U$&Al1AnGbE4tphQHuz%-JwU( z*@({J7k#gNK7EEK^>x)yXfY5oz4;GDJm98Pq5uKJ&TTQkIyqYmkGX3f4$KRNqxrq( znF9bA^w^WBVLje?A2)#}C-d5$d}KB@RW&NylZhp3sajB5R1xMv$ywnve6?n2An*@v zgMGy89Tb}(Vr<3nfdNwx<|1nB0G>$JYKbLPuB=p7J3U@MK8+{KxOF4}$4Ny@xCt-Z z*5@#yf1w38!LhZ*698P#?ikIHRFcY!XfLlEIf zq6F*&;9_xgxCKr6dtihdLr5h7=^3KT*?xkje}aenndXXWjz*m@G{MY$$*_IIF^@HN z1E6&s7SJ(e%? z95^@|FhS~7zpWCSH))idvP)SKKxk{uEdO|TOc80>pLZ3^g98ek(U(GYAf*OzK_zNJ z(69I;(p(lC#2x~KK$9AzE{{CD%?hD$P*C+{U#q--omc4f`Vd-&-rm;)Q%uF}aZ3M0P3 z9-4jGhP^5kurgjLEEB{vrkfVrtX9mF=+mo@X@6A?z*V(shJ-HO%f-+qgfz$bjp8i3gM|> z;qYGKLBitdTy%wn;rjEo|juj#ss$XSfU&#JXH_Cna zLfT(g6PjcwF+uNK_a~Aib3W3k-htt4t2E+10;^T+Ea+;!z2-K0-FAexVx07@HuPL@b!@SJGF`R* zG~fQ2%)5@i4V_gklwXafFO&Bi2%XHUN1PLyLT+ME+RRFE-fftbZfB+c=(ndFe$^NE%z++B(I)S0+sts zd??gSMMpK0GV7RwL*>w`)FW|9#<9`^Ql8TZXCuv3cL|cz1Lpu2+w1)18F6g-A#^wM z__O3TEb~O|kM6y+o88XFL`C0ryi3#aXUaM3x9mn!<+SZ~x0izBQo;!M- z^~_MST+iJ5)~MU8XG?>0aLNJ2klUzTX|7kbPgV*-iM%%X_s|;|q#_1uM;$jM9QhB5 zIn_h2+&i-9WAy{41GoEkp`q^q&f0FeN05kTSOcL^Jd4jZ2{f&YH5H_ir~_3}xQW=@ zW#g2iq#Po4GL8|q5woIZxrRmrd$c%V^ zoKeN2Z!NP|{oBZOB%-3ymYU5l;QwR!zYLSY1s*~gy7wUAEj8dfdPx{0q2iafr%Dp~ zn&@6WiXIcv5>vN|8gv|*l7LF1+fJv`4Eg^q01p113lDdpK_M{H8)!;f3|I)dd1z=a z&Ku~E$cQ&1_viRVr}H+CE|xj;GWfsp;D1NhzUS|5S@|7;{7`z}G?dUCLMDX*Q3)u8c_>Ehh8=_o_Wqw%6%j zq4U2<+m1qb20Y%6t?cR}Q<>+e2?nzacwKm0f;Ioh_y4T{$0xZhPtHzgk-=JYH?Ztq|51ODH`bx#HHIWgdouJY`eSUgdZI6FCCQxvGcIB8V|B=is==_!}j)G!R062?N9mKbNfeW*48io$YUqY8{PM= z4^|~O7=6-u?%vKixNwFI4cvIi-_9__gxD6RDbUP?gtZ1f5~0dS&y>3m$7?Yiv$NKic4ep^03y4X5ws_)9`>n0d z;bQ?kyYa>Ll2FCFU6SiuM{jEayABPpX^~xZ@Cw6wsz`|-S9{}_Ue|}vabKy1a;ykZ z@@h@#p=rQwDZ_qj>((YT0b|Z03F9FS@=hg^4^1J{Qeci6yaNaY5t^C?)2=PmN%bb| z39HI;43yyYYg29Dld5(V%kX3>yr?8sm6TUaxiVt`!Z+-c*jdBZc*>?-9^d}vXH6&? zvU&ew5nGmXnm3!MQt^Xc)#VZ9K&!cstT$e})XBf|-ju?**Zv*(MD{mY%^VjhfJz9l zw#=w2mksWiYF9+e8LqDE!Bs4hb7wlj%QH#>J)-x1R{kmogFFjS&j}QJNtKmps{egHU*c zy4=?0xY3jQ2;R@L%F&tMydp-eLtzTBvqR4H<2TDQ4hm(`rQu_fM}_yDmvkoegt?+f z1BrYX3lqruK2ceeZMPtz2S?V=@9a;+31fQ_`yB?R#0wh*T)KuE*jKPL>s|wob_<4| zmEPJoSlUrqrozj-PqKuAGX<(RG|*j2%TK?P1IfV#9>!&bxsv^hgraVh)q6|Srke?> zfJ^Fypj}eMuIuG&+p?qxm7tfV`9?iP#6uc zMF2L%kJJYtj|ZVCrl_avH=~(B<3y6Oa;-<$@5vKN4G`%`^xGckbD3|KDT=FMPZ|o- zGZ<*;8KW7}r(hrO+NG2n9%zkiQ^t*^PouULb$fj+FZhPvsvUJ^Wtvm&xeM^8_6_|( zNtXW~T~xn~GXQpBS=4%pNpl@3V88GqA8bwn0)nKyy^840N#ZUzdA{`9U={%V9SD1` zP%r*fsX?CvQj~LKrfim|B2;|1it)F73f&X8Tzl-C3eR_n++CvKbxB|(RTs~Uv3Uu{ zfe%#BfmmW4vwyF`kgC%ewWmxo78-PCBKK zI)V(U~di;(To3egHdh<}rjA1s+(&?sRGT zseU}VO$oO_f1_jPiA#;H5I-bBkyfNVAwlvX&Rita_^O&*epCl3(YSkvPlbpwDS>g} z(f&w|V)6Y_^t{-xf{D0(aiU13_HhebnEf0!v1^%m{#KZaY_+(}pUQJKCOrY=W z?z4owGP(VFjuuP!LWmw^h4)*d8RW6ukusG<>s>? z9h^ZxENBh8E|4`0gTNS!3dKFAo>WTQ@SEKq-AyARt9grPV%NgUg%yhKlS0H#2`3`L z7^G{NKWSOrbp%piienLW%Rh116>yX^8X({UC(`yT=~8HRf@sh`b~v;bQgmvuKq#py z_ix;F6rjAMX1nK}mUOXEWaO5?Dz6Da1LH@?(-pqe)p)ND1=1`Il zcZAV%;1YZ(8jEz`dVR7{z`4+@Dy04V$C<0N4ReAa6G1wpIfC7#q}Vs=Qj7P$Mqzip z@L$XGSi=iPm@F*O7TD-dj1q#Z+H-Vy=fP{XM;cg&%wmmjxBFqBvh*akKBYguTPV^_ z`#bmJEYtyoK}s}_&~I>+lSmI1k*QJq*TdxKP8=;Ve)eOjejz2%g^e$Az$5qL)%~i6 zF=?0W8jG5*f+RSC%ErrK_P{ueJgmI!YCj8d0i=NeG`2Ui19EY{S`>Y4nkU!KgWC{i zE?UuhGSwwO(oi`K`0Gx#L?Mo3FcTpMGw~w(u9(eB!?+h($OFTNhN+){LYHpbOtU=Jc77HHc(@T?aFCQ6sVv~ zBEWeuzDvj~)?cS@T<0=MFeiwSIT!imf&WG>ZoXbjQW@SGo#wM1IbZU=zMw5U3w1}! zO#hI|DSy4EMw}q%rWYUB4f6HD^^i>32u4{19sKXFNwGWdw>Ar-NstiI0;aOVI-wNs z|G5!*dD=&H*z4o}puF%0T;r=G%0LxmPh8*Vl!35e>WYnU_vf#L_yxP6g5#iD6*(>M zjRM-KjPPrhDK9CnZX>L!?JLA4sfh3&w+{=7$ul3AqglG;PqRD_{}!1tUxlWI;cX4Y*qKO6 z1q2r9uncw!7l7YTOhut))qvJ<4^|$|CdvVG^kGl1b5b4qD^QMEViCd?|GWM2o%9 zpsQtjH`buUJk1MIGy54@^`}jJQc(6?_ul$O_;prGYKtz5?EPOWx;tO!pBty*CW$a1 z_v>T^e#VphV+e5;kV1g+@Kq|jI&r5sM9c*El&3qFI4`|=nIFUNFW<&#V;7m*1H-6kc<$%hT+87Fdz;896}olMHr zp8`ngFQPq5{HmjpLJ67!q(10f5)&hdq6b=^2fxBl6L<3Y%q`d(!jFjX*Yjj37E~1; zD6?8697;sm*g9n{oBYw_9k1-h_YQ~&x35+!y<_%6mGwUp65F9lKnTW(65(edWiG-v zUh=N@J8!p(c~xB&TC_A}BVIC{l~o2DcWLhTrnv9+)+$$tW)7a7=2;J1X(-UACy`23 z#8v)8-{Ul92of4QQ8#8+^kL$LPZPlo{LFcUv#phCKR6+KBZw?OaFD+fHFv_mP7*@! z3(Sof)3m}0LUbx20&2oNGQoVpW#(Kov6?GfzE4s?LzxFm#6^h1GE}AwS8(&=Z+WR1 zWgDUqzw3@vS@G&F|1Ran)$CO?;hQs(y~M`K=U;;ZGQm%ZjSq(Vo-XHQ z6isra;+^RVDs)E~2Ngywug&z-PD(>B)bA{)#!LZLi9GcCHk5{0c-`uWfRY#Xzt=G( z0UQ`~pVYC8XILhY;*~6kH_qEhCri^Swqw^XKBZfKe&FX~O4N!iiD5K0j{ysvISbn$ zZh|nUIsApw;!I20!OB;t_e+K)Mwr0l^t;+9BQ=g(~Qf~Ec4O^!w!EM*PUSH`jSNFs+2|IsA{l9 z#bKGwsK5ayiGW+enC$`F6g`2#{wP~(YEn1?|KTWcoP26bYX^uw}B%x@7 zOinr?*pRL5{Y}HG^oRiw_Kmtov?sB2Y#?PkdV^|K*L>@D56%xNY2L?i&@~^+evH#o zJgK2#3w9e-ndcG|;P>4?F?;ox7x<#qwwm%h4}zsJy5ZmSO67y)Icx?`mu!|cZI2Qj zd+Fa#@JmJ>u`uhQH5*qdfkdgY^yq;C9%>@8P$9_P(15l+Lj6b_NI~#@63GIdG}zhD z&}*aHZ`>^;j4ww(@7#7KB1Y{tR{=8aiHxvZ-DI7{O~kr9&o#pPBe( zTELWP;oj3IewM}$a+WBmMy0lGss~I-cS%%y@xWa@yE)Qg0sY6HtH*#3hZduFUr30P z2W#^ZP%P;s{6L;`Qmew8aW=1ovH+okEw?inalh8_WL-@;$=UaLo0`Z{(KeQ+8TgZeXFSvp(9qBZ82=JiBSvj)&r!&_LrFGM?_mFxIh^N5W*Qd4;VS$ z5XYmEV9#*3cB$A#A@x`yF|2@7s$Rk?CCOq`t8oRJSV0B&5^{Y0Y|B_%1!ehl;D?(F zzv9^WP|yBic3C9?%ljc-(dII27}!M{{6&QX(&R!nl?;$jTd85ZL(LZhoocZEqtsKlP42A^(mhwt#30%1HBAK4rx^Sv)!yD!Z90jn=Y*ps!IYk6yBQ4Dq${*NKqQAV!03;0t~~_WWxo-Uvkgh(H($$557KDbG2wke&Us#hRXhhMP(DUfMmK!Y%jKH)R<>pC-= zhIkX+J=!#N)RkvIk|26t_&hdu?0R#m^mu8Cks%ifL^p^Nn)hD^6I}@$_;-A%Rgow_ zg`uES@r4}8tt?Rle&zK#>9$-g&sZ6j{^oje!+E5A++nM2OJPM`g_U07H(Mm}2qHlv9w2_Kvy?vzwgVsl zJZLFnf*<%b7qB};s5|J5a7eiMbS4l1)@|6BxD=9qrrTwI2B}!ucUtcS8Vo!j+zA{y z0SDF{fA~NGQn&$*(6L|w8Ib%k90ftUFwH)mmclG)k-Y((LgnS=vBsunVC*A49{!0V z6(aV$xB~9bxveTlIG%W2FQsQ4oueJguEQxN+-t9pP&`^N@VFdKA?UC&G8z^dCS6Rb z+U9~{2QdoYhhnd3lj%y0eh51eWIeI+njQof+`%*{Ie#@W-92)rf_Ug^fjt(GvP#jM zd5vLnGp%@{N%cG_MR>EnFz;o0qb*II=Zup=pZr_?6s?GYT(M+7+{$!{v@pV=NWx?x z5<(3IC)2bIqh=Z&19#s(12nI4kgrIbV!u7%jQEceSK68R@f}w$%>O>j0xQSlF~0KfTr(bRH(N8!W>Z@puVFT}B3Zm*juKj$d&= z?J)GD>;}4EX{~a<=pIIE`p1uK~x$&zC7Lz^@!8-=KaH-tzD^Wi?rb`8OI|$htp6a%*#`WHkT%a8ln1x+)%XKiECl;5NY#zm2_F|-mWGb zRxW@FtQZ~1dCG`6Mfid&FD?=y6BIf#q-EgE6j2V2?gYQpKnqC$w>^g>!X8Pg2Q76E zgY(zlQ4;cjF)oTiepG`L(22D7$l%)-^o=$)vp^6u1rKy@JYD=@$AXgka}+;x#&Qw< zgNwK&{%r>+dW~E5 z!pYFY)$~URnPE&z9tdnpb`*V622pkYvVV^=AcXhrIQCdHf%=TvEumtb=&UUL+X|P_ zF21BQ5&a{`2)zxFvg0_=W(`qA&Z*3g%WyxL1+|&FlYd|-m5Giw9;OHRFKm{bi|EbGcJiJ$i zz<9iE-W|^vY#=x{=b2!5gm~I~t=U31l7%wE4$<>u8uqo#ugj+8`Xtbls5mRksFgWc zUJFr=xAWy0c}#Si>cLlzwAmHQ2WAk9KMZ3km8mvI>2>|7)?21tqD!30*d<)~1HgPl zY)-hM;I0IH@TZ>B!ct-jfMI=J#fIfEVeoMH2*GMIka;1x6%6JJGxFEv2B&>lzVahG zR;18=S%Rh8UGM#V&9OOU!$CsO{j45fd_0_Hfm{zEHE@!|2aF|p`}&;>v^zq>xX>uP3+3p$7ZUigD#r2p?e2B`ANE zZ<{-*mX(x-EvMzHc;I(qAqsh$SAk=RlOdI$&v_;^;5Bxq#mM(8bqa_><;;k4t`r(%(1)-`T?nwH}$o4pF+JMEzGgzQDmbA@+*HUt5H@pYz1LI&UPc+Ix<%q43FyPMn!ih73RAKP^zQ^a)7_5GMPi?8mV(5!Q-a|(0ASw62z%@ zBy2W;htNl?%)#B7rGQ_IU!wnzP5C8fCXnsN1lFfSk7^**uePvVCLT!3u{KFfCe#?R z%@jC7R+joeC*ULoX%B}S7ubKZ*k@n5&`Tv(ODI&o)eXlMAzKNYr8ETu8338f%&s$Q0WF{NN)Joc`bzz>J(LjeY zthhXEGmh|J)+9mI=M(BaFKCBWJE+01wq?P{iD{*8(IIWYyjI^ZP~NqLq2`9;S8M>C z%(6odP9k%!1u!CkP1#br7Ne1@q&~l7kVzDdG1mJ-K&^#$Hni9w=*v1L#BvYk#kCD} zHpf5_Ofj}lpWyMfS*@T=Z0f!&{(W4wkLv;FKx;fcUz~omv|XT>2Uw_a>{GCVl-%#w zTKiZD6{9893-z1y}Liy<_X4pNFwNgz=z zF)J7|tx<5HurJgj{_pZ-kjOQS{31(hF)4Abde7c|z096thD*qC>}KG6>(MDWAj;;n>E)bvXRA{c0O;+qbWk#r3uNWN@Z>vBt;3TOZGiH=14^@*;u8L-yJ4UJ}mK)?sl zbnFChK+RL1V17KstZZbzm~cjd+@+&H%6e&9JIC#GD9T{zx)oER4GFkJ->>P8LJ8_YMuv9Ez4q#9Ir+BN4-m>#ORCe-!C^iWY zOfQOagSrQzxfUH1A>0FdKEbM@K)(mhAc!*{Aj=*Re4I-C;v#<%9PF;X$5jkAj$bpj zpW4vk_Bpu~8aM0iCn7TRe3OtPDm}`=Ch)*HojE3ht+2tI8W;?E$bBxiiz#@hObd@R zbYpEDG-t8~CkJRAP|q&Wk78$X>(JMELkj}cJj3GBi{p!$PIxhbb6l+Ki^#^-f|*23 zv8BG4eKJH6aAf!rcj5u|5?E6c(&u@7i@ER4v1cC9J<~aBB!y9}PX0qw5iShmY0IFo;RIep1;xQ+W5&U9!6VC^@TV)1 z7-%SL7@9)r7m?E05IKd9GvM%Y64b_nRaYqGp~S}YV!<^h%dS7pvH(86WmN)78mRH4 z9Upb;$0?J)Ryv8ke+({veyAN(U0Hj>l%#z2j^V7Ws5EMBr&z<-#`89A{1gJW1nV5)+fU z3E^HQlOYJTfhkv9R{W-fN^y6J{i)``Qz}t<^XElrRS&4qa3e#}8=D61UPot7#LN7k zT2?R+v^2k!bIR|RBqlj$V|UEK;k@53jC4$v(b(+y6^r!thUt43RoF8__E@$^`Vy~h zMWO7mZ@N|z6lo|E$z&n=OT-pXf!*Fh&4K@kmZy~ebypy9mvLj{?sNEdZvU|$NJ`3aE5S+Q2h zY1288!3w5afw2}`Htm7CrRT!i)I+1&=-UXTpDb?!beuM{EZrWfyx^YyBiee?5>@u9 z`l%xIyL)ltN&Dm#e?HN*_DW*UmP`tY0I z#@mI}5q0BM^R9q}S#jTS1B~pD`r0C+!4r4e5YBq@7>cZoKdE?MKJ!Z0lJ2huF*zh) zJ59lg45t~1v^v|Cg-3qJhjRyx8<3DXrUPcgqn?bli`iHCHuC|5vr8S{gwmhiFJ<3) z&Pu4;E|Q!uE!8!{8yaLA4C#Ut665YA6mp?}O<2F%mB3gx5zaqN997kCX>wr->d~R& z)I@T^F1Kb3S%Rr)*j(9x3jIo+|3Gj4wO zAot)gXhG6a!y{hWs-%hVLvS%#Fx;svdew*Px_u(U-`&Kc$q4`1>tvYx{!(68jZ5qf zCVs}l%WfH?SP&>2@X2c3(xiT2?Mk;H^&x~KZDz%KNW@{0F`>qa?#hL$5dw$Q`r(0& zt@*0L!n#R6<(Y%1gnZqc>;4+W<08>yZHmMRNBT9p4qT9%b)#0UXRf}H%@K)sx$#~yg?N4?P?=>bCS~e-r0Dn6%2gT z)xG4})=21bEBwe5jK40<;cwq}fSfR>uOnZ`Y~={~3Ie7H{Ds6XfMnA+si%kz=kWp-4d zV>(e$(F`I29XcNM0KEpily1SQ)!yrU^mD60vQSnq*PyZNE2YEy1j?gNdTA9QBqwsp zx_+tiA?>j$>lH||!9IuCKxk`|M_2=Sk(JJrRm;uq1DxbgP`7!3CX*dIk%}Ic{85NL z<-5|MqPF5`pTADjJJi6Z#!A{HLDuBmXlGme8r#)<0&5-Gx64aom zyrw`B5Ijpp#N}$^oV89v_vd*4>so}F)#A*Ic_bYkgi^go&+{@|=D_RgMadEDYQ__n zQPbx!y~k4U)~~GQZR+D0i-84dvb9v^@Qb>;wsDQs^O^5EY2$rZU11&|6v$pq8MP7+ z9KC|u@u|_a6PHK_4Pjwsm6tBE%()tt=WFrydhXO#Rd3_{rt>yaSkY)Zh{eeOX{xXz zFv^U0xc7<8dA?yXRkO6^_mO8QlKzIF5h6fg6Oa~fqy=p3R*2mh`%7%<8oQjczv|zbw}ebW3YZMC;(nj zmxr96nGKbXD4HQ)70B<@8T1>c)6vfzQ(kK{YMrA|dfKhDZCf0Bd5s1tX%knLwX4Wu z7m`_TDcTMP6qYJb;{2PBmYk*+71ZS^EY%zU7m zCKJ|8E5%|B>Fit9AH72tvy?Q>VwS=`e+}KeS*<3NG=?lJ|1P#~aM7~p6Lfp4Tf1yz zESmHc3$5Y!$vDsStLyerb>(-mt{L`ndi7A9)n-~vO^x8>#U)fo>4HP5)wprk_>aNLpvqS$$)^B17E z3*FB(Xy?61%k{++mU5@_?jCx~^(ItWEoM4@Ma!FVP)#Na(6|JVvG+Njwb9Cx z#Q+#@)mptY7t4B=O!hvW>+jY^j3`t7*ZEh^Ys>M11`CE0%kxx!xcfe+FU3|PO1vXN zvZd-yy}iG^;a^$ey!48Xxw&cb&|b%2_`y<{~^ndh-`$7fkE&qI2fo8U#5x)XFdU9Ct{HY;#P_k7V z30ZdxSEB`OKVeWm94tf9z1;08l6sC{7QI`jnx&4liEB>G@KrphC({uW;q>+O>Okn zYs`d&d4mf03L0ko3fjIyEV8(g&tk8q<+{^6j{82nhqp^mMk4Imcoe9|#e&7T1QFl{ z)ugWT&5H4sD^}ijO2V=S-dIrB%M8CpM1Ow8#NWBA8-`mQJ{eZ*aTbhsCA520Xi^O-6x(8hpft`~>n?_1%bS9;md#nUJLfCa zJI1FWYeX|w&6>8}0vmdWthQXh4Z))Pm8rrUW7M-nl zLrxd)EiF$iZ_fWT+S?^-+wBmvSuS8vey&ciTqk;1E#>5iIb&3qRB!3jdA4@EVcR&4 zgW1E+8%8a6z*<&Y1;1IX`FXL_751pmp4U?@Wm+6nia0d#P?LeP2ii@Rzv5M_=##ICPifpLp#Hd$vFc|5I^4$NH?N=^#w(O5rm zRd28ms4H@ns6FV>5+A;vxvZObsBiN|Z`Isk~+n6N+U61~w>zwKhxXShM&qBuZ)3g&4o_;cuL86gF>y!zbZiPtRJ@_28fHrQn_ zWy0L1n(;`wX)Ja>-Ck`&Z} zU_5wLflQEj3!zL`L8~g%O#kcgXqaV!6o1{;Lr6}bL&G(-$GlTtzOH?&M#Jhyxu|62=y_qO_CwPWG1v1?9+I-Os0*ZHFqxzXp&J!0*w zBF4Hg{c$tf3aEL?&GiH3EzRe%@#DGXg2l4)5Q0mOf=7f_GvA|$OO`LaUJ2g`t^pB=D4-bxb<5H z>#`Fae{yvR~R**%KF*ATC54 zdL0f4*s7Pgw8m34iN*XG^j@*t&2ClPZ@+0*RyjX2Rj3SI>;inx8m2stEsU$wdq*u- zQTntF7=WBV@15J8+w16uWmn_Hm_IMe&d$@e+|k5^$1g(T_;70V?-(Chb+M~yKStip z7gV!slKJ$kcwM`__rAVzwLLx&Je>D%Jm%Uqf0ZTEI4VRxc(`9&eeF2EJvJ?A-u;PO z49)orf_i=B^_-pbK6ZP1gYBH5QJcNwGA_U$MQ}@@nOCfL5zyoD%`Oc4sHFF!5uJE#)%vm+hDMPROu;y17`|s5~Va6hKe<=?=RF4&|>QE%7Mo*NWV~NNx zQ$a36RbBVW3N4PbdODgXn+BK9i6^v5`t#h`YIgQDFWW4y&mPhXE6k(iA@4iv#l-=E z0Zf{@HC)$z4Y?bN?9<}{p>_!IWMOT@FXzgjxG+l$TY{(b$CHw(HTV3A-|$9dKCb;#Jz|wy zm4AqK-K&(zv^Q{-IPUxYh4aWc3seR@k#L4U*{(^GqZ&%?eo`B5gD~6ytF8mS&Y#&w zopb2TrzYKc#?<8zG|*yS3+-Vn&RI^&uD7ZuwT&HYI-ol%@C|G9UY&MN`ciGLM(kV- zs1T^VBSXy^Cm<@YIFuvkv8Bx@EOv9;mtdRK=@~)i8)3+F-;=6(60Lyicn1vb!45#TCJ<_f~4JH}*%YIKX17<{E!$ zGwJ2SB9@g7mn~}(s#6gs!_W2cl|6??58^)v$kp(O=KJD zlE&*+HmvBlwZ#lxV|K?I*d2^pym{%=YHd8f=-(crS@5_u^g5Q`O%F8VQW@#zKW+*q z9Hoy>bcp|RL5Tl~L2ActPt!0s3Tm6XEYu}@ z#bon~O0;T6=z2t4tWP_sudE zF|SN!^jRm{y$quEWh+Y;*$-6B?g9;+_@60aib_jzVh!OxH?+C@yfj_2xJKz?Z7xDp zcEFP?Th-_*t$ww7)lD;ADw^@3^rz0F{VNUrpl@y4oOC8mpJR#) z3MN`qxMjO9cyN1nS!IbQPWcRze;1ty^98im4-(pCBo_+3^Q1HoqR`}tq)C9eb|^U~mmCOAc`I1JGrL;TT<4vmL^Zz~^Q{;-gau{hH)f3 zx|LIrP-!xh)*tSw`njDn4-?dco;eq22iM=#Wn-DJGXLO05cqMowr#{wrn+q{7FWdNDxpWH*;zI(wfnVyCAw$RH&B{tN#V^r- z;zc98g;JWvYY^h{R!OzsC;aBc4kCqbp-|x5XI#!S-uM3&7@ZjyqhFolb$M5YP!Tx=G z=!6}oM|*BV0$eJB%Qi~3>vrx!)k__&6F{8+_6ROQMNn0hYN)KKPt^jBp?kck&TcCRhvAb_*HX{0mhVdD*`vdt<1uw5j!5#-ryqZ zO)@KU#_3c-H@Ytp@MQnC4pP(nRmH1!Ce3|V6dE~Hmdn}{{(**~+~MlcvY0T3NNL!bj@8-wU_I*byP3P75inj;U0-=#x!+9*Ss+vc=%LagMDt zHjF?wzX};trnLe2wi-u5EoAFqUm{3jpHS%x;y--q$g*}-r6V%|l-N{apkIDo+gtNr z6=d}s^a}<|eu0aW%TPdCg=mg1gkwig!FxAfhQGjm&Fb$W z(A0aV5j+vN-UNWub;1Bh?Tmq}%+C!uSl|d<9ao0~WR0W8HLwvvbLv zgsKgY2i&DSmfyE6G3g7e{PKUb?7yphh}|KY>?O2vu&SBkNmFjf1F3u*;^7$BMIOPH zR{u;eru{PX8wde>(YarBxNc25W%$gDJDzDpk266rFOc5)jKqH*&w2OzK6*L1^CfmI zqOtuhns-zffJYg&#@-qp>Z&C-ynfk{{%QEUAWNbom&xEiQ!I3V!PkJ$T5H+nn!F*SMl$yd zs%0ji!YQpGN!;(KgFC$eTWshNHHughXNr07G8eQC7Au{5)aG_=B&(s#3jlNq8q}93J2UQST3b)+X~szt zX`UiYI{1q3=pK?OgTDNX;dRoznnbs@MiYrX#PDh$Jtf+K)7(>ML}B&sAAD)3wHy$Z zVh(AqzTBZW-SweSe2GnF2TXDt1s?e~E)^J)p<`dK_Kp^Rie5&xNixb8TJaq8LZP@( z@_p0?C*Q7ce6llB>rRp{uN_IAs5)lS?dz6;-APu?)0@FtL3&^nC^^h}T^$5@0;MoQ z?kYU*Ui~|IDzxecn6w*a$F&x%_10$WmcF6zqbljj))v+Fq~WKXHbetCw9JE3=(!TP(>@q2%ZOHO#^UX7H5D=CD$GoE1n)<_qvS9qm%%K zF1)+q|1snQPa6#C1 z$8QK7f5)zQhEx-%6F-5`vt4pjYeONN3EPJ4aq;;;Q5R;cwrO#wo!>A@949bBQRlvx z=||yXe`wyIq#mt$#gQ9G$c3)Z-VkJWdNCAlBX~IS1{DSrry2%3B%dSi$YK`=6HAIp zzsUMP%3#I)@RaOskc9r8f{4Cd6c=XXq#_+B{%x}NT6|eMRqw~IqWsLEbDvFK@QA~D zl<2X~N?!*a9&m&7@P`4-ERY|huE1s%M4rLYpY<(xAWhY+sxez{r4I0@Up?A>Aja>8HiS*BJ(_z);06P6oZVCpA z^TQno?Y3MzAaC=}hm$h~-=oI!&>|Vp9P^MMPi^AKllLi65S6)GA0x1v7;fowKpb2( zSSrKotSIJwq^9EU$NqH@mAqt9I4Y>X;09n04tG9^mLbY7ygUrmBdMJk&k+;90=#32 zAd?33IaSN|s>PDi^Ef!G!GFs^$op^*qMrqPD-eZSUg`UW0$!Hdu+h}_{1mUWOESvM z+fB<7+P_4ySN_EEdP_W$@ryW_Dbu1A0KON1Pz!Pb-;NwCnt6Efqy8AHKgcqxEmWv( zY`f(HkB7ctH!fMtc0@E-4Tz>UTDK%1_-#(Sj>){TjjlkhSDWWwamCv=W`6fNez#T% z1nI$nH<79g!uRu2kkm!b+3Oc}#C&5v@P3NZslpp5fASKZ<@xv0?uP-HW&JEutsggW zYlT%yrYiO{tcn*PGC7<<@#($1PHkZ#@Pw8XZQp*t$`AbuIm&RMO6QVW=*6$~dNNEf zfa&%F{c%0ot}9xFm9ME&OsoGn7x;2VX({7O5!^}gV%K_;F}Emuv*f31dloqHPL<;-98< z958t+x}p)(OCafz{eA`T_BJVzOAZbgO&irAGH7gm)?pvZ@;>{d6BW5qd@>by+A?OO z*4=z^kXJXe2q8GMI@3zgPc8w>I-ylF77oFoh%81>s`Lfz7Rw@%p;q!6-f#JNS^Gxm zh2GqiSh>1++}ne9lV4|Eci()b?udVDAefsmwbo8p+Bo0Q-b$0X3pHllYlFNt<)#CL3(mE!(BB!HW!a!KPf1H{zltWmgEa z1gVs_=*Cw>MSF4o->ia?l;%{&7l8~Qp>kaN=hd6MTL!XeYc@fvx}uNtd3=C-B|}na z<+wr^v7WZJJ~_)oSd3`9*)H@n+BN+oeI1cB7Pg1`vp(KBW#$iAetfkkd(J^32P{RKrh67QZ+PNK5 z9NUd)N7~KL9V}aGXms8*Z`3ev+{OCdMfK<@B+n%w z$zs&TSacf&I|nK}oFf@^Syo!A;{C5}DokB@>`1`df+s%nL9?*bJG6&ZJA2&v_WqaN z+<%YZU*@>as^#{-Dg)bZx9g7q$hLV+hvl)BMVf1V=i*@rjuw2rA(?U+=eDcHngZ=T z1rupjauX>g+0Unqi^&}>F}}AdM=i(;g@E;LJZ0*Kam#8%W}y+Bnt|c07g)lCAs|`N zPtX#Pu-~-#XqwsD;*PFt#>9s)lGQ750*`0BuT!K{ODjfGo-U^`{@3Mh5Z3JE^>r?7 z0HBPtRyT}<7C%fjoK#HNByvs(+RyW7f@~W_$v|-0CwLjnRDLgv9*B=YDyS)WX@156 z%DfWWRXdw1IwQ^TdaZZH;AfhSF#2_&uXg~N6GoHkmeUQPS0kMkpN@3@3d%hQii7}9 znHq@PQ8^CDK1?fgNklXX>9daKnDc4{otPyHht3g{8Vi(d0Rcl!c5Ww-vK(K(agv1R zw2WhlI`#9~{UGLDN&NwfX2Bx=hBH)p8rNd-$uCJnUyJjfxMmD2zhsRt@$eXA3Kb{2%W!qiahYIJ#Se57AX{rO|uOL ziyLvIzq2OA!+~Z++e_WW8*?6*Om3f+(BsaUPdG0lu#@BKZQaaJ_@r3$0YeCPdQd_Vm z1Qx~?E}3_xrL`QVJ~I^%g`%9&fp1sxCFo9`tNJH>vMrTqAF z-6K1m)lyWyNI4aa{TuK*#W#c^MXOtNua$ah0)Cw1EHPcrDr(MiNIWn^Vy%Xni zZ)fMg=`x{Bx^+zVjqlAd>PqvB#frh}f%rU!Z(#dVTdLbj^R?aHEI#<+n7Jly3W!@P&ngk-DJGf_?`AWZQU)X1TMrrGoN?{r9y*?}eB2)5;Dn;djwmUUUv}2U}C0 zq-#mi+|&FgCViq39RR8F96rv%5+%A!;9aUCr3$=pT1#YONnn^FcZ2wiMftCe`I?8@ z7;Xip;~G{ZRmPY#*wOE3w7J83wk*(SXJ0XGnP4W2SV7Hd$ftlY3uO|SW$mU}U)u>G z@By>WShT)xPPumNY|?1Dg8YljS~sG`>PO*$2Lk#kdD)VC}@L5QPN$AF|w9_;7_MG3)0DQML@1Bx5Gofc1dDz42qRXm?47@a2(bZ9( zSJUy%Q0WAWptD5xh-9tkBZ^;t`1*PM{lNIR8d=mX`b7+jd^)1u$lIAFUHo-Tc;(I5 zAyiwJCXHqMhXo@m*<$h_PM6$fB3tm0*oQk^Xin%(0Q`%~G;Fk2 zZxodL6Hd(s-Z)!ps!(4=>o}A31;sdHGSLLA+hKY5HTuQ0`D|GpnJzl30<>v$iw4gOC6;{!$_Dxp! zLt2Cg(4Rl4>y}Q!hw%3MoZifd$%gl!`LhQ_>5Iius@%Rvh6!yn;tHjNH3~T3dGLeR z2Jec?yMFg^oyP91gIGtvB#mkjPup8z(6AZ(HWbzO(9QdPotXa~FYrgXzE z|5Ni6*-FDfmG5N-V-m4|?KNM4p#@8XiY3Ned2vHMjm1XO4urRlZ1){uw;%&Q)_tB- z+;4UTgkw$5ufqe@<=EJ{uvyC}xXLw9%Ci%;Jfnhlt3PveyxH82QHiUV!d~=Fkc6=3 zKwB6f_yz`sJN|EU<8;=ze1A|Yyt6p)C`CWIAqw|q5vyggKGU9N%rBcYI-J)szxHXK z1XZ>|Yi6@&wy2n_aD(DeJ$>G*U2J2tt4BL=ZJHu7Gvj3Evy_V7Tk14q_D(vf(N=I}+Q53LE6G`Z zy^JnAg(EpQ# zLxWeK@Ffp&Ir;=s5v#6Od)M3l(tvg-M*_UPqN9d!2vh%~uBUe5zuvsSb-!kpT=u7q z%T^d)r7-RcjOJZ^ayqu8NwRLHB)n*`q4%00=>DhZbaQ=P(A$>P!#GdTAe=99uv-mj z_TtZtct8hc!q(g4M?`g13^;9nX~r7hC_GY|z^GuWRjcn_YZ2vD#bTQkHzIVtxsxG? z?B^Kk+w+};?Z8yLUPnQC^{nA7z*X+a1FjIB9|rTTaHDyH$uhdSa8UF_D!##K!0)~T zFWLxpnrFuTalL&p=hwRuJ0l1*mm;uxDFlA#+^|pHdN~rCB_VJ$U~F7+z4eIM5#$J) z@<2@wU%#BhS?O?RHmOeX6|zJGsfXOloA|c+KF^1iM;(wX^Bd}oImy)&8>R840^O?y z+lWPFXJQhaXR^K#NieE1)$Cz2#5|cHs53M}!$3QcWzcA&p=mrZSZRxv$^GZx5f43# z@rz%D<&he6d1I~lfRuPPbR$B)%9$B>X2y0tjlOwc07x=JiyH>CaNn%RyM6j&bW13w zs-4^7>_8A?$Xuga=>0LwF)@!UdM_FWYC2v6_mc0s&0Ja<&)H`u-&DM6izls(^N*Z& zfzl@Ftcd9$cGGL?11;nrL;{1w>C{tcC4ACgl{iv8j2GJ_i?EBN$aNYrc{^r)C+74q zlx0AcEDa$i{7OvO2i$hK{f3?X1k^@$(>?;sET@R3KB8`ynKP)x%o9mmZ;kfy-n@Bb z)>F7$j;!1|K6>s{t2Pn4KY5_SVl|5>&M|A}klT;5BF=#C_A60QePqilwGgf~isC_o z=zXe!30W=uK&a6XF9G!>_T8x{eC$@*30o@~!C;gR)>NIq1~w-*@$;PZ*3GX4?ppZR zb*X3qp+*8B(K+(eE7)Anwwc^(Eo3!S(;;Xkt5#&%Svfq`GhKyd>}(>Elbj9?Hip@O zDW@UI-Rdbl`K_FGMAEi(6X7YnUk<$k%I`FmW>JY}eP2hdibAJi_)+uZgsn?2^|@FO z@?`V~ly8l>p}ZeR?ap(ucYh(MH%YSCcmiU5Jt~Jw7{)E88>3jVm+Qs3*sqZGLD!g8 zRpos>OJusfQ>Z729SAVa+$HoqPk6yiJdyVYj~NsBBF5<=#Tx-W<|t z;dyW;BfHDZA1gIs9b+9mNUjTO=QWgU>cwpXTFzM#j46!}amfVD^c_|QwFv0RSu@95 zb5Zh~K3CK3g%9AFI15KjJ!SB+yaFO=cA7x_I`ai4Ag8Enru>Y>%yQ~+zIGFsRC?P* z-rCajwCZNMW=Viu#&AgX2`H;eLoQ^;deLR&j@7_w6Qr0PajMB4NvLzHk7tH*RxoZy zrL#B}$Zsv+a#^8DoR%KlxewmDhuqHGzKHi1YOW@=`)3eb)R1)@FHSu!FaHeQ+DJ66 zJoVmYk``=i#dP~FT|%ae(AM@#G9iE(CyHT6s2AH`_{E$5FM34-9TmX}sdA5(df;AX z66YcT+Ph1?d%2RVr(%QCN2GmOIVq;3dZr2`ios-LMjk0fh1X|mfHbTA*fV^s!ldkI zg!7!X1nE=TTCZ~RR7v4%`&Aj7tXN!kfEodKuEsjWOmg~)MZi>db{z}t-R-p@1WMb< zpL+#-gtOnPB&xH?-w$XJ7o3JDXS=IyIiD4fw#kz!Cx#StO>A*R?p218m&b8XUaq7F z%9n8M;|uoiINx^o>Jdyo2nl1VVrO{a$%%lZx3nMvewq7C7|u#08LA6Y`elu=OVBbB z4X?AOkca5jE1zfC!_MPtS25DiJ(RQ%E#11Lb$@7HnTa2x$ zsd$1R8zosqUHA%IdfcqoYI2tZfHWz$AoeUVnWp22{@h^6Bd>mzd~EP;5ujS6+A@SL zL6whZoh}es{7Swo0r;g&HJ|ux+PRenl_IW~#y1UAZ)5@qsdV<8N+vF@W5qS|YWm7h z;svou(N2O7!y;&qwV`Z$C+YL$(WNTs&bkmB*Vg3tL;T2`(K0vaDI=ex!eut(3hQfXhkN9c)y2a{FOPVOtLX*kKH+^HI0>^s6 z{3y4hWzRQ5e~#stb}aDR&-J3mAI1!Qsd9f5b6>f;TSM-VBPr8bgFyExj4ZprGKjt3 zEqv5yzbvY3Nk*<-!;ov?ev^PVXY*cvQ0Qm4_rZD3gD!Jz44o*4_?b0ky1GAJ$GV&j zW|>sX?s)0?d`vPP9U#p5bHtE3AOs?JZgZg&bZX7*v86oL0o>;o>ht2@$G0W-dsMV5 z?n20+Fk*}@k)OlLgzQFW@(&;u{&~?6Y$vwH|DOVT2|-|T0tEUVZg(-7vIAO1NdW)# zf@*$%)aDKXRF1mfwiUZ5I%pdK+aGINEB)O>wm}&jGMluEqeh=a4%*8f?!(>rIU4IF zZALM1WQ>s>!9afkAEw$|F9H2QT=n=aoAwG_lb9Ejyr)7fnL$X0EQ5ZxOI15AP$IM~ zU5m!JdQKY<4nlu`pJZ}iO~Zxu7`>T}`;_G0hw(jiewE0Q1N*i0Al zb~yOPgS1&Ui3*)^dQ>CLH;*oW=Mf=^u=|}4BCWa>#V#0aQdSdy7OrJnNmndZx)6n7 zfAo%y%dN%|G(+8HQbjFM*c4aofF`*y>?eJEY4ZM1vYW_w6qb;9U7J<5dLvrEwX}3! z(|w-UAFct@XKVmH1xuIn7c>fzAqtnYlnih^UAubhXs{MH$ML z<>0#DS&3V-_-@;3+AggLGVM8Ca+?ASmq_;dS`gYTxg&allk`9HBa7Alh+$haT80rm z3N71TGq_WAE8o|*3=L#v2L9sO3j=nf!k;>45;zCvv*+*T(eFzHmw|_!%j?C9wX8nQ zz%HWDMltjTz$p)eT~uqzjMJ(G3*Jkr9y29=u((Q}@GU|x%WJwa+|$?|8exUVN55nM zia~oLK)HI3VaJtO^XTAU;8Jp;KW?XxZgc=7s&u2imGud>+*SfM6aZpLWa`5aVpBW8>x zF=@rRa6nIV%ued5Jd8-o1cY$M&o4g;UxN!5`PN+1c}gmBw|9GHKMLp+E0;g14tTwW ziEflm#2vx0r(hUu#$ECzV}^=jlXVRm0a<}_2}jq?u}68&dc_-&fKa(pwrCEe{y+U% zF|6yWx->En2PmI#P@JXLIW{Oc83%bGOk}n90m-Tw!xVU~D2R!$qVm3JkMRLk3p}$z z1ol2`SX5Sq&@M8vr`F?>Gu~2#msB85mY{ zmLo=h`YIOMG_e~AVeaw1n)xF+g+Su*#4Kwa@ zvHnul5jlv>N=E(#x&yHSEz@c*%RuO27)YPV6kW5|?}2~iO5#B*V(U#+NlX8>HKCG} zPdvWZr>RHpkQ)wOcOlDVo!S?YhNq303Ql6}INWa?5n49N;PH>2X zqY%_=bLOKWZ`wuCl*xH!mnKgh$CdFTKT(H#^L@MmQBv}`^;x!L zMv+nfETh@!+`(+^+U)O>IfQwF{WYkK#1=XGtuP6Zi^Pa#{}Ggm&bFsgiDNp3B|-( zfBdbt?Iz4~`ChPuXUD_(rEcywx}*E;#ln`I5#g+j@Z63%x-8m4$4WZ1B0^+L{%niY zE7qH=sq5i~jzH!PHK(^i{95!S|C)^cz#C2t{{KS!n*I$$_UvWy?%#p`!%ht78u{xK);I4G zclxguHQD|KLUr$F>HS~mVY9zp9A@^-oTmS3k^X;J!|~q2b%Ossbo>u<_=4^4&`ZX< zP}cpg7Jq<5YWN5Yo{CF}z{MsZVgD750TLulq5Z9?^AJ)=5(Mu$GHW$}=Dg-%h~&i> zs7cHD|9*@GA~08nGe%otDM?l`vQOgD8P=DYd!+Svo6<-KT4s)oG+w;#F#lbjMDNVR z#QHDq#y|RkzcFxdVwuuFx;uZP+0yv0fBa6xmJ?y&!c`ynPDwf>(e2qjT|3n6 z19wShAws^t-6sT*OY^Qg^QG1(lKI~+cZL6jaWlvc2R4>!4XyC>eCMHa$B+@8eR_X2 z7v=N8=Mck0{cs=;>i-^x?-c#8-2gGf)fLbmyRpYgWYbJ^)0D3j^ZZTI*OWTxx`yKk zS9x$^Wjvevh56@D&ft4Ih8Pq-9mH9c!DnqV!s=~=7DAik z4F%}_qSEM!GbeegS?-hhHCtc^$h5AT%B1ABu$xtqL0a%_WT5YQLHP9ilItZHdgoTy zRl-2CPsMHyW9v}outeXumKaw?NAaoQy=b%3nlyuoJt0%1@9Iib3iuJ8e6{EE!~4X; zzx3R|+OgfW4K3zyX!$hl=eJpog{mUdVWJ%jw)oE*MVS$Y+pQ#28E9WSy$s|r@zuU3 zr)j3WfVldzvz_pv~MOR?>>B|X~Pih@z(7i+KTc~|9%b$jetfgvKb??>3*Ls9KZFptn(3OR|zR< zN{lU8(75QeaB`Lc!NzP82CzB&G}fYzFbD}ojVubFm_?@0yc zU(YBBWwMWQ+DqDffFwH~ObLAj?nTA2v|T!1C0JtRr5X6CHhD3UZgOUQw^X1dn*VvA zqtQ3oGdk$d*iC^uHV_<=2vB6*7rJZ+s~=r9U8COqbcGbso}bcu6TN?nwEDsoBIJeLa#hX`CVfw}6ZT0PC5WF3G z&y{sx;EcCk>byEpb-=4+xC)$?qUD-BE!7-9tP&5VVV;|)3{#14_BtQ@0G20*x3z?Q z`O1vs8xuD$Jes+Zl+%7z=s|Il0+y^}?0X^mp)AW+$7sy7blNU_ksOg6;zu0{YuPyP zNp@sg=CQC3RaLbb_IxK?D2ZvNSKm-D^6E-jm=Ak|Pt@Baa zP~^2&8BY+eey^ScXx4G?2CPDN!X=B>6)}v1A&Z|*=MB#a?9lgPZhKah!AeY)##i`= zk=WKDM?737f8riCf=<~N6uU|+?2ho&<2AYX%WJ5!{_swQJ-6$(XZ@^(j$F4Ag8iP8 zXz*sM{qHv?uW$s9=8z3W3jd9bS9Xy%iCl)pIU=X(aXja13i4q+vEacizV6yEbTZ9= z&JFGz^f~Nd=ZcH;_dCI+z|C=&2rTyxArZPc8!y5N_9O~`PZX8EoMg~<^GYYZ*qTxO zerx(|JGmfu`ckYSfIMfx$q8l_q5%3dMTEJGqu=H{;iy;f`xGg-i90*4c)$7V@$e~c zd6f&0-?g}F(Qwf8of0T4K+|dC(Its~=VeG(Txm@|b{jwif}QzQO3v?kqEUU1j6Zv7=Tn zi-bj5Qs%uYYZrZg=S9YSyDNaS!> zY;-CFCO&#gL|8mrR4SU|CzUImXT&gk8LBsZpc~Ufz4kXeDPyT2Ql$gV=?UfFAtX5y zsE^%0MxtYL(V5O?8j2F*j$T2PVIpBqR~DwIf{$vJT(b)NWz8%QXt!Px;H{)b7y}rY zSi=^viaa0mz&ONSNt7YV`yRt6G>F|-C{17$ja`^_IV<*NmGc`>An|s;T4sysu?Le(Cfn1HfoS3J%m~OO;wv7M= zS?fY4UbwXPb_<4frRQ0UrBJzcIBFiUXx^X0V2oa>pQ1TTHoCMMyI*DIuP2W;-ii)? ziC3?N7D?KtuMh!n?}lQVa81UV6;y`oQ&tYV<3fIW$JQg^J(-lVd8K{8)xt}|DpyM0 z>)3^iBgW|(B+}e`>Eg}B0#GcYyTRSHkOl;V)5UWVS(2Cak(C-9-^W`fl*u^zbso1* zmDf|(0aAVggN3O77(PfX&DW)U3S$K}H*L5IVVn=FavyyHjvS?Rr%9D^fXs&-BwA|% zv2PirHnyGv(zEeiT9icAc!Ic*XePoL&ZWp1I}rZqJ23z1JIYbeV@N!Br@*1Gr9UHZ zy-gHi5fH7Z$|#GhV(Th?od<2`&Ir?u0TM3_Dh4;Jp1w4spDF0k67itfp&rxp`bUP` zDe`exrBuA1S1BWPh+;iF2L4Q+KUG{uk=h>oWb`wIT%&^N{zmY~*L+L&Y2#IM=n6Jw zHM;1gNZ7xvps0{SIiv_aer^&r>jP%bz|iCBa?$J`{eT9eQLTrLUv(;(ei%RS22q45 zn;FFUztLzWo?nh8atyU^n= zJkv^g=DI&~$abVNe`>*vS{pPG9_xI#D({}NfrgM9r?AuIfP0KXnCs+l7bHn_7r4>l z^&dRtJk;(Yj2I0fXCGym7$WExGWy1i@0pB0wzO>oiOl%{M$gc7*l2(-Vt>SRZ9p~H_YH4rx0B*)Kl7DT*c2^2IS-@^ zAzG?j3>-opQ|HbG6BXSMHo@=a%-0aZgCsMTI4o9jhHstF(o=gw z-RnQzpjPU+%ti?N;H-r&<6$RHV9sH*r%IhaT2wwquSel0od1%^FEVP2F`b4Jy2;K) z|BA%jlX4H5g*thrXZr+?yni>SLzbOmmP-Y4u@sT840gB6y&48a>Av}O`g1Em7mUHUj>1E0h~l#xiNi8FOa=r_VjwzNAsM0!KYzQ-&;K^l#D zYXI|hCoI=JaJYK zM5&z05KVm(Q{f-FWddE)`^O(FHjPB#k@R|dv5VmhGTVqLKTsXPXFC}RsTwQ}_}H1l z2r66%*UD(+OZpdQe~zR1AJap`{lK0S3SCb)(QDs(mJv z^8A4cTu>~=9P!XjA>Hze-vY0+1l!Qj(RhbJp#tO9C^d6n$HHeKX1^Fpe}4tb&7h+ zTeiq2_q|_o`T%x_8^S|4bPW~Z*w@blZ4NdytB95evmJ36L`YjyI>~JkMbTw1>d^Lf zn*8<*)*kiSoVph-ycpeB*XSm417QBvm1>Prh@<5lJ?&x(2Aear_4lm*X0QD;9uxQ3 zQVPF&O)SB3!)YnY=ebZYrycF+&VO*Jj=rtOl{7yO=etm7V{Q`AQ@7xSJ~yf5qsj&B z0)BnJUYOUuQe%3Hm6ZMiX8TYcT+_H>=_lL|E34BB>o&-o;Ps^`K}*|Ffs57XJwIZM z`!;W_AWYy8QosV9``YVs;lQ|W9;7hB1Y{oOkxS$WY*0YZf#|VB^Emf3+Zoha7aH)k zWj7AVNWi7q$CN$2AoVw>pL7$Uu`%}V9_Z(XKocy;_sx$w3|IVms^y2~0O>C3O%!F8 z5)Uc)ONTs6DLeRrkHCA0!tlX8ttw6?@_5xj>{!(-!#mVbL=pKw4wz5CDO1q8Xy~Fi z00KV{hz~+H{ypKrjs~5G-%h0L*mMB4*YqUMo0gFGCG8VBY0mpXk!WeBkRKJk-WdFg zMMm@=769wU#BkF_!c$e^*@SAElex$+g>-thy$C4?6zh49t@Qkr@-Y>RCdes3E@OVf zk4DycP5!8`dNJ^(nTU?Q9@ss+LHy`;NH&cHw{p&#O3P+~&C0+<5cm`E&WeI%Gu7p3 zEv#!Z8En$j0=jrME4YeTG3>0_P!Z0<5Xba8=(!C>5G(h8Zr||SLiLk4_kNY!OIh_a zv+E$C;ue-=*4uT!>M+2CgI3KHw>$e&Paw0p)?d4#4&FO&4TmM|G`D${J9N)A7%WE)mwj0Ej4jvfFc~b=(wwf zFvK3bdBe^y`e(V&QzS; zK4A7(nc}NriP)yGwocoqkVMOVGv|FWa@$hyAqhQ%@-w??GG19MyN^Wcm~xq{mCr>) zZE@EoT)DzGcjT#`hh$foFJfVV1A-MNCP8<Q0x0k=h2w;tf=Q|93aTIMY1=PU{=F=v|7%&Q z0D^!V8f#MDTH)Y<_Y_#ilWs(HLaCen4zN4+@WGD}*qZja)1S;)jx6 zv74iT2FGkg7?r%|G24ed zn1%Y9%cqBe4fbyu^?%3=E4pC6&vd|Ke0J9PrpB|OcqXKW$+30saERWZ_3b$p9K^x3Xoh<{=xDqV$Sw@2N@#VuwQPm`p!M>U)zL)`0 z=%oJ@nEwgAV{PL(GDj&9ZhaW4Xy=z0keDj|LoC-VaVN$Lz9P&rtJHyD2;;kv=J5J)Q=`gf7C$ zuR3o~5cD)JU)P7Z>h{}V{+4{^;>|F}FC3Z@CjSaYKQ3N(^N_-;?n^`2){;7tL(#T%?AuBR!(@f5{H+U1 zAkTxL$@z%e7EhWTcO4h=BsoM2E_Kuwk$-eC#fl9{S5Z6e-Zu-Pw=PxS>el2qDMx@0 z`;Nq&>L}TJkoFt*s+wEzWP7*N-!ut})UizL=ldOk!-M#zACa)~b<96X7f?%6rv$Ar z{Rsiksya10GuhYfz{V{8>2j4XvxMC8>wBG)HsPOlYkBQm+2Py0}DD+w)g+ z0UJJ`o4U13)v5?C0kdz&I6t_zR0_c=pG2t(N!d@twPQS2dnka&N)eRuMy*R2_X}EV zvu%&YdLCr8yq-1xq9jlnohOCO4BVE{{*|Z^Cmn=j6d=;C%>jL;`3Y;1K+&K`d#1oj zt@Z1`&N1iWMx;byi>>(S6&V6K2E^wf2TYj2>Y8R;vy@M4PKNvBa$t~0EgExR_vRSs z5Ujl)_om^~p#T$97tA6|zLJ$Wa+Aq-|$)yJ6trR zq@%jnWFHyn@ik=FDj+VNRD#L}(fxDXriVplA!bD+kX-ZwL|JDJ z2R?+)WCMCZMmR^?E0Uf}yF<84-IbFlP{C4X24wB}Xcr$?LVI|EeCf4YJqwBBR_ z-3s;N!mPB3afwyYY+Z=?Esf3G%vw&Gs$!?~?QcM}ssMayX_mM6=v+%p6Wt;Ns#~4a z+WLzlv+uN8Xg<{#zPhk1`#?Pg{JXJTjRiB@`L5V;jeUtZ_zKBV6g5%t_y^XUr$(88eQj;!?yMW##*TyIl7*0{FqwHs{eC>LSplkn3Q zaarnwBXRoa2_~(HSDlP9NE|3jZ??7`rgWmoKnkMeRnO0S9JEB{RRuJ2T535mV~nzi z^W9-x^7-r~1*40G%u^+@aOLVSK}NtxK^XJ03ZBA>3OB(PSPzd{D~oa^hGc7-`l??l zKg{-yq&?5`9ZrTgxKGAdpVD^)a2Clq$j%xqN#eN^Sb6_EzXomH4v(nv}W?fi>BdG{v?%^g9;`401{B31wWZ}6Qq(# zD2SBp%1!EHicn8PM$p23BOSXoWgRb;)>isE77U7P@?zrZ65LTwF^KL`pb42L zVNghPpf`%#C9PAFUI>a=LH!@D-hwTzsLR&HCAhm22m~qI3k~k>?oM!bcL@~k?!n!H zySuwXpm4eA?$h5r&-o8~?6uYyW4?1b<=?KZb9PAMNE?jsy30#>t7Su3S9A}PiVEln z*@r&?`P-aWdk@G|`Hk1IK_4t-?1(l$BXU{^AYM$NCO(nls|K>Pwa<97%eGAp{UL!H ztPMs_t+{@~kuhTQvoox0Gy?Td}}UOaggj>k1gPbcxRs@5{Z<%kVx`&?xIvAr$bbuvFr zX?x}-hO~dBE%s59EB#ykB7%gfK8ak$nm%8+{!rHbTif6Jd5~~^u1JaTmyzG)#&V^= z>*HB;ORbX1Poe6=LFr;IwXqLuPTC_Qf=nd?1um!*)~2TG<+XvXmwOxw%f5R=>ww7e zikMTy*8sPx)zZ&SFom69tAq@?txKIm+y1{F?^h5XiW$YG*f$^KEE(V7H_>Q{)rNQZGrf*V?cdP9tnuT>;#aJHA>u#xZ01{S!@W~*rJ#p_pp z(WS$*_2=%u%T;!~<>pWA|)&zT%@{Y;n!VCbJ0`)FT;Xm@D{2%#M za1ircRLT+YX${)DScX9-y3CNTboPolAV$;@PYzE(!@FD^c)bsUKM^o(LT}5IJ%8{_ zQ$T$iu(%<;Br6SENZ4vO&d*tGHQ?H4#~fYv`<1FnRa_ZTMd3Dqs4x z!q6wyo}MifA-X`64j;6P5)#2AVyzu*Cr;9HCT+$2IiB=`5a!vvC=A>ktuR0MJ#IPf z^7VdMP`~;MLJIc#@8^)>T5(SfGZqlc@CldF#fu%2FdP=NIp!0d6%(cMa!A8x7Q-_$ zoIN5wa%M`X=sbDNJUUXdGgH`e9zKGtjU*-I#)JxsBsX!4I6)ve%dWhDIfP2e=s-k7 z5Iz}cziH?ZwQmMn$g1I&a*Cu8N<)hVG#RSNH*6=N{u{;I7puGDnl_>F)T!l+rc5vw z7qChR;7v~--S~xl(U)rpG|D>nAgfjcR7>JV=Ij>=`AxYsli1KnS%z3f^EVW{ z9vkx!0D`Q^O#%1>R1SD+TvOZ-Q?n;ZEsYqWm1NK@rsAGH{8BjW zFnDd9;}`WVX-B=Nvu)JJJq`noGmFEfska#^yDgIM0bXv?nsvOLU^+E0_M+qR5{!9JpB*?#I=+6A!KvC+q{={w3DaErkB}cK@?F{BK%JJ z$`;9BTcfUvS3IVi61kAvyAUXtOTTodzg&1@cR5`AeGB89dfl;OY{-5 zb{PRm6Mbdb((krxulvMdRh<~zUTkjg;kNT?+|Xe{4&t|xofyQ1S8&_e`EmZJNd=G&21-&V6^HG+14yh9Sz;cSE_CiAC@FV zgK>K&sp2K55O3q(QlO`lGx)pJ3dLh*XRqupxBNBrd?h6li?r93Wpz+VFX#V0-?3jm z!Di@d6bFXhxeT?7w!2RzX8Kha?%L5}BemAaM=F#}I%LMWON{z+)VnWsv zg~zOE^6^*NHV53+EMoX6mo!(dhmpe(EAaP+D+5PaR4`;KkacRRot(ZhwT#piviBUb zPC`H-(g+=}nc7X%rT5*SX}*!VV&aRY?flk@8K*B=hK16XCk+IklG1+0*~7tYpbiJW zzX#spp8<;|1%9-@rhV4zo6CxwCt!;UQPtMf0&>Ub3TZjY?kG|$rfrl2rn_p1hxV*Q zy<5h{$2pqoB~7FqJ8Q^Fr~MA-yB@E5YIAH8UtZug6B2WY7w$Bru&h_sCgBFHqq9TbbGaF|RHXS?6762`&}+*n%716%RL!<#l04N8`xFc&r0 z%dg(NNX%5;ub4HgZSTH4pdx)+*|zldH)xsC=hh zX#NUWwNX@&3ATS-8V1Mtf8?9Tmm5yEXr;kY{s1_lA_q8kKJsz_C!qfS#N(f3<@-C~ z0|thiD)DfkOHEnNG0IUtbKjGtrqq z{3I)r{t!}^TH|S!-_6kk+rTWan3WaW!?iRZy8=oQ+Y+VbY@G-ZdwBo zSr)yl%*9V6{@Zw`j_3&h=qVhLA&lqur`*s~$%4%hU4jG#xh0m}?xo>gU+ARngxE9l zUvL2T?%Mvbr5-6A8%?*1fo^@;b>*&ePe-c4QOVn7pGlmw6Q zT7gDE%j9oG{}1)uSJzM>O`4eHks)Cnd<~#LOn37Pc{ts4WVHO8LFXy^WF{{V{cmtE z9Xo_2V|ws=8zvaxVKnvU9$T7~ zyv?tnMU8WlYrl@}zk=J#eO1etcd=mI@lO9cv*Sv_qkV+=t1yGD+Vg9JLOTiX#gU10 zErS}FROW>aCWCyZMJL~j?6i|?|2vctjdJ6sHZwNg3I^eEZSDLP1J9hZigD=tuD@+v zUT*v5m)rp~R3>e{oy%*MGTf562KYyLw`buFAIv}j9 zvX2qsJHIb^{XxfFsFc9V>K0S6P$JdV3!RBbW%i9kW$V8(fw2GISW%1lfrN7Ta8bV zeQ&byfGhn+_pN@|9xGZD_j-0+aFQno(!Qj z{fkST_}Vd;mxJ3!8Z95{(+(@;mwfJ)c$}M)Ajx~3Xw#sau{XR3cVffuNdTTJXc|W+ z1ZIiqdb;pzQ@xU58WZtQcgXL^Ax(q;K>j?sH-Mqfbn2!qHC#3IvW(lppF@NcXSmn;8pLT7}Bjx?H`b&%WP zA*lC8Q6ZzsJkG95_fpnn)nAf6!j~?VN*&%9F+Yk*_VGzfjIV$T5ZQp zzFu)ocjK1R=xN`dyUVnk0&g;J!ea+^eoNRe4AmWDOnj8waEvLYAWuma|LVXd-TJ2HjsvuMv|N-aA?%t~&pF0b&l=c^e- z#$p&raJ&1y`lN%sc@M!{iJdoiTkv!SjdZK@VY1^CIu2|Gpjq&R>4`p5#Q8@nxze}u<>dCe4!TsNSNiqq8Wsh$1FsH*Z`rh6?kOs5Xs zTy99f*V!Ew1fUJIEI;8_(2o1hm}eLNaCv*CrQ*`uJf&hOZ~#14u+7JNN6+l^GJheK zw)H=jF-d|u@!nhn2j>`P_m8s^q8Y)@7s%KFv3%GqYMmfe(*EDrB^0Pm8Th~`_8JKt zhN%X-07PACdli5UzKVui$KDxSo7NEu6PFrM#N3P|)8^0cNOmidMpQAsHK#ni@5_RP zh~Osc3emst1)O`+1zPn|t1^g`?J#G{=8_U#FJNqc{FFQH{8{w(eH%yZ;)|F_8*4zm zF7mBm0i~GrURSrDJa!-TA7n|Mm>+FCD1X7bpRAI=7P^q?kUq&$m9>q{(i}hDD4Ib# z4bRvkOqQw=R^GItY0i_4mtrVL4YJny<4%GUrE2)A+;$m7ix09Cd8t31) zd(2&%^!JG*Qe#8u#>S_g8 zHf-(wmo$tyY+8D<pbEE$KGiAJmwwsyM=eaTAqUFgr z(Z&&%B@y)RwnC4Hw|AOLouT%Ht@xwxz>F-~Nj{Rmi?4{;Q1G|9BRU+lmI%AZ8gVK# zve;L`l#F_(uG{{*1x2L_feXg%&q*v^Csk2H@x24jk5IXGKeI1b%|ElbtKsf`V_OvG zy&pOFsAQ7@f2w{b^V3E$5(-;+vye?M*17ggd2djCMZH|K8jhWfQc*B$RDNpx13o3I zp4+|TYx4LR?1csLHHOn*GiO+<;Pl-u@n)~67e7w!341^AP1CE2|2S{qC^zeTS@DNA zS|LVZM5?N$pfCDAFG|hO|9(*>au|_FojrdsWiDbKnJGaACX5BW9KW!&+kRMP|29>s z3j{(5-^6~l$#GSC3(MSGpM(M8WD^od_ACtP3NU28$Vm`{47~l^Q!0L4$f0qePV$!7 z;&4=*egIo3`4-n`x^>JY5by?&LGO8eke^Wa zIP+lfqc+%B@gN2*Vf-FTxKha2s7h7Ra@kd02;OO}cCYrn{)^U4q8GV5RzaxX^@A^^Rsn31V(CtjW)cIcS~@f9 z&Z>Ih2(zB8629xRaIqE3S?S4Y;n1GUeni3Oe|5--r*ip3)8x`4CS6gK#ZfV!<47*U zo1D(=^YNgJZPwd|&dCfK27<94x}1&4-B!!nTuPWKr|r5o3lZHOi`PV znU?iu6|d^M5%_sof?Nl$+Mw>|^}6rnbE&@h@Mk`Q%TKll_Rje66}{LTDDAo3t!jed zr7G9^8Q|`n@WO{&MexDkEranoTu@)=>i9`22Lf^eYTV3G{fsOX!)`->k{~U3t2#gt zJBwsqR0yvo(t`m#YdxBgL7;lCF$&i0kBQReX3;*{K0<}?XMKJLH^&FkBHzl~tubxB zAVgJ^{E&K{udAj`=#wFGD8mCgZwJfn=efXF$cOwaTt?k8vdw49h_^wLSc^$n5=?P$^|O&I#G3D9Ddv-1_BSQ^0qbNioILm=7ZidZ*+w-jg%%* zt^=)R!MHR6F^G6a+KZN&@ZP-8M5nyT#kkn@3IiJpzprCN%VtA3Edze)3st@?G-Nip z=r**kyuw=rH|a~97|6JO%{Ug-29FSCqe3gkg*ksz;kvq@+TaejV#`U=?JnP~T|i9y zCv}YZpVYBeoHisgMRd;&qoY85Fz`W5&w7p`u>aVn2exn9BSJrU>B_ z?8t=?3xAv06c$+%ZkGh$!Qfo}B0D~`Ij%P>^ky^hHzE4EyQ@ub3efqPfY*I6oj%C1 zrq^wQM)}Bf?r!+B>zH||qBLjTyXS^6+xv`eE%I#GZCz*G8>~^PFqc`|ihpX0tP)BK z&Kd71`Fxwwa6LK&z>gZaqH4fxgL+=4;#~&IW$wX9sg}E0PB4RX8a&Foot@ll+@X%S z&iDD_@{0~vo~j0|?%DFzB(M#sbHmKKP{OQwIK47$`o#MC?PqU4+6@PF%@7S*k$FXHUGj1p~^ z&nXqEL1L+j>zuH{psEu~l%8a#G0bP90gHRySA%(7b)(ndAPIxd*f58hRZpoLGz&cM zEY6lBa%MZa!C6;Ny@T3~9*JIKks;!Zl*lRztE&~`3c1y4@dCAvTTkrBW$9Y@z(z;)zV4dCDnA zxOQB>@EsQ1f_9RKmjJn;Ibhsl1?Kxx0!z@xg9mm!EokK46LTN&{U!2T!^X!)Xt*U# zO=DPpXg)*yn*B{l9IqRK17w`qiw`ntu2qY9O_&apstfB~3&97X_*$}>E0{ATPJ8`% zco5a3#Hq~X*uUc^_3{b^s`=m?W%G1pEB>>VmK`W&EXvCJGq}vPD-6(VeUv^Q($V0c zy1TgY_14|;oC<;X(HlGHvzbTAT>Y>g_8r%==vOTWlagPRAiS}f2pO!%sjncqow_Fa zCuCo!KsOJaLF$DhkJ_*OU{d1Z;v#U*`e(*g`{k z)^Eo+LPRz{gx1aaFEq77i3c})Mm=Lc#YcAlM$<;$Z1)Z$d#>q~x*FaNcrht__H2s_W&yIqkemLxaYQzk$9Z$+41~KL9Y{bf+^86C* z2FEL66b>D!w+|w~sOPxgMqaTc4zF+=fh;F+)Z8eLIF8c{?hgjgO(>d)t z6ZGBZ2B~MJyp%D3oaHDEi={+zl0%L1g?82;quZVN-zcga;F$N;x70v3im)95HfIQrc=hQH(>r3az}TIb(!NjgX1rf~ka1 zeHS!BNa^E9uVRmcau@}PuB?RRBvsTUha#3A2yz%I`X0A1kI@VWP=eN7^qsb!vDj+V zb?AP9ni7l1l5~GKaB*Z~Y(kW<>nf4!b&38>$RvnFLzf@_zAO+JAgSceWbuzExEEl> z@o+gjnN!a9u{*#E=EkCNy4*}tUT)T#z$xmA+5CnoQrUfi-BkMX<-+}Xc{EviAuLKf?0ua zD5}28Vk}xlgTmDXzzO3+7+vooxC#3_OFUf*e9d3QK`$5k$*PoV+yl5h^|TpEUMy$j zj6|=4fc#-7^z@*`F{KmqhaZkbFZKbNB*Y8kU$_#_eJroz=+C{vA&CW$I>`Nc@AOcW z>CmR&&~YGJbiMETiYHjZymeovUb`uoIoIy9t10kz*I&d$0*2wNC(@ZeL8y+o4{E&= zow6H4;@oFV_@K>&I4QSG^TEov!~(A_GcUtcxC%jQcYBV+nIJ|t;FTF&EkB5Z5DrKI2)eT>n%|t z0FRdtp93juFQm@wZ+HM+>I`*&6lUzqYL)^OE4Q*Z~>t6+oyVoZs%ULEQ;80;SY7N$rpi@*i_*$pwa|HGvSg)*(Vwf0#&=eRGA?jIa>6598LTHHvjj*$aH zN*WD61^kob1wG5PDQK7k{b7?HrQgAi{?*B)ve1gMSPn@97e2mRPRGLr6(6yG*5VB?SJp4R9`X>Qp|2za4p0F5MN zB0VaUPAT@>fiUqnW43)jt5(NnUbokvvYziDEGTx-^1FONOP-O3*E{az`ZgjYN6}H3 zwY*Esl0jC77~62n-1=6XE`k!6iF$e5+80+y&^aHwfadH8f5KW@hvq!+lH_HTG5$o- zL6$@>dttfuJNN5he=(aAsCG8;?)a?eROiM-pzJtsl=j0oPF6; zX}oMRdA{u(X;CPb@eiV}IvTgQr8ZHx;y>)%Tgfu+w?FeG?jv-pp zn-YN;XZ=-+gJ$J<&oeXNIAp81DtEJ6Tf&%Fd?bi@u#-Ogs5vG0(eI=3*V$T+ia$8D z(sk)ph26mxg(lP_p)IUU&%KN2@nQufAnb9lVEfeD>I;OUnIop>OlHb_C z|1Cjd{&xvFY*CUE9o+|?1r~}TPk$SBv|p9FUXAH1Tu<^e)au4+c`^Af2FaN}ViPdX zkD?+}km3c@+t6fzCGQiv&hy-|Do~OLe_)lK-=g{Mlle4EL<8~Jq@Gim3jVsQR%~yq zmy@NLgO{SGMfdcpR8pDdnjQsn9sF zB-RtssGgl+a6jF0-AFEHw?Bt3+b^9cdsTNMqNv>YN}spd9?Cv!7PWoR;OEB`1QQ!z zjJ2CRnoG7tJ>*)Z-L%ow!$4?v^z=1BJl6AE{%)n51GX2#K7GpKSf?hDp!w}?g`Re2 ztfUVC?lou4C=#2CD%3mSC$h_3+Z4JcjU5PH{YmZ+{m97qwPQ}9C*)Jyg83><-t2Zm zh8wEYPS+0m_UD!|y|c)lYJF0Zzn*+{WJw2DI2uRyA=@Am_n@J}Z#4)+Ve;ky&<%_) zq-EXSIUBVKe$PYbUFL8kT!AeFC=1MFycNU~v+FF08B23zDrwnOEp}J)&zE65odr_<;-iq}e&*U6}J2#FA9{E^Fd4()KweMsb zp=E?bw?p*u1DyNhT{j!iFT17oGwIiY7?t=w(jeLM7St09G)cyl=kPq(95HIF<_De# z$>kC3acC`5IIftoT%0)@q`<^_Bi#!sQ+X<5eg=q$B?7L2Cm5-g;rOn;!qWqsgUMBg zVy$6}Pul^;tse=7)g^N6+%@sfTvf-Q*Uy(xG^;Neir7Y8JF8t)o34Et6vBSH5*Wih z1A%PD03;O)h5$i8y^Jo*kuz76*z&Na--56Z9O_9Xzvpi^!A9Z2aqbcHNvICobF7je zQA{}?+8SBbi5ktvrT^Zk0#|zMQ@e1CxBL*rneWv!MBi5tkmJ}lCedK&+^iP->N8|e zsehYi@lYMyw#U?M22Zor_G?G{+4}OQ7}@8Fjw(#xwv_L7$F9D>>)z0}D7>H;Og1&Z zyQo`UDIm8f2U;;sh)dR`0`4ivStAQAM6vm|-^Y2HyA8Xy2%bpfUse!YW6Q&7okI>< z(jZMLSUyBx%#2pe{n2PLgYSn!*9(df|Juxz-?L870wMs}_u;Z|;32b|oE@OI%Up_w zzAz!KW3wCGw946kw<>3alxllCX38ysJ#Y`vOQp507TG)OTrlG2b1?{Kx>8d>hy54l zKXOI+FS$+=%=XHHsOwa14q(wU6ndKpLcTuu9nI9S0R%6IT zL3DuqJ~R-T|6o#FN)UU>V=`y@UR~XBN8Aacv&8vEvityD0~6?nEAg4Kh6VGn-kZ1r z{|l%l46?jv4zU`<=Gto+1Dl^OAceCWlfVLy>_Z;K)R6786q@Ou(PmTW{wgsR%_e3!ulNJk zS0j}|KT7Qv_!RlLOXzfxc#83wbA-ov2LTeGH+DDNm-#94tX%OT=` zjvaSN@)F_*b9^=!GHgwe98%QpS?U{L@JIKVn4^A zZCWsZ4eEO6e*=|%>fcmP=Y!@HYnxtC&w8)yFp(pQL0H-n@cn-h(|!EHlVxliB-}jb zd9xp`e(-MeX+e=+Vk@=NTRq0Td%J)~kzAk6(#p(KabP@QVPOC8UK_R5sPKH>!OXgq zz+xOKRx{K-od0!;ppgZ7wPMqt%4>X98Pk6>m4j3ugRnG{9Wntxp?!(O^t3JXyHO0M zi6JWFWyfYJ3BQB#BHgYSORjWD8JLpg*8F=x4i(3FfZo3DPNw?UnO;%TKeb`kr|>n~ zCOARF8%H|db0w?=WATDJq7<0f9t$vqrqR4nsV{F!KF#3{??QG*v3l;j1x;+!MzSd! zP@hT1X3iA3zYS{Lf5MOe|NQIa)GjYOcn5?HH`!j`AK}6O>MIK^0P&?@g4T)muJeqL z>{vF$Ar8JEoi+tSI1kI@98My5n1gss;f3yStASjDCIbc|_&*cA6SCDBI85n}8^usG zQbjG@!8<{f2o!2PKH9F85q%yFX!{MFGISZ+?YZfI5sQg;hrfgi75+T}uEo%+Ve4;6^!;7O z6_SxtG=S%l<|Q>&KC!8eLJJTWHe_ckIDx4}k9h0Q!x?@+lf&(e{l>8d%zfU6U7Ym% ziufv#M{z@UQVe(nvM*4y)xP&la~!=p%yp*EvzzyOK&c~RJ?(1wUcS7tcOcS4u#(I& zU;ISBFu&MYs~XwCM+cFyPoZ8Z#jBt6-y!4)WAP!>zHb_Al&Xt_KT@dHDS%+fIbFYm zQxw!s>~-o#^7c>Nbs-?AXK^d!dVH#h|qbnyZ_!BC)pI?La zY0vS{fK_c+XN#z8yI2h*HbC-ULY9tZv-mM`#Qumf7Z;^UU-o1ZdPreh52LVL7o*Gq zBY+6t+nqHMZq>bzDeqX6$qd%=9}R$CBNQY}2uvVxm-WSYBTb4<3i+&r;JcVq33fTd zkb)c#OaVMi(#Z0(C&{6j6m?oE%vu%YuqQqN2^8X95!xoJLutfka{m zA?}XKlt`gM7rIKUJEHbFf;SU& zKT}@T4@BQZNTx4OgO zB!f)2OfaK-$(F}W87_&S0UOI`MkImerkLj7A_k^OoGMn>#E=9vU8HD<--RYl`y40du#B^f>lPbrL3{Fp5 z$RYKUFFtveE>o8BSls9i;32&G=xJY7i(GaE!~#}>Yo#b z%Ea@@0Lnx3N!na)u0}Hj3-N99npkta_}rNh{eHrK3=e0pv~b?%Yg5lmF)fM2$SP}g zgHMkA)3aRFFC}S=N;fpr!$NMmO3OG|A?E(8LNM)ixe@TW1jJ7$2T48{F=^GjYFy9Wf(gK; z>30``4~6x$x~K+mjpHG83J|3~ms|-5(}4v}avAK>!&t!1(k@eMUW(#`z6^z$fojqyH8*!ue%=U-x}$g!gpJ7Y2TT*KZ}VC64!?TzEIv4!=dyHaVboplWw2Vqkz>F}tOr5loOb+GmN zK*P(V<{6!l(tnxAL^c1U$D0oINXTKP$9a|oLNG+l$7H-0%B)kbR|De<$ z`6U(cnClq()G0T(sMqIWSFs{@^R>#)Y1nrSKB*?4J4?u=e6(=fW%uth$bzv5nT?`| z^$nezSQ+rOS$C{IzQjCg9u{pZmiQULg)qJrr$lAGXD?mq4~!MSWpd5mSH~5}Ir)t%OMewo)Xy-fX}q`!;aD z$&q4>__yu4zu4zfwi>qw=`5;k3rz}+l{^(j@zDO8?-A5QLkWzG{2^h>{EbR4!^^_xoRl`>wQP&aFXLI<88vrMTYu}2P z93rx|Au0v87mrF&akG@W-CFH0KGf5src91BNinRU<{e2soq0lQQ6dSWFg0=Zs?VoY zUu)V4XBG=gQwn327KM`7D!DJq?`88-dJ@=TK_VJjB=HWw03 z0SzvMLvo5#$i4zFcft>a(qlT0Z*cO^WYMEmy2n{wQ4jBX>L_`kL}Jl~v9?oz7@Am4 zpm^zsdpZCaPMHkD?snt3WkkR)lj(+ML-fFzcUDk}N4tzgj#F4FgI)~Wf(=0f<3pT6 z*Ezf1-D(reWA7+YSbkZ=`?o4@=rln#3*rwgYm@=Qc*oHB-^mJL!iJw_%&)VPXjYUN zF@E@;6rc>{Gmc=GbBwIseT38sEGrV8xsvZw`X!G&@39sA8h`v~m+PmxeTLaWt{Byr z*HCjI4|f~#XakSTy)_J0KBE;3uqki#+I{kCy1*EWIo#rUS)qHri(X?!6BG34ocBga zd`|b4lZP8r@vdB%+YQWDOG%Nj0EU>_;{XCV{fX;+RgM3ZAqza@b#drDEja`sAQCl0 z$l5Ll5^C8!=HB+-q!Zqa(DEANEBMbHU(lc5I1;BipI6!1;CmYC$B-%pnj?WD%~kGv z6O%t9$IRiXwb+rKjLPE_)W-34>yakr^=`&ci(-FLSyuGcZ7sPtH*&jotz?l9@Q~{D z(oU6+M&y03OWjYm!j~%CXY7OvEX?6d9mF(Zuzm1{M(A3}MSWJ38W6<$DOmb`9z-`{ z1tPMFger2)HDE84r=PI-drq+mJZ+e-X-a2~Bi73t5Jh>tYNy*B%aKX;J z^0j0RdFNJTMiwGRg1Sp&4b@YshLrcb{=@4H;b9v4YaDSox~pa0s6wy9v(~*N? zoc-Va^ZMgFw~LKRX5T|MyX|Ja12!#z5I4wI`0iOrBT39`43wmBVaJe4j|g6KIYo9L zzAi-mNem_)<_l_{g}9_8{u-*wiKT=_>o&rGCL82Deb&b-0%JxX#Mo^brL8@z*i_$U z=B;uIKorQ#c9ev6hSI~jGkrL@T>)#HOT>4TDQw<^e0+q3-^X5W7Ja^~cBw8F^R9V3 zSUJ0{o;Ec4PAl2o7#UycW;wU2Oe^?^z7f$-PatuXCFnaN)D`q=iXA!9Xm|OCWdFkz z;Y?{anyKNMuTDfQ8=8w5?mi!Cx@j%_p7tKywFuxyF6l+C@;Niwe7(+{IgPdm9k^I( zGHSn{S9>}1Rj{OZRlrEhjN%5&*!248yw`t0!PUT$L+e3&fMk0cd~!^IHSeR5S`q{O zb$u<1e%9*OW~Lv=4O|y~f^feo0Qw01>+LDPd&+kZmyba~Vm;w%Vxu|xA?{Yaa=U;9@N#R=y5E&4ZPmii|7^E8 z{p$8!=Vk0Y^#k3BNbeGVU%5+;QA&*ePE5InJA3VRdG+U*VJ=`IznYEkTrKS!k`zFC zUx{7%$&2dCK)@U1X{U~4p#bd%ASX305#dEXkMQ!oq6#82Y{qbVOUX? z@IejJ+fAXRZq^7f8|kv1#3xf>tIh`dS~wX|Z{K!IaTyLb*$+W1=n!T9dPLiVblfk& z)s>gO#knZl&xHf70ETJd!rRz6tPhqiO&i7w2n)WS9lNecMLTs1xuOj~=m$v#fLR6{ z*Y7e|OAy5aoXM@n)N~Lj2O-{ootMH(p&stvx zx;4egm({y~B6L{ftSgj*pUddT{R$?yweqf$qgnb{?Vu&)r z?1P^EyIOd8!h4!#h7sJlDcu0&M)!3>j)ytYWt#O$n*GPzFal4PT(-nRIg^x@)D-cl zK$V31nll+L+3KJK&=I8@<5%D58!!G< zyze#Y=Iu#?a2=b)i{<<4uwaqI!&RX0t}f}bDi8GUVygEk>E#owMjS8+xC#X$ zCH#+UJ;`}@uDKcRQ+Z{l;klefS}GQpU^4eb|MRL zDHOsCFn37C6R(DXxfBVH(*TSlk>6*IiFC5C(zCrQ8v~4%1g8-!0T{#;^ zN23bt{c=d7zu7i53z^Ar4ysI{hb zE)Ie}Sq|Ki23p*jy%on)<2VoV0a^EY;k(!qA)g&FysPVZtCjP8r9#iY*`6sRJJwki z)2aC6!OQE}wgx^)b~=&5@6mO$H4A+PpW5!s+R}XI95!o~MSb>>DAOMC2M$;+sqATL zizgplulG7dzYB+BRoLD==f7Gw)d;5pADay3?MGlTwFGE=pT6UrcctYFu2Q=8vF}H^ zdb@0PDOe&--E8V9TBc+M*E>Z~XoaCFktxp@%jg6;W5XiiyFmhq2IT9MPeKgmrJcQ8 z&T)N@Yp3Q{>P=kvGV&ZY;f3c-veCeqV`~9oIHhi6_HeIo6eHe_6~e(#6ed<&$Arom za<-jSdJ?K=c%k>aLgY7u3q9_(Uui%ko!Q$j&Ig{!mZlZ71-q)=f1Mmh5dr~M*HaijlC1RsW05WL$K!R%q ztGNfNEEQ;$tDQE5TCLJ_5IZNUV9#6kIJns1L(#oTt5ABX;kFHDQ%|qmcogwvU7-h! zhAa%O=X1qCp?IA^0NzLH#KSBWn-d;G?s|*xpj97tLO; zmU**Yyn*NYu|e(YFL8|LvyfFbm!Vq|@UO>ijZe>kX(!a$P#)CYkq3$tB)x<$)&b=g*zZQDkdtuEWPZFJeT`E=RFQ|_|OQ+wb0p7Y`UgBvIE z!-`n3G9%W^%#k@~&K!f7&pw8=c=iYZwPljhE)V>Fr%govH*JEWlJZt)Jk9)-k;_{Y z;$O*0t7EILNFzi@82Wu5(8a=G)o))r+L4%HF2k{=Qes@dY+%ztA++evk3cno$emL1%-Ef%Co$GZdPNeGuG?kWg=(Jdyj9^3#sW0N*jeF>`te4HYU1= zs~+hlrS*MO@`jW)as^s)le046PWUn@nbn9-;g;30!nSryQj6rQ1eAsZiDMzw%zpr& z2?jX-jGhC;vi;8aol=+}-kvqsC%vrnGNf@15j}a%%KWU1mL=Lw>)gHHq$&e!4&?z(EZx>GHV)wZ@Fqh9~ zk(l{7u3BGNmRHNfpMEs6CQu)=x~3nVb=TVe;oFZD?60we0L~d}B|hW=A()gh3Z9MQ zTzVY%;6B?I;?+RVv0oVbIsjhPY#Z+MzW$+Du( z<=JMa@46N$>pCi}8VNOugTU6;fL0?XPj8VvEBWd=gYNBmF=MYzA*MenK*dx*BUi%} z8&KAap_*#9t`*ZdT2B--ChNpyrnEcT`a_{2EFN~sXcY8@gYX%e-E5tlKAT^A0l;~@ zW#1KW6YUrWTgrIwd*@&%G6!ac$;3Tx37xV39weXbv3+Pt#7mF3 ze>P#2@fj(7u5LEXQZW$AEN&GzxL%F#EfNo%{gU#i9~iQI7RE?$ayf6Y{f0TkZ-;pl z41=iEGsHBXuJ6*x;J?q!v?pN5I&Zlyy-{7>LWeW{dVpoW*cxofxMuI?bw{7Y-JlL= zI69ijuCDX@1oxWB(|^PwfA0qJbV~348fOEosfq-?WV-l8OVC9SmWI#MJfi$~9ebO7`K5f?nv4-9~R~n8s=q6*-7=L$O)*`Nd zuCnG#>tnLDo;^MsZwPkDUcF7ovIY0pkQT-O0~w`#u608gGGcbIw4@DVUlUp7FTFgf zdR-T2r);c(P(|P+2rw!8gU~vVRb}>Z)>Zz;fBt{MSe0ZpKMdzdL?8nbpv8r@Na$k@ zPGO7Rd{MeaR;|+=cpiZI{+zp3?x!i@tZY`>KJuWv@r?AKkv%yv2a^!zyL*9ec`HrX zt!KdlrfjaFHD2Gtc0s*8f?no)_QgutaL$vhvaf4Sbcc{tZX zAty^92vCoSybRN^7~xu;U6=$U8S^>KG;uTK5{|wbfW6dnnkWIHZ|dhF-c{Vdj%*9#2FN z;ls)s7vp-TXLG|&GY?rdNj8o&j(n;NP{y}_h350>>}~bR$IUiaO#L^rf^FNDeWWJB zwUZ?bp0~XkmOF%6Vm<@=@reCnKYp+2hflvDm;roD8Iw)a8EadeI@RVV1y*jwT1`oY zUMwQhL2ADTP99!iHlfFXxbK(d)3K0yzRpQm(J=z|sQ(|GhEpC3O=S$!ARoIylF1G1 zWNh4g0qmqCV(}U^D3RfUL9ck`f--(l9=kQMtqvy)v@25j3|@Uz}I5+DY!ngpjDhsBf$Ye^cWeE4EA)aQ&5$cR< zpWE*63z$3L-Dr2rl_!$gA_wc#{JQvkC*#*ML+*^1PVc?Pkymu7>Tp465^I);pF7!j zUs;}qf}q|@aopaSQjq6@kRo#83XC#hpst2;rQ&9<_M2;6S`OE*iKF;AvF5JJ+>IT< z^t=1d7((xJRNuqe2kT*=F_Uc395vUT24txcQTGvl=XtefVQ#$b<-Fj>v)!^j%^5{l zLYQ`b?J|0HCyG<`V)(ZI%a{3;d;!0F?O^X~o&A+x&y(CtuQh>H0tzN3Oytxm6vFK| zGo_nI&`spj7&rGc?2WXP0{%WeRjaeZo}pCEDpD)+Uqh56)FhBd_2@a4`AJKhsqMGh z<*zK@)$-Ffl>q0~!o)29RZs2dXW!MEb%(lZ)#-9io1J<|m)86HFTwZedv`7Qk4cmG zg&A*{=gp$P`F)bO*AHj^7hchJLGJTn|66z>DfcVEr0GVsRq{Tln9mFh_@_V*$6YuR zC*UsG3AMQzEvA}GJFVx_95}N;O*EURAfRu$EPDYN--Nm8se>(=rF3rZfSv*KovP12 z2;5|3`k{6@?$oPgg-f=%DXB7zI*@`1z%+I<>>GY=eE1jr=F^dgP9DHAfgbHU^brN5Xi3Cjy#>OBywvv&j@lN+tmAXU`Cl-J@8_bW!*8%sQG;~#St|YfW`BSEGsu>5KC8yUdDt)=W>rlp0qDRWx4}5S> zyOhrR zecnZQ09znrl#WwLpMQq{^P*YIx%%>7&zyv^$gOWDdiGu*HOHUL?!eFHzos3%%d!A& zv}afb?Dw{OkFciejuhKK`3*~U-kpCVhpG2d$d`)t65n^rIps z_UvESE6AQ9KI-L2<$vBTp#U3R=TQ_#ilOB5B7r-^|!j>)Yad4Mmz(2Ho4@DH_RcwUI}Pm{HgyKsO*k4mA_Ru2TsJK|-Zl~cIF)n@bw@AfUR zWXs?^S^MXnWWLl)b%QZaXF~7E17JQk{3%giuY27?LsAQ8(SzlYeYQ{cq}b#-#2Q@y zz z;T@?yi8+Mwd&vPf>lMWvsuLtL`qPeG zeIip4M@f1a=Hpc7P^`_$YZu7%r48Goyu;8cdK*-s+K39=!X@&M1Qc(PoXNRj?iWO! zoQx2T8T9gQh^nD&lz*{``9`CMc_?mqWp6w=&hcxD7MYvqtwXE7u7AnaakBtE5fsXd zL@9bnsJ|&Q%JV&TO)W*^e@?SVw{Tg(NhHf&#$BG3Y%p`b4#V5B=$UH=NMAlcn{$gt zR$$crW2Isa<&o?yUnLUYgBBE7qp^r?x{fRI3>>Y zOT2aLTq0|`Qmi`bxgVyvcVl9UoVr5pca33Ud`-$moTU_)%!A;fqO?~?+x{|7v!(dLrl(^;AvPRTXr$|u$Te&ht0j)qwa|_;mt;ryW`7C0hQ&jY@Tyn zko3!+>Oa9J+(zKuxr3N~qmBWCF35$vBTIr6`TrLd;s0lR$%OBmO7f}$e`*EUx92pj;f9qBT z5)0h3QCt3HgGSNi`mps1>p?@Xo z;l5A-FNDGYVKn9lawG*a%wsubZn%?;QGek~(^EOzS*x2)J{tbbly-5SwvNH=U7?P3hpwS}!liXR{(2Jejof!8t!8=&{W} zi<7yUwL51A(&ndb?dGpok1$yNXG&*cQ-l4T8h&Iyz@Q^lfS1!B_gkALB!S>Hj8D1m zg`GKlQp3XxRP!GUA+4{M*%?!t&i&1ngoquBnw-`p10}~*dd8IbnBg*blgc_OX-`}P>5ZbqzgI0Wb@;)>L)Zw-NJ_-9eBk&xa-`!CqtPwN@j zUxa~YCHe&8oB%7f^%7pjy2LWP!!jdNs8wH1t|)iJi#(kTOtV|^ETrp|{xi6kXF}VW z#emT*5*V7xOh;fV;M^;J)FW5EMQ$6M(y`@3KZhC|>|3##=g_V`H}Bmx8C6a!+wC}^ ze~Ff}q0TYHX%XO~H$beYczOF*FDtrr-`r$}(d5dm_wF|Y8;2J%ld9_VU%6l^J(A&s zf(dEu?UA{`;h!AsbO|92a2r~?=uG%!w9`hDd^obPXE4d!^Xx{{6+Chp(19`D8d*7} zV*c8ACQ%}S*Y&J7|BhCeg8;Y}2R-E0R%UWrZu;=JujLoZErvW+-5!ko`UD8GCRU)9 zPzc|A2A(Ba%So+9JL3@EC^|5eF#v9b(yTyjH-khh9eqR97i{xxP-oiUb&WlW-@2ok z%s|n>GZRcDGvfT&FVnmd(ECIZ-{$bhSp;)6x(va_Slklmj~G-|~!BAyKFK15v5+;Am!d)CR;nS|~%5CLAQoFh~ zQ<+6T1MI**b%o({`n94&iwYT$+G$RsFhSqz*UPnWeK$WWYc*n&bUczftA_L-{24bE z)yA0r67OzV(}o0KT3Sb^V;(+DlPX>tJ44?CmeRVDj5E@|BJlvFF2+!O?0XyqR(h7{ z`!sPBW%&G~9?|Ns@lU_&jr1u-XxXHBE_|s(e}E9|jcoIdnk9b(z{wIeUFyyrlg&1W z%nMN$wJ7^IBw@47-)2jeQp_S9YpUW(WN~;n+RNgPyq$g@dD#pI4fNATfm&5GS5ybs zo*|*wLZWB>%u9w1jfEZYL}^u;=F34fgf}A0AZq1PX0t1j{CAz{UJQyN}!}l*uuZWeN zyWPi{6!0@*m4Df5rf*!*|EAaqG2N6R%Htm9fuXzJU*LKk8MeXQ(aFcB*cb8Wk4TU1@J&k!mm(~(r_ z42@G+l@JY*Pxw`#I`aN`Zd(~?&=z|Cnci=Tk7gP3N-N@Nxm@63BWjs zO}<0$0A+zgcWo6k_y3665WxQXTP+>X8tX`;SBzWrD7}&YY5WDBTzO38wN&$a13r}P zy~%+3Z_J51)G?k(<0^r^Qz+hRTGfb+_@)Z1>sh09gEm?8th={i!9;p7+Omvn5FRh@bMw zyIgLjm%(XgajC_(tImVi!--(yyug$IS`_!nfb5Ha} z-Ba3dtJr<4ei=q{B-+Wa()%;?ut!9}wRkPeFcL6F+T;8mlx)uggRwr}t3?K1GDTyR zV2@P03(cyV8Y5FApMKlT(Q-gtDtI>h6Ah!F%#5sw5bDUP1T+R?>-AeYP@7R!NKyFH z$>)CP;@WPt2(#?y)Lr>gtdeRIKQ9#WikOK=@e-|+%K9WErx0KvSD%^q7x;hgebo`;x*092CH{S@!T*mgc^s*_=Li;I zM~@+sLx(M#2x`+~#Cxp2qZisN(k>vs6A5h11G&88-PO+}5#C8az+jwhLnr{@y0($k|Z%GFYRUzq&|ISgioV5^bc7rt;^%|+INSI!kz z8W_vFl(WT@q$UgF6W#0VkPwa!{Q4B^nkVNpz zgYph2RKohuM5{bkSUzo1QaUA^w1q>rNS8z!#|V3|{YA6rvO&WT50`e6c^0|O_f%Px zH^rC}Slz|KLv1Fd?^2)5qy&+GH<#rPlPt*(YT$aqkT=GVc~1K$!Ol3V`c(N%m%*37 zZ%ocT_TNf8Xb|1734b)OYT=N?}zVV}VKuAONclKUN&<}+FZ#g$d_yKCl z*=ASq>%X7>r^^47evTm_RH0Vw;FP`pTk(I4@;}f2Yn=Z(a{m7^JDT0S4oCNIBrtGe zM@PLqY5o(!^Tp1<-%mF2e_Co@EH^AL+|d{kk_W>5?po6MT&})~!xFM>^_tzzlGn1< z`!B-%2j#wTE}5BW3{Wn!rB-u!pp)8&g`i6a&Z`fSiQk-FXAb+{rV+8Jvj( zvu4{BkGS9*t_w7`D&Qyf>L@mKGvfmPiGd?05qJ^Hi7xxRdkx5KctZ}(M})BM=#BbQ z8JZ)WVZWbEzHiBg8z7t0Noa&_WPrnRS|ubXFetEUSZL}^&ua7Eo%QLeCah1kxHmUp z*)>C*g2@v9>G(%o+{*@(5D%{kFCCo~F0wDNr@Eg3d({s+fdwMAeQ*a@OqO0Ns+3OG-|jN5xg)#F zC^=D!VO}Hr3aZnH&X-Fu|{xB3-=k0Zzc&t%ur#@S!tls(~T`0$DxM% zuoL_2g}Ncn;0Ct^g}wcd{m${8bXiHN$6|K#6We2n$*`>_tCp7=iQz$jc`u-yI|<)r ziZ*>SwT0p2o=p@BAAkngYLj z*WzzvoHZ1Cl#q>NSz)N>QS0{4Y+%uj+6lN1+sgv}n!V(GtP$>f_%Tg!kzm|;`eV~O z9>={+vBqSJ=xvR~`B}axsP&@BLjl+>np8D^~Jc-4+w2L%P!s$a-%EZ~4k9w^C% z8>{NM6uGbcrYDWoL#_PsJ?h1=9UzMcp*7A_u4*XJ+4e1&aEsl#z=aPs8b(z?hi}Yz zPO1bi3`4QQ?F#?F$eH27@M0UF;nSFSGf8er zoGR8x!z`%zqr{l?f%cFp;*2>uCydUvp&p(fH1?Yi4knGIX!qDX$;|7!mr@jBV{=}Z zBs1LAA->FwZ!9BW$*_APoLs}TY}aR&Lh0??A6wriJ~BPKRE74ob4C5>!v9z8gjobK|sklw@VVJnX&JeRnaLc*6d0?6Gn|^+d6aE@RJmv zBCgV%vD{PAqqPU&pxkhvuyGkVc@XfBmdIH?+=zWV5Kshih&Oz6qo$YkY4X6z`N77Q zz5>%qdrk1*mU6d=M3npqNH@b^kL${4V6GgfN6cd44e@b5Cz1DnTIpz_SdAKYr_S`u z@KE2)b3l=EU4vUD_=;8w1tTzm#P6ij5zAXa`2^Bc7J-66Hy14g{@LZ61!l~maz#p! z@V!LI8NwX!emUtU_B-fe5=w1o?L#AqbkEw)k}7HlOTcDf#!#Q)MU@z)M1<2W=~7ee zdURxE-=UngbWlh7>nhM(mYN8Sc(|l*{z>essjvxAs{oPhi-4W@ER2vPeKiSIU?!i| zu^=#bE2ZVcUHBAwPaH(NIDIbVWc*Zh`u9S!?wuoA|MX1C1qWQ4;gK*9Mx!A zlDV+MGKY{CPkwUag+P5NJ-Ku#scCU!aBEiXhfR))4*uTh_0tCiYUMf*>ke}3>+V`I zmj-?A&RI03CAew9;;=@>V@LSmt-$L1`R6`a!DoPq3h@ah6WZcOM*n240xrXD>|`!f zW@YF;R=lAkE5^M(eE=teVmqGlAe|vpFmhkj{vTlc1qqHqf*pFKg&Es|q^YD$L(s8K z94o@aTn(xh_)BUk)BNDdr=KmO8c`8dE`J<>Mh6BaGtLqY7lQdXYO&VsmCjV^ zNoq+q3R|yvxf)RX&`L*RU8_l~Zdn~p?Ls}_AjEa;{T^1m{n%Aplryz$i;G@ou63qc z`&hw5hOWCg1rWLi)!eUwWr8nBBZJSqk=Q?|HI=0)y;Z$k{6nQNvMkbW$vOjDIz`)u zc)D2`@~yDp+c2>xDfuT}vhB%4vV(vmK+d?CBeU`554~Z6#>$Ea?YV+tNsGSV12K7x z2B+`IL1wdiC0>k5KNDyy4(vmMMrb%ux*H`;t)XF=QNNv^nR~}JqO_@quHIEiW(5)@ zTn1D90dH&pPz>!D*(-*T(h+L69!*3fD_qD;;Aow82@Qvgj)0^yQ)Jb@$f@gZ%$gn~}sKMUjr0r&&{)i&~B zFo*fi-;*qQkg%sAg67%|@6Q7*MwLC#VV5nENX0#@ZwnpUJ~~&z|BN5hMwOtHUqyW^ zjYm|W?mTGb(W)q^MZM^6$#1zj1gBgwMQsr=RG6kzY8_$4?tVU}LTb2MgiT~D;D?Vk z4Dz1W+aJ7+rCVNWep?)b9-mI@5`4_ZT22ZJ!!#mDK5(^Npa~>N^I~RNt^}*hT%~Sp z1Z1{@GaGfZ7g2Qz%<4eXbJ-DpzQpR_jD?Qj~b*cSK+P~yh z4|y`3?(A?!Z`wfX*O2K;@UF$-K!@+SHPjn}=`EY1qhLgH;nt`hVd0L8eM%nxhRoI1 zbLRc-Os?G45ng@yYB-Gs<4+pgnr3GrYS$k^1)1*>vV6;OAQsVUJA-$yoqX1Q5 zpcKIFbjd*CC+WO7f2TqO#KK??I~LAQsS-lpqXu8V{A(ig!b=7JeKP;A;?p1(uP3zp5jZFnVZ}MgP)1}LMDAs(L;N2Qq>|_0y zJ)7yDR6h}}A#POzKye3mt9)G;^wiF~nvOPi-evAD87lo}x!2md-^GG2Q^4%YO+dT3 z>UK5mq&1o*IGc*7^f=~Yi|_>Zs_;xzR*7l^tvy$MhRPgtRtvl3>Ta~BJ0R}}| znudO`YM?40K4o!$bV@uB|hqHe|cNN%C#Ao@- z63kr{rSGw!4JH4qCka75LGeC(EYplhTI}Lut}PVIPZq~%^in;=20$>fThhi6*k4Lo zal0)K>hD{&00|-B8eXv^kuMtomk)NfjEE%!dvjjY(ojh7QDpm};(s=KOGZLG90vz! zErjM;FgH!AsxeK3Cg)PGoprhL`Cs>C3-h;5Spz?9CgI478EvdRsw98$>(?;=cr*yt zvJ7ijToc!we&%c3V!rSFXY=LG#|apl6ckGp?~ozXEK9sfhuqWq*<3}IWd%&4@HxU(#qu!E z;u3O25g3Yt2vZc&A6JxRWbiM+-4Hc+kl8Z`9=%V}nFKU$961~E7pzgk_voJ|NY#%E_jioNnZ9Il59=qJi)`Kz=ki61 zI5gcXT@5;E#f5gP%ip-8wxYoU;%o8TuC zihQV5WU7Sf;$h4$8m9NBcbw(~yn+O6)m_El?-Fz~Wr8=49rwSl+Ud4Bxa5LUn^s4i zQcCu_adWJxx1PtQ=ZWX@A_);B#AoZUpegkJ)Ab6&{Rh>ELr_*Qz5Tw#wE_jr_Yl>T zRb++25+as})7NJuoSUBB);=3H3s@`hWr7};a#>m2DQSAj6bkgZ)Ny~!o^!48xLDAw z5?rKD!EK~Vv$WZn8mt<}^d6O(@M8K@(x;B$gW*rE$H!a})VC{^?qH;4ZAG9#4&f*z zJhJ{>e^FeTt>PyCu9oT}H@az`!>)hwl#-nk_E{7OdI?J?%%{V-htwQAN1blF5kJV> zMl1EQu?ofbOudwo@jjY=c?>+3#i8th5zh{~K^YSzp{k3be$SeicI1@+sgP#_8z@Zt zyYKWh0Df{z(AGrL8eGGJ_1Qf4SA=O3fn#sAOOp@9T`Tx9r&d$OOO%-y!-qlv6zGXH zFtkv+X}dk213Gvb1lT2$RJHe{@ZBAwnpbN%s|h7WacppXbm1AhnCMs)1l#m+QYTQ= zGhv-F7T{hH46InHxX*J3CSI=lbCfK>SKGPGB2BBwE?WnapD0}PJhyOZm$C;G0FoXj zCg)w<{u@24uVNy;6LcyWD1nwraQC#VMUyg$oB}AO=ZB zXAsQ4bxh||RxzmV!!u=-&40qrl=)VbMP4xPO*JpCqce4;(TvOdNvA3jTXm60-9?me zUFhoG5<~dQLJE`suA+!kzT-iO#WSZ3it4x2W1Zx%TkM+r^O`vKG{qapJZWCcke%w_ zJ;sWnD|9RCGrOx2KxjbGG1{Z*&atn_fiKv2o@vDtYCNEpprC0{ZT`Ncf7dv`A06#z z96B73&i4#M2VOs_>4}M;O9b`fl_L2CCEQv}c-NYuAAyd<`6n{+YVl=KlcOuQpI_g* zfyqkWlos>!%fg7upB^89o1PX-nI`9DC~23wL!&$( z@;O(QJGz_ae-fD5*_jeD9gc<7G@ImTLbJ?6!JneX%BB4y2AqfU;8$TGV%U8&7Uo3T z$^>8f2ksA8=^R2XzuBY^yaAEJJ%r`~NfNlFC}`CtOh0dFaf6R~9Jf!1?dR)kotD3~ z`;3q&lQ9yu;bzn)TQrQp8|C7j{G~Q@E5;7VZrHhO)OcmxYo_m4k}q}cI&|OZ4*g56 zCkA@7KiNMy->~GhNfs~DCIrW3*4_W8s^8HX!({u7U!$;y?joL{S?oc+x!Dx;t)8&1`pfj<1^)s%61k%bY#55D392EQbJc--;xd zG5<_z1N@>ybBgA&>0*1I}0VJ8K>ZnxjDb^~DqHJ|Q|F1Btui8#GEkIsDKa8w}@@9&O1x6V6pr-S08X&u6w;toC?A&s-0UNTr&D4tLDFA zwv|3P*#D#Vp#zqp52trY zey>WQk9~UiibwyWdWdRw#i8w0zO-ZUZTUI5zHRSRa&)IDnOad}GJ3_2|cc=%|D`i$y& z!H!s%uCz51rovctv6hvB^$^ij;Yr z2|+AX5E6VPA`sgdA)hbE7{m@mRZ>G&LaHF0c4>c#`M4cEc5(u#2L+XZp9gf87j#t^NMGB`HAN;HP7|+l^e%@-u~8?CGIL6KKs57*d|bisX340gciVYCm(WXtGm%0t$M#;O!o}@ioJ8S%Y^)X`AJ@zf$c^TQt zw>@~<=xf4peol;dcGUCK(T!vx%v|AGxs&4}d_W=iZrAKud9F`cNHA&$6kupeCx$|y zO9_TC`Q<|4jc8jPYE8-6&}MNsA;XA>_Y#S%lNSAJVvszNg@R#`XPaN(#~CY7qL%3> zKsjof8q;Fc-DDaui_n=383OVOhfS$_V0+>#PL0QyW9+XJB^O_glanx@tXfub$z{nz@zE zhvCejJiD-xp0uX`sO%J}49pHY9^G?ib?#keh~D;p<5ZkbBCvb<@D->twrJq=Fqp#Y zs5WKP)Ws<1%`nY>|F#s6l(Q>aABfuOUOYI&BAMsmddO%8eL@UT@kJ#2-Av#|cL|yD z;lc1nq5j_2qRgZBNaFxRcpD@hX^+CMQ)tc8ESk!UpSjM~cakgP3!lST)VS~lluDwW z{Bli9#5^ZSbzdZfCwyLXgh8}RwdX8VBrD+HmnvBrN@2=|&!U`!rPFdDNcwk%z&@rz zi?d*H(X-9lgueN0zCUyQrqzC{Al+S{dZlFV2qwe;rIIm@x zP!?;zh%+aL7jLloPI(oYoG8$~VpFTgmJS=zmp1u2&pO9TQ(YzhlLR6Q^O8##jPcARZLVpSUw`Fup|5vr% zc8F2bb&J3YnW5A>>j`r$r~v1}O~Wpwl5*-$Gk5MpJo}~=NBm#*Nko)x(>~o0o_rny z$R&KVkBHR=B}95JpF^vBz5mSx(C*q-HIX%8uEn67tH{ULaNe<|&pl=C1FYm>9yqY( z7LMB2jnDZeaDMb;|J2Fo%&}Iz?V^Zmy6}vWv9~iz86lsNd=6Ct3tIX#(=_4s|1C1D zdTvhbp`?lpk)lOc*5Mwq--0tkZ)l@(SO-48SN=QiaYi{cKH2+6fG_bW0c+mW#jD~IeG6F z_jnJ`lVRwLiPB;EyA-#TuO||VW9d2MSm6S{dJ_avfO4*!H%dd>Rx?@CP-%a7*n3UyF{r9ti8(uEV&Svr@~a3d?2$1o zW`7*d_D`Ks3*lCev_=l^cFe)OJnL=KHLvB5bo)-In>>}SJt3s2;_RezW+jihzqf4u zrJEdP-ZLL~Y3INiDX;SWEj_lJ1P$>C7vlIATxogn&VD2YB;0*VR{<6;zw4p^`} z82u4?shm)t;@XGv+`Mg8^qIpAB*B)2_dD^0rBet#kFa~v1kU^qtho(8V`p^xu6Gn; zv5erB?eCmu_*i*8LDsjmpP9@KI#CVs&ntaE7Li&4um9BZoshML1G#lj{2~i4410<~ z&^Um>u*5N6%fiN1v3G4|%)JWTdjy6bqPBx9y4DDM=$Rai^@7jwTyvZVB*gQ>-iWIf zA9hG}X-%~q=gSoPV=VuiIDer0#C64Ho)gQA&F2+qJ~Zd&h%}MA-XqyF(;AHE{SlF6 z^7$_UwtTTa*|vUs+0_Ux1j~aWp9Fl$&)8oXAD5#YKEi(k)LD5)^ANd*-2vO5TG;PM zz}sw+3-pK=sn}@A!!YK6qmRqCKSkoM$;@SLJg$$n@}h8}nO+~f)*dxf4xhy+ z56zP*45aSvZsVlZtI`MwB2fT}=q+s0 zWzg(ho00#Hb=+X7BCc{LapF?dp&#~riTM;F`o@nxr6P)g zmJe_O&g?HYSlKteMTVb%4nnKzp3Q@w)Tzcu4)ITGi8l>BMd)&>LT*hRjHO}Jb$awze5}WQ|2o-?jVY=xWziod9L|@$(1hdV9^?q65pXK_9Rko9 zsb;Qi3S2#NIz_#qu_K*o#+*e|s_@bK97bAjt|yuPQ1(;C#Rjxpu~fYfy@+q}0Hg?Z zgVtOIs|?>JLu+;pVadCt7((!KzMzJA1dLog_{b8T(LritQ9{PpLhvX;vf;c^rtaAh z4EDA{mO0yUA0}O^Clnp}TYKaUUp%ppQOt7Dhq;!ItoWY~@_1OdKtGYRP zT5NUQa9TUoh+^o(dUZ!Mz{|lP1$&$~&?MB}0-XaCTE)XUmFZk31#O?lM*bdTp9FNA zS_mABX-$ftiYP$gUjI2Jk7kj$%~3WVj!Eh}>(h|s0@cV+cXjp!lbPlet+UCx!SEA8 zg8_NQYj-AdqAwp-ZaC-|)6Hly<8<5F9|^iRY7@M5tv*f>0(%PkMcAMhs(k6=-L{=Z z*48#=M?u9gY#y8T9M#(t8Hx|+V~=Ak@dW`uq1 zoVC}i?M1`2n#XWM(7hN$#pGcxtirc#4&4}CwoaKGT4qZbpSTxr9ivnhmr?)X6gAsB zLjj0IYEk~yRSTow&81q#_5`i^+z*&GCH-0gzEJRH@)igY{9JPoH6g}lA*&8{qfAqH z*$hz_TcX_K5E5Ub5AWsfd9d+*qmvV}q@}mOFt4U{>eeYou?x!3zM{q!8&i$vaGp-I ziOKM02%NLIKPDSkFatGY5u*eKz--@A!GnpcqhOK|o^U3bQ=i!8Z-yyXMZvR_@o-|P zdnxHS?y)qOMJFdD!Y)N`&aQf9p1zz>4 z=+$%ZQF3yo<|_5k&1FS!W(@pwNcWV@r(n_=7xk|p1t%I#@B!j-JM+5nZf%JFRO`3S z2f_B-FkUWScZ{a1T7LU%wRcWAm=M@+&q@KS*xrfL zdrP)c<}X90VT*;i)p;WDm(n1E$n}eKeF1ejCOu#z7kBwcm<)d&I?}U)bwG2h+O)=Q zLXsh&z{XZwO4D46KKrMaKH82&_ytXQT7((tzmKucG@Lrr%Wp;} zQmy?lP-9itg@wGOlhQqOX%_GZ84Pv^XydxR6-Q{>2S*BYWTHC|MgrV3A{avh1rE$p zyVi6uvMv|!PNMCaHQV)q`y5KvQ8z?(GTb0T?$5vr~34@RP+!=b{=LX6zY(?MMdj5blde3 z;NA@4bT{Yvo7+6d4!0{IcWjQfX$m|YI^wgV=+L1r2Rjl1T*6{OXhCPCI*aP4Z&<)$SsB{zs;J zg_J3({pgf0kP|2x@t5em2GCMewgyRX0n-m5aht>G%UIDA03L zi#hYGx?gz~g=1HPi*|2;CBs}4QOWn$dJgGd%BzlM^&>yc9iM~STa^(wo9Tcq?fn?u zacl0soX0{jPq?KsIoU@vI0k7y-+s?(gyM*dWSNx{A8o2>c^X*+G_%L-1K%%IHT_4d z5epNE$H~2HE$*1?wj>g(-#d)3>#=@wTD-9`cr2E{i$m;FJ@NVy+}&bzqs{%e^v@eu zlu=ZCO9E?;)S=d{IEAu#Gi0T2vTqBGbgyE?0}$5HlSH_nXz^s|+}NAzd}*B4Sc%0G z*9HV7FpIRGw4zMoSd#e-j_(gR$^l!5ORl0q2zH}DoPx7y9)+3M*w!3v7nA*BlCd+8 zlzOqbnWbKwK+MC`V$sOY0qB*dQn8P3U=wuERWto^jF zl~=I1FAo%nNG`)-YO*cHuVckZE`PvaK z4aNTnwmo>$6vvn&FZsuMo+IqAM$^*?{|<$5HBYfsPmgq00(24<3wc4!0n7~p6Lma4 zD9~m|NJGFBl)O`iT$6+tv0Ovq{GEq8)?=A$Re#18(vm#ZfR!|^Y)U^9xVZXHZJzUK z4`qTl6?q^R;viP=X!37k)qa6aqI>Zq&}-iwr$kdZK7vlYdJqQLneIaP`>d_ld9o#G7@bZ`yU)DmP~JRv>z9@-7!!E zkQ>-SF?j>O9u9d(`|U9Ci#Hz|gMBkbPR01DCX5V&aA%6pE@TkF$l|pDG2qpMFmF`S zD^7`UVv2lu;5LV7esj91=St(jf`kSm3j|J@I$>;eImAJ)prK&n^cKPZd4^_&JH^3MLa%PvmtgU7S4UFQ{BTZ~NY;tKP*G3|u1y)P9fH zkeDe04+eH9BLj}ivCe*Gzt0S9bl0k{${g35bc5lD{vOji@#{gscZ>yTgRo>zV2XKD zEXj0ZB0Bz-BS@I<0aI9{knjjgF#1d5q$8R!RJ@b}kBJByG0V%Xf&u%7-PW-bV~y`T%2fo|ukf%l5y>NoRR|z9#2rnV zT4}0f+8B$5lSH#lS1y*Pr_)nQFQ(A5n)74`I0OPamkf~z!F_YiHLSSpih&}4+@O|`eEZ8z#@vDBKPR~S9UBOP zVK!EtIC6X^xIB^8Q$fu0l{Sl@aIp&DTYLi>q7V}c-{w7J=`t=va+1PBJ54v08g45@~g(-}7s z@IqOnelP0?he-;EA_rnvYg{dr&NJREQ6^^@^HD038liIe-IC`#joFHcSU5Q}Lh3|5 zCq07rl4~#&Sr2JGEl*&fF1b7=%F}!e)9h=IzDLghZYKJ+MU{<##T5)(69zD0awCId zDS8$?(s3T&6(IZYMnBh&`0<^`N){!eR}$umLN>dI{RA6u@>q+$9kj)j4=6*}ct-}+ zXp}wx%Q6HpGe6u$`FyW_l)=+)Ebk~yL&rRch=0aK(?4QqM7oksAW}&1XiAuQG@)3f z6B8{db#KMdow6|OhmfAQ^5e-^nzm}576iu;XdSJG1@I{=mD!IVcj&!eL5?fq;#a`(? zM4f#l^DuTbK8WOeY2Q&<;fYlC{^9gYN{g&+uotAMkbs|iLAE}Q8ajqf)_XTKJxzbv48rLY59edX@1Yl#$9k( zS7$k(0*wE`%GuOkIv3+4n~3M~m%rN+13Ov(*%@QoVeEkA7mPjw45IHu6YRUD3WUW3 z6ES^vuo~(lyxDQG$&=s0aFWk~d1A`(9K$+O3&Rax6%ENnsKZSZlb;^GX9A;N>=Owu z%TjAg18k1VUtvc&p1x(UCi0svo-I$YAuPv>7ycMV>S{)=;aLAzDG``Xfg-edK(nlq z4iMoJFo2LVCrxJl&0nugbF-XSf@Hca&??BLpzH)@{F{j}c^YIY!>HHBs#Ar3F`e_a ztfscsxm=bd07TyQg#gB1pMF<<0V@kDnJLNn5uvz(fosPA6SDg#!i1u&}-Vk;3x%bL=#3@Rq=QTD@Zw$IhFG~98(*eh^n@x%Q%)Ocy#*^QO z2BH1ul|+$XgO=$flb#hNmY*DB<0~Z&dX>v(ygVi?zXD2j!Ax7b5Hy_L6f~@@zbHL_ zEvfkuCVh)=>LK$U?>x+wa^|?&pIa{egpYX0IZ6xi8;rbJkjiL*9*=4b;YDF0J86<( zvBF|P>L(r7xP{0;dvhJg55xyZ{KMKz5LNql)Mze?x#cz-3fN;gZTrAKZGfMl8S_<{ zs}y7LDjYS`L2DH-6=*D@afMx6#z4m1t%8jW-oh?L)nn$QgFBW-ZYZ~F(6_q07;fKN zndzkGN6YEN?>t%cTl?L`y$JCneVN~*Z+l%@IC^`U+k23&O}90E9rEnHed$vl`1SNG z9t->&xq0N*y`OC&`0e4h?=^?hj0LRBy6`G)n_^&F3m{HD(a)WPF5$MbgloCOK9>nr zhF3)Y@8T!eKusu3+GmV8DBk(y+@IXr%SE^)x-pohs|>%4)MN$XJsv zR%2hA{Lrb%&eh92hR57O@6`kY`mN)B#B)ri?sl-rHmWNOjFkcXSSGh2-SU=t$By)X z<8c~IOeGu_&2C!vjQ=KMi|;mc37u$FJ@exy&?t}Jelkwsjl0vGw7j~ST2mB;@Rqcv zm&>H!A&K(_=~job^w(lRz<6p-o6R}KAb!;t)>b{tMOYyj4A&W(3MUE)JQdbL;K=n? ztJ}bY&EXk1fH-LyDb2FZZlLvD`ru%no`U@$zFJ#Z{`DdE6nHs8RLv8r6iloGt2B;% zDrXx+1r(r=ZroJc;trc8_#OCs|n5F{>@w$M-ya zh&Jl=&+v5KsAnDh(^p9fur=ktMx*{TP@9wH;c#vtv=m3FrurQyV zJ8?Gc{ZGC*ecxaC&(nc}52rpW9S!J>htsWq1Ti{W;iB2@rdeo`9avGiCr;^=9lkSW z^=0t!lU^MD#&1eLa^^Iv{9>;}415dYus0UvgveM1ecGgH zFyYmcZ47jn><%#k9%anw@+9kUS5rtRX>y$^)gf5`n+e)mt@9)b`5)v7~w}d$WVCsnQ@yiSa{J+3X)lP>U1!FBYY_CsISZ%73bJN z%|Q?@yI_#EAIpqbKJu_t#bs^@pT!jnTptFwnksc*K<%U5nO0g^IY*zvoQd(#q3`wj zo|xqH9V0ep;sB@ygpXklTErN3G2BaZG@1a z;+BWpTgE0r}ZcpgaS#egS5+fVuAvug3iP^j?(}s z12|UHF;jB`RXl}Am&zW^NiJXq7Z@EZq}_T)aq? zxi-OkGBpu{IRojw{=lG23aAQZ4W1s0+DFjrAoS=rBt4H?(rr{*RNZne_stC)RQ1<4 z6mWH?pszar$w#PMbG}{ZcGLdFgK2h=og1|bL5O=iLRiRyjW3~tT;e!)`kqDf++X9y zdB#QNh3J!W9Y)A3s~=lSWm=qL52Z-`6QVsZ$&p= zFeIe)pA0+vTRPeA&yW#nG`2eHJ3qlm~36bML|n?m|7Z>)W3&N5rPQiFyWx3fQPmi{A!{Rw|SGs)e%@9@*oanYZJ#F z5qmwzJlMhLD3qIa(uBXbf`RM8Kx;j%4$ji&Iw1tiEHK8_*I~R_fkZhW{fN#QJ(*X9 zk9f~dH*imL7lo@E(PtT7!*#|aHr#DiB}TyNz~sBCA~k40!|cByyfgmB+&tE1>u8g) z=B82f_pDs7DiGPy>m8%P$mrp~;^}=k6^$7)hBQ;^^;XlAw=OeYV2goIX?Q( zy)l_F=n7=J0o_2WKOC%3#&PP6Njt+dCtjw8H$< z^7t+7f*$Zc?jw+Pv|+FYq&G^JRgYEb)KI&IRVYO4%1R(ydW{dR5I3P6m7uEu7gY zL)+OkIh69CMj%{X!EwQlu@=#xA1zl@IT0)9h!zuc>G3*3HG)bmZGbI*wlM~vQpMeT z3^-^RV9Z2qCUKePu_ggB05JT_yJ3o?)pi3)&~o&KZ(cQ7dx1Ehe`;j*C~+D!$O?vzXqWQWPr z{4Av3PSC>F#nV?{#-0or9+(Vsb#PFgD`J zP>3h;qTPbgA+Pus)dP-&D6U}O6<{F50fdDS%zB@0HexlyvC(I2G+6=A49hWW?{*-^ zc&FcG2AoM9X?yILfqwKWdeT6vzpAh;Bkt-1Pgg1x6g0K+(lNR<-52&4x-wdaZs4WD zquH8bMS}6dSka`(%g0n&IzWQivCliO!jG}%xC4fpx#MsN##Sc)!5m|170LjWACRvR z$L;b8T_O(fvY8bbLt9tYrJ@Uz6~zZ;TI;=)pp6O&Lv2aiupW8(UjMXlcSMRS%VY$; z!Qb-oYMMdtkp2b^SsgLB50W*v>{D*dK3fP2DfWOUUQia8Clxf2gY}?PQRwDW&?Ol; zW4euAWlkm31C{rl?kuO1goxG=6}Edb3cMBC6SIlGPHs*y?#!3j_qLX zoyZ7xwPJu4OdUJYM(Qx&#}EPq9WM-uy$&(Kcx#bjQV+saA_%b$AFe+*~ z`+Wop>J(+-Z@?!%@g@YBBtJAf>k`ebIB}3T|b2_@hc5g^ay%NOmW%7q3udttjd76$(U!>#uDq|YV zar8fY=zuLcduBcuTTJ$$VV8cyO=2+OC6B#H>S0liu)%(cKC1y;a7oQVuo|N6b!BymIXtS1suD2)Zl{_v9&Iv`661ldx!xKJ-JAw~;GE&=BKk zV$uZ%w&4i8xW8?xt2x*@D?j7|?!q*eQdqxnb@~?xaOO*y$frM8OY<}ARfFC)oJXKb zuENI(a*ka7-eMSVL^}4Jq8z8re~wQ3jkLk_xb+qKJ^gPq)k;gu-yM{3hoBRuKmJ7e z=l}JOruLiPmcHXZ`qOFtAf{Ld5z8O@t@P{v>b+@Q0iL;Cp1^}9A|F88)y*&G$y~~N zA0c~c-Xx!G=kDyvmbs?ZiW{A&=P5 z4vb7_gv*52U4XHe=YxscY*=MbfayRyhAXVGx?&-761m2-CVc`feA&wZS2f<{qQX+6tPVVQ7eClEM@VMrC?tA@yO{)@g@zgr2bR29|KE zDun=N-Rv{E+CP7lzXbzVivb1xMVQn*Y>rlwjzF+}J}s{;1(P1;OZ0n0{QxMFkykz# z%b_%Zv4B|~aR9~uM!E?dSY!8Tk7I4SGyCD$Ifn*C$pCHSln3-P{`!Lp#B-&wmsb1B z2s@fNt-x4F-7wi|%rTzk(+W3~b!YcNpFE6WqK6|?RARmW8J95IjI@qN<|06KyQiTd zrx{OdXO(tQzgFiEFwm}IW;Gt3fE=AgAV9!s&9WM>2kM4dQImMh1Jv&VE4e4}U!iVG zp@12CTUyXOo+>Sre+VOwH|a@MU%oEQJZXx9{|7A zU{4&&K(1hS-GC3BQP7&2qD|bO-aQW;SpqytA&vFq$ZRJZPYIfmJQqj#l!J09RCEBfaewTI)zw{@g+sh&n!~(6O{N;n zWhR8>wLvwoz?`cQL|cmWc7JLyJ#%&~{od!FVq%|Tl0{%5scg^;(oK7? zoMszK>9zMAO?U5~O-q<>eCl*3J#muM;KsR7g6L^6uJq)iaPdJ{01|P?l}Y-ZJCCJ1 zZab1LfTz!q_K9a-O#9g=+t!o~4XG#MJaG5D>Gs?1NXr+_r>{Q!mGr_HPK;?$Ch(v@ z5F6l_h_hW=#G2S-A50k{d1mN1G@x+^URsm z^tq>AOkaNfg|u{GIW=eI(`32Ti4Mo8I;{52r`p{17beQ}pLk zFzoZ>5A_-CPhWj%Iep-Rzl}Ek0IL_C4u|Pa&>m|BGwg~Xf&iio-;6(K*fd|7Z`^<1 zdith!9b=@ig3HRrpnoKN^~>|=7k~L*BLq#Sd++I`Z~c}BSaoDdLt8o+us>rklYaBp zKA*n&rIj>0znb3h_4lW{9$;l+8hR2QUe=9A_ zG}G5Uaz}cUUw{2%n!#RV01b_k{2KEJ2Gj#V=QE!_o<8!ik0C70r?2s>A@G1h z@sKI3HA7Ho?n~z{%%=Cg_rqz8m6+iOGgk)s5L`4nSpZ>8B8Xm`q=%W7=4E3}*6Oq_ zq(cYC>0R%9ARRn_-~w%LQr@$tyXk$u^2v1i{2VylkM{UHoEyq4+th#1ub{~o=eKD4 zLH~5R^R_+do4(=oY45^51QLWSa68yAWhMVYd~Cf}<}PLeUKy;Ll-i!6$uQGUtWub* zriJPz>=G(eRcN|mrXq8I=eqMEe98>g60`U3NAbZ*r1$VZOPH3KCp&534R21T&wVvD zIsIyyLm=AoCn&A{T6AV$Dv=$Z_&(H~=tg~`EL~%OJ66PN0)}GN` z7FJkwrT4q~s8rK@>pf}w!c%F$34EH67PtK|Py~=0*hYC1x@4ch5dYPo%ji3rojCAz zsiSgk{F{Z_e(hZc(%T+7%*p_oJ0~W>QMi*buM7%>MbuPo__P;qi2O`D|*< z9ZoA~&OGv!84IRc<^dxB1QG3(A3i#jzU|QiX{on3QJy+?m}_7L@ga?ypii-M-)AsC z^Cad5n1`)!tmo0&7t>oFIf%A@5iNtdzA=UdVaR||6acsj6jaT>VNquOG_aNa)K^ZX z_kDVtj)4UY8nhjkp%)P=Xf9uWa4x;;b@w0~>`TkQYCZX4`kgPnknTbl>nVW*_J9TK z5Ck}4GxWF+B~OpKGPZo;g7ohz-sxop9cA=Tv(0!>#nx z%06(jlD^30M%u5AG%=%XH2;FODszyARF#01PXvPC!lcY7(40M<4((e^-}KJ6A$UL# zi9dyXeK1YrB^!1B!ESosf%){s=kH7({KPZqnUm;%uosX0I^u_R5^fgQs3GmGFcO)^ zOU5Za#oa;}u+=q1vOmNrc=p8L02niLOix@>DdC89EEw1R7l#)RGHA}G-}vn((|`9r ze2{emPlQS7EnoA7^!kSmrkPn36|59$%G7`{kWmnd192#jU?-Rw(A2LC52Vh_>(l!_ z@SEv<9C7)D$B(Dq|J3INcad`;b(oeH&Zy@+w*l|2ebkllKW0U^3%Aodo6>jxnZxPZzWsj6 z&G^9Fqes|tr%tCI{d*scbbsyp_M|`l?t3A7u+gldwit(9RuZ0m{<-ucfB$2Q$&~)9 z|Lkn~oB!n>OM}%Hpu4l+%JB^zP{fE+FAnWdo-t-zE2D+LIFfYqyRI_t?(&NuJ(*OB0zm@)|a_UIFHe9;&e$S&oPR*ToY-OJDa2`bngCz)MEwp1pg%JZR`DP-I}Bi(AKrmq%`C7Y!DQzJQQ<0Pow)&*b?c!mAkAL1fCunB%_Mq( z@HKv{jyr#(y*#~aM|J`0qV(XS$I{y#+?zh|@z14S`w};R&T9&woiGzP+J%8L9~0n+ z4bcnSZY!hEXR`$Q1`PyafLjFN5e+Q{e*9z!uwr7eXS223IHm>t6>Ks&TiJe81GS%;}0 zgyKSCNn6A!(P}z~`N1K+kAuq*QkSMt(;(Ax_~YU(H`LN@5>_{&k0E;Q6B+dpP{7-m zN}suKCjH4{N7B2${*g3&WHFi%-Ew;JL`rARg9n(J_Ix)TSZt(+*synW5s|B@#*$5* zoFZhi41nvxO&c6H; zl>$$Oi+ggqYQizEWaXmA%0+K@Z~9;V;fK@D{LA;Ir=H~&V)||EoIL*MotR%g9mYoK ziQ{8_Ur8VOy|1LlzHm7GF5!(of4KN+Iv<+zKUW#v3eWM&7)hKJ^rg_ARaO| z6K?gig1aj;U4A?nn>{r7*+D-U@KXp?Vn%!N)_5t+cJ`!i|IY7B>3{l|HA)}(#EJBS zXZq>zUhX9cx~!>}8|7IgMo?-DI6Vi!;{19yefEo|D%dCy9(*vp@r`$<;SwvQC{jj4 z?;0X5_;&9}pN;P4dh;QC+<(uZ^u@27NdN95pGkl0x9?5g{&s|-3tz%4$~`%NWVO1( z%ESn>R^9J?ZZn_o*z)HjX0;IU>?`5LoqORpxTNkVnmSEPN~yKxU%JJ^qjdbKB@|M8 zRPiI=5`Wguyhz*77sl?1S;pMfx*@L6_l5|19n9=NQ*o~Z16%ROw|!hWU;e-@5$`;W zO4p5-N$W(tZl<$*Q4XHS7g1j4`Az5M@~B04$()~_RBTux%k4g@v z5K`v%rqjKpwD`?`HvPq)`{A_b*c}{@fm!6Qy+3{EAN()ebpB#G(O*gjzW4jn_y4Cq z#2%7kjP13w{{CM~AN~jbb6Q$D%Msh;E#kzXC9rHEcdgQFKqO(w$o!ruTjP+4TH#PcyLTd@$0}4DcCFw>ftE9qDTxIGFBP z;O5W0bLrc^;cL^(;S=d+Km4h5`0!EYc-VE1zeKCwVRN^~)oJdfTY=&IttU>UkAD0= zV9pJ@j#f;4YDY$x{RwL@JtOy#Fxjti^yci|J!~|Cv0)PZ;mHX1Sy!DN2fb69wo?A`-;)9<}hm>|)RbbUYjm23Qs@oQ^&4yXZ#{yGt>e^Uc zPOn*9NJowx4Z^Yx)mw!+AKgEdz8>M~XFvL6TG$6OgqF?~A-JX3QzC;T9n@q>5iXyI zm2v09DFF;zN=0$%0u9Z7d4Wd7W^;k$<)7RP^{lH|3jd5KJyR$#|7;2|PG9rLed%_D zkCViB{KX6D-~ZNE(}^?Ks55cL5yYhHvWf0a>ej$4<1}V#svq5}BiJ_DU6->nu}4tF z6B11sYc4OB8}P;5Y8XJ>n2$`gBij#hPn<+U^cZG;drMr1M<3>9iqu=1PEQ>_mp=Zf z$0GVU)arMz68957znXsZZ_Qxp$Ry5KT;~)e6$1(*at|F=JI8cLPrU1m_aJCLkbdGP z-kW~>AO3Q{x#zaMY3ccM>7V`NcceEz@-X|H7^iW8-Ap>ag5bhx%CCIz77gO{KmJYFMaIMG(WdLt#VS$6nnvzo42K3|M+w1FaO|=Taxqx zf9hEJ@&D$}G6vYUf>zbCNh_vc+PPXM4cFN7!Ky&k#@6G5)gS1Kt2sKyw?lXclfG|n zBYn?z+><`^tIwv#S-tttM}9Z`h4(xF(O}%Eq+wudn&}F0TXUs0`%^IQ_`iSpr+_q_ z?mN7e-tl$72hX19!?F$jsFE;;YGJ0j!YN(7;e7g)U;T(#vk`wavA&$1{K_D`|HEHS z-~9I1u^Q7wbwXa`W4XLA@z{}>^z^6xI*dPpCPGgi#Y(%qCw>0uZu(Py`o~zMUQOTg zC*G8P^lyACG*hzZ>Z}{xF{kTd$i-&-I0yt~iL0rQ?QoAHe0<;cyfyvJzxGY($UZgC z&=ZiQDeQoi*Dhtzet&KKT$=8V)508a5I&}+S@}T_lOB3+O6&=wti|0p3~cn?3eWMq zLve1|>uK|)w95We;gNAVV9&<%%xv0w@L-x-q;s=(X}ouD^i3@vvxSe^WcF6Y^V1G+!s-={`%*hO&@>uT-wJ4Ok+2IuC1k6)L2X4{<$+JQfJR< zT0_I=#`x|k`$s5ETa_sFQ3Gaq)hdN%X@gqtJ}pilz5KZf3?K}k2nbB>Pj`iCxF}(M_bLppl`9DsJ(3*t> z1QkxbI(Pv4@7}3&a1R@xd#&_Cf9BEjz3;p?{mjq)6edG!jOVkM5Y3PmT2k^lb_}yn zHjB^CBP5t-YhOCR7!QY_GCi}#Ey|qaGnJJ zAy{+y6W}nrn(P)WN!(g(g z>)LRC2p^UOy-^5IhYylo`f0uG6W)=+J{RvfYO_CN>|F>OxS;B+iYzWHr6Y$B{IHwX zfLV=qgWJ$Ncs6nIYMoO8V8} zqa%YkU|XU;F6nDCp|2zDfBDRE`uUH2CjIUoJPCu2X%_Rv*S+xwOg^SQXtL@%GV+B| zOvu&Xjj;{^SeWH9D;Vl&w4RF#b1?x<&CIaL6O9Cd&h#v12CRgvU~@e^zrg&7eI**S zY2dT=&o>h{D>8cw!>(I{2&PFUW>#sY*c8uX>pdJJX3{B4!=_=thiXhcZrI}_T|>cE zbU%~o9sAm89xH-pmwM?}fA7ik4Er)c1gsXjErGPVE2KNNB!@c(D;&7&>7uENg!?)2vO zYLrx^d9q|#mTk$F06Un**cfaR;}FP52xAt|>CQlBC3LzwG@Yz;lhuDfhHi$ivJ#9j z7~B|REYBD`VWYvaCQB-*q*7I><~P4P_3yXO{ocFvTqSvuU8TCG>b`F})3?8K_Sy5% z#(oW3@g~mXzL%-T?#jKD6S1>N-_UZnAyZ&7w#sn~hr7nqEPIAv1B>)lLZ^u)%jjDj zO~d#OB`&{>mkyN8o@{-TE>s8nUd6_-vWj`(-K@bQf96bK#+L(6nZT#-Yb5!WSfLcL*hriu9F z|M+_e{%y1MxaG=|@%DfJ6R~&u6hRbPvA%+)Pi7qR33eZ&4kB#T7x6FY#O0Sx#y|MU zza8^vI;O^FaRDJbHF(S2$lHXE?Ha`i^Fwzl)AwL$QM)WsP65JlGlz7FZfh^Tw!pkO zg~Wa#rl&BIg0bj|1CjwL#ZLcQ=B|}#?%Hau#MPIz;u^PN27^5K*r~YdzNhou=?LwB z!+d#!7(Fx*i)-WYK44eULfm+D4X5up+ASEtJvma@fJx>U!6X)OBLBh{i_gZ?#7g|N zH@_l&@GY;+;-C4<eZxSk3ofB4kF4alMLx^JP?$8HKPwP1PuCIaP&>-~?ifCCs!8-6lG-KHS(KqVE;W$cLAOKL9zZ>ha zPnr8pY3H@$&SM2SkBJ&`9WHscRJeI*#!)(NAaMH1cHVUR!sw`yDoA%09K%TxTC#~B z1`eZGW?|WY-S*sWd?%W5_ale!Jvf=+?RFD^>B_4vjRnH_vT{L`7ZN=ks9i-(PIT&E z>7`zXV2I)_QpPTX%(^k|k=FH_le7g9jJboNxaD;=s-ld)Wh9?{)u1pVJr-7XEm@~5 zj}lR^qCr@*K)c}b4(qhBq_l&D9<6_d$?dTiYEHI{`PI!tbGc#f#mT%Jgc$kY=l92f zleIX(`nz|o6}MbBPh5Y)6Z4}y)g}F-zK}QRx4}_FCWA7J z*u1u~B=-{|A`vZDnK2O|^}4&f!2|SH8N(mu@M0&mLKfdWI}ukxr1e*h$95v*w9$O5 zLvRI**&2jl2U87qcb|ZPL}$a|kMtOol#xa{nq}C@>=$2LDJkFEeGfK!%IPRwU=UCu z?YMAEFd~)gn>?neQJugL2n3W2DinvgUsLl&sN0Wy>d|;?Um=SB#`j+nd!~=YYwx%! zrY0ui399&u&pb?hGgw}-{|%E?rn=5JWsrhvrjdYei&Wj$?*ITm07*naR8N26{<15$)(4jkpdN+puIk}5`TH$aWtmjNcjr!2j9#6f+jfU>+!z&<6v4!8x8u`gDI(!4)Q&; ztvwi%$#Ej?;c(tZbE4ozlQ3Z*v!Hoa5t@{eikjdCVLsf41r3Y#yNsC@eV+tpgLZ+t zVZ`YVW?6kyIxW^0&E;w^rT*F=`XX_zdNVqHRS>Ag<5yMq1z1RUAT&uvqk26TYR9Zc zPZ`l)@;vjfR%W)$RFxhb&tnJ-R<-l^4PL-q&ovcoffCO(94wU{*0DpLb`4~aUttlS znw*YDpFR=~d~u(oEzz8sar3pi@BuN*uCtZhK9CrWvFMcz{aAZhfF`V`cPe()7UH7D za%}4!i(SO=pJE|&PYxH!9#Oei=aMMsA-!}b-U&1s8Ka**b>&9*FTrjEEJ=bS{9!iM zAx>%#+L~TWP)-6~X2@tW>nwUYkv5^6Rxro93RA1gE}4r%l)wKt3m?qYeMEbCWdFgG z+U}g4iK{N!PNXY$N=I_bJM}RWaQAZ^`wcbh5jkJhFM}b9@>ek%oaVKrPN~)K1}U$( zS6CNd&At4wKr7+R7gXA)p(e~A->>F(P^w7_x!XE0uFS5q#iaC5K9LJNGS}mcG z5HU2GMzYd(0Mji@G~1dJ+5q@N$8P)8M-Wm6;TSxk%UqBEcPDhsvKnYtS8+slKMj*6 zK|XgTNc@VYk`Pg_z(f_NxbKGZ#LWQ(LrLN`@~BnGpXOB5MLSK*H|vDg{l4$}j?C)p z`_x_Qgb}ti`$ahrZLc;9Sw9z#A7IYLGjWPJ|DtPl5>ogYGzDsE=nt?-lS%Mfjertk z^?BNB#UK6Q2V}|OMVHoM?~Y!~Pb|g1{<$}2d-vS?M0^ZpZi2lz+Uyb3!nCy`P5>W_ zA?#`4_fdlx?8BT99*oezzJJlI`VLJ@Hpi#+>w($R(Y}f1m0@5|0wYy5-4!|+RmVq3 zJ$zZ(yvu5DS1hb;$7JjA9)d>Tx7t;}8HcDT_FD9A7|sM*catfIWn&=_9R6jewc~78zCaWpOVN zshT(*t{i$S+J_#A*2(?RKe`X%`SCb)?3q|2#{b$fj$%m5`Ye*Hm@z}hOgvL_2UKNl z<46G|FkHpl;9K&+q}A{w1oSPhd@!eko z;$CO^Ds9jwEaYcO=G@G)H3!5A?c~b=b8WtrNUtF&T^+-w9e8}?FQ1G9C)nAQqI+kj z;zz&dTjHm__uJw!_9+NL^iJTYItihsre^}AS%>H_nn;s#O)-?B_WUknPiE8p@P1{t z`7`%_~`PYx{{_fkU8TxG-ER`SYkn5Zl{{M)&6LdJ!RUYeeWe93T1U=ctQzo#IYFn74(M@%Y_$-)UEZ z*cb6vZWDK|fCps5%sUOt$xl#?W^FD`9Ph;Y-uL0mf5$Doc*D2Aq;wC(?96)nRWv82 zKf8B{y+MdJ1x#zqd9Vsif~Ra7JknnW4=%&>;fM?O2qPrZDVroN;H_Yy`s-><(AdB@ zbnuO7qOA}f>6A`5Um3DA`y4PX^*Z08br}kctElotAe?Iv>RcZa(>K85?ByHc*xNvR z%$U;8Zyjy4?3g>d+n%=hEzkWHqcnoR^9}*$uRoLP?wQ8j;JI^x=V!`M%8&k@PY@`W z|9tB41=Uw3nuI$Gu+lnBrApKmZNHhSNCbGC(NLCH(3hYI=J}#7Ci-U7a4uvi&vI*M zFw{Djny4jS^|DLj<`@4+Y9?HNjqucF(H~>ix5NL>fj(q=|<6Bp)J* zF{O7bQtp&1bJM159Y#Y9h#CP+xzu#@DUjhDVV*Q>($~Qtp9Z~bD#pW3`KD{Gj7u)t z8(1aBahRURo;=K^emfxCJMqLbCt^QQr7pwn{Knn&_#>S~MLqlbfHsNdggsgtkn_n59xciAX@$^Fc(FZ>fKm3;KnD2~733h}6 z!Cn$8#QbhU+@3Q2_aN=rb5ZVFF+l{kRWz1b2fAarQ_pE!XMV2}Y@&xbs2a+Qrldv! zCPgj87*xByW6q~#G#=)c`1d;ZrzmJCTT}R1n*eVt5|v8xMYOC9r2L6fz&-kr)MP}| zu2dc5nC5Do~zwr@jn~Rs-J{xa-%eSC;SV+?)16-_ve<#3?YF?Kyt6CxY)j$20`pHbk z^*8K|Z+-2zrgqoRzT0+A#A|QAI6nI6L-D|4i?N>&#(Q?aK!7LFJ)rrZ9`IichGPoc zu!1A{3L1#37Q&;P5p z;|s_$`mOe;Chj5s+VYWj>vvxfZ~MMmK))+_uc4rcf7Vgs{mPyp3=2Q-D1B`Z5QM`6 z^=qr`1zeg@%-ry&wsdPsdNl)}Bqg0NylP6?=DUl&jgRzDmi{@av zG48&4*HjQ~H=bPX5VdD1cH%?PWg(u&$^9Y1{oZomVBEC*nz$5a^jmMdIzIcwgE3Fv zYVIil;oursB3Q}b00-JO`9A)!eTfsvsSP@(T39VR$mn7Z_|o(s>+nAJEC=1eH_+UK zJ(6MUdivM!yp8Sp!^cFAXK#GygO9~2t%w-SFMkC)cf;B@Cg(Hk>g!*3ef(d)LcLE% z{PM4UH2&`Q-^_T&7lS>0y1B;&j_M6I=Om2p%5o0C)b25ZAbM$u@!5qqsOf<10HsSt z$VL| zwTF3G(Sk5Dl^%G{iMctWOYyAJ2mBzs4Le(h`ESFdO--!E^;cKK{dC;_$np66g9qZq zYuE)G`08~3#~*lLP|reKf89jP6P;_7kb6DMucZ2W*>C(c3_rYrCgqXhXXAz&S6z7u zI2tN^Ii_Kt>X@?r^gnnT49I_sKmW_e;(d31I)37B-j>fb?d;>zGRAK6yczh5{yO(T zpqi&usW50VA%;;$3*kVifV?a_{XrxxNib{1bJ z{E{1$wYB*j*!8ZmuL5z<8tcc z@p$z9FT^evWGH@2pRrj!9)}4Xy3|2SGS_66^HzN1-W5!;=85z}Yev0QheFX*T&U5n&}&|cSpnkfk1x04}JGdvHerE_`Q1{C#o0b zX4vj)USgyp8?%no%5ZID8}A6~QM!;J!01e-gSjZN>8Q>j!Pw9wi21d)4gsu24We^- zxf!4S+~cutpF)R-fAK%Qmc4RrCQ{o}9K(O0)tqN zU$TSUhw-Pv8M>bY_VLuL?A%6s`y+QMUc+BR=DUmbV}iNh{vl&TPf`=Hwn{nr)tb;; z3_=!7X~TJgu%qUlA~GKcA9@Nu(8#(AI-O5bCLQY)QuGi=n0!5*sS76I%K4D9Spf+B zVJ=dHWBwofv82h;ViJya2;697Fd>&(+|FXm(#L=MKYvgBvtRtn?a4l^*sXeAiild)V)~sg?d9HFnf(uyD;m%yD- zH6_GZr--;yNaZwtpk8Zt`4oBBtV~IV1rvEGwJI>hR|CyP1L@%Lm6LJn4ZGvU%P&gv zt7S|sw!;X`%wdC04Sjti_FjTX$aIeBrs^Ig9cj~yt^=ht0xN8Eicj@#@&&R(K1SwD_XQa3KydqYgkd=i1gLj2}$ ze>DE>zyA9Ws3)je1_WjYI=h8a$Hhqh8Qsj;e(ZbfSiJb^UD0BGIWID_E<~#_C=A&x z;jETHVTcU7z8&>RrRoYc8t@&4&oxpWV_BTSm^V68L#9OLLkDaUCHdo$WX@Gg@ z-0*36Z^~?>GS~A`ro)W{$yQ^&*3)-J-x!b~nhC>w*Kxpl%UfQZ42W#nC;oCder$!X z;=u69Lrc6m;cnL&aXnE4Uv=w?a2h{Mj|hQo-_bTS2AU$B^p6mw@4bKgi6BTH)z{+? z3WsM7A5VdZ=4JKT{y2GjEq?F^UKhXfyC00ZzVJkRH5h8AOoxuG$G5-cqWHnTc1v8fhs|Qi z?#7K>w6;Y7{u0^(r+1GeGgKQR0vYd@-vYR=8+Zg9-=a=Ko`WE>-qD}05(4G3e3gYq z#YPZ#VMAcVfSkkM7da=AeT@=a6p&`I9O;YDS5v{-TqhoU6HUc7OakU-rgO<&g4#HE za6K+394{m-iuTNM@o9-l^4a2 z{;fA8Ltrn}OcSJ|3eQYR2HOXMfY-m!V6RgZhky4hLTI}9RgG3|)rZl8owVIPAaGjc-#9U(;yKpx0 zBE;uC`%lD?N8b}a{H9mOjhF5r(pcbdPXsZd*yuO23}IAjXqIB1ksi~#x@``=S?TTY z8&o|W9WM+BlrfegAjSTS6UNG>gj|A@=u7KT$jOB zSi!LcE?7i^no;y-oALj?^I-hkKOKuba}dmoNy0KQs2P{|i`;PICGp-rJ&I6bEZ+Y6 zpNn7k`M=MYeH6kJTtIZU7C{(VYC{N@+eZ)rnVzOfhI*}`zFfl;$vtkA@XOpM>6hMtCIJCO;#kEv;B7QTi)(evVVf{J3-SIxeL7zA z>Q}-)EW!Zb;?H+ci$Tr24!D(XlMeA&b9s+E6-K;+@0+Gult>>O?&RJg`r@HUs?sF5 zd!8`J(@mmof!M|on5-KyO(sf{Iq^O3HaRhq!lYsr$C|?T(i~0DGF*7~5&o%Q`c)qV z;nv~#RaZ7DID)_n3j!ks2?e=gT1gTgVK4IH?-%mO$p=DiMZ*iUGZ(V zz8rZvexxuE$8a*8a{*zocXKk=t|rWbi(Mv=q8n7z*d(lnCSesqUP8NuI^Sh1&8k>% zCBz#@_ZovmvMhphgUm|alBpO}IgDc^7|e?dls0)nUnH|#o85e?v2-|IM$G&x&}t-h zW|4Gfbao0bD}T+eIa$&z*(csUE~c%QUOW-+!;HhWS-v3*vN4|813OcgBTn*;%}Y4= z)SP+kLy}B{(#I~+Tz4n-J)wMZp-wX^Gf_x}OHGAZptj~|eHRX)&Dc4&Gj>j}u^Lfl#$XzI7;PBFvk&26-*Uf) z?1Q}}d2^I5NC=cqpOcvPuO^vyng2P#n5#189U`(3+33CR|8U&@@RLEb+<5rFIzMcT zo+Zr_DbMtQJMW4gW3P~&CYN zc+Z{xJ{Aux$A|y?@wnqVzB7K~9iOC<9dZ4&5pR6WjYO@}8DAd>uowipK{dM6v)11h z$Cl^gpZ~%;;@Ycr$5W3#gZ5-4;-O<3J=uCP4GuLu@W@I$`Q(YXl1*0?Wav+$W?NIV zF?>AS|0iLvwF2S8yJ&u;mX<%{;5(u5X`sEx5W&<_rFB9gcbCzoY@4LdGJOhEECYPl zXwq`&Lt=mc-m`{jR+orHaMi3Z5;OhZ_O|13xsBKio z*A)WBHPlxlRwM*#wJ(gz7lQ=JL_lJu?=!!hE=18~f%9N7v(_NA|_c_8s_6 zAjMwL7vsK1 zA7ft-%&w@vsVNu>KQ8dJ)r(!tZrpO?6>;-ryW^7i`FQc=yWT*XIU}YYs)H~d zNCHDvfuF`llG5U>3ne&qbd8sKb$nnxw!O zCLQjt;=U+|k0El%%felQsFZngIp|{k4yybRk24F~Q(a_U{<+Sl1RXhcm(n8E3-BuD0ih>hy&i)$EHGA9(u@ zA>GCxlX2_ZP%}5p&eq!Yul1+m@IpWS*}wc9cEvs(|M^$n8~@;~|2Va*UBkars3jV`Z^{xluR%#lLz-{HI_3iI^pz<6``yY=hFWttN79a2fNo158m=#kaL(X!ZW<}oN97JY-?Q{}J!rR&Gtaknt zLR?6QSj1}^$vMNjCTy6aYJSH+bZTzZ4$#$PekNgwZNyH-bL{{zxVO@55M(^cn>?Qzvb22;wOLTHgGc`jgcaC#4q%(p>%`uf(JI< zYH;E>@ZHsvh$Dmu@Zgw?9}G@mN=x=8cxNn4RDrh|Ti!iGI)k(g~B;|_+0 zNd)iFhc=PS+U#0y(+W(N`! zZ8QRIAUKIse`(cFn1!%+QPs@AMN03K+=-d4LxON!G#0r$!bIfm%`hQdB#EM!I`6Q^ z0(je=9dX4ayHjIxkZs*R{DtH3(BTF42#~O+Z}@X`u|*!o-lIW8oTbHMF|%WP+yVo# zXTBLP#eVD09z6_W!XgihjJBhVw+vJY2kA$FJbhBS=sOL-%M}mHg;Ks%!j5WI=Hf5R zwE5O7O9`R-8OV6Fv0>M5M)QOzd|3K0eiO89D9~kgZm(fhRbvkXcWh|Umr25!w&>6P z#a_(L?~F-ykd}BldWvwIOUtnrV$coR#?vH4(CcSIACmbgJ?9nd=_p;O5MVqypBx*- zFT&B_x#L+TnJ0|De$2+lKK?*F{Mhjf-0;2M74gcKPs1218Heqqk~&O*PR432I^A)I z=xuTH^^@_)zT@%f$0P3j?7eaG?bkU&sgtp2kcsx;_?7?jr{k8_{YqSRaV!4#Pxi+@ z`nlhYfAo`Yh+AK@mwLe+?!3-!;El$PSW{yFURdhwjQ4!-p7_{%J`g|jx{G4ZuH6V0 z)Bs3YgOlt(PTaYfsS^L3i^YN3Pdx?>s&()yq3&c%fCCeQbLU0%11`KjnJqF%K2sQB zeu?#x*B!lExwi>Ye*`kMKKPVp|K{i4694@F_`_J~ABtc6#ox+0ZoheFyzx7~72%9b zOJS_U6@G~(*Tldh`c*yt%R4@t`Cod&SiJR(d+=pb(1Nz0%?6EVmHYJx1UE})fCyW> zG!>Ws)Z3B)0Z4KGy*P{fAUGH#+^!=a%69?|;G8;|34>^Crop=>jOYhUm(KjY89jn= zuuaAR_|2deRT6)7xrc)e---O<7RQXtD>%k@TD4dPoWPjx)(48I$|uU5N?C%@|9q(1$|iWPsWL*^>_kl9ppwjTS7Uri2Kvgll63HL9>o~mMn!=1WS`PwLBfQ{; z`DgB50`beVBpkIqP=RKYsfu8v%jSPQ2x|o#B{^G5N=BWUG*@aEC4-bg1>xlsN=*V_ z0cJHAq6S*hjPQlIk zc4f>=O@q^x5H=NjZZ6fiBj!UujM7&O0R(qNK#(IT=^yu_>Re-uW4mUsHrEDfFE<3X9`V0F8p$KY?K_GoZAo>F(A+5 z_fZJtvg-s{V>(KEFa>}pMCxmG3_6U1MD8&M2fY>WLH(MuLyPkNbh<`+e`E-r|lGy{#RiF zb=#%i!hEGiOj^TVI(L=GNd)U4`AlabK2E64dk>$8nVmRat}T$K7tzKxtRv+Ub>&(v1Bjz6)C_%u0fLQ^@LA!Nh3^dS@`f8OitoOD7iD;J7%Tqx#aP%u zf)EDykP^~3;?7S!9QQnN3c_NBO~Yz2OW&@A0et1`j_6&<`@>u*sm@4cFi~p&v%^Ml z(ol=k{@Eu^#%DhJL|jR-(#- zpbrUHLu;>6wjba7x^InN`_+%f(dnn-_y2S~erA!JbIe;D$j1!p&A4nZXTSYhE{Tu4 z>j&dI-u65B4L<&v$KvCkiMZzD2V%RvO>R!OvJ?xa4#x_izj2Ak1jdTnUU^k4tsIW= z39t^%Y_+jDrWcwL=8EP=W8l2{GJXuJGjYQnlm`tpH_V;d$qd#IZ1$%Xgjq3|9%b&x zgw)WKOm?OTP!X~Bl9>#Zt&l`NF5%T?{-E>)_rVx2_r->}u_1zx2E@)TJn?_<+i#CA z9=RV4$vi~)$#~5jXh&Mh2sXeW3JB1i)LIBzn8xk3NkSb@$HzbT*<_SnbY(YQaTAfX z#&uRVdenGoNjhjYC&4*2+7#O_tvrQ>`r`N}|Ky*>5B%sa#r+ROeCTt><2B#$ida2% z0C?{NQKI>1A)JA!7zfvxuGrOLKM@5+z6UrLGpp`0p>r{ za3dVt6w%5K9eE~x?Z19BVV#>8iW7lLA>Po=VtVy7dxgCId#;Y%doPM>uiU{q!qmzH z!QiS9HtLrqU!(LjLLe8Dud$BvsklUhnll9*YDJSOz=V-8*kG@ner*LA0UMqwXvlSs zAQl|G*55S=2y}EOxhp*(NjoH*@IQAf_G~;9ffaA=;IoHxVU4#<-Rd4`7H4K|w z?UQCTqjYXUV8nntkKaXephD2QfI3NNjQJ@}atbN+))~CJwh{}d{l}3G%+5~7D!u{| z$YYxMuW)?#rP|B%UP)c>r=5FVN)B@&+$&`{m^=w06ww(vYpYIzlc|bfkV>SS%>w(}L#01YZt*)+0XM#|Qh12M)&^>nVsG-?h82wx2x>bv@sv9C)5-?JpLC^J2S zVC9J;@qn>~?;UV}kZ{kH?!F7ZyZ$YFCpM~N{b{mx^zbXv+*B=9f!%Y}GJ5{35V+8Q z$a-8u<62v0o}R8KIz zU$wjv+p(62)p_RFdhCFq*v=Y$1bRci&<}+@3k~egItI_- zha(2$dHgu8qcS0CIhZ4vJa%=)WKndQbeMb%2xp^QX?}E!h2~E_@i}(St;Z6Qtv*u0 zbR?&a+^v>HShc$5MQzLqR#x!~VKO$y_4{zm)*va@X*3Z1SVhv_LMzf{0sip)PsiQ+ zkET;<1Jf-&x^Nf}%AI8N=Sjm>WPo$M#FM z#b?<6;^BjTN}csMiAH4CJkk!#D4HM%C2BRCI1Tmrz+;Ewz!6v$;IOdP#c2}>C7Y$G zK6Qt2vL=mCCj)_D5>Bhwu#e4M7N6R`7We(`18G9Ah9sm(pVVk{+e=7KMRfgm?aw3c%EZMeU9b?)U!sRb&+(zJQDHuiDkA0U zF&>pJ)?175BR_Ua{P<6O4+QVgn4Qw5|0MH>Fxm(iGI|puZw!rz^}%tc7FLa0XY7gi z>3@7j{MgUF0*N>#p0L*)oX=;*QR`{b39(RDBZ$dTXL&jHV5<3d-+X=iy}$O-c7p(@}9zT>A4NWYJNMr(iE@okj9=ZA$b^L#C4Ccw)0 za`n*swvgbiEH1?4>Wm}<6Sa%MRuroai9TWPl0(4+((6a8)6 zz|b({d@8PKcKvv4n>rbX@BLx=j-~vE3_Ss`yO@yr z-ukF05=q9EQizQB9t1c6-W{S6PEltMCPb4^wb};G0G*D~*9rj<`h^0=d{17Oc`(o~79s(l< z?{*<5YGQ;{0s~O*~WZ{b((T4lRPVu za&5c|*FS;1b}}eTQunZ^shQAzlD1fOa5iW1lUJr<8R@2e2)3)beVzN78Wq{QrVHkS zA>zK1J}}o%fH?tkV}z7GlUxEqMM8r%)ZUoZkOCs`h(ilV=DdXoN1bd?5Uj&|ng@_HOR1+hUJZlad^hkzuL z2=E>RiA%KmCTRWL>6}7|(u^q>h*g|R$%qw1i%2$ov^bqOpqa?wC8UW5=#%x9?;|3t z%NWtGKFnShCd?h8g^AI5Bu03J(~_@0N+Sq3<7;X<91tQA6Jyo0n$mpc=i2f@T(o;v z213|AOB5rdi8aiDCeU=Q!Zf&3x%Dth_)A4lrxLbm+%%5dHivu?!gdXzhaq&^Fd!vb zo^u-phH0~o0HTSxp&Qw4XYZX=^1k@Gy>aPYoUMB|GS;ac4r3gr_i^_QGWr`rg$}|8 z%_Wj}Kx^veeEA-5-;Q~4k`eZB$B20dd$e+H%IEKBZvS335N*;7K8zb z@hSY&(E3hn+ZGFapGFgAg*-Lz)EKxzNiNa3W18RAvxkslTzJFSxC*2$ma&w(&L>XeU0~?w9Y+K}`p!{K)4Udp z4F?!5OtpCbkr@l%8>O!d0^pg&Cc*~7ac5%8so~Q!99L5`ZXlME$K&KX{~+h0SW28U zaqV8r%f)TISUmY;oO;&-%$kxKSSpTfy9lNnMj10iqraIDgECW?TdeD2(=~(!n1|GM zQb&1SN{{}Ys}LA5AkX8MsiuHyW)c##RTe-0nqWL2yp2-Qfv8B^Mu~A$@);r)``$^e zHAQeCNV5p3Z+`G5uHr0^I-5eQ(|{TkeG$~E$gtEEt!(vSW0D>Z={SYW^ z7FZWM7cNK+2oW?W{Jgh1F5K}C(p;u2%0ZAV#H-t5HOJuX?uR?gt zvM`RZaAvzo1Nk>*TlO0>vAH=+%phbCfuc>Y4?G7axfh5Vt;u{SIm|_uXD*yZl+i4p z#WT&8WFGi~^wzxxdejH98|0h8aoslCM5Sp68|wuGEb+-m)#%u?;d8lmr*n_##73^d zrX-03(u6sIpqKzDxx0-sAhHb5~qLH*2CCvHb#077^jGtEviBZT(mS&y-9FCZ>>GH4;cn4M*KjSb?K=pS?}gYLq#k76=9k#)_geFRnA_#44t% zr;C^ zGWy`WalT(~MW4TEzZ&lW!y-je7>IL)XB?6Je4y6jUNkVFWYx zp(U88>rH~d%)pGG$;9f>X*f#fI0Rg!M(KHifPy*~`?3gd9JC{`sti)1SK>m9udQ@S z(70@{Am%)BBMV+c=U=+qUZ$so8-m%Vg&TgcZtXt%RDA#$C zwi`M|qA3{znW!NdBd^lX3Dl*lm>5`K6&uh7lD4w=smXyjg1V3aODzsegUrV|#EeYE zIQ8_f0qqf0Ml&vndlyp)8r$$KWKfL!<$Jb~tg20E!SqOMsJ#(Rbr=VcQVoVg2l@#)j~WjY{S>{JipsAiiW z%KSFGpUe-7;B zRG5Gf=`+R+D?QHQ-eo~%5kMS3Jplkx&({tRlv2GS8iR?KOPYCZ>4I{A3*4uJg?e2b0mD@A{*pa0Noz%@du! z`eZrl#7|1{jRM#}Dz5;;pd4cm;2jAK`k(lcE)?>a$)ixkK8y31Z#tweuV8Wn4h22X zPXr_xy$baTgiA)1qm~py$ZWwB!M&g{!sN@o(`FMwe+?US-?t@aA~QeUqPS3{7aMqwPmNE>D=1xLU_zHJ;o zx)tErQuP7u;-&bnK!ooJenrOvEDQ7125&a0Q{=pcCVP_hO&u5!1u6QQbXR>(6516* zx95jVNQSH(&ab(+HUX-kW{7Q~?U*VKF|XyM-|eGL$BVqH)mWIcyrpIm?; zW-POU<`_K08hX#+C*r^(htsQ7`6;6_f98@^@hG^&Zi39`j&RR?ZW(5DJkIaM-}(lY zWOGvr4dWPipam`=03dS@0ifDr#`pyWeBSr`N{o(CdOjfFq>%wh^PZeqEJ$E}=?SNe zjE8yhF9g3*Nc}qMEKEw|Twq;#a(1OcS4+^r+C8y(~-6 z@6<_tC5mbmSTV`NLId&OGbNi6|C(O0B+`x&dKM!x)m3#$0HASb(XR&AZ5r<~*^_2x zakiXldrPllM&Me9$3`w*#Jk|0W?5)ckgUl}lufVfKfV>15$L~Cm?y|97EIobQv6sA zYYwN zrVJ%KfEO)(NBQW`gTFc%})K1<0EdmhtWQvIc6zOaZ)lOn3~nP6U<*XR|QAl@H&CuLd#0E2QAFVme-HuEY??} zK^rZ6)Fz4Gg}OG|ZzD*lv+-gV(=2hXOc!K)GAdo#7N0iJ`T!ANK;%H+s9!~o@(lzr z?l+{#shU;zpqRnQe7${~I>E*6Awr*8n3svqWVVEb%$#e5I7^({th?Exct-pVJd}Aj zL^Qd=k7Zro8*roF!IC+C94w~HXI^j&<4Oi9nG*1{JKf9V)DS4Sp`uu5l)eTCIDapc z#Jjp#aT804`hkO3NfLgZckh97E`R--;ve4qAmfSg==ke0w^{hKPLM6u98i{cjPWkr zgdGRtnsJB~hxChka)FE}3oc+>w-EwNf#;a4S!U@J$H(?ZYug<635PAp1ILWgxeb94 z1M)n59}%}mJ&*jAD0Sw!h~%{J0oQd_mXr`0&4GMs1C&%Lbu)^U8VDznC6h+>9OfW3 zB%F`IKv;)#w2Pt4MTyA5qQ`|yMqh0QN%C9G0agke$;gB@za1)!QXv#N_JR9-2nX+Y z-gR|TYRN^GRbrV0w|%2O;0K@Ck-id0kVHyr6Up$7w53E*sYqKN4;IW8QdEieKFpH~ zvR%;(qszjprUt48ri6E-4(-{ETD1%_V4q8vKg|b#CvZ?Qs|2>x!@|x&?fdI=E|RnI z4z}rPAjp>QtZ7#+$t=RzbuuX(E?q^ua?8(S8D4BygVKeruLk7l?mPcXg%+};b1{&%crb7*j+KZMx8`yyM z&}2@qw}qxub>`(7gtt=hx)cFp+dVcqXeIS)Qgd1SA&k^i81x!Mx3(k=-1R%~k{o%Mn?t(qD?@r#FC>%Id8N1H=YXYUVCwzGxIPZ$UUKNy%enJsryZ}Dy&1t`K7ErS+XJ?4J;o!BG# zEpFA3T|BWy-OWkLf0Ot^v3LJbto`r55Od65 z{h~DcZXs+yq``1@UNg6HY&yfl4BmH?`)n+Qm^SUy&FRbYJX0Xcyq@%?RtyHQA@bbg z$Bqyg6yfJ(+YlJ)=W0Epbgn~S#DF}HUns*yvIyw-=;V>uErdXsQqI8KdqM)6#Xzk{ zjRhLoA@k>65m?vmp=1fgL$ z+DD;5k0hSUGbIv*xTZZ;&Lo(%b9UwT$9qX~H!;r=iLjbeqtaCg5^5hXAv%i7SWy9V zH+z-%5+D*6zy|fm{J8k?hj*bJBp>-6JWEJ%E$ocz-^V}3dm<~F5M{||2n1X94Hcdi zqKGRA5Eod9uzXM7(Hbbvfvlv#g6wx1LR``p=9PexnR0O!k}?*q)-K$F7_uj8kpN6c zyTE%3f}oKfj0b#I@Fce(dbqUnqTMV>M-pM$A==L!i_6Ppy`w)DAOw_L;~&shJD}!` zR7@Hig!~wVGTW(Db&SiTC_04ME<`u?U_dkptfd{bB^;nK&6bw{V18(Z$(*xJXT8BA z+}*~w6Py45KHEt|K~%hkc|&W^R2{8@lFgR=$a(Jo=G5_j{Jqz2zb#kcq+e+h5{?L>a}z%8ku(D&-uaD09}P-Egs? z#+LUiQ&)nVOk{?fC!g<$a6$=*M2>=uOq7wR0Uk~EB!SHU3<`XBZdM8V%x4+qEGmW? z+6A5L3!1fV2>1q3_!J&tcA~Z@%Y(0EP_%7VNRe||W)jV;y)sZhCSVFb!5wj-&>(?l z+q9RM0eql9q%yx1zlq%VI=mD8hw<LQ*ucCNNPgxIjbWOSpDdSV*j7K zH&#%Hv=E@AfOIr;zueFEP0crAK%PhNyI@v}W-i&zI1xV+D;Jw2BwT>}=M?iFYr>#U z68g<*u^Q@U_5AcX#@#`ERo09clSFN)wCqk=J+&QbppEnq$;!$!hXqRHkOTv{?1GD& zgnY6ZE{yq4#Iczmqf33NSX{tdJbCPoOA`6%qb3S9nGtIRCKBJ~E&Z|P0+Y-!c**k4 zT=0KTRpzr+v$%j)H}aI5?ij6hM5f9&P&#a;QkR7WMY7I<082l3#>3R$SgG%lCB4s+ zyr!^?@;=sQ8xn&mlVvh(wUqHon}e)=|0Mp(GwGUdkT?}Y~e$BN_D zap5>~1ea?^P2TVtNw`d{%m&LZ*AUZ=!^8!SJp~MyHagF_@;Vpstist_?)s!?EEOJ< zaq3J=;&m{dC2%cP>b8W5J|td{`S2-q%0%RJvZ;v>EY9k|5+sO%2!9 zlJCsX9RAGf+$v0j=A8E3cjaEbE2VO-Gsg|t%TwW1i0c8|gbO5)1if`tm?rz1m`v>| zu$1|;=XSU>&pk@0QA$|THcU;L$UzikUBV_KYuOL9thAgA5gqR*;|6abzQ_v6lBI0M zdjoh-yXIy2YP74+q=a7E6pHY}Qv|Wmg{(dbG5Qu)_3nb;ME}o1%FS#N<``f?H-Z`h@ul$X_6|Ea? z!eVrs{{RH-A{%+6utX~g_w^`TKcyXmnpt7?$q+=t$uorqgw)QtBRn0*nx`H-7)L(* zk@(ZM|5hBm?~}3py2}XkfC;F+uhf&)6Bh{F&)3%+F(A+5mout~^T+v8hs!}%Qm3jHOb`bdyLS5Ma_Xp4Hu6a(o_9n@D!%4@i;%ic#SkBsVVH(Pqb!ES} zskGCTQ{o3xfwJgvf6ykqqfdpP@LsN;KBf|h9P<|mEcv*uCj+(FzRhMX08=Efv}2-8 ziGQlhw(}hak3>&i+ll<=4QdgR{x_Lb!f8+gw^^+1Tt!UyBnhRgsFW#{W%(XE#*(<;gL*;WKZ@^A|=anWwD`Ty-Db023z#!TX@`(nLDF& zfkD9emzod9gQ*afIb3ph@H_`6lR>S4GDoD~j`xab$dZo#0r8)HBixkG7ym%IX3gb~ z^)X(3mSfO^nhVAb!-iXjdI`1mmWqo}YCeAr4^$5?* zU+%L-2v3FGD1A*35WE*uf}ubw*;+jwJMbqu`d|NZ+M zLUV659R{8-m35er#~jciV{O2INC%N|KqYZx8cbp0*uVd-=$<$lJ9cf$h=7jT_0&=# zgb)Xf(m4$QG5sh#ZxCQoF$Z!URCwMS`E$|s`6hyK?)tyr3 zP*qtf2@WbLW&u`QmK*S++b6D5y2w?5PkC?a$v#j}fp6)LwN)usZrUE?vRJ9EHmi3;o@~ZIY_=1OkgQgI!)f~yu#+c6Q94eYbNx=FmV`xLTK)ylF0i?XL zPUl3yJvn!|>yu0aB9%o*gW%SD@iP8zcyOn zsTJAzL6X=`LZ5>ZWsr*SY=hi8^0(XbBY*@5aEeHEp_)Lk?^1#=f%>O+5)_h@qfMNGml2!;iIj#${`oP8DM zaux|HQ#C4mrl`T>xOL`u&+^u#gZt!OLRswE$!5XOGWd7u7nh@4v(iyI=OHj+K%UP} zBw?G#rT`3j-BnWxLmEY2+@j3v1^xDb}>YSAxKbU2^q=A-TG21gs= zS4;t{$K|iI?W02Emp=Qnjr1YcDcdpw$sVb?*CEn>N#-OY;gVJLw)E5m(M8pT*nYTh zrX-GX)?|q+pM*{+yC)AsSy!l+zX>Uv^AvJf{N2Q=E z4wTsVQAu9W4K+eKqvx|y`Nlh^WS1uuQCISjlftq{_RrpxRN!g5_OqC|48EC-Wwr`J zRiCT!9t%9It6X_DN*5{wiWIzx0_C`NEIAL$*j8GuZ%0mU=3@_L#bH(@g%8fT^aIPA zjw;G$JRpwX^j;h9%tOnQDH*eDPxy0#_KGhImxH#GvB=EDL{4qihGqvm zrT$6mSNhK}eP8s?k%$65`oWOHy_*t#HpBZAEtD7HEPr~SQAWI%?*r*aACw;3wM+?T zad3IBP0dQV7MGjK^YV_pIzA;C2(_vtvyA?Hr4YzD@s$=jzw^5`_V58q-&D+@Ca=4c z(70?)%D;&zg&3@l1WAy3aD!g`#&E;p8gs_<7vqVHH}jyyh94=s1CB=WY$VRpceJdt znsYC&6EzRtH#Y=bCo-R#GwXMzAJ*n1IKN@~Lhb#C0eK$3Y(}Nc#gp}-kou>!CIRmv z?1CowSx~(MvG-km1_S_4Qk!vF>A}?6pdzZtR?667A)KwJEHti%E_^<-tIpWH0Cd6^xzGOw;C;QDH+?FUN?lf1U{gx_u1P>-eWlLwt*Y9G zI($x^J|F!QW*2BmB9sjU86^b@&K=RUaF&SYnC3Xud>2mKbAAnQg5$HyX~*2)`#7No zHI|vmwf6>PvOVf>1a>t+EVY(;Id@bi7RgR+ejhPdO6l`Ce{!BnbaRfmP*$H^C}lh? zXZFXR$-et;JfXY(Z7{#makUOJ>QKeG~hRbV3XFB9c^Wa8c2DcSOBL?zfY zUn&}f0UWa(9wkvPrq;qkb=(t6oin^mntvD{laAAD3B>cvXPGla3~J#el1~Gb)Y)8a?78d3cq0<@grph zT}-TFz4W!LJ>`8*Fa5&3s-X9kzo8}1l5*^v^o!(-s+w zcsXeZaKc<)h~xKcqwHM1e||C`IU3Jpu(}j5xr}DwYLSaYITmT6>r0}0CX@)MEGjMx zdC480Dygd0q0`=W<0cEpFf5Xgu(ncvj|DO(Z??~}Dq)@rTB%>+*_7rMpoxA`3oc6} zkU_mm$W21=Dr2+X9cH;qm8JYiB6z>_8KjY&VF8CRk$~T{8@Eo08VhGB%Gt{zwewwF z@=C4thjSh)74deZH7TS4_elAU<#gz;i#H?-&Dbd;Y-s{f;8C(A{WVl#6W$Uvh43ox zhE=r@d?;^3A06{u{L5FfzrH_j#q-JpMZsxV(p~h0N9kosVQq6j(3N+hi+&dyt3D#< z2_+;%rK~S?vQQe3)m?_!T@AerHZ+e^Raf8{g(hy&0%NT|yIP^bt|9P@?9wx0Y#Lz7a5LrG{Q z*%wFnW(1Wbvwj&Q8>Qa-ak)`1C5-?j6XHxt+-mzWHN2CWf^;UgF79tQn*&$kQE}G@ zf7VAGysY@FFmN_Xo3vZrmrQCb(sWDBi&_fHxtuy@3oM0~I4^OZ7yhh=Uos!ge{y)9 z+EpGG4Ts0_%nd%+qn&KNZ^5gHRvZiY^F6KGYH4>c9=t5T_2`xL`7_xM2Zv*VHDZAG zvy$x7Ag|djpj5t0d0ky)R9s27MH;up3GVI?+(K}74ek=G0|a+>cb5c*;0f+Q8h3Ys zd*eK2-j8o)dex6!t8TBlyK2`tyGzd5tZ(;pT~EpH;-K(xqo+BpP}8s1bVWVYpI!Xn zz~YH+6czOI7njO)gM@F9PI=qFp!?}uUNz-J=L?>NZxQSdt zeTv#BBD5c~N+w9yTP;W&r;7H`zcK=0Xx?RO!Cmoax zjVU{&Z=Bn*91B_t0)FWtJQbQ9L)AV>P~VamK%U2En4ehog;hRrV`XOLaa(pD>Yq{C zk=)Asp@FtGO=k(lB9-+pP~v?}RWnR`@@Tq9Ujkv#V(v+@3NahD^693^wVs)N>TcX& zi7DZS#@&ZO#Z3~Vsh80NNbL4TanwD^RP&r?V-`;}5sC3NuNM z%d=5KAycSw@MNrq1y!bKGl+xv5Zy(Tu?QPoVUFa-VcUageE1G!#DAi@2#n{S4@34B0$~4qS$`_qAA=f46np5Lf`uuSkULCW!#a-TL9&4;hK2A zA={zeWY(Sv=^@*n%Sf|0)&(Kmj3}R?|F zrbzhVi2@9h`y@2tc#zqz!?2wN{1GU0g;|~X5cM0_5S|q9kmxrefP8FTs=lD(+UqE} z#+}!fJ+xXUVB5%<$5QXE=-YhgmB&j?c1TZ<0h}>ArIA>8MkkCwy2Wq-R~D6g#~kiN zJo+Mn&x0p~xXQwFd#v`lwB#8*EfvE98vjwS z=FO#alT+hV_;Gs?OP4p%!$IFV0S?K(K#Hzft#OkBK_e_E+LA_02wyc(4sT zbrAvkJqQCSwtPSNuu<1UP=FW>QLh)d8WXSJ_kbdrS#3SPVv=N6+|^k20D5#J`7$xe zH^{+gkUEZrN#$7LxbGf4L|ZKt{K48F3&NY1XjT+4J+dc|^)BZ;Q!G2T<2pyqufoOR zLoqn!AxFb7`{nf8{7(GEm9|;CiD9o>xdMLByer$XS7@R@Jn5)erQ>EReR^9<|MW?8>5LwfcLq0 z(P59iK<74B<;RIm37K5ehaQ6g-_^10&?Tn#d31iDQwIZyPsy^s(^12}d3Q3BO^JTU z{!LRZw`+f=dt(lD5HsSU2Ef*=(kDfq6}&cQ$K>g(9=D$tw9>Hzr{+C6(6?mJj|--F zhV4fM*NYJJ+MEycCUKUO^?C?dU8Jh5_@_WBf6a7G4m$}4S;2+g$_5S_rBvE?9jJmU zHVuq0j~M5H?h?bqB6252-N9+j`h_d=T8f zpqPh451&Cxmzs7vz``-gv^A z>~m(h+8%84jw^E4D=i>8w7yszSPY8ljp7Iuswo&{nJbkQ1=Vxkm5o&2u=5R{QjJGA zPpefdR7XR6U9m|!c3M@~lK>dTOtm6F(~Y;@eeN)Pe(;>V8oPG^x7rq*EAps*U$4|_ zNf;#uSZ_dCzxam2nc@8y8gAM%JqxO#q;Vk45-U;C|1QvoIhQOmK$+u!iSb_L&qzH^ zV36B~j{C}rcd7~4KCV@MxFn>w?>-m<0zj}Zqt6}SVOeOo>K-xb4~`JzBvlEj9eF9V zPa$P>=_SzUN8%?GJ;6Fn=$Ap;#VlCkG##>|G6uvxOJ9oPWcZx>o+NmE=TYO82P$gF{o9?-E-4|${At2d_9o|vQ-nwj%FqFi5A;#M5 zh-df8CZcG}LE>#W3jOIubjxDEcPH+|JF{nWVZ|kYTW0iLZ+Qsl@hg~%+zQqx;XBH6 zgNV|f3bja5qoU9Uwh;XL07je1MO(sEvcE7@0gd@bOFaA!U2-!9AHn=}h97d}5I^{{ zlL!}oa!tp~E2~mKv(y?DdPYvAOelwjXVuG+NX%Ds#J2%z&J3y}>xS{ks3RV;?>f$S z7q_C*a!VmIwA}M;%jppXPC_q`%^eYrXpCCTkjGyQg#@J1{|(kABtqr zbWr!q;L3Ph9tgn;5~f*wjwUYccuX6LiVnzEo4@IEYJg79F4_E)J1A{ynN6IOv!F8~ zsG?p1RWq%#{B;xi;o{o@$3cSLGKv%quu0)9tV#B6OSdlP4^5x_hl^}WvBY0QK%g9d z62WB!dgA%KP=#VKT+`_2uS_$Jll$=RW%4)wfso!IA!ird(2C&w5y*p>)&lN7y5v}9we##9d*MYlNt8q0w(;wueW>UK0 zuG_Nf=jYd@jEA{I5R~@yDs0*t6&~_M|EZee#hp_ok@9WlZmQGDQ{>b7xrgRY#`+r_ zVZSCb&Ar9TyJLm>a<5tE7WA_WMgoob+4fD&S+1+xlNA^JX(y8L8+*R9^VZ#R9^sk? z_LZ}$ef<%Au*PhCW9;RZD-TzLS$zYHG>DsNl(MA^9`L&4sHu`(bSyQCM8}Y z)0RiN^eOgp>jub*rs@g%KI?pYaTOPD{g5ZdY2V~!j~kt-8TXQH1w4PuA||O$qQ#gc zJe;^{`?(L4m+B`Hk%+f+3OCH$=74|y-qo9v)uqS`zK&2ZV@a-cu0Z@J{pLAR|I>)g!9>jXZro~cM6H+LcqPQ zl;7WxAee&uuRe2?^x$97rfuBJ&K}ejBsWd+v%II;$QVUdPYTgszFWbLugqWp?FpTl zWvfJyq@704DOdO5;y0Q#Nk$zpvGX$@1c#jl0tXgWs`gD4xfZed0u$B-IDbSM{Meg* zbX5N?KCTj}Pf@ItN#xUGxsnQ+~^)H8$JxiYaODB{q_mTQd=HMMNj(+w0c>8*(O zzGGr%E{Lg>V{*u*4_8J{-6I9`G?bzTgiNYBR>U3=BxPh%H7YELi z+cIl%9`D-hhGI6a2hAu*ejj7hC3qFTpN{M+wV~UM&ZyFluY;UX5Y&q`t77JOX4~?7 z37H>(`@g*>XmwVENkgeNlGmbNV*g@33MtGM*4Q_h#yVVJpcasl%?1{tksx=a+pXB)@ox6e z+v_!>*kI&fQAogE;X(1Ck%X(2hqLt4;}Sbb*f-1Vy4FQL0giqySSA95MAx{2Hgvi| z+TvWe8^s^!-Vp?b=kIxke|Z@`)Br8$%FH9w+OM0ShA!sxFeGV(YO85 zTj#B~zH<=7C!;e)s9stn6C_ZnWpOgpNA5qV@0ltY3JJyEDI7;z#gc_Xp6{nGO6Lu6 z@s+D3YTAL@EJInF2rtLo>AJAZqZ=rkT{Pmg zhGfUj;#4u_w#c7mbE*HN-APX~p_rt_DNAFU7c-hLjV=f{0tpAF)(tLAz@bJmsKdAE0Rx zd>ppqv=Zk#D5HeQ@S0hKO9J%y5@14Z&(uBMpBfvg#?DP`nxrUbd5#(`p^vi_ny%<+ zM7})Uek~nbIock1RZk#cqEqGBfs9i$(Tc+rPsf&(^Va(|($ll^tHZYPakICo;kT+w zEm!-`W_D}kG4-pW>ON}~4{x$+B@;Y%JLf&?I%`!^@ng2W{-$PFo224t+>ID4=+4sW$xE0Ggt4g_k^FkZ;?Y4x+esHYeYal&>zqx!;Rj&2gh}Uqud5SD z8}bTN5}-*N&0%0~wI{ZDoqhvlLT~CrEsjOBYu4;w7oEAq6MElb`;qdtUza%Z@9CUI ziin7iMiKPi+ap7j;q4%p|I6Ekz(SX>zc7LFM`K*x!xxNW#Y{KTD(Aev zoi;}QEKTBlw^7h?mg{BeY(hb+PxJKImQcq4RE|z9P&P)8`^yT>E<_}%;d^Ep>%{g# zCu?&S2fv5zlj!To2Q!XQErv9!YhP?U4ecDOFH? zZPUd{Ky_#(K1bM~rgUjHob z#3RM=jxXE&&YN%i{66DSXt|wBn5cUE%4($kW^wLlpRx1CL(@<(DC_k%-!-CD0htux zM3DN7ezKBD;cOocGTnK}i$W#1o%)t!5%cUTy0PjN7k`0qz)8Y?uztn~1gMneqlGW$*B-?#E~rmQz0#FQg!6QD{?#&w6Y zD-m0aM=KBRH=jhCVT0->vMom&Oaq6bw@P&;pcgi>Wx&>A)?xkQ1-81+q2O;{l(@(P zHJ0Vw^}#y`P{Rx+H$mt2(N?FDA3wQ3KNpTL&zqq%M@dgSMofT8x8*3y~9C6pZf>vp$s}y z)d<9BQfkW{qOoJ|DYvRp^yOlPD^*nvb_CIFkDonzKlS?{YzM%)0?3xTD6BOvZv0#F zMS9Qh;3YI@1l63f6hdWC+q8>IJPdc%N`xcimT&W7dxz93vD68X#xJ_&g|rBBzIqla z&J>0B9t-fcu0`4q6s5)v>SH$WxjC`@Nt+r)*_v)wG3+Tge{FU@m3LUS#6gfX&{~^u z$WfS5T7RWjN;@#hvB~&;~%)N4YIG&f9e#93IpBU(=Z=Dxmr9cb@fM@?q;DOj}Z?#!|X?R6qt(K%DSKYIWRG9#_tRb^PL>^qfKLci(dotu~T)xB;aJXl;97{ z37DfM?(sD5JHzwK`l)R&0_2=&$$Kj^wx5pKTNAur;JOm46w!qaD2I@|d-vMN!hM66 zzELwuE`E+QHgW$$BFn}X^pQBr_`uFhZU4Kr<;ezQ8?Aq7X zcivOU;E7^JA$q9RCksH2>;ln=4TWg0xoWr@`N9-EuZ;%YK+m*|V0k5^7hUd_Zk!9Maek?c1%jwk_%2{i$aJZIe4 z+2z?%EjlTvns^IgZ>9ON5}{$7gF}2&4TGM~hbZok7e&9?KU`so5NAW+iro&F#cVJGqNx1mbJyWsnprDJ z%ukTBxF&-~39~A?Ct_-7Q^~=5=}ZI>mdG5YFB5=(eokBOIDLFyH_e5Y$J>hn*@3}` zw`}bMwnXbU=9`vxvC`IBzcJ15fYg4!+CiP8?280|gdiPp0aRyue_FMJ zK$B-41^-&pBDvb9PpH=kNCdAfI{8ig#+(Y7!@pHWpr@#^&61c|=Wt0%Cg7xpyBUo5 zN*XOqajT98Q`11%(i}-h6v9_&rbITJQ_{=3nM4#{uM9+$75(Fa;^0D&muvU5HEH

!nC`fSE*Ce3dJ$*ZQv^g`8t1eC)?{GeL2=4SKi*qco&+mM!zhTj?#HIEkTb$6k>Q+F5rB#Bz*z|mKCND34Q8_|1qX|K=z|_;=zyoV{!O}E=Pw9 zpvSF}$VD+;)FnD04yX$Jig3Z$@)&EzFKviIO=~-zrE6}5lSpNedeghdSt0y0-WtDS*Y5FB zKOxds;kh#>AHJ~n5W^gaHvKO^!z=c?p2AOnZFzMa2A zePo{5hrNaCg=I>3E$RuZk6PZA=ldui7~ZQlT)O-RcNjB$h~WKj5l3c9;k$kqTBB56 zEFEtf=nsrm;~{V|8k|?rDY8#TUG?;;S|JL8QC}Rw*)vGjFbYhad?hO2x41&+>nwS3 z=;(E(Oh?qrv=melB9|N>Q(K0m>epsw3nDm4ByIE7Hpfy{4fivEyBX_{TB~69-r*l^ zfEr|U7g|uHYGeqOc%T;gcdVU8VndqVN6vtP*eZ0DP52|-I2FM65P-P{-AsBVPKq(Atl8e=*^dxnN^Dx`XG`MTb*M^&ESQZwVI*E%vLX@hJxQ zBRgsA=fa*UmkFWefaL7(E)X@)N1LfR%rU}pi>XOd(iIGou?f}a^3i-4E|$x=(LOyD zgF1Ai&#gac09}3U?xP|9XWdGRB?>vD(0P&#!EyMZWQyQQWn?CzYNJ9~0;ykSACak- zXtq+&2#h2EV*`8=%}DXMuZ>hNluk$ho$&-Qz6CC(;uivg?#Sgi_bx(ezRhk{1DvK|@C;7=q$Dip__u2Qm#7&X2 zC;x|aYXeIKJ|}odMd+g_O)DzJZG{DU?RsLNuo8{X-|WW-zhvBx_O?+qM`SU(>P_!w z@r2Af5H?qlYEZMToi`cWr1k}|=IomWy=NgGd%S|5#xsxML^B>YClJSC|L}%wpkV_u zU-z#5yk<8*QFNRGeOQ<(Ni2u2-viVAp%lf)h3)`V4Dcd)nMzEjNM47*Ifpu+UBMQ% zJlm^=Tgi@6Ee*_0P1a~35ebe6842*1% zsdEyT88&y9>F1##s;1BZ+qu*0Sg`7sX`~=5b_X=hFG|fU*=3v-jx-jE-ykDo-|Sf4 zEL)nmzYVfFbgA@_JpJX}b(|IwEAdpGHrfAZxH;+pPd5?ZqP`7$R+_cCiX<%9 z`6CKR!=yg5VWaqkrRFwJBf1eQDMV|)iP5svO$%5Ep|i*j7d9{#SL_MGmcj))=l2en z+7QJy=h*Sho@M}bJW_8rj>2oQdpGxdPcEODzzx?VZ#soyGr);N1gz3xTj7DWf7jB} zxDPqNF~j7G?izL%t0^31Wn8cErrPwn_|ci5Mv9k{TCuIbGhC%zh+KfFRCQmQ>rul$ z35^L1*q4SvrdGnMwD}kr?{~bP*kJV- zU*}*oK@?O+PAuwsZpDQZ^}97U*Ur@(*OSVekUspQ_?X9}m&e#?|ARtLb^SNm;7b?_ zyGGH3q!5V(l}UdR4{tWp8B|(t3mJIJK#P6^bO?9!TEhEe<8ung9B;ozf4JKG%m?{p z5c8^w9PfnU&Au!G-s?r1cNw!&*L>e6)8O*~@YLM9bLt$S--$$J=eLmA^q$)8Gkaz$wtfuLTjlsNeoW0JlQLeew|e>aS-WYQgi}NHa;#8-=_-B6@bWr z5`)tn9(idq87T28@`r<)HicIhE(RY4LQ=l|@@RjX!u;6hyY8R_bGQ8bo(R(RaH zu6ZS30ATWo1XxjuWx5nGNXKF*i9~ko0*#yOb?aAuG{5+TjxNfFXwT*+4^xt?6i$wpMADGXIA8-Q5ErYVrlV}QxM|rDA7pr$;6@hp( z^NwF#cx)F;{KW*ifcSynQXOSb+P9=Vk+El{nO>yYG;zZiLQs$q(^n}V;_`XsormA=T&a8!XRLYbqCKy^F+Z%sp)WWrTuJ`AAu7&?6csfh5phyGQER)N(V{4%Fzym8ARDj|8mGO>P>0hr>{Lzu+TNMKhz;4lcwFT{f{ z*bx!=@gqQpkstwPA9E%@6X)BIV!pYPHXiJg<+2$${#z&gvv>jX!*yQeRfX0c!kF6s z7`uKBpyQ^*aR4aeU6p~}Nl3+B`W()e!a4aO{^>5s?}i?Mf(Z@{H%L=Lk&$}~`2f#C zxQ5l^YY+})b)Z1O3AA=-QXt+X9Bei1`~1VaFVI%zO@aFVqlk3^th>LbjitseDYiGZ z;e~i8g=dI;seMu|GqDV}$jCj(u`V{wAfxPC0U?-}HI7U%h#iDQ00F0T2sfS)l)+k< z$e4sCpFRX6{)DECyw!0+!RH%9^!VH;udyQqcw@`|%0?YPN6POh@D!)kKfT;PU1mCf z$)(99P!k|WRRA6Mk`(~6?4+KFm#^~f*y76p4ml24GQm^PTtIQH*X34Fg87b9sXt0z zbk86Yg+v@4R;K-uXMk{SbT!VKng2(zrs#6HbNQ35YzMl?78bM~^0x`F@Mb!Cbm_n+ zuZ_v8A7ttYlX9A&5$sq#k!?Sp?lTR7ZLe<%*PEh>3Q ziIBcjbG`rJ_#4v$RadAqQ%v<-uvG=7m9c74 z<%Fi$?Brg%67*IGykMsK7mbJBr!6!w@BCg_-`B|)I-?eTssN<}!{QD2@1h%r?CSAw zrDXpC1PnljVb0M%3yX2ET{JP1ts2H9YUTN`DAF6=toy?W!`*!^N%v!=#2GGHFGD3i zUek9>r-k81o`;ixE^VbR$iQ`Qlu|xzc?d1ha<5b%qDY(H5p6FAWn`1l-JqK(+}nng zcIh!uq2xaX>kVYSG7K%ov6UD7UM1_=GF-L*m86jadPNo<$lcuwb|ma9w);0v&kUiB zMf!$h0R#RoE2rzKP_$44y|lN?)8r%oNpxifYH<*=U2w{dL$dPf)1DRY!=XDXi2}LM z0kWZKOt)thS-7sGUeMf!{{SumS|cJqyaR|=ylOerjGNc`Mym#nM>3SIq__TgM!Oz_ zF<{|C*LvT>qCjW3E#|bLgNe~TB0?vKoc}hUAUX6Acni2QhJb_o2a|8t(Dp*x=7*(c zelB@y?O!_Y_u|6E_e!rah%k(dhsC4G+R{ykH}ME>+D~gWv!dLbnCbpGDJh+t0dxHW zF2<|x@rZ>YQ3O*T!Mos?MTptOZ-WvP$mTxT>S~x#0RW5FpCYg-7wh)h3^bvFK-+EHD~=1kHwAEZ+w8npFsW$N}M`(=oIw(<0~jSf+B6t zHIFxA5Z1gkXHs$IW7AFPo=aM!Tj-0yGMoux6v4-o`DR3*Cs?&AlM*I?d;@bS3=QF< zJLoaWYn;cFeY)-8lE_`ybMw?>KzG!pbddrPzUV)+*q8*Q_7oK{Xmp6xGwKQEv+Bg| zulS%S<#3FwKJvc0oV`MVviyEJZ+Ca;OS2E*>_4DrVINVU`}n)5#lx;?BoyM#h>YO5 ziUlDjW4?HxAif7Spr6LJ3vo*D^`d>+gg>27I{tRn;mUjF>%!Lgw4`YGJZFFw=2S0H zr`)!q^>30IOT#!vc(wDVLV`hFI3dki)b?-3e!8D~-&RL9gC3o(z+)n9u2FyJ+=Ug$ zl{k5W0=fl^x~}>IuO89tDP3+c_II`)f5$#Z3BVy%F`3X_dwLtWeUSe4btMB188@YS zGq|2+E7TH5F532p8Au~3ow_1W2LLIOR5ty`BE-rXC!L?08^D_58uUVDc}h7V_xSHazyF&9qbDm^E&>^=shtV z2yV%3c3=2{B)FydaERxVFqh)SjDPC#_01c^0G%6XvTz~Q60dK8G3OUk#%dec{^dj{ zov2}sXdEKZNO$wjARm}y#8E;?ZcKyCq%II2y~WI0lCh(=ji8yrbrqaEc!)oAP zOV$7hh(=*`WW4i$XH;%(I&b|^@(~_d90l!_;60f&5@ydykI&Cv?u)Zsic;Yly~J35 z)?zqyMA!+O_$2^QU~;$c!tDR>^b6)WN$>I}9f~!j+D8B!-0SEi^p#Yo==yJBpALLb zn9UP=BumOr7cJqpgZw2KPVUZO2KhG9T9J33yHA`d)k)af-~@A2HktADB;`h-OJr+0tHal-BgR_!1O&dYHv|FsKaNd zW=H^?f9W@oY*T!v1c{1gv7;}Byv0K|ajx{5IU}@a#r}u)dGkcpSovZHdJB0}hH9CD zwZTV~{J10c@i+_u9z~NWDf^39j4d1&sz|Ygj0b}P-9jsu(+pxwpMJSzVxk06N^l<6 z@K>V)+_S((E&uS;Z(h608Ofe8XmD`*#4Oae777UyMV#uGD^UpVjErmR@=d<}%iFTU zWDOr?#ggG=c0L$GV^LyC|4@tuxa+(X?z*9zd24qi3dS9Mk;#!=ZQE9a_CC} z+n@hd1WM6e1qMVtH$Fs&xu5)liG=I+za9MZ-NL&hF%R^=0@5=}h2kgl{tYnS9R`cM zok|PpKWzp017yex8vg|{T7Y f{yQ{pd68c=n8JWV1c;1KZy#AnC5dWrtpY8?mheNec$^F zUeDKGRj;*v%W741O;1mlqPzqm93C7106>(I6jK5KAV>fJFc%>7J4M@&2?+o|kTDY# zRg@AHB~i4uF*dU_0sth#lD@#GDGy?0YbudK0>y-+_vKLH(1fIc48GT7q0*AzfoKLI zik0~haAn$J72iro!U<6-^}k^Co@!vhf1o@1+F8~D3+A}+rHyNi%jNZHJk4i}$7Oew z4=}Oxpk#*h6IQ5?k?O^9(v>|+pw8uVg&iVGLmH_LJ! zn%dWeH{FP2MG9;0L_;RQslycM{pOLs<}5D{iiGZoSVCB> zXF3*u_)cK5BHPUh5zQ|ja0ApZWpqhlLU*PJUa#NS2;Z8wcWIz^D}p}@C}W}JN8;|D zNZoETQ>upC2T(AOp?$RiC~DCkSAY3xTu4TtV-&Lp+}28E>j-p>n2^2-gqDb1cFcQcpjQpDKwPcLrr7bkJUg_Nj>8nZ za(#5>mneuaGYNNnc}z7BHr68RQ3-{(?1e=|u@E949gjvls+Xc2*cL~aAHZN4QllqH z4x{LN{oqx~u8oB;ZPU*71%$%qOr|^%vETpYigimwrLij;c<=SvtyWj?YY9rCs2ZX$V&J(io+G@X7$DZ+EY=w|J^Q z;=9`?yAOgFm-ODIi9^JmOh6bd6o8r#m<3)cLX~erZAlyaYO%XNfOtR%8U-xG+gMNR zt8NUWj)5@PJvtd`EOPYK*%79n=YS7k*9V>plADhZ}bTQ|1C@)v|YclDa#}?p8+{`LoNcwXwo0@)?jn z_Y+Aj-?ZHc0;~}@HauPXu`t7MG837sL$~-610nNB(0cqRm{HwxVCNbUWTDtP`4u6h zJM1f<69eS*=zf4VcX}%#r*}x%VrhYY=|Hr_F3Uzb2X_o`S!eSnp$H6SM)B%_tQ0#& zH3^KmC-IZyMhl=IEtZ5P6UG>jH3TX7mx>L=F-US$A@f9LiZPN{4G?aVPKC9IgYs~G zMjz&i|G?x$Gs-7mM~D)o&c)rwr~zpEGJYJMkaon@2+0;>%Hx`FzJ^*10Fy;D_*$3> z(bw0YMv)v@V8Ck0sT!H|HA#(O7MOFzQA&8!1=-b&4K-x2h+~ zi!r!3-I<+6K%6VwB^(nRLS8XK3&L#qWcjc$>nznQYi%oS>=norvnI?Y38$qroayjE zgI(qnmOC~ZRzXBIygpniygFC4lZuk=)g#2Yt7-HD%%hXZ=Da(poC4w>IltOP+I8OA zz^wI5P^_4L>*aUi29#~^cDDw@2V*0z2|ja)&PyZ~v^5!dx zYxl_-2yW4D{qF0J_o{bL#a&9EihIOfvNSWn-lL-5)LZlWx;m{^ zy+u85fvEavSH+>ut?9x1%J|9}9zCKGi;cmY-n;s{S``Bu!<AGZ1ue55uPR5n_syRy7uXkBZa zb&7Rbe0sEEQ|UDS>6r5PiU<@pu;@yOL zUQzc<_t);BZla*2py4k3{%;1N{bhI_OkJ!ZXrG8-$=u>f$j&6xCFH_*(c~hd!^=Xw z@z_2X8;>-qi64KT&#FAzeBMg#U5Tm>`_jWjJ%O%-_7i=T8k(X^){>aZe!0{xB_1KZ zM+$N9`*z^=$)La%M1MK%THI#3QlhvxFaz?q(ztYY2! zxMyi^1w1AzFO7O%IyE|1(rffGEa&i+k8~f$r&_1K6bg=?kEtb1rX6Icr!P?Mh7b3a zSBX?{8nuo`kF3V6WF(|kQ>SERqZmp4A1ob)$rPHodF)ujt zkmZor3{3k8J~F`J_bP;kJb)fBABYR7WCfVzEYb}%h8>#^B8mj*fFJISph2R{`EG>= zBW`TOW1Az3toUhJoXu|051CL7yt~ljztSbLQUuQCM2fnSf^7Dv$85CpYV=P1`vsxi zRFuDeqM&Q4ov_#_{CH1x@oly@AG=)h`InlSXJt?E_nPftw9fbl!I;O!ORL!xDV8}XtevS1uRSr^FhV?{ zpJmX!E8wqw77z02&Atgf!Y=n|7jD=%6mO5J&4}bovV5#jZ+W;)UT1JhQcWt*4AZ=- z2dyMmoGddP>;A0Aw`5v)bqX<*@c1nI`@sC}@GvWwFXeYGM|k>}Hf?j+G1B~s;*nyr z5we5Apiae?%DWh^;wS4<bM8QEj-6Ls8xhA5Hz~`EziS)n2p)gm%!&T8{^gXi!o;O@(J(d7S$H!4 zd98%H97>DNBg^GwDk>D;ifhYewJpiM0?ze7-*i$K0<#oFF?Ll76a~VrZbUVZMUhUvGibPgZV6LqY01Y$%f~)oS z=r38wPjKIOr*BEmb1DuI7QQS4egwT;Pimi^?P38u>cRA&ZVqSxVv~T-E5QE#WPsB; z{hZ6G3KkhZzGd`ddU6KztK6q7DW7u>Q~1Q6jC!U|Oze39NE~r`rtjY_l8w})jOFA2 zAKv>w02CM+0OGv|_Wl8Y;Q^rj>;nMOVEF&tR|2E?w+uJ{5Ml;^{I`t8d;7-``+mNo z|J_2w2LoW&WMpP!CIi8dkdW}(8yfQ} ziHZLk{(dDuX6oo@%ge;%;^M;S!p3N0Z^FdF!^6YG%*w>d%J441;NWKMsPD>P?Lhu7 zCI6*I%*esO-ptm~%*LAJ554+dZJZnh$jJUM^xwz7{4{bk`;R4Shku9l9w5^n93~b< zW~ToQ=4fX8e}VnM`4{ZZxc+61{|{xnie|1xmTF>VR`02PcMZhF!_EJvnSXHp*48+3zZtG9bU#WjbsQs^qzf%8>P_Q?9&x8ISu7OzoZQ-x9f6MbT z{W0`^DTRO4*`L(+LIc6^GyQkbg5VAa28ICuA%K*au!<|#u@{V*6q|51(V(7anH>{gMp=Gc;_|JPm(aQyj42j zh0oft&VhMti9dxbj{#HjVylbsDHof`7>`5vm&Zi6J+TO~Tp$g2xbI&ZYyj99{6sKk z-ak0uzQRIKC|SV&DgSi~Di$8Pmh<~R-1^|VPw-def2#3=4}Ld|jbLsi`9CcG z!BhcE^87DxBlvy7E~VtzYokThZEja<|NM8?{J==pcMd+p2)Z`utF;pggZ0p=Uwh)u zj#(J}BPHu#V94R#Ohv`WcUfdxeQTU6u-ZoB(XAA!kg{XM045OVlGk92> zFk>VMYb5x<1CU5NM$nL?7W{AN6GFB9nCp|*WxIX9Cjv{>P2uZ`0vdDLWZ$M&v_)mt zdUXtvdQ<&}`}$(JDFps%Dmr5+)wosrIxBAo23rCpcufHN)65cA(kVC97Ju>{K4*W| zAnNchLNwWhbINzeVXp=M@RmGA$fPLK!Y0w-rs#Y1H^s5qnK0LTHVCNpw;o?W(JI}swdN#M7V_C z-@6Eu@&H--5xU2Rk%a-m^^u`7zZFn{#Q9X(fiOkb91ICf^dR4r&;RQ1F`6jwg}y*{6R5E=(qr5_=BGGuMe8YhB!ZQT%i! zJiB;w`L00gPzXn-b9k6I&$;&Rv4(e0hWnbqw``ucXNvHNiuG~$*k@p-o-qGD*Y$wFNM;*BNwDwr zZ!pB8H%p}aWvf5`QBh~4;43X&^%R@;GcR|FOfCU(=Rh5E;YIuGrT zym%Bv6XL&B_4&tY0`{>35nL2SNc>c-PfqZL?jP`mbs&P^xF9!};r&wkI*NI~Kiwq) zA|%i=bAxU3KNi>jV+?%B^xl`m(4fFJy1y@>9iim!i)E;2DdIm-LGOzk7TROkKhjAa z{mvmrs^t9VLWc$Z!B&HH=3`jRnkzH?YN zQ7j<-5%K>I=#TOG|0DEXoBywp%NK76qHFN0iKx`dIpB1!|1}ZGHHn zUVagtIn8gWkyW-sef7Z)dKuNcs~>i|zgd6|>oB79jm=>)1(6pWEq)XN1ReZ!8OvPXuUccT@%BzVF$pM1{#m@io+PzJ zKO=qIecXs3KfZK>{_)p^rg3j%Zv`nJI1dS>V(?uostKEjZaB{2;?f_gpe9&s3Hf?ICuetH6(Qy2+z zJ8ezkCp@OU7h|R^kncE)HwbO#$YGN9bnM)XnYwXLMx}yY3L#}Cl^HkSB?>a{N0snx z%J0EWv|}5m4&DKYK0P1!-fC|BjcM~wkY(JEjC5ezkia#C(^MuGU4f6!6%7&(_XBMB z$OG-OCkczm(*cX6_Cm2fp2GxG*LRq@mi{GN#L4|@%j7#zR;`eDaP%P-n!R)& zB_f|UR&|g=OCU51hNAKFz`U_D6Tq71c9-vfoZoyX+n5ely>< z9o>i9a@Lr_Dp5(+8NUxbCSWcIZjGn+sWPkH*q2tx>#TUG=nOI>RkrD%A;>bSkQz+b z@0Ma1GAQPW{ULZL$|zlW(><+c@tAC^1j*lA4Pu_X zSHPqKQS2#`7tqm+u9#GLOiKxwzA)cs1XUk7-LBcDA)D@Ty_rNE({LN@>%!o)g1-SC z9)=d;HI>K}j+qiMXsjhYYBPz!VH7w9kJj3>3%^HkMz*%+l=DAMVLeO-6I=waTIGTh z1%<;!j@}ZlQf*1}rwf$jokTu6+)zE-)aA$fbMz^BG>IBVDa29}x8QXdVaWFg-<|Yw z!lYMVtITl8e6*@o+4R!=)c9=Xk|*g@O%eDg1$kS2ci5Au9F2t(bYq2#-VPV z&h;tYpsSLQPyVts3w^q+oufW0xm7}bP>`uA>{na2>gPvMneFVI zX^Id0V$a1{M{ern?S+2(3eYTVJ3nO~ZnkU&@S!mE>IgM_LTM+&H#$f@$Zk%AbSBRK zuuY34pri04ZnG}5u7`|3zLGu+p9LjnY%c{K{yo#n6C|MSPIm^Q!Ux9}_WIsP9nxuX%g2ev2 z0KdCFke8nV+Q_Tw+J`Hp&20tb(s;KtgA3W^HP0u3tc_PJbX2N{qUZ#H2kM=@lKSDJ z5E(=Jz?@9{A2oY$iLbwaTHk;OR(q`&MDBXm(%QJL`bSSF!D4sfbfsfJJWIPc1Aj4j#6tGQKFh!;yiwfUtnQ#t6 z)BIo+ebKfdj%y!%Rh_0pu`znM_4yqYDze4O{lZ{nJ?;m(1e-CQr{*5zT&RTpA=7*H3ft~69DM5GU8A8kWke+?VvNOCBoASjDtzAU z0vMb4f@(GbDpSVML{+Y#Hu3@`Rc)r5CdAWfxj`cA>kLefHOTT0g+-31YqyN?YpnH^eesiM7Z z_FC_MwbV&vFW7dFTYs0Eo{l%%+)pjDfRipU5;O%QT`(#GCv}(E z1yf#BOxrIzTo5HBD$~q^NYhPFC9ls->57&BTomMF6d?;}hC(=npI9EON;`-TPI&cc ztCAz~A5<$O=FI4%U+(Pcd--)x%Kv&`vAs(vjej=9$AH!xCFA#bHk+ zXx3o|U%P`Y=cCEOd_}V@^x;c$Pz$m(*rY)%=6+giCf^|Wu<0AFz zK6CX?6{YW7FzGPKka*f&RitD!QX4V^7UlQTZL5fuuxEkbb$hGN-vnSx9Ef3|z>tE@ zF~axAI(5KKc55A2*IUlWXZ-DTS&Yr3b5AM`_uiiqw7%3lKL=TDF0IZ6OrDg(riZiF zI9=N&pPpq8pWICyLO%>goVk0_^Tzm`-Uh{kc=71wI}JafUfiYBk)Z@NSL;fA{ycgj zE_4yFUTNnOchRlsmoORs)7{N|#hSMJY^cgD@Fo7<53bT_327J~CMH9`H)~f1%hxOZ zNrYQxxf?D1>yA$5&zOK5O88$eeVsAeS1wGw+0>Ug7D!zx*oCsYa~m)H$2OmTUG^h0 zB;sQ$Bmj>;-P-^7A*-|M2zb(LOzh$>0h5kYJ$_nV17DB8gOhkJ6F~CVs%pfw@Ae-= zgGT4*e=V$@k1q0VV|{;qWeD7o?Qfn*#4$ZFGoFzX%JwiQ;;-Z&mL0?;N4dYE7Jm<4 zet8a<;NNWO~jd2;x{p zxxXjP{8@M+KVO6rE)ulASwS0dZx~{svAyIn5^scp*JafuL5LHW!gZ4Hw&W@a_cP-= z;W!T**Evyl=(;FhU>qJl`csdu7~wtRlVNS?S{4&=yAdgn$J1ltjuTRT@*6M`16+&i z%-;#e2!q zAhM%V3zMOt5-M_6$bg1!1y+8w(+2D4#98*iv%JiVNT70yO9R~Au0D5$&%>f@n@^p=OfaGy9^J?@~X)ZqaKfg+VFPd#?&KA31m+qpFAud08ACb!HNQ8FMz(!wG)*DEQwVPr{M*M);M-bj)v(wdT!$foZM}qD zv_nGo8&(bC7M-{?0Sw%AJ+(&fVWL#k%2;8`Y0geRu>scLShuATf`IDfl zym^J6rEN`Z(^Oehq+pLB(nxWT9M#wlz$@O^YM4l%46x zW2;8;GuWZP;Y!E*C;d)7YR!H%eoNi1g7Y#n5Cn2(h(BR?ZcP&JCgV!BB8_SlO>$NV zu!3a=3g`^)k=B%rfcxa1Df9H@^^S5w=IMUgM_)T}b$1u{KHFd7iFr9VTD?2ux@|;! zu;N}d`O(Hve)=$Q0SklFnVM0CgH$-q&qK58Nj6L1^D`n10(c{#*CwIg)|?UJRohv) zgL4^JhsR|2*+FZ}K<3(we)o3}!k*O`on1lQGEUAWGVe>w9~V!!pL)gXJY> zhanO+k1e?sxb;@-Qy1aZkaL(6 zc&1tUkW*o=AD|Kl4oVuJz0tL}9U6g!wO{e4hjsighb2qMRKH7{z*HWr?Cx4WKA?C( zXKtC2qb(>m)ko#{xtFrlO1JHKyFlB1_ZnApy2+cM116%4h`xmD3GeMz48DQ5R*xaM z8_oBsA|l&%ty7CsAgm|CVNRLwmeKCi?yVyH=(X?sp?~BxxQ_dw^0c*5*UrbGzNi9p zdj@$&+NQ?rgI-zK#lq=zvJ@TR@ixp3xx8ks$RszvgYei{>&yF)8TKQmaCb#vvKi?J zA0z@p_CtM+SI#Y^LmwvJ^=bM#O(W-%bNG7cZ$ilA<6GEvIp(q((gLco0siu&`^LjkEkQ6 z`lP>)GCB{hdb(M@2%CY~)rr98D0qmYbVjWJm&}Eicw`?#163WUDTlHSU~OBFlN!!R z!h{F5r}e-UR5{3qrCYZ}Q9L#z(}1!dRuqUr+X?Zz2PGSqiw`$R6zOfFQ z0?}~1u>p+Kl^5Gn$U!{(2*t9tsrg052TA&ekyG-jH`gS?;0Ko|4`=j8moXVExzLm+ zYO0|cy9+%yukRHts<*@?i9UPTiAeK83P=|&Ys5=i_9HX{7}Kpebcw!GbFdFb@I9H<3BxzkL8tQwj{q_R)^(w zShQ3kSmQ-mwx^1>>=pNIlTnG44V(&G_iemR;SdY+Tqsteqe(gZ9{M7uv<0 z`7wtFy4Q6l&xVPZ0o$)w*%;?JkY85JTN|vUB>kfF2Yej5p|mV>>R3em#42Aq*lwJp zWF50b&2maM%>`;|1oJ}ff;j$c7mJuB84^@#OgYK(E=?e+9I}1j1JOW&9seaa)_^iQ z7r7LO(<+k!KwO9J+onQ!qw5*5}e_9m~>KM2F`N51rJY*n!|WAt~f?j=cLk80Hg?Z(0Ch5FoXA`SY6*)=IM z1O0La0uv#n!eITr?bYCR=lSd1-hRR z)AzCH&W=(y#W`88COr4xW8hdvl&{T9qMVm#=l1abPAM)45P@f#7e$)wC0~k>{Os0h zNJ`2!hk2k)gs$fPGyr#OmDBk+fD?dD<_IEwSc3TMGP4f(PUc@KA@l21KM=4zS<$-OXc>Gw!jy!~ zf;zq7d8;EU!U$K)!%)o4YfSdBgq@Q^26v=;Ov1wCx4w^w>gG6oI?ZHUbiVEDEYi)y z1~_-tRs%nJpb16zq$%Y6aE?tD^;~ye3<6OC=&}(Q zeoQK1VL%f-0)7g6$4dCt$4E6FE75BH z##dj@rw46Ts)1o{ld7}Zu1vhUQ37h+CKDcTy!*lE?q2&V;#p~`Dj@#E3AQd|&cfUG z3BbcxtIYOdS}_^{j$W68yQt`R<2(nkAJ`tn6#{CAgw7IWyQ^7_Y~%%-!TenQd15&Z zHIZP08)N)0`DDm@hlhJ^_VY}b?`)-WKXV*ukqsW|x$Xw}LZUmLyP*tC3{)gBL}Gnx zf6G1$S;0q=bU(VLA8loB5%6V$Ji)H&;G~puRvpz|*RJ@OUkzthEYP3alRIC3cp z`4+QG3J82Vf~Q(E?Vh)UZiui(5_wh%HQ6t0Vd^D|+j$;)!~Lowhtev;C}WYKJv==Z zTWp>ivrtOX5>Ik4I}%5+>u8CjkX9CUBq*>2Ls&E(I-Ra7#8{iMwsi3zMyb;g$wUcf zqNEG%Nj!7fPN@Y6;{r($&$|PV0>@Rj^bRJ)&?rt{0+xqv<7|I#(D2==Pc3~GNVto{ z*0#+38};&~~6>mJb>*&u2DHigK`+eUWK{F-qp$KXxp zOOz4RKBQS6mxAgLGRlVssMHK2;fuXbib8_+9Vuc4InR3%<;j}Z#ys(uTWN%j19k0r zOl!WZMHMyDuXWDl&*M$q@wmv8N%+R?NJZjzatiU~KG)*?Qn*-O)j$3+^xh!eBtBp| z(E(iseN5QlrLi|Iq$H#9ZJ*(+9U9MGAsas(Nl~M*CeyEaJ$GW;W~68^CNoOV!eh_! zU_9W3KL}B8-e0oW7=I*)SM_-){uM9g2JO^P)UrEE_ehK>6wLf=Tn!dQ&URCrvFF0_ zXf`4Fb}?K(oJu`AY{RuHP0=#3MGD!VPAqD=a`nsb(%xLdXdxb!70dXORtNp49%qan zNn(ey(=|#B=WQ}y9*-KNoFxt#NMmO`4sAhIkqUOq`PW&RnYT1=R^DW8VQ{~8A_xib!&vdfl<_Z;+DN?d;GY4_6h`8c~~p3D>q$t zMR=}s>57I!NN}QrF>uhst6U1S*8<5|oO7+y_da%T zg@$pdlaYvRZwx$%vMFuL%*V1SZ;tNvqr7jhH(^n6Ep3~opj-OHq0?fgw&M9?0<@|7 zfo7$5yKV=UjXtF*T?R&qyiRQJhMd)3MfG)9aA7$JoyLMD?sh0~FN<8ND6LSap|yP@ z&tcLbDD@Z_KAKKU>JdOI;rL(i-7zG@Xt8}Ryqp6G0) zJHQE*Mz@Jvq%4a?NA<-!sz*438)Z6%=mzl;xeQD&a5EZC0;o)_4I3gfHjOmb6=)qd zfyTx{AcHbXi54ok;i5{mZAOupS+=CZW$eO~qtD)^>*-#?f06WAyb(2^i9ZQtA~DD7 zQT*azxa4y2^{ak1aIT9;Rj4v9lYpA9tyYWbs{o6N`&sr~OTzVGr$@e#-7NRRK>|KS zQB`NE*Go@1zJ4eP$V!hWYQoDp>iS_m{P`{YL{=} zQ+e-X-{kk;H0nQcH$ExYkYXb|ZiuWkwA;0^`NXy-Sl4uZ70xAi9{DMC`LI;hbs*h< zn%U5fipB&~dR`7LKxm*qa`bZUQ5yoYZ#Nh^(e;AjmTrWQ4<>*nB>YG z7JnKGioM%w-W__Wr)M2EWGSBM!Aw*cq}^6A3!J6INKdEe$xx6AWnX9={4ptY<;Cq6 z=I{Jkm(xn69wuyEtGEnV+LeDpys2`Oz%|x)6?F5}@x_<4wk|P|8|k>51Bqf@B5o}Y zx{#taG{B}0Y~I#Drne8x4^;KGJVFIAx3=0Yw(GfPW*TNo-YKN7`{Q#_^5O>qF2U5^ zNetH>xJ3bo!dppvPMQ=JTdRce98^m_VbS(bu72O%R0TcDL%lXdm?#Z8Sq>VEK0Wdg z9EfQFYiHM0Tjp=Vv|&{neo0lwPYT1^IGHMq?BaLPusGBGZFVWJcUCOxEs=P=A|t<) zfdRwlplDHqQFdk~2?K3=OEO{Pfyn0B;iv9gJI@`yyL7}w(3$C?Frp{aNZF6ykrK{F zhTC+KLMz{GJjWJrX{)Z9U51a(1W2Wtkfx4xR)QR_Y zU+DIvCd1%(R2CrFocj6ecqf7re&8@mm$bi6aVd(j?&Z26*wpdNzyonNxd8npn&a;x zu`zw_J7$arA26vfREb~vkE%{o2+6>k4DL(uLSDxPM*`GKI5A)|rJx9gv#s zqg?ITGEANGMTPn%;^y70Lkn^Bbw?$S1QR+z5UzbrH;K|yoY&MoUxQgd+uP|4{Na&p$ zhHB1n_F)_cD4!ETilO6Qw^(M_?`&D8!R+f2mmtWCO+-zU)V`4o# z^t~BNyXn$Cwbt6b&_oe{V6bwQG!6U!ca2^EC6Z${Lf_3`1#xyvWh4Hg7?wGTiAiMK z*$R)sYn62lY=Tv-oVT^CTJH01bx9XX5ll;?xu@AE7qAI|GfZIOwsHqv%%;x72>(gx|9sJ0+hZy50ps% z%G?+yh+6AvtCL>v;Q;fpS3-y5=vT>U#C|tUrevIYp5pzz#gfrpXTFjWOdg7XC|i=) z{eV;aDgtt^}OOsu>A$GD9Lm~_Uove6>0X8bPbfJQL z(jEC8l$?y)IKe&1viGQLv8z)^qJe;hEQCU3nDopJaY7A)1bYcMysc$kl{c1)E+W7UQ9FIU?U3f4&@G%(7? zWi~z3NKcr1?zk8hZxJ_kG;e`+*Lym>=!r($2Q6ERJmQm*MCnCxhR==2t$y^UC37cW zFFXvt=hqaYdcey)k`)p%%CfD~zq6Xr-_~asi|X55CyFh}L;Peu6NGH<%t#(%f5NcI zMQJY270XtymyyAP)P_^YwGJP&o7hlMf{XggtNB&Uc$FtlIBn&b{UcQ#A^M)CWX!bOy;dWoiRj{6pd+BYO8IUCrWyt8c!JUSrzaA00Ea==V>*i(R=lQmi z6(10mgYdh>XA{SP}nu zFFNtlpXzGi<_Xnrs}$Db7|~xU0m1r_BJqBD-)KqtaQmd|!vjO#0Uinit33avTyJsT z<~9vabpBx**;6do`oWN3tleFsm75ZTKL${Gm~&vJ#j{1#xNuVi0uPypG45PZv=%q| zzTMTi`uKxQEc5Yagysf@ z;UDfu&E65~GEpB4Lu4q=4*z^;nOStrDor4qnBbV<7&w_5<-l9uMmag!mB(O8g{;%} zd<>87*)nOC!5gl&)oI7Kds3$%(1yzJJccgRVO4F}LkN7Fb0LhYy2MNPLPe}m zG|ios+rgzoi2}a*GQgrYm)vL(f$zX_97F7nETdIwaO$wd0A_H1m$I6~x~>9|fX^y< z{EH5WPl(PQ<)sg1EW?E{%{(30Wj5X_Q#gREv%DY**a-H(=5$E!R1Z3N+t0Bu^0>9* zQ3;Bz!ExztIm*7mA)7wG{r17lM51o{GndP#;A}S!FY!=ZlH{RD5}D<#;QjD$6~s{i zCg-e{j3?t5T{N*mpYtXc+!M0bDQDO>ZQim*=prZw>gePbJx0bpk>FA&hbv@-vIJ~r z%&(q{BLqAAj2LLNG6p`6xO6qC!&MTsx$RjF5~P?0l6cqCwTlt?xJ9%eQfs95HboOU6dv=d zGkL`QxJW@>MhGzo(UZTb2;d32ywBc3>-59TLkp4&^VB}>&4eVMfXCe%L^)@m#E}c9 z5;3#G%G+&)J$1u+1OZc}$tUIyP4{4F6A@Q!Es2WJ!e3~gATe+ifit3{N)XUF&>{rR zAk;nVIm$UhzWqbe%t$+L#w>wB$1uDHH%0T%wKB%0!{YMHqkj3%!!blYGMt?*N&YqjK)n!)Y9j)9k@ytuK&4F`)cz08+w;F0IXm_)4cb258~almPwW1x zP1e#m?f#$Ne^#l2JeSbO0n9Ahh$zxzYy1>e73TXEKI95m0S|H|em-Bl&Oo+e@?9{| z@0%gI#`aHjHG$9e$6ib%gA_h=y&Tv3w*4lKBDD3y*OiE1OdzMH-_d)0peEZPZglqG zt1vZ-1Mv=Fp60h%g}pEU`i{|-7Q`I%yq!&b;BAb%G z>~Uqa@H&p&0u+A-*b;RH>jLDAK$$1f=cO3(;C5C-^6w84KaupKdJTQps30Ac1t#Fl zOn;#bF&jQaeA;%wN6J9QB6?9ar9fpxU^x|pi!%P~rTm3MLOyZ$Y(uM!5MPu)Uf-4Q zY=aKkf8ue|y!cn~Q4*^Zxo9ZKn4~#wLo={mbN*(dA1KmkeVKbEhj~ ziOy}1)0GWX8@*UtpajXbWpKsUr2Bo~!|F3T^T(B|smIZqRy>WHwU@Q`m+c%hw{OUk zltLT5@FFo0BmFbSJ5j}z#o<+gr%9u`X}EW1MI|d^L}~l{dNRa?7DA=#P82J{rVMMP z`g~^9=B<|c`~r*d#@{ro)A%ck)NWHa8e%GKKC>d6Y31`9ZStNRVM6Q2aXu@G-kK(X z8=!uxVP3@a0yFphf{mo7Hk8S23&9uu-N?euT_4k0cBVtLV6~ui3oTqUH;^wywwjSG zI(poSpTuW5mEi#e@}F4qG8u#1~YK=uZ4nC4aZaM2 z{~hQ2l;>$-WAuZ6`;l-?wvR(msW2q_>ae@E9hFxe;Qp?)_p*InVSuJ`;tL(QS7~JL zAXZv^91Xehk>vG^I<>7{&dJNIe;A^|r<1iT1>}(z9QZlOacGZYE^_sTWE`hB$E0u) zCX@j4sm~Lr)$Ke7gJ#FI!je$uSb^JFddqIoHc5IDKSp|NCH8fWWVp_#bA6v)t~9ql zm4dN8lh(aN?aalRgHz;c%vrD zdQHG6?KzjEd(Y_}R~jg`<~F|1>f~!LbM6ZfFVGiKk@3TAp!sM);DXfgUW^}fTlln8 ziI~Wb``Jw?@%{R?t7{!(wi6g)H(W5@+ab+f4twyzrSBfge7J{c9)6#3(jvAx5~OuU z>Y*=j=QHR*TY(AVx!~6riHaF_*rab7TsguyQ#+xV3!pBCzQePE>s4hZFWQ@DvSYgL zOI7^Z5xw`ZQGpKwyimN-a1dc-*?WhuGO`ARoANSyKi1CC0R57dBA!#A}OPl zQ*#LYW#Pg?ky6K6|&?8;Q5$jpi&~CLw==|-nSu6A?%Dml}s4q;2IG_K| zqG6#CRqT|^8aG=YO=@h96Lbt(34~LV9F&3;sX~x^W2quI!+WGB+#vEqBN3_ZJuPty zTcjDd|LzSld_4zIC^5!i2pww!;y@KD9#1)nbcpIX3z*(e5*|^^CC>yNUhno*AkADm z*W{?^b8i>i(VT~w;pI^6&2BnduYH<$MH;&fp@#*2)IWkQxXaURn(>_Vz1v)-s}$v+ zwdiBhDmx&pK7w4K{RX8@9{__R$2F4=>uyq|6Wzzib^k%xkh%u)9|9ZHiJxcZ7UoEWnAn;BZ+;vIswAKOJz4;jiI5NaUqIIhxVZP1$D- zv$e(Ff6HsYFbwY69)quc%@Hl z?Dxv27Wn&W__yTz1Enx~*4yJubq!0NW%$ikz4M3MHub#OQU$!$W-Gz@YA%!f z1+5s4&l7sOXyO1Rc%~W%=Ynb7y)h~{ku@AV+s}5ufM0PIfcT?wma&D6<+tGEC`=ey zc%tFB^ZMn{k*&-O&gR^MlhIGadwZ6ZqW(r}ho=hrTNQHQEXZL_MkkOxf{Fw~GUnVZ zsu}uIU&;N}uRHsW)y}ezUZNlpqYKel?L-7qsd~C*jdgnnR#2jOX<)0$h}Mj1$1fP8 zk6o`}ezy4n=tzztdY8iy<|yX9LacFGc9fh&vQzlo7%8O7i)OYQmI)-;3Ce8%fwlve z*=|Gd^YU8#l8W{c^>k-uV0Dl3x9Kjpv(dmjCnkeJUsPe_j|Ujzf}B7!+Zk4w z9WYEvS3Z0c>R6E%yL?ELkjIo|l$&~}ay?Vtymy*@N$qEpR{Xp3G+vhM>sK9z38K^ z0&cRYj@zL9*k#w_unw?Zvw$O7K9!9(PiFdLE+h*3I#S~x(x3}Aasl zEu5Xgf*+p`D+dk`z}6Esixqv(KhE5*Y=V|q-0pQ%BvT=ycDSZzu5ayh@fQ#HXT;aq z#lH4`?YXb)7i_vSUJ}#Vshf_h2{1h?6w9x~vR1!bJ zjWwJHyHKTxSu}i`4Z+{_n)>C_YLVfE6~LIN(}p~1)_AGsbtF%?bkH%b%eCRXl0x8j z`HOLx3iMoVZ@~sF0CI``(~e|^q$r`cV2{#rmU>4hnlq#jyE91bmv(S~L+k14>2q1@a-$@;bZ5Hs%R?2wib>5_mr%G9I>V3s+fI|m+pGIY z(^=sK6(Ya?6iFUa1SQP>-n$466Y2#3j{5B|h2K&sEJh2EQ-ynZg&X0m z>Xjx!T%)py1O?6pxf|UfCBm2|{g4DiwF*KV1*oAww_ zoH(z+Nc=AgAhgygBtO~v!Zv<+4d;2E2l6?uF;JzYTf>KC(UoxPP3vg_)c0};I(kjR zKvGEDF)XNIY`O|*h z-CY40M~&hUBEcUDWra!UcNZ9r(0yXqsh;ZE9oRA$0LF&C`ohq^#R4~|cS?c^5PmbY z-%jSa3_y~SYI_Dm2GfTIvY`J{Sa3ZydCN`iXh5 z5b{~;u_9a653|ww@8OTn*ZE*N4ZMVA`UZc>w}U>?e^sCIsBCu*=))J}sq}M(#f&QG zVeF#%2XhVd(9_MFT%VT_WJoF;H^6aftzykz8Bzx~1lC?v_HlysYS&k3E^Ml zgDOyZRdH^8)Zt`)!v7=^iGX?G1@9>$UELv=PdLD5N|H7aeS&?cX$Y0N-R^$&4ARzx zJ;>mHr}LJ2+9vNt7?a9j{CR@~-^K$Le@u$%DW2JHmI+2tnJ=)y2mWBa+*1 z1rCrG1)*5=Tk&3&a1sq2cz&9z4Y~Vs$PJlW)hm!b+$b|Xw6xdZdR~v+bG__tNXv>U zys@vvuQy~&gO-6k1Ws|Sa%}hi4k4t^q2^V23IQZGu2uJk;Ad?N` z83dc)ITPD&mKZLvTH;e?*#a*}QP1>uJ`vh%bqVZ!cm3Y}KI|Gh(pOgIfDf|N%vW&_ z;^Lr{$bj2c=7@uXv5Q{eo7uEy4xkB}F=Fu{A=ZLbe{W<)$0ubXGbGmIYq|(qZ{->v z=rd_<0pPy<@`8_E-1oY^y?1lsgAu1Ik8@t*y5M1&_yOpoTDnZITE1TDQB9-*H~|m? zL&%{^K)C1$`>!t=fMk5$ebdK<=AHMP)dwkHq!PY4=I(N;Mwqjg4z z4P&vg(eiOO&~?OZK?NZkCfuau16!^8(MtBnn~L%GE2;hSLr7m_d)j$!dE|vs=6Q znIxCVrJ6E5d3?)@Q}r38%)c-D3}j#?svomEx1AvPk+_*(g*5j7+vEK5K2c?FDrkw4 zb+F^x8BQI>t_bfRS7OfQjtrx1+VYG*4QQnTWp<=|qPA2(q6k_QtjYDwCJ&5i42hH< z#U_5E9M2asB_7mTjDYmy%CCVZeyEAI4G~KvQJ-$M+Zp^`e!E)*t^qbIEB#GBdctch z_hdM4EqJDXqWE6EM$Yu)UivP^CJ9>GatYCh5qW!| zQ|q^tp^uP-l)YnY4|hLN&qYi_(kR)6zp#h@)Fb2k1eepu_G)gPZ@#}zn}4HdXxQr) zn^(q{i$$`8i0HK-f~IH@7?a+R!sG;PEfS&*`y6_| z{?lR|uI_?(BEwTiX7Z^ypVtPy_W_TWr_a5Fs0V!<&+VUwS+VzeL- zIY_jcA*5cTDX#Nf-k2@cGZ$%>PkY1mSQ?h&z7I1cMh6o8)mr|Jwu?Qd^%p(yv$b_pkoYxKK8wp6|=Y%=+5rO;~T0K1;E=f zU@4ysnDz%_`X-ud^J~k?@9p0OgB+Q}7-?RIk=pX6DAP8b^W+Y-@T5qzO`-1>_Lr+H zjtg()skwb?xwq1K*7~;+OYR77abY6I_95sFN%`D8mO5X1`N5A^#xCi;Vv@yWl3-RX zo?Lh$^MdSjn6L#%{q&}Ka?Vj3pXqBR65nKWD*E;XqxJT`eA>o1^We+Nt7N}x2teRQ zNFLd&n%Ow}ys+%MGg726=9TlvK7XN2*Pzpa5Uj)NC{5)9#YRu9Uxx0-#!7hbC<$eB zl0v;;m@tyY_kWs20-F(@b;sO?Q9zFf9R9UFfJ%VXm{6V|h-VC7srrM0YiGr~LF+e+ z;qRHMfH&^mc+X#&`PS}eqrqKP^DR!=uBblDnY0Bu?7PQXwD;I~;WP4!`%+%t0oOoa zK}W`+Cqku!i5Yb<-U0_MUI7c2egjqU zuVjLXnFTW@mH1HxY6|*}I}GQmDg#n)2OREHD$UtqYq zu_<)rRrP{vj$5^O5NW$)4K^@s$t0CD%7u>f6p;`Y)TZ!z>F>MsHM@3(t6h}|1aB{4 z&$|ShckP%$+NKSUI{AI#J#I-*u@w^vT>sJ|#^}W8p6sH1({P6rCkd07i)1AqQbsD& zS#U2LNku!jWepr1Ga{aon1)f>Dx0W)QJrA<03@JM7})dfxu;V&Mzdb?;h2sDLey}=7Vmi2 zX3Yp#`H&%{oew@$%QGMa@@DG{*R|%-<)|R+aIq>n`sQoQ(o&(^Yw*2FwKM;g`!owm zwg&N+&bItwNVdvOso;G-?SA67C8JE4_G|WX-6vr_N|b+Cs3xRMqB2GXob~>QK-`E9 zq(84QP3y=yJkosGE_OMA6D?afDSA=kb9R=E)7TffcO5R~F4#Bpc>^JBWNeZ^vbf*& zZhvoODuL@=fQriU%99Q%)y=ztASms6b?x;LDV2`1s)Z}XqUTG<9U73U;YJjR8Zt9m z`Vw%TsBlF63L_lz7z0&h1`GA1X5sXR*=sIYcWXPwyN_^p6h}gsi>i!l*)M?ltiY%I z41l}M#k=p07|+=7st@orT<%X_O^zpks7iJl%zXG_DYOhgW_^H>#oQ&^k$vXOR#5hS zodcB+9i%>BMjQ+dl!ZDkCWw+lolsGKMqr&6lQ!~73d)=7ouGMZ?EfKu{?U;nsH9={ zt}crljN=F@77fKABI9*|_yCThHwsWK7DuHWbvahCnj3PEe)I9L4>|w$Y7P2(K<;_9 z^WEKI%l-?opwBg~4q*K!8WY9v2IoPIP=|7Jb@s%V981zXw=;&tIt8JT*b#EZ(q5ra zm7PZI+i4rV9_=MR@g}-POACL|%O^o47m$NswGJ~ExFdS>eg-$FstgA64@6ZzrKL_u zLK0N{^W1j58oG_K;_MZkOkid+K|ZgnPTO8uI?8)H^Ys?_{QEyRtwM;wMW2mpJF-W- zt-a~8I8EQ1bKaTnE|%a0+ZgxPrD~(vtV$Hk`PvRB;I*g|h$1j^YJT9NP*`p*=7Hq> zy;f_kS8S*{6^O|L1{a6k4v>;V=TS_F>)NsOQ?RhJ3BNXIxo0MR66<%a-)qAc{xTvf zFUcaH&}}o1AtV2DM|$|iZ(}su zdBxOiT(~^<2VwsHMzJs@5b((N{=7XwNqMd~{otuSKKh|qw?)Ip{Rw>3_9Q85%!CFi zpW=|xiHuo4p^f$#e&4Tbtjs+5d=GIql zJf;v8jGUcPUCQ3!07(GO0E#MOzuR^s!O4icOL@#Kjis~YC=D1e8lqAnFBSh+w@nAm zf@P>@TtCO;WA!aNpEefER!2Izjn~U#>+e6#*_k0VgRT^jM4M!VLazg{G<3{De%A{- z0!;m^qhhKtkWu_)IonqfKzuU&+rPI$#oNr-aV6arVI+3pmW$4c*FPo$zI*1DWRMN+VG0H^gZW| z@-fp7p14rEiIbmh%STe^i|dKD=jUz7NEN(Y?xjFPKpapsjHOFeyZiC8r%l4uK}cTm zuHjy+XJ(1mHqH8+#ogcS2j6?~m$7LRcVeFpZCW+j6#-!iDEPU}7GRKgbeEcWO2TnQKbkg>_X)iNXq41O@0Mo&az+rjJWO- z+p0c}LYs?{SBew0==gl}Fw{9|(l)>gNzX4ijmaDtDATmz6%drdLQxcNhU@2|SpTk#_`QHmeUcwY zRRtGrQ3@3xVBvMm_AHlV6OnaUwLv=rCb2PfM6k}cC?t{T0{obtXc(v@clx%Ml8Lg` zCTOJR%&6W z@fbJrIFX(yvWWz(RQnI!KkAT&liG7MIZ6?C@ECS0DZ2P7*Y0Fw%|Mt<`%Gk6Tv5w;RGojIEMM$uwkp)?J-IsHYFhrI< zhS3^r_||sarE%hqmgKBCNucc&7@+}=acPVO1L)nKhIekCUjuJPO89{NJ3){pb|zIf zy)31&LmE5+y$bJ+YQ>Tu8BCX5BfBdWQH_3e#Ks_@Z`?X-q!h^yIIN-QW_%NFT~A$5 zb%(<^F#AczEJ$JIOxGJP^91nw5KB{RC4xDxLcF75=ssk3I zdLsDT$jD;5jK2Z3dQN}XCPc6@#wy>&q8&Cw%6rxIJ{5>}f>C&$;UuHu#ci|cu72?} zhJNo~w|Wb0X2yTNv%T;~5y09>LN$id1?@dXB5yLB9hz>u`mxLN_T>^a@ z?s)f2S~0=!b$T1S-99&}0G`Sn9j(nj53RWAn;FJHl_jL#m1cc6=*qVyQ>r`Nf5x$+ zdJk)nR1#~GA{u@~T_6e{ui_f+()p!8_9{)(NEx+ zrkRMIeH~{lvm9JFDJdR!4ABaS?Bvynf>Su2%_{2 z!Li-UqwW0j#rxLw-1c9m0E{TgwACYL6ay@AuuIl9-tcA`$_w>#waj)qUAJ-*5x?=* zLHjU!vZVml6^P2t8V?Z^9FElOI{n?9qZ;82e~~`%rB0A59sL z)S`8l;6j(y)RV3YH~_{Hjbk!YcLi48pkgBMF)Nq~8v(}SA&SlHU>I(%9RGVv@-){4 zg1ppFFX0%H5`20*-G1?8Xc0o4==9Q^vowG<65J|r(plM38NN0tl|XS?wwyCUt0n3e7~a&a=+KQU;j92 zJ7ArUHZ0+$0GCtsHBT5SG__%NNn{Cepy0^=Jx;WQ;ZLKBT*;j7kYiIzAA)6m=UOO> zwFQC0`uZj#6_Ic<@;Gr_n!nsq5f_3bcQ_RJp37w=A%9MnB4edlXo#H&{N|tL=m;7n zG13q4I=lP<7+(%EJf}>I4W=Tr4@<&;=!O(4jp)fLWtx|K9t8%8SdoQ2*#U?r`Z|!) zU7vtFaEBIAkOq6(X_I0lhkd%6u|a{Qc_-x@8CwXyhN@IZrG3(UZD+; zmPOb?^cX|;S~FT-v_ym1@=*eorSTs}mIUl7PgbZWb_TgNs6WT45Da|~z`x@kUN_j= zQ=-x&8bgs7Rbu)TR1fdqtwc|(_QuHLiXM5V(8c z6(RVe90PP=#AxB<(pl7{YXQYF_|7>)&pQum*i9Kn=T#bl8UU2}XGhb6(0@8iU$j%s zA%=+{M1oMrM51o{7%#mS<$b@t*WfaWB|CIEm-L1BR?l-TM}~!dY(3s%I&7promOxs zeN;US-a#vk*})NPm)cs=QB@|Kl66&OKkAy7HdmOY{S^2C#;Q2S(-J9=*O97>g|dggb|c@`RFsBzA33EI7e9yiai@g|dx+ls_yu9)kH>4NVEjvl zcAJmxq>M3Tn9A6Um%Rl3J=}rFuheSmh@9B5CzwKg;p!~!Alcy@DIlq6W%x#R!>clg znCg53{Kwazj1xlaW&FE;kbfUQ&oyVRmWE<@J-vW0LMX#*5uiog4=R;3v9|Np^Nk#6 z@6OF#U~eP^x2Tl#8|mQ^Vc5rx6n<;En8ePI1wA1h8B)sS#0tI(_nQI_ec*C4!$*D! z62O+E*N+m7>D;=~r_OO9U{>FC{;R_flDHQa?s;bKD`pTeYeUu&gyALuqS2)PQbUa3 zy~goB{5uJ=k7))#_CMAWcw|h|Cy(k1qdm~8`#}7PJvHu+TXAo4)=MuKr1C^%d*Qw3^Uae=W(ZfkA^Cvx!=up50BN z9jiio@J9&$i&#AewlFMXa$i?yKjCA#E0Q$9b&K~4LOMb;4*FC4^X(7es8I-Wx{0Hb z3tFh3HZF@D#!XsiGx;G~jdq6J9mMB+q1zCKs8z2q#;lX_TF76NvF|vsamMw>_`xz) z>W&zFmG*jA*A_tyU9eP&mvF(025BVc+*;)DdF)6bvaU!$V@r=%`sYkJ^T?0cbm1iu zmT`Z*`qJF=3%Gs6@e&g-=vWkX#8!IkcU-e#-?NQ3a>yK@rQj^&-e|3HmX4aRaY_!V z@DE2JkHXQR;JXZ1j;Nv}nJ?_t5oI0php4~BmpOjrG{yKlENg1GKd`mF{248=T^D*G zWo1Xbi$Fk=C6O4WHo7%dvtnin#+n8Mf#quJ#rWJF<7tE!)zcl3%;JUgDUOMXBOsVo zkwk2fjhlG-#KgY_-_ZcSzX(Y~;ml6H#f&{dh#zR1b;|e5`Axh9Q=^)h?%i0F`FIqL zdU!9f*GKo*HcqnaS`rt-mj27Ep{n$LV#eSwPLQF*wqyfe{phaRpd0;Z!5Gk&6x`>- zBNv{af9Vae2#O4>3dq@>H3z*MUV5RQdV+m_*QE{ieuA?1!YmalCDB?B7>KNoR|CF{FQzjD_k-{v@9z2ldJ&$R>OQ+4aHyHF^I z-{*~K>im$&CoUed&~FzPA?hx-VYzjd3=%;00qrUKKLy=w`h60OtdL}yDY;~s&zI~; zTIt?|?KU?O>DKDxdw>YT?&|9NtHi?r2C)MN&n9~RG)ef7v6IL0*A44n;b~wfb&N1Q z8dz&ip`BIe8y;b3^K0E4bN8{b*tofHn(QbYh-OGDyA>fO7Z*R6F(HIE!jDydFtflB z``f!@nYcLXt$#+f9CMGn*{{u=pokS9-tF5!{0=Bwv&?)N7x`kF=?c1AV?&H|AP$9R zWYCsxlQr77tbdHM6Iafost$E-)!?Kt^$74UT*0!BoK7It!Bpc4eiSx3%EXFQyKc4ai zb1bZEX+WSKB!64$-f6hOurjXJW`=TSFp&8xQ+JeMR^3!4n-ju4n{m;~44+}-+-r6! z4h9de7vso#o}s%IZwr}hmqlnoR2`I3{v%+vdWRZ_3CH8l5vnp27m7KO2k)sIkT})d z(V#;6$AX1JDf$FJ=ioZl`|_Vk03&#`*wtX>`tY3>tx|+k1cJGLH*!@N{p5PEAj0Wk zj{vQJTZSWJiI%~ zYFK>RK8~1&ioazDA=h`D5elF$Wi*DoK>Q>8#(n%Jupue4Q-w>XM1aGl8gMt9gPO7Q zz|+}8Tf3 zae0)gR|5xe*9WG~T2z<=AEp7oAtZ*8p**1=fp#T!rX@IvJS0bldZ+)CX)+bwLUZ4D zi3q&VU8>G5fQ!|V59f%5+5a?GfPLHDMX2@mF-B{}xk$z#-yFFQSbu0nJz1mYa^G&s zDY+RA*9z8Fjb#LT%+t>+2tzUQbfsbBJg;Z<2=$f|@M0*J#MPV~yk~p9 zS;6GdX;>Wq8W&iakydZRb5)VGrx2XDHN3gX^l&|@ z5h5^K5HLuPI}83}fz|ecod&E#Pfk6!VI*ks>f?BkLhZc$Kj?UfP^iS_Hv_LBNVb2@ z#PE;1v4*6N-Or3{b8Py*{Tbd>BzHhikJtHezeVh`2x5#}?Bfh15iIr8G$MgS(agqX z(07@EGqs*5Q`i=Q{YCeGO&J?%0pc0ZzXoRGe`9Nktp0(%kx1bv=fa~vU!7T}MNAuz z{heD|T~Fe49#RcR@Bckfo0(&!j*eh?+Vx!eKHZ zd3+$|s;vpl0xunx9MQxlz-1(1hKCD0!I%vEtx;)hmBJGxjE*z0c!;(C$1JhGCU8=$ z+q`0r@f0#Q=#UG+w~d+t&!x^D4bhsFU{3P<)Smp8f(n)F?^H++>;~0L{lvH0@LCiM zvM8)st`h@bQ_4andHg^L!H2Af#2~I=fsBg=+6VgauvpOb#j((_!IFO;|GkF9cZb%M zultfd_h@_^&Qef$g5lPhYeY4a34o;2t~G%(ST^9m+@l2hT2W+uNS2B!`ny zaj4IgGEBXXK4h8zu97{QI}-(|85gp%70MCmE`vl3zDMs+n0lYDMi6{&gsPxRgNDT} z8J5{GnM(dFzPb=>U}-81g~&BnV=b_zl^zG1Oy)OkI7>``29)fk1*%CcS}6hIL-bIQ zsiA&jk`RhUm}xF22@)ez_8c6(CI}-`uiqNkRw6Nb6PW5e-om*acs)UjDjGQ?a6=4qZ+ntU0v5uHUxF+xkNanBM;DpWeXT~IEBww@a z2(B?IaTTU;whK}BG}V-thMA|4Qx*eb9vIqcujb>n^fW=ilrWvVc6D+{{$*nGA6T12 zh{8@kOagjC_LLComz(utFHT3ik=Q;UuI2Ondd`ju>jkbbNE1A<%F-X64eON<9K}K+ zR!^Eq(pXr4=Fyfr>rqgM?MUefqcb;7)G%B`-(-)%liNMjVa(-NA4iSVyA#p+YOqOm zk=Z*3a7#M8{g`y|u#yT=1udC;0J4ImS4e!Ax`@ z32PkWz_nJ#d#>Yd`@jrQ!R-x@6t_;;EF{C5Y^-`7dt!h&jv1pHM72h@*HXEx^ZrIH zHMGZnRgY%j`$AGv3G-^Qq?&){Tc0|-%$>MvJ|{atPn2&?P7uZfQ7PEgZU4> zX2}duC$pxTAQWUl``l}c8(t#F*UA0O$3fRzJ6E8q6VIo*`*>h=?cMd}77<+T8Tsz3 zmU!C)=9TZwV+EcVi&0AyQ5|wUiFBtN1$KxX4*`I!M}XrTvQ_D?q=p~!0_=ib?x@Io zbEi_EFq{d2!ties5h6A-omKUKFosv06rY_iowI6_-%iSe&CBL z>loZ}_h$EgIeL=&RHL4$K=#^)7UGFhJFcY9J5Ypm@l!gGk^<^2O(P)t*&_AFd?(T#`O*n&hoD6IWG%)aKr8O z<{066CysTZU2P&NQY~Z7YJnMam#|soJ5!$zPv=$ML}Ob(T96)_*|y``E>VaNP^$Kj zY_c*fFD`vLeWC(7QwQ^q)IRS-ldFrYYak!Z(T_ElLFt)Xz#B7$<%kdW!syu;(h!N6 z4ul&)38_PzZQfUoWodyiMDcCuLCILn5u@j zqvpD#F?qwe+27jJ=Dv$}0wg=bTXKCY#rxRdKTmw%^KLZ!D@+pHK#HTe%a~Pbv&?~O zV=(b^pFNGK$oL%Deuxa&Qs4Q@uoBBQTr&cu|5!(_Jg&a^H@)d8wBo(-lr8ve-t!7G zP$x{zPmhU|LUSX<(MnvdL*s>O)P7N8cuI05apQsV#zu}~%BC)Sx+>AF(Itj#EuJB~ zfIPy03Qzc+11jz7nD@AXI6v~-;@h6=pV0d$VIR^hEzse9^%Eg8Ye ztup+^4xWj4%>AkUoA*^`)u9qrvY=7?H}In~sa32gmLdFQPKOa%=M!dS1}nWnJlj?( zP?IjIuwW1olu`h2>SBO0M4gG)B4Hf{zbHSa;lWnX!FDxzs2f_kmVrJnXCg4xd0-C9 zpepNd$~k_Ijgm0R&2+q+5y)226rVNyUTFB4pGIsn-{m*$=_bdP@OT@1OWl5YV&rWG z3=W#gQ^spmCp?(H$1P;c?$$WBZmsu>GlQw*&bEyZ`r~?GznTidUXc#ccgp_bm7aIR z%5=4e#E&nFf%@v0C?Gn`nGTK2(!{gXh8s&WwE|?G1!BrBvv_uyBb|B98ayeQHeBYe zwzCowA>OYtJL%aih7|Sd!av%;`0k$!{`)H$eH=^*FBvHbuYO>;w_soPByWi(Kq^dn zg^E$|95~@^h|ZwqcIQicOt_fllQ2xnv&EL$uLbW&4_acIBpk}>O8uP1g;~YG4UFw3 zc$zzm-Ca=!vN4h(-6v4)=u;9@#kZwBvA78yFDqdj)XLw6>PW?Z(D5{1`c{fb-T4Ol z?RC^0`Y+~9{j0GtX@6A6w#^kaIoFRhq0d=8Yw(4Wzxc7bcmJ|;`8)E7xJ{?F$aHrNijQ9Lqkrdew)$3)?sZ00r< ziMQr33E^8TJPaxc(I9Na2?o-e{76T{uxqiGOP1Q0gxKqi!o@JrlFzLqezZE@)uiEh z;YoP)QfOp(nxuS;AK5m53;h3VyyyX35Vy5G=gI$f|9_rP?4SpZ{Qv($to~<+@C7FK z|MjW=3}Gb}fB}Mu_n_KA{%^BwDAI!)7mH|7J@S9`|L3hNup93G@0_^6iSWUv{JgAw zdj9x7=lVZ0ye{hqn+e_c8k)ic&e?+6>}oL7W@4jG$;qr*M9H`{tvXsz-#C{2?UE1Ac-&b+7Q!&``g$*bB@T)vR3eFHYT}Tje+&FARe|YF??HKt!F= zg^+oUaY?bd_;en7!_&&Z!hLB>4aOZGv?U)6G(rgd-4LR52Ry{nwb)gnHrk9j2VU%j zvvE@u{Z`vs$ho|p5a{J|eyqZ$PJH6m(SO&(dU#KSfzW_>mN@Avc+~Jx?y5!lNm)ul zl3CekcuI{)^rX;;tYK5FyTe$HchTaefcN0$K088xK?gw18YjRuL{L$+y2&W4D^zyj zcaHrkbFVboB|RI9B^JrV6|heJlQWg7iu?CWt;sOkXp? z5pk7Z=aLNatAhSla=*FBzQgy<%_(!X1+7dd+X`Y4Xa*@!4RV8DcDEagU+1}zJ zzn&5^95SnHFJvX%RPA|`@~Mtt>Y8VzuhYA}>dib8JgKIPu8Bv4ap5FNJQs-{wxq#p zkhqvdf^k1rNin(4DH~CMX~0V@4d;dhEnH;-^KcRFYLAzDq3wW!ewg3|%~<4^sI1Z{ zN^dnW zCj$$LYqkhFhyResDY9fvqEh08DbW_N=&`g~tNE(acdAXClITyk>fKjn;BE=rn&vNq zlZB_!YJz6hj3Mhmgn@H5WJprO0(%X(bez9zCpTuB^7|1lVfe{Ghn0oC0~u?c^sHo) z8N42q#g;vDH{mz?|6M&_+p|YXNN;eaGjW;qqM8dPo`dh!i{}ZbFIf4+}m336*ZlZzuk_3zd`sB2E@(T#BS4S|1E05F584 zjS{O11hjDO0TU<&;+}Xbk~#@eb6N~NcA5N8!`tlV>;8mrSKLh9{*4!57l8vXhVmfk z3Wns1cj#&ktsLv6_*%x9o>F@21+SZ6$x6!Nm{ zHMLoo^fwyIOw>9~1y^?7aWE-UF2_v}<3X0@2I;+TiRewx0D}rQQFN7l3#gyZfpqub ztkdVqzMMLn>Vz{MT!VJ$kZ`rfUc@pVNq(UYc3=Xsx!b|Ms2MW!yE)COWc8}Pq4Y&^ z|J(Fj#22_9-o%mz}y7}dlrD0laUeWL|6?qP+ z=xsKS19>)3-h;;=jHxVePwo_x@BAHZJ1fbm$urM9G{-v_n4T|AI-33;IsQLFzlRFm zAG6;tOyX)7OdB#XY~s)Ey3lbXizEgnRw}7(_)E_dgl{mv=tBHfSOe9oTo*k4pNI-4 zFIuk@8X4xL0${QWRDrFlLQ|(iLuo*Ta*jL_`#nkR<<5hRNa)`uk2?`B_>qwifVk`YCBAzh>Mq+s3CZJ@$S$HQJ-b;aU{?Lh}GyB6C5?tDBMN>!q$Od04lY(GGRlig5q_VK9Wm`X7< z5fr9(8WeV5Q4oqKv=9>$r2%pa>bu_?&iXE>TG{ka%-zdo6GUy2ZPplr9J6Ax`t0VO z^B2oFSit<9so`PyZE_<8;U)uYw!B0<5wK=IwyKzJi!bFsFGw~Bx`ss)>+CmNT;(+w z&fvWOH>`=5kXHDv{Ss{av7Dq5cXTkBtomakov*N!RIE9XkEqFM1r~U;L?wQTco)P6 z_1xDHw4&{te@h-*2i@D1cq1@7XD!|aZGC4&_@IWgsPg0Fo)fKA*6@$dFsn*7*ITLL zW@M7~@Vb<|Tw3%khgI|v%z1W<&#&Bu43GNRmf}?$g>4>_amC!*WA=osSD!b6ZSh>1@NOu4=_D~EtKxt#}f`tMD^LtmuLOnu&Z z#DE9&=R5*nTi$OC*}=bMA__Z1YxtoGZ`l+&9rVBZIPC{?x*Y!5$g_H|CZ`$oxiW3m zFt!(n4^O1W6@O=!NU*)mY+#ZXO6ua{G7xmT$|4A9K^LhnZJX(;@in|IcE6b6e%oxd zOu1Fs6*7xKRD3dZt!hMMr&zSBTg!#kJwaJlH>a zx1mqOrgUPYJ{2$mG&9?VTzSxRca-k9?dNt;<=)ExmvvYW^d815n)mCwVP=^iOH?_t zDlXnHs06nci_}hsKiqnkd?V+?&zb*Kl4~YV)L9V1iuw}_y4~wW1)6=)SN&9)Obv@a zlyJgbryG}j1)TqiiIrAhN!|fHJ$~cFr;)xJv7lw%6F8x!o{XlyHlgXEO$u=_UK#a+JB@#(1=r!)kG;6H^vuO%OwM@?&sZMP^N z<*sH68MAH(1%FW>lE&(je{icRWEr$d^ixqwmuLkqlmTRlC5GYeKr~E>uD~nwi$3w! zDj%7-3#--C++-W{!THDNBf?tHYRb3x^-W%*Xp|;Nl+MO=5>keg0Mw{_7Bk!qJytW1 z0k`ksFa?^k({nE$7N)s~v1mcx473q6V54+kpHjlY#{(23L-Ieikl9xc7a%Qz{XZHB z{yr{TBC39&f1}Jf@nRVpVCUbnzYkRLt*V0U=s@QfZZ9Lvel9hutg?D?D%z;(akP)j zN2|(2h1N{>BmV|w(M5<6|2{D?Fv=N4V2b?2V$Q)UhaAcwwJoN;yJ3yBMZB0@C;ARQ zFDlxoPx^=ERh|18xZJfU6@)I@@yd<>M#Nwl&`KU1ei(%lmyJ(nb@b}6nrkVt?SOk| z4Wuk#6Xd<8iv%s{&Ha^Pt9oh`q4G?rO>F(!b*uHZn;1J23p_MHTaH@(;Z;M~tNNk5 z&>FGJ_g+4CuFG=ud09?n1%b!8Q-zU6NqNDFFMVN}yDIl;NhGoKbW^(Ncabmx0XhkN8yd_#wNN^0vscWq3TE=QE>X_`z|Q*2^)Y@(Yk9v<$tQ z0<#kPe=@lMu~3M^ICD0rZ6^}7bow4X(4%$am(v$IwiipDmDu1n*-El5`|Fr*=l+vT zU3DXKvvNTG4I@MpjkYx*=cw<@Fz}cxs0Logk(=10jiSF#)Fk5`;AG&C&vN32nNiDo zFl2F@zCU+40xQ3nFc&T_jU$MmJ?vIsj0XxWWaGCbu|!{;&4MIIb21z@tAa6xqFuh_12vn{||d-!4y~5 ztnDDdZGhnJ5@2w52(Ah4?vfB7c<{m9EqDm-?hb?d;O;I#hmZH1I_G)*!dG>Ez|^d@ z_g>ZAcVB(4Arc*}@&0fi<1~^!O$`Kd(mv|fQoK%zH*w9d5wgF~yD5DIV}G8Ja^}&% zhan7)qYS~5B81rP!8ha^_e<)aFnWiP?Sb>x>0(gMcrph zLs0>5vb@gG77&!K_D>!dH{s6o?_PRWL3>sHJoH3@7)`eCwE+H;Txz*wE$;}4-*&I3 z;PRwAG;G5wk6%-aP;fqJsX}S4!N;KarF0_wWuAG^!5~$u)E>b*$3V-}D9u8|oXHKI zWwyVF=eYZeL+V3%LcDPj5ENrywuRmEjQ||>bHd*JdF-FSn+$+u4u=5*0z>K^*J3d+i94R!$0su?3xnN~%gM-dCKSo*K-Pw=V(UL5}nu($oqNw6@re5$= z2l{rE27!!N{&>e=*5Xt5qvi7VTMT?h5(J@rF8*FkD-Qj#+0yU!x`Kuxneyu=h$yaz zkzbzp_JC9f7Cf_IxG!VOtI4u3!#gp2ViDy(s%U!n5I>Vi-(mavpcg;8v(+z4XJ$yp zGKZP)Px<0VG!1HQB2s*mN^hX-hIS*O`(F}C*s^Xx-_Qj^9kecY41+4_NEIgZ&#iOo z3jzoZEFGk#s#hjdOcdI!6nUu56H^4yl9`=4>n3BVy<-&3i0{;%yVZ1G1m&TAnF)AY zVjk8A^GW8*Di>3-G7xgbc;iU~6QDW5U5XW?jFpWWSV*-~$nx})9gj0!G0moqGtHZW zn}{g0>QgGXQ)t!J^`RCjTI&%VN1tS+u7=QeL1;TpD(6#{XOv-5AwTs8WWt9U2Q6=$ zSbEQe z8v4*SLbl#KZaa#4!VDxiH?Tz)$FaTAPRS?@;Q2(9lMn1%_xu}RkirxCZML{H(FLXW zx%B3qHfGIvO5v4hDKe z;KUkWoB#+}*~T&XWsuy*`h`OQ(9O^TFr`nI5*n_QT9@G_pIVoCXYlj4w})hygVYF% zl|kCr(D%ZO*b*m0+uBCrN;6nZ0H{zOG=K(Dd+^@)h;6-QtuyTn(pK;ulInQ;1}HZ8 zPv|(q{lGfedMzwcykUqHRh1)i4F80qFv! z;I=&V+Y5aitpm`O*tYnhRJPhQ^J%aU8bFaEmy#z}*xhEs>f^Cc<@2PDm^oONWKu*+ zqA`djRb6$m?PW7jU?N8wlNwTaMp`4zfWaGG)`S93@ zx#Xgv>k=wX*rq1kg7@dopvHH}G0oXrJ|nLKHg$MFq82N9DesJORf5jYS9Q|#xKm;# z7IgaSRlA5&JuBU^^s7Ht)ApY=zFyoCAlAN~w@2`Vg;3`_5Goxd3|!jlr}!lW6qfFiqGxR z2CIm;G~%>!OW~r}DYHfytdyKC1vYAF9)a#^k=KvJKW{X#O1N{sjoGW4uoF(4{YK__ z;P9Eg_KdOSN!A?=6fJ%fxCrwg|D23}XO9L&K>Yg4*W4lO7T|M;T_k;;*Ut~1peeqn z3z)2yi(Cn$i4w1a2SgLRTdi+0mT)_6798u4`aWu9MnI*Jn|RC5GwfuB)+6fa)ehSI zZYXbHJ@8!x9PuV4X~-EmJ11{9s5?^)-keI4bna?Vt-smed9H4-{%M5$wAmg}t{Lgq z=ZUmizZ-lvinVFv6FHAgdxsG0^b{#sHgP2eLe5 zkk2mPdKrrm#nrrG0IC{HM_EJ9$qIUJW!(_N)C)kuEvs!92`N2oC(a8Xq<*nT#3M#X zO$^jv$DTcC3zNNsaFEAu22z9NUs_Y}Zg9t@;Nanoz>@7$IPmVM8bPu8@#C?{lCFPq zY7hf;6@os8hjdkH=XuKj6~!> zz~Met{M`DoSv{I8m%Zp^CIPnvC4>=UmoAY4Vb9QrBH6!pa2?O;YpJp2+eO9Ya%%L% z(KH-H|4Gj^TZ6d@u1dI>&$p$sAWb#4P=tm zMVtFo?ZAkZ|1a|j>x$>S(7NcOG@YfVoB!T;%2=n%|H}3LDp;`0=`dkiAA9J%ZizCw z;P?MhV*R!MBM}~jjQFO;b`TBA>JQ?EGqH}*Hd84#x?=swpcE^dOYITbFE_(KvHnc& zc0SW>u27_@(QMQ3p5Bsw%@TAG&FpSNER_C}RQF znMxZ-z^V2s+&wqn3*egRCa9#Y^TuwC#=VLsud|4?4`^RGVA<+|T~KzTEJpwR@A zpnr^v!uoFqYkT^w4{;5~+KDn#Ejy)oZOy5`mu23GV4=&~0pDb&uxGM9Rhry-?23>* zv1>_1M{n%;X~zTC{mM&~^<^vcQNGj3boJHkwuS9|sy&B}hM;L1#Me-pRh5H%t~%*( zD6L;6P=z2=;%s(v^gVI@$<(L>zW0#dKg|?>6|VoJT{=?^?>)KA+hD2 zB9ec97#C5;glhLNV#!l(J4`F_em(DF=U*ul*V%s)e=(8dAOb)R9K{qxif^x5r5bp@cRNhGz1=1r^PveJMI4;%m4 ziBF2b%I+B2;<_msCYGN=J{h0Sr(VxL_=!CK$LoZ#6}}GOV3M4UFt`#r#qOQT!IBo+xXfNoM71Gdn~9u7R6#uLj_of$ z)%tyDqgOHA#YbwDNG;WPKyRvPt<^aS$<_ccQ!mXlqnLzH96zLa^?@*ODzQN^J#M44 zMjlf0kj8Xagp%5tB=uuP+w1Ed>YFmyoV-0 z5o0$M8mjtR11qG(Zacb9D}12f?jUJI+A~g2MB=iMe4iIkK?VL!4q|otJezAB|K$mV z=P3p|*cvmg!(6iR%CR`ZA1E}jO3!jHij-rIB$P&y6)OHnhq2)I^#I#FHS!9zu|#qb z@7riS7px@K$x}1BUUX0RPC?5VZJ|W0@6Q1XEOOi^N$!Tnr)CNu;dPNGq%4BeRW8q$ z_+3N<-_2_loU3MVjueN(Y_P|b0Ygz{XchrgMka;!J4=sg@1U<{&q0_!yV>Z1hcv2h zZS`BNk3AG`2duq_9{My#1`k~8j9&N3ujeHWbPGSilFW*cxKl5kXVJ&>ymm~@TD)Sg z4DXgMNM@sfIX9VT>Jdwkehoao$A5sZi;1h2JrPN%BtBbaI&^IqxA&0h%HL0fT)WX&Xzaz&q?Ue(*SBckb>WTkuZSZtPfE_ zssjX`NnHR{V|5$&hbak2%@x|c)UM3DPI9sm7-V8{@v zmbuS%8wq(zg$cfIl5H@mV6M&)Y+_8kfrk|+;#l3RLhgC36xDLjqD1loucBL7w?1NH zN6HP4bLE*Zc3>3=V|AJ$d3Ig8WQ?BHKJf&N-ui;ajw+p*@0lJ^xfI^!;H`}J)&zWL zQwfH_))OHp%rt*y*{OoE%=a#L;ZhK9`QY|Ez|tuXB9Z)3t)dbl z=PHkrBOt=C(NIsAF8dujS^c5et?B*8T_=hGjME`ePv6>8G3MN6=TcoFAUL%1_8wt$ zc%*8fYwO9H!?_E@g__AcRRQn9&;ghdil%OxUgxWdo*ZAgqo&em4;TnqW_n2O`B6lo z6d|$06sAUoe+}apK?^uw0Z%2|E~Mfw@wvW@{%hNGN;Zh{eR0C~Oq2YRv7cQw(#UpV zAVY9;)ddo2e5uj#7qKjKw*6D8)b+bu=axbC35B$_vb$>;s14tv}Q9) zz3c~Gum2+kZ6t(tg`0>WP#*1UwED|xxk@oUeiVV{^mhN;7XcE<`@-0x#_H}5?*JpU zm!aR{_Q9s?%opct)==%fo`6FNh^Jt)^L|D73Cy}0Sd|Ve@4X}Pg|jloRo-Z8^Rshp zvfHZku}txC`)k}3Y+z!r8(Hcl`rFfRiy!}Un&hoRP@e%YK^FRl_ji9gYeZ$^UETXJ zWAy8KS5VahOQuV)z6nwsnI{)SpuV2rlh+&3-7qNyt18qeI_j!yarEMGAyA#w;#BA4 zD7CZ;6IxmeV@&HEjX3jFqBY#L3`*>Aw7hS9Cu3`HLcjS#&x)UoG z!BMVf#s2mM@f>{XEk9-|Cz@&RL~-Hvr;}@pv0JlNMrN~_eY|ks>%N!EP)G0;DhktVo%cLpy)x?(7W`mERSbD(mU3eYIZs@N(>vmoluiw%gRBbn$K)Z&miS z^hV45>Oh1vm~#G}t_JE@gE7JNm600I^>#TDeiruHxmicjaHg;K!edoM_K%>SFu?mO z_9^tU^y0J|Mrz@)^vb^(-xFFqRuleJq=~|7qQS*uR(s;*paG8ORy^V|Q-uYI)L?l` zEvaY7S8sg6p2Q7%_Y6BQCe4kSR5&9FY5V{_Gv!KN<4yYrpR1 zMu<iBy`=w-Ulvcaj^zlvDMClX;j7wjEwe49YMZx5UC zFrlW&0R|D!e+4k^IBoykPN~>LGXgvlnU_|&$#1dRw2T}C7>l?x@YlJc!8T)|vA*@l z^j54{@-E@uZtAMjcU@DMzCOI!adpf-543@_zNaGGQ^h!kLG~AqBl=J;6TL~#R{u-M zwssF%?VM{=C$brbl%EHs^{-Z3&MW#lWp%?^q~J4K=x^E)6#N|!U)N}gas!$2d{(#^ zqXhjV85`|VcO3=W2Y5KAKO#3+|$(lljEtJ zqJz@tuFSRg9%+Zj{!&@Yy0{yD2%d$Lg)QFdPD1SA7Q`Pr(bq~(-1~wTo>}-?gF{I@ z&6J~nHm=$DJ6>oP?9S8h65ifMq;Pk?Z_DWZ9%=0o4EDelHd^a|*|$0ot2I|x?fJtufi0tg!T5VU-EOB&pAoXtvZ}Eab;H1S zVz)@tV|MjAE=qI(SwRz|*a=b{*6{-+#4AR-uxiqckVXd$_^=jw<|RGx}6EIpAv?latrQ5V4QX z$=b~wNcBVLYXJmEw5y}Pt|mscDViy;~RzreZ8s98an-~w@{B_MnIH{~m729Vu z)6Nu?lp*gGKj(d|Es(xf>%GPLq>aBX2b-B5Px8nvz+qdST0yd1bf&LZ=NKIw(lWkr z;FD0(*Co4r8Hh<#j$E#c49K1~c2=jzmIf`ZroyeNh*DFQu4Qh-m{$-e`w+@bEUMaYM@3N18!x zsm0dVma*e^1Jw~LyWh}1(w$u0b}SQx9|X2V_zR7`5G6$V_Z%9A02l%uR2yrIk)loK z=S06Hk1{T^U|!R*6Y{FQMsi@hM3y+G?zjkUr$;d6Txk{2>!7?Ru|1&p(H%R7XO1BH zp8sdWa5M6!_-TcRDG>F8$3VJMpxeIe%#l%$lUBb*Umx=@-to>=E z!>duUXQs8hPV^`(9>2sKJbyK~^ z@z*$R6ejvmvDO|;a??n@=LGou=;XPgo_+81>ysmnoIBgerYL1+Br?(v``QfU04||y zq#TvhDgpd*l_8cSBbL%PApRwnQT%Jr$-yi=tk|-|KKfoFiUU#>Q+=2_nM3y`* zo)X2vQ0Yavno8(MCJSPZfkWJcoG5q|s2EDKMOCv;j8m@|eF-PTX3xnWseXN5;6!&= znf(E8I(*pV`7SeRB_h|jtEE>$8zqOVDpArkaefQ5GPjH|9SfO6R57U=_r9U)!RTz#9V2<9*EYXy zRtP3mcGC3sRKtOV59x~zcGcq2Bvq|k@UR+k62)E@>hKnkXD(AcTQraS?DkujY5G;PPmX|)nj}YWX zY6vB~c^(>*1Uq5+#PeI=b*QB$= zbA+3?albZfroTMqv^izep3Qy-YYhf^Kv%G;olZY}Dca`k+UQDcLU$)`l0)(R^oySBqhb*i5sb1njQ?pJY|Mmo z4N69NLsV~}0-$eZzxD4`hin8O;R*I)F36PO&hoVJEe74APLdV%&Iirc*W4pK?@s zG)~c+J(xThkenyQShI*_V#fx^I{Gn4G5*xzqSpDZ;{Od&D~@;rXGIO3+udX~I{3w)rRvXN-luf%@>m>WY4=%}C)>pOjO1b${P!+S~2`-YNdGpNlDq4YVPdz|xc> zB<~%hgNhU(Q%UBnStR!kw265J=}_2x#@TB6|9P7K;ci82{sZyK5d)lJ{+?UyD2NpgD0d$EPg43{|5%0g zMkbpRqQ&!0{UbX6S1F{;__nJW^-t4JoByH`|FgJ{aBpv1=l{0ze{bjiKDPfK&rWQW zx}pbz-w|=-GFALt}AmXlxXKK;Y(9rfehyx&);*TQS^+%$!qVuSF~Cc zJUZzTCX~}>H+D2fxsF}hdYgJgnwDM72-TKEJ`5{$P*OC?!;GFJ7p~P-?~pQ-v(p^w zHmeqTba)&Xn_LI1c@;Tnzf1Zy(oG$B*JtY0Sab7){&w>ie?npk8V@6~%P5xP=Vu;- zfrzNMPgMS)!A=1e8Uu*3whMfx=^H*J(l%c{+jK&Jjk$PUce}ty(5`c z`|AIA3wWJ1;14#uPy9%1zg0cYhdvXs$tT3w#g)UK(Sjhf{VpoHyS>Z)H< zylFjzesoBlQD+Bd=H}oGMxhWmPhuc6rC-%Eus$3PvybLI8M*Z(CdioP$BO5HXm~G< zaoPywOWLjVVQ`7?I|%3FxRto48aReXp0ftwTevE&R!v9ZF2|;rSn%6u#$}kuk%&-l zcsxA*G_Z~^CieR=zKqa;OIJ#n=$>ey<7OL=9;KqAHxY{-t+FQYvz{N{qEJ^(IfVA} zLYq(C>(QU9#z2Sbjo*cr(g+jlD%jU?Y4PS62UY^-*Yku%K!?;l=d%;?h6d=ASd}!n z8WaP_Dyz`2zmTL&yK7lU8!TDjXZ|*;g0bW^CLB4~q)|Zgsg~uw;tpL+%hI++I6lW@ zx7kKBJ;9ODn7@F3Uf5jbP1FuSQXkNr*jID+5KpG%oJg4_-_1x(Z_wP6Ils79v9IZow(eWZTDOpzx5b2!j->#8gOM^?5v{{18UYG4eEzG*1>psT16^d^gP>j+EmqwH+wi_OnwLO>Zl(a zFddH#9>ET5Z~Zf=o~EE6f1}W6?xTn4wRBSs{jQ?8%+Pljv7r;6<@i82Y;qbi9U=m3 znw)Z?hdh4#EX8p8d74NCKEdb1Lo(X9dltABU0)J9O6oH|#%E*iS<*^caU6W5Uuy9> zWcE5?@-eAy;pS^dW*fw;xHY8gfNY#A%7w_qO+nmJdtLYSG;%kJ!G&`)JN(iL$KD&3med}!=BSH^~!a33Nuh0>|+`)tmRc1Pmm}-z7+rbQDlk& z+DUzBjb$&6sBiY#Dj;O(v4cM_e;2@d3e**cE#bN*<*I5n0V7X>93ZiyQM?p8$2(iH@MwA@9M zVTHs!@*JCOzJejx%gq%+Slictb%=_TeT<8$@>R?9nw=>B3^sUf0A?a}hp}D-^aam#Kv1(MwmI2ExH1 zU`amfz8E*U;1F`22XDM%LkhAFA}P3)J$=2auwB;wY^sxHlRUhamX%FZl`0|c^QU@D zfbzNDT&}bx@%vZP0q9z`z;Z`!fTX}wg)91^N;I#w)-gP>bwQ*rXf&{}`EId6cQjA= zv>*D@5{V;t@) zdC#Vliwu8ROjfIDu>hMMa$iwAkBcnL)5tu^a%*+Z75}>$PW3~lAQ(b_W3r9O#m=u? z$~<)t@@%`tTgC7LN?g4pthfS4Y{rENdzMDwjpXEHZ0F%=Z84IgcXmw>8}ho_!2a*C zSTSFR&bBT*9M|8>E`Lty>oWusR^-5FoIYNLM!BJHaekHpOUiF6c4hVR-vtjg>Iy_o zA-U|Wa%z>4QGE*PjCW@KIq6|Ls9Tyz8d%i;FQI>3oaSdL6k>fIHsJPj*Y8&PGdJ2t z(TuAfzx5BwiHp~~9tN6&p{76|;qB$i#bVGcdK3hT?sGTZTza<}f}xj!fNq zeU%H^65pFoh?xyoMn5JdsrI`w!leEJD$5O)pRe>tE4h;%5ciqhU-aOWB<~MWz9u3M z6+1d=#5A77XuQ+0xXMz0RK*MyYVVl6yJP}SR4eWkBaMCEd*a(gldQ5e6mDslfu01? zWf-rR>Ml_j_5S6;$ZNH+8mh%qx^ttg%|eVG4J_ zUmg77SEmw&jO@1arJb~M?d?Jlwl@{h*sAQMb3Cmft5z_uwh%pcOGU)~UGLd16Mofr zyEnX}#;Pc!#&lu8`vnzzxa(%;d7iflpK)Kyl`ivij=TN5a>uk>oy!5NPcadAJ>HDi z)KAe=DM{ezhy;Fpr9QsLHL>p7u`d6Vu$MS8v&1XHZsM?Uzt?OxFJ@FAHwWg}x+=*>yIYym~xRfU;u|SGOHBPB11%qmVP&_pvl=dY`w+m##ZxbF4ZR-Y$5G%p13_!7iQT=+{Jw1N$4ut5T`UxhP-DM4gif66fzjFqIW1kLr_et2dPjzbe3L{Rk*)!G4 zG|p)=!e=Tn)v?PH;g(*J{qkADDk+@Jz#Kn{p;^1Ux3&Kc48JcePelvzWm4RFVi8Vu ziRt6)#UBCW$6}f=lI#~9EdHUFB`VR|W)AxWfgrBYKIcXGp&(DEG-yIxuwZE)mSCs> zu0B9J`Q{tO6weV#R(X#?I@%>(6>hy|jNC>44V^SN*@VmIJKF(?rd@ct8sfaWqg%ra zSbV^Z=bOZc$t?z+iT*Mm5bD8-R?mYcFYr@p@{cG{#23SaxZrBlWUogk?_VJjM51^6MLQo zj78SeHcp)+bn9Rzps@<7wl=>@O0hf$e@zZP8toXUKpABSK>sRN#GwV*Muh+i{N8{y2 ze^oZicEU$jtQ@%Sp^iVQ(Nr&>)X-q zbbp0N4JhBsyHKGe5K`OZ(=S~?WQwrf%}UT{y{8ms+g_jOpzTgV+T^OkvM3{zn;SJ& zE%15W3>)q45qo-&U_^qmKAwkQ>kYQ3>O5qIF6g$N00R<&rTpVu+lXM4DcBNc z=}$*F29-?xtSMB;eQga%wex_pM8ITcCF!XT0{Knc`}Ji89K*G7Nzo z*#U{_GIf*mx>KW=S5c6;?OabgZ)*?HlU+PU6)ge1sf=*CH`%qnBowz&QVO|Gcw5z$n7@n|e- zAl;ME+(H&j$+BkP*^vT~!|pU_oN2KL;-avNehNX*wy)(3a~rH@4mT%7JuYo2-0Fuz z3oI|)>4G%a5&yP~^f-fr+P$(4fAag5v;B6uEgK;>Y#;DFt-fvWTZa6)ZJJ-Q+K;=c z`+lbXX@guHM~KTz&1L+O)^eTum5p^Qu`ON&Cws$CF$!|~Nf$3hKX* z$(3V4CN+aUQ6uV|#b*N#V=_0VKXop$4zd zc*9%@x_;%Q@nyKnI-l*mc(vYd4s2(}2&Y0{-YFS9Qt3KBDEJUYMF%-U&Vx${R=?eK zK~6A^^)^VR1lnLOz2O~faC8l`qEKmXZ7?Ap%KtjfTOg)duzwvGx`@ylIenKN6@?^L zr zVCYaC*eAQ~N3&A}KK|xma6_i;8@pBiE3Rg^Q-pb&JEo^YC-=)I1{s4PQt zjs+j|%Zq$?f6Me#a%K|uW@=$~^wG`bU&ea4&z0ec-nqXn1AeH&YjVNmz5lLrwA$|4 zKztZdfFgiK`(cNqoqCso@V*m+I~6Q}rwBQSMS4y-wS&v`!aH2h;7K1c@e@qJyDm&- zeafHF>UFAC@cLqL@z|>3RE=MNw=Y(?B{tDIZ9|GBek~U{n-XC*bBCF;OjOWM1@sIJ z8P4EXhq|>=J{P{I#P6D=qO=7p1!X=bekn4~+$ModN+o#LV^8o-c1Q%+{OiTHcisD0MI0X85YN+sxvS#jo;KWKsqgr@*eZ3R+3 zYS3)B%HEns=W2#k=?Gc%k>sNuUUrI1TO;#Yeza*|-6fv7&&7D$U7fpo7;LBl>~|Sk z=#j!7652P+5bPJy*{*<^Bk>Prlpl{O%C^ zjD6s2XHCN8+7}!}P(_b@2O^+@-zPh`mV)8>^_Q)c^}6!OBBsPi*%pQUDH-zdHz*1F zdb|oGYF%);?~u>JCJ)1MhU?t_C(~Gik*8a|gV9^;NPlB1eZN1VDDNU$N5$Lo_JNSh z>6GVLyLhk>8^DJ4*M4-0^_>Rv_vgAu7)AAj}fg4kXPh51HfE?sunj?&`6+( z7Ry%`&Id^1)U)XGs$Xi*H=sYBVN<8|B&U7-+#ca^(X;ohR2+vngx1Xnbhquh&fW0D zK8hR6{JFs{RnDRB+!&E4eW#I-7a*x1XFNF$d0gckx5<_Mc9F#sZ+n;FAgyz^(jZ@2 z`srtnuFrS7@>|KDul(`zi|xk<*HDJYC&VbyJ1hKUinAgXV#RnyD^PuB`sMvtG5u+p z!EpecJO1{!yb?G{f2NF#y7l(QO$$3?(U^Wkm60-4*igUAxx`IrLttM=;_e(k~M-pxN8g|C&4 z4Ucu`3du9uO;do&FK7K2-W(V1Cgr0o6%n`LO7Sme3aNOG42UsbN^{GLE8Vueg8ZmF zUVEztem;3?1ke1u^sqFjCN(#Tn?EB7I_w`82g7UWupIA=B`D3KUHZbl2I(Iura7cw zISzpLmrq1rnZX;%U~yD_v%+B|o0GbXuK@vzkITSz;ihUXAjK+Bk7Eo+vNieISkETf z2XoA9O-T2c!rP4ex%P7^8(S0GjBM(v%#`k_apY|AUW2BfTj40jeF+oqYIawh+bD$N zI7COltGUGDnCh<3qX%9+f87Zv+y&18f_*{^UKcRSY9~(C?WY$(auuelNj)&klNbtJ3Dg&=0PQI>5S2MepZ;Om>T$35*W8De zte~oU!h*@`6XaM&%lcaQ0SN})yftKKRH=lq-`?5)AL)j`4RGW@^)ma*+G zG@-fFhN{G$4JAswL^O^X^tTEM~TLB%B~4?|nMWmN`<%w(^Os z^!-r7E3DgMJCKO#haNwCr>rxa4R4|V{;TPwFOFTXYZ@cN7vnGAybMcTL=ZACo2j&VZWW0~&D>T)k5G*RRl zj=ai&ZUmM4|1JyosT1tRl`geqv-(WQbEVR?W8?S7^c>J#t2$y?zHqVatrDp^xT$a= za}ScE{^(!}+mlNO2*adgBw9$Jz_U1_Vcq858{ialg5c5Y#{hZPMCbZE2j~65Ty2!g z;nrKzRz5`}Jj52vy>8K4NvcLkfO@tFgiy6lrahtkp-TRTv%XqC@u)+E^HEs>j+*sU zBd*Jy*v|FHpY>?aY^7=^MT7uc1aHog?J`yGr0Mk)mbVkY4MmR1?1%z^bOr%{hl1T& zHn(1+@s`W6;UZ3F1rtr=5@vC92naC2dxNB5l_)j}o1~&E z&@G{eGt^dFpyW6*QL*JSv+^w(B7#)6z|OfxeLJFGucz00lSxtEFk$NkRvYs@g=xnx z9Bwwe01EIz#REsbH$CK6j?Qzv%pZGVuS9sJ!L(Km_XPeeb@eJ!0Sty*Z+&NDYGXws0KLcnQGFzdYZ#~c7mK~zW4A>=dPaWoA0v52%H;!5r| zEV_I3y(y~t!WTMRE?xr}+j~hl&q7rn3Fb*|<<_xaf=nv&pf8a&ilq*R>Gy%#=}z_H zzq|<|{quhrLf0{PiuT!uZ(6Qpk~b2=i{bd+hGB( zI8{3*cp4yK$&RHzRdK5S^zsKi?TYD)d@2;sD%!`F8Ale1#L66G|aBysprf3@g6 zE!CXP5KZd&GA3Qi_kG7tsU6$~?a`KppN47)k=NeA*G*HbpH{L~32@O+U3~umh0$%e z#cE5y%I2^^%`GBKDU6h^TU&JJ*HCzD0=RJSe|M+2e8PZ`*kF-y$q|2%lS;F4pVMLK zYgPQU*45nJnn6vtwdao`4f>4_L#m|P$fN^{@Zj@7><37ev>V*iX-<{E`qTuLyGcmmDn2IRecu(5x zVF~nGUp~Wp;1<58MIKgSDCk%S&7L~F%h*?1he=ZXq962S?A*B_1O<6carL@BVNk-h z>vfB^&R>V{P<#|JHD~4LyoIt?Gaa;Ehr$KWn`&SzdwD59z8jH=s4YWrVP)T(#?7Ik zGA5g$3BJv1zwaw7y|Z%4u33M*2rsN|*dB{LD_-lrLdv(iOJd8t^}wZfey`mWB$q)j zm`3O=;F#4FkyLZ<#3bp3HSnIsB$R*egp46Z?%^GitlT}>=@;f6rE(1$iyIWLl@~Iy zKhp`+RZ{RhxCUFbqkHTu-=sAjGgRzr&=(~};vSS}Na8Do{1rOaRn!S2iUQ2Flg{+f)ise3S?b9D*g zXq@)55ycfQK}Oid4$1*hrNKLlC?K}pOk&u`DEGE~kdy_d%xVI-IX)yxHV42BnY0NA za)UGGun4)akZay!s>>6^5M8r@QU zF-|5k^1QG>Fh^tQDs(Z15kh^;4CmrPGB)VPH@=CP;Kn9r_R+|H@$14$GI=~wH4`Xh z$h*@7pPh{%wLgQhxzH5^o@{!LKZBH1iKI!%&iX+X@B!nq+q_1qbJ)cfcsgWC=!=)N zg0V<)dLKwg@iY`HIq1 zIv}3@lMDRQbY}IA;ekV%uz^gGG#^S{Z6WoFVTKN^Hmm5A=HfY=aDyv zuyp-N2lM)z%O#>2O!j(J0m0Hy@Wr|vBMkzQ>wS^Tf4d9&s5XcU#jG{ZM-_tq!h@7h zesOk5xs2aVeN+yhrq8z`1AG*G_xm#O6RQlab^^Jei2GPG6t|9^G#oBKgP( zbh;W7aPtAKB;(oFgduq$oW(Sl4k(Mm-hZWlg?eL;;i<;7qX=1@u5L%; zRPX7v^)emox&^se<{*^Fy49-p4Exu@w{zr%aY#Zi~Q2-v*<8LwsQ` z7*{#ELpwbz!sG``Aw9*UR%7^fDDLw4wMJGhNey$C~3m(~7izSmRdM;xhWL*F}G zxT}<&Gs2|`DZzxioky+#cENbkzpcNwb`QuqOO7|16=z!8$wQkfe{ui7+t&l2Q&ANr{oe2Tf9$0UzgoV~Q|ZiN`5d)eWE@jvOKO_+zcXs~yr1bZl$Kk2~YbVHvKpq?od zqbQZ6S@k;Ai3~8we6g6T&`0%#-!c&LlsF>ig1H~!mO*^M_=LBV5ubeH6$rcJIf(au z(B#G+yT@AkvCj+s>PJs69{nquC-!T>yYE8}BDe@3=Jd)j+@#JISk=_9nIm+>7RLn>NKIBA0U$9W0jQ1NPi z_#XDh*!qV!hD>$oo)pT{LL}`l$+o4?=>0>JyWc4J!|S)G#-jLm&EQ%_o_w}riLiz7 zYK#LKLQ4r6zhZVvoyM8b59WbDUZt=HYj$Mhvk*O2q*8CN(v(2?@c{K4r)FuYKb>hnma*H7BLpOGXj@}Z;4`!RvrpzE(cEPXKYkHsMlWsOr z%$D9Dj{=vcAyKB{)|&BH@FSy;{4Z?qfLEn_B2SU#JJjL#%o3QTsBk^uZ6)2VG!w+( z^-9SjGG)*T$R1Qf20YWB=vJ=@Ws&p#9gmd@i{AoW$a@ z?v5u`kquXosH?@N)@F|t{^-4lDGNX7(R*g8VZGQ&3ul>`lfF@F8*$~L`y-)Mv6Yil z7{2(kFkCibr2#4@>>ua~1d3Ue40Lg9ZOBgpZmQ2id&bgz9#N?9D_EXAP?j>5)7PbP z;OtnM0~-p*@lolyEtKuQx3oC{i<#~b{o1gKasuFz9lY=C?Th}p56$ZTCl^45?k4Nj zLN6|PA`I2dTUu}l(ktQ<@`@JQ@DI{d7#>8PD?ipt;3@}#5gQ=%6s*7o#Ru+9gqkwWM4aY52nea*1ef zA(LE0YVu8h^R^ioMsc{4|39f$p$VD>giyu@F|$PYLWtXBEnM_xGi!UHr{tVbQ^Ts; z3e0kpG*6VYd`h9(okYe1ux<_%NW_Dhh@twTkdq?Kg7lr^p?k)$_pcfUaW9IzITnGA zXRp&PXf8O{9wRCsDY$`O=1-H<7SYgyVIkS=au?R5aiMo9zx-jJY84Y>^WGlPgTUwL zqPSwE^cQy$`L+6sx_*EfoI(VKbyzH23+!vtt|y}HP|2{-AfJoRC<3Z0UVPlIWe*Vet6s^J?_(dF&YpL??GRW6-EyqQB zZODW^+!H%|SH7Sms`!M5x`>n`o@9&a} zv1JVxnWL=e!4kVX6C|#`dbq7w4=3q%KD6^TNFK(XK)-|NyJ{cyC*z(`6BqSKVFKNy z@MuP`c2lJZe$VP@3o;^fG&UBI)og!-w+huI1WmG@MZxfThl-)=xn;A5*kyL3Y3=@2 zo#%PHc}HG1Eu_jLyUQq&phbdV8+nzfgxYhZMu<66|0D~{(@l}GpBnL_x&Kl z{6m!LDgqC19(&k6T8Ym5^Rttn#HZ@;eG^i;^Lsd*?w>$L<)$K*m}Do4U-=i#FKDE# z&9F<-gup3t>&0QBJ5$%vXv5qb>JIrg2PW)5l6MmS04E-yp5-o*tw{|50{- z2(rb0pD$~Yn1e$#Uu76!`FWtPI0wS<{fBQDDLVe~YG&~fLu~cO+|aOptT=$&AcJ!yb&WtvHxkH zTwhoP1U%5&&28-DU~60+T};^o&*MuLndyWL92LlcLa|YdJmxs zeD~k7w8&W%2Md7)Y%4GwZf@>5DJMUUOlmZ`q2q%t9z8$iiA49mXo1o&^352bpH_ul zi^XU^pQWJmv8hJfzL;&7J)ErJL|1ynq+wGmHEh$#JmCz>9J0;J)Zv{k%7Ht{1h5p; zA7%yiT=VIA+E{YOw`th2IB8R+918^msgCP&P9M74pn6NH1)mrmFqdK#rPG%<> zjnOpb8mp)|-lcD|7Dt0HXEWEVD`?HUh0h_C2Vnk^ea$^)N~(2BtlD%vB>l4(MpmUwQT!FoY0CVZfhsF6%&Xj{TqiLI6OtpNj!szBQArlxiv8k=0lZnoj69$dERt z1O956>TeM%o2yDbnk}6Hs^Ly zFst5P#)#EfYu?I~WmPpOde!Com8-plUYr1%cWk*fMfUDlVS{S%{?r3hOD*Ez&+p+| zSM4}VXy;z?}< zQBXFrT0*}S9~RYhRb+uCyt#v?`kYsv`|H*bEI3HTaG#4Dh84zD^wD5puVkejLr=#P z4?EO_5u^WWb31ON@&Q=~!m~70-aO7x9y&Xzli_*eD_uVch*o4Y2>U$k%AuV2hO|B6 z@@#OG$^$*)0#0?IuDqR9(vs5&16EEcBIg9PZl)<9vv1tTQ$#{9`vO+N;r&qZzJ*36 z7PHp)QafoU0NX7e(cjHN=HK^{=P0>19#~6;o05ZQlxJ&VTm2RknhD^Y+g>C8$M*{C ze(Zyqz(QjN^H47vi4w@!9Gu4a*pgd76zlROX{Uq_8#Mva!L(=eQLn4Bc^j%2&n%dY z`1LVP+nsr;QdLv6}0A|>7ilWE{EAoyEXSBu0*~g+RwP74r1S~kH`g{$?aYyH6<0Mj zZX1vbXPg2&%L6jVh#fK`5qQztjko8=x4a2MzNr|ll6w3LVF^38ava71O*jk5Pzf8_ z`sVUe)eg}48EJ&+#?f!7nxdTDMI+9-*A%(793LEn}?#eT{M#)Na}423P7_Qvw5|btX?!!;@xXk_pD}kP-b`=2wYxnRsFyCH~6L^Hcf^Qh+w}0U9!` znGy9Tm-gOhxi;DRBGDiEO>N5c)R~;=&N#e3GZ2U2IosH-+7be}`j=?j=c7+9jz8n= z`KbEsBi?GI;9zg$26`pU3p+K9Xm+g7%d|m)Zt;ThZ8hDpraw|ZA6wSH(0=hoGeAU-Iv z|B%PZSM{`1PLZHKy45sdhTnldR{T((I)1$v+|?V|V=K1oQ9Oz~#958}1+xJmIoQz1 znrG+R3#nMgsmCcFllN%ad-uvxGm-{MVc;Q2*!ud|;!S;T<3_u^CVw%nF=#bSfO~$= z2&`J2a>>j7NVsDLTeoWV{(cOq{dmc^-#>g@Rja`pv05jC>BdWXjZzM9?g-sKv*Q+F zQh7;%C1?sDs)M9|E7&~pL_2mPThFN}L8JoCgsS;K*vb*XyqOHlTbU+h0e+Y1Z@cBP zgti|_qDRARG+l(gOr!ts8f4%taHe=Ys|JgUB@E1_2n@1^La(9q>W%8D8U&?l5Y8FJ|v1fv0NM`XHIeSEw9WttPNVd}FMg;VcVU+xZNY_K#Knx+=}r zv59b`QEI>hvNhpi`bnSEFP3_fqJKwh@!vwB0cWw+l%@DU_n0=c01&c2rv4sDr)aY% zS#iGrCc>&f^KHN&Ha`8yWrxV21&L9#NR%-9l4g2Gj|E(kvDjhjTAufLlACM?dK{Uy z^<{AKwy9EuO$jk_+Cj}Anf#^RI(;jC^*Lyi<&2Rsa!~_%7v(ao!PzNf4-zxLpElFb z1h!}BdApaGP=FJG@zYjQ_80co{ zvdZ_hu1+^P8O+0YSB?@9$XhJTwQFeH&n3)QrKxz{fS6IT2>iI}XI>sGSqMPNu@DJH zVCasUb4zpc0j5i+#1Sw&5uaZxPYM? z3veF6po_2Q7i>mDA~G;l#u>Ysg4#W%5iWFXQwX5URJ@><0AQ~RcMveH^w1170WjY; zRFB&OnIA~|sRF2bX8vX>6`$;)SkPI6`^1=31|CAc(IAy*tO58w1 zTBqHobJiPjYjiH|clqgw+XLg*rv<*l-S~9$8z=}?f*s{pQwc$*2U~=1yKgVwYuFgZKv&u>qUG!>On{bYH6n&{jcs_OXkp z8R^N>M!DCj`0Rz!6aZ98GF$vdhp6EDC4HP|l$ou5bCv>*wV%wTi!nqlsTj3&n6%gV z?*bd`zT;6ECJ|=n?ot9OO`Nq>B6st$OZ~_9&>n-3H=8!Tp>ENijjZUF^LWPM8NtZZ z2T>;G;*m~j=JjjK9>_Std4pzJ1$XH+mi@v9pacOUWI=e}xDra#mP&jOSNBXjuk-qL z(NIP{$^)e72XZe5Y=U^1hPhVU$PJio5Io-KLA_u~{}zCV6y?~af&dCmi{nD?%q_9w z!pD8YPDwM5WC287Rp>zee+9}vCeGR*u46iRsP?8%{XFmOttk6K-iHz0c&m!Pc z*%^rwh<`1aL#+LK<|1%&8QHAMf5=+yQp7b0QMx?XGT-Q^kUr;Dl6~bQWxO=l-gduX zvHzTOat2vIZ}~->)d$d}5dr=4LhFW5HQ%)+Eed)ulq6zxVD5ng8~`NJpfB>OlFrom z9qh8rK)7})HAQyBoSB)i{qq~RkEog*%>}a+DYIg(EobL8BC~`PHaTEsgr*gp^bxm^ zE7Fhiby%1%r&>nTyim3fmM#M*jvP(*)(=8vrMaX0nD6d_3QVC)axpYq3 z&1~?u7&HSWd05-^>LdHZ%PihX&ZCZ$`=Vw66!Q3*$jv!X@rXWYK#F<`w%2W<^~1(t zHmo^-5R;rHFxBj8MTjsUgr%4;{I_o2ffmYFM>b?$vGstu$)APl{eRG(S!zf9e#34i z;|#;ej@%ZaKG#Ovg|$!;>kOA6{nJ+YO)V#i*NTXl3ayIj^ZJ~dz_-=nqqOe7h6 z2J*DXYeT^Z`8kzl^xVilB-(ssnT+#?vj79-y#ZJ+4bK#%*@QoAC4tr;`PO<#3E`%$ zf^ZMiE)?w0LJDR@oF`?~FCtxX175-IVUaf_R{nr@urT3nEbO(vbN&;CvsGN+qB?lq ze9go{^!06IH{qs))MqBjiw*7~Y94Mq6?T43T*)&C8im`j4+@ag9hQj~xPR@S3T{uD zTl((vBP36&c&2z8dfZgw_h-qW31~T?9}tJ)A&%ER`V7F1A^x61esu5p*(ZvfxUC@ zpa(MwLN?CFVeyLr&Fi6o^eewYALZY(6GfXc5FPI)p3IkTwM7s>YfSEV zPYo;M5WdS`Oe{s9;ZZ~V4TUUJ`7o^$2B z=R(J`Z(+^Y#X}s4>hWj_mg2h@WEdg^bC%@FNP}+{p~Fv{N!^I4Mx6ir8UP z`sf&z#m;)LQI!1@BR->O8)!zsq;YhYONUgMsMGCTN9VG{pFyV8urd|&zO=(eV}3RE zO9X+kucO&C;WrEh{RO-dA(1bY4=nVY84%dqS{MKePPy=1;T@+XR88+INt>eX1?=zv z+FB`lrIX>@O1)qoMs!fD*&}1p5EXO(zG!v_LToU^*-*L!r3{e|4yUrR% z``gGVz}t{E*t$^K7n2po^k2*!3jPaA=dDx!s-V?XHGYl<3c0@T^_19Pz~J+Cy=Q-6 zX#$;I#cg_xiMevf{T?T56j=L?ZB)g?&Sr>B1r6@E?gr9a2xUS5urB^lqG)0}>d6rP zWGF}NCB>wl##Jr34R$9w_GMoo?_Pn2D?wo#Tfbw`%a{9&$-!(I61aC?WCkcw6;Jv_i6LvwcNTsXaxhald;35Yy-H~FV@is!4*BlsNMbCT^r%f z_H4urs{%FL7~%5on`zv%w*hr|xI0%!MCj*Mju+1JDtv(+jac)g1uZsa0)uE zFVwofZ^LAEd=bMq#38yeavr^V_P0vy>l1O_<=)g+XsjQCLey+ZIgcaRb6f)6evy^T!#~&6=0chdfgE}BntrSF2Ow2rCItC0vRDSy=Rh?Np7VnbVU}#g% z^d~vcy4ypCO48T;=bXl)_Oj?$KE{NnRfoHV( zeUy(_t}^d>5l6XNK1bq6g(+rQ>rL1;eWhy!-BB3RF;db)_`PP9v zjtXBzeBz2NF7sG~li(@uEckQy1Glw?0N^Rvg`QCuqf0iK$HgOnAFsDGsqI>LpUf8u zQ!rY$hN$|oJPFtE%-0Y^)0JOu>Pn3_ge-3q3 zgcT2lj{A1++BOsRejr7zCjf%offJ9Pvz-F4a4o1upfXODK9S6rM?7}2o+ox{(KNY3 z#hpVcIa(i0h`jMprR7KJEi*)S38n7d#*&O*<%U$Gv}ooyH`J}K&(y2P?3Q=XNVY>x z5gZc`o9EcuAk*;BV@&;oC4{Y+b(6k>tElLT-pEK*Hc_Wa1X+rzOIuLWJU<$=!aX)J z06QcH53O;VYOyo70-q8X?LWKFRVtK$v4)_$~8DOl?txM2;qI@_Ek| zgPfFwKf1*%wd1%1O!GjU_r5<#uRsYgZbqCKw`$`af3#C+HnOtBxtAxkml8A}TK__jRrb?>P zhGJgo%;`D63|TzfqE4EbYIrDvj*&0<=a76UZx;`ZKyNxkCl~J4lsmzEY%av~W}MWni`6DUm)qrP z7gSY{2io)F8q!tKt=G(1Ftp@6O@*(9 zgu0aFK5BnSkliHtT8!q?zK*h0(6;CaUPam+c~BkPSLSmEol*zr03R5*sp5OvQ2}T5 zscsCu?epP@6V3)+Fi3O*Ax6pUgM$T{_J`Ll_`TL^Q)a-z%QP`3|3c&fxDrCq_e8x;b{+oK+-vh*MwSJLn!N#i~*EauFD9CG4+(TU# z9FWNr1j|FZRyZ?rndLGNvRtOOPLBEKl8?Z8*Nq@Rg^7U7g)*S5JRfBiTo6@E&tXg| zE9lg2)@Yt7ci3|~#R8sdbW3o(i8t@rc1CEvOuSq>TZq{iInrq}1!I6_$*|Yv!>lBe zA9-_VCkq%2dh(}sxi;I8RY5+21_!QxM@=GL(*lUSd!X()1xVo)-Lp0oqX(aFa!$VG zhx_6iK48$UCgcS3aHg}0o6-^cep=Ss8 z?G2Hb9=+hey=BY`#j-;Z=4!GxeW0d&2j`&?g(D=|{NLnm5>`W636q8Ysp7Q<7NH|! zHqd#3en53z7{_KQLS$aAcr>E}-r$%y54$a07}+{0q9FxNK(Pk2MUvea>qG&%3o%Vh z4vdd){MW-TV6BQ}rZB<*4;}ISNbAup!4EEtKB9f;5(S_K6f{1`vL&0}8WW)&!;( zk@3-Dq%Kqt)EY`B48xs!9vuePVY?Z>NQ;s{1mVk0zU);q>?w|$UY!#$)(i#1q)8{e zfn=DCHi)in64|30?C1D?3<>-u_C*^>ya9g(Q_XDTfjQ(TNLP~kfl&7h53LFhZC5uT znnp!RQrA+5+NB3Go5z)nN&1Sdd=cpLPk0i)GYt%-9wCpIKx$XLm>WwbAA!K-K$%IR^G&RXNoIV82jN4U?r&iA<&}yn?8}*# zd4b4~Ot`UEF+%ob$6!b> z@oX#zBG+NHTDAKEu&h1c#B^-;<#?+4O0TtKJ81(l$3`_^^tWBk3yd)JocR|d8h4G1 zLMmI566|%;JRUWTcKguSJ?(9=0wkkqnaN-@dX>#e!5IYpwI@2fEN)dvg`2FQDj}Hk z=37rJjP-AsLo9=Sjlk-;bvZWOpRP4EyxaV}j4A>ZUqk@vFc$_rXmO7>)VKZqu#qGF ztv!)%(xJQylrW>{-ccaHIKTnY`f)^l3YwMF-8Q^h44eXc=nOd}w1$Ubpj;nr(G1sV z6?Ho4eRd0Om~Ftgi(woamL6VKs)vqVUM0#g<2kTN%@j-nuEpCKS_j7v!mG+ z4jW2Z#L8>lMdl`Mex@;UR3rNMN5^2MyHfqj@l$m5_L;e(zc;dd^CsepLM1N#pWS7q z2Xb%kVrIZ&&v&@8!wGKTI~Vpr00-v3eiBD~A|~gv6)5>-^4ViE-mSPA)Ll37a)guU z^4Tc;#_T6~$02~;(2JY@V3c)h;g`!!$I`_CFa|#G;wFGd9fgCN=u6a9w_(V20yw%^ zoIBb!?z|yJCp%OeZy>aPups*}-^q)l_UJu;ndsqlm|JBg%H!8Amn^ z!2+{bLw^c()=O$d*8a?|>16~+VyD(K=)fmPE!Z~4K0l36^1luOcvU=p(IiNWYzYe^ z>!&yDorz##=6u1AQ7ETBSl!tr7;m}8Z`y%^q7qzk;c@4_@s34FZVaP^K zByZCfq6Lag39b>PiqBxid;Thh5Fv_j8d6}<7FXM|a@uW%oADgSN{BBfLDx0I(Q#FF z5je7e)cyB-Ik*lJQ~TsK!<_pSUyidb^7}B8_i`Z$#q1k&r2?iRO>UP9xW3lun8on34R^=-+mj6OU8UZO=nq2sCQF{{LiTsiN}52|^JV z9IPu)XRwJ-cJw_-f8*vRKk*s)ESv(3@|3T#zIc!mgpl^{J!sb4fa3vCr|kYC?=?eY zcR;NiyF!lPbdRO;x<7VoHnt6p6;Eu=>Jr^Hb)j=h2kFA2=l!)&4yC(&p|2IZDqm!8 zx25AQX*M)AW^82_;=<^ z`|!J>>d74O?G+KtHvfdGk3RCI6JxpUw{E{|bf<`q-Y&8LtgizTyHUlN`^G{WKd38& zlGS2@ri3I39O3^3Uw&U!<>6!2HIujR zNne&bKwe?c)9}{N4FSh?Vi4@n8I5p(YP5d(fTIH~lZ1J3+AmZ$viFL}cD13pQV0#% z5wmXwb1GB0DC7@5H0Ap9M%niBvwyRzEeh(27>SSe8sMU1e!~no;O*IQF%+GyZ?6e|n(t@f!##XgX>Qnd zkj{M^M(QJ|9eoNwv)4F|OgsPRXb{(|=&yz#`#?&Ko5tfTfsZoWcbwbWID=^fC$&A2 z_HBCq!9dBM|M_rWG@lK7Kh9+)Sda87*PTy$Zv)8!h=Wh?fVQ7{Z|q z*S!c8W6_cA;?77rq@(fAZ#>DidZa7@fkJQW>@78@34cL$ne`}S{nM*>)zB79Bu20` zU9QB>oe5cwNparR!E}-MSzIyfSeEq+Q}p;2=t9yk9{BxVc71=2Rc79;KG~p>ht}#(XQi^vty&G~ zu%Tp6hp@3!9?$0CqKPfSf)if^Bz~en-7i%E{}#lQQJ&qVok>o5>I+DFW27tZavJa-4t?HTi>~I*5PQ9Bw~U~iU!QVh^b~nP#7g(;#O{l&=HgO z-aOyOe;meH>^ofD%0qBP%C)tPLzAI%>@&2Ignqvm%^Du#Pm#rY>E?Un*i%zK=rCWU zfun?HdT&v^$n-;{khnpW8XkNh)_b!pBh-8Rj+pguLzlr2b@)}`vry%k$A(L2-u&u* z3;wu4qBzS$@e_4;b4kY%*+kaXVDge~WN;WXD&}mU1?`OwM8GwHkREe51Ci03_f{T> zm*h9c!3mn_&D`7x-YwR^<8KDXH;da|gO~I7g46UMBtVb8f5vkT*xw-5i%oY6rWyIo zAJ1sI!uZ``s~h?x>~@yM7^jqFe=IheLfuz<*DEmfRfVsxyxAV4CKuNb`@(CA7YN%m z``ouk@v3Ab_J~kmdkyLDFa>j|BTE zQkJld^4ejUEDi)oTa-Ak;mYI5VS(t`w<1GmjY5md+ZS;8*gz=*cY=LwPdZ_x8;?ECmf-3HVv+ zBLW$H9C`83wC%-Elk(Km@A+N6<&#F_>JnO?{L5S47Q#+g>dU^T$Xf@5Tx5;2soT22 zcl$=8E?%7J}tmv7=1fSnAj9b15<7xHfeztvkqil9| zY^z$3@Klw+{7m&)N;ZY10oSR}-_ZAi*8!2|*xrsrL*cn`sQ8_BeO->>$Y{JA8}Tmj zK&GrA4WJx7hC1~ROwAwT2uy1?eUiysVCm0I~9eAsow!$Y#jucYDmo zUcR`9ux=eLJa;7e;_RKI9%rR*#_iVt)my`Zwq0QEZ;4g7?V0%M}Tj7FZRq=hbS@CeMYBOt3!NK7Ag`H{!K4=VroYx3b4* zxg}c|6$|!~{N)T^y6qN$liiI#%X)qr;1=Krphz0xg55L zBdH!!%7thtHWg{B5{!m)K!raTo{sf|s;*w2r9YeOfh>CYsv5C|5;ktjCRMpM)XmF6 zj@r>-KgiPQT=_l3RcI<|5YmHb)O&nE&3nh);MT!+{g9zo20bAZWU>vRD7&%sx#^QUnfB_h2ImY#SM4HoS!F~zcN zyp4B9(XAX*F7x0VO!Gip)TPu5vd67}OFpkpMs&*?vHL8`qfOEw!47C8+(p2^6yPgA z95x>DfK+7yNsbQ0uM$e63wBpvz#Wl&qURtTFZS)W;vrQlT3;Zt%*l+H^0sBoO@mc3z1A*s&X?M{0a9osW(=FG-t}b#;lacck?9LGl{CV!fL<01f*X;8nY7lK< z1*MAMY)^hy*J$O!6}h2f(TbzQBIM7zlW9qo4{M2wi*>|w4vy#!Uk1#RTg|sD9R(jqJWd>rImk(rykO>|aBa#%ct#eL{!%O5#5rjp zzc_*lF*9`}-w=`5YrP+3l;BfK_7OQjA@Z#9c6wHnzmZd8a1CLSe zS&lA%J}SoutUL_57T)YWSO%3Ld8Fs>oNV8OtszJImzIzohzz<&LJaY9<4X|JOh_Rq z@6F}FJWK;4jjEu+LphbS*eiR8T>!|bBVHI*?-t8?S}V>j&GG8ZGZRYj(AWEe{V>j) z)%p;Pwp%Wrh3!qG$4O_{Ynt~e#X0{wo7?f4JIpllOW&50p#N%%_={Q?M-y^R4(hhx zemGeDOJZ*L9~fMU=m7K*lX5naYeOMego6-ss~o=vdocS~;-_=hMr+=qHR&l{6m!V$ zcY-x@{q4hQCLJD!;$5OT67si*?q)OxeK-;izT!w*~RdajcCmw%Ti; zt0v04R*4_YD}T?V4VWbzo<2k>^y`M%xxzp@R%!MTgi}=cr3F#%-uCNV9(uFhaM^p7 zIS7id>Q53Mm6OV+;hbrEp5XwP>yF+v(C>tIlR3K-!laizpkE~h-Tm|Z!pBDaRDGyLA zicQykl&l5u-rSg~nsQAtY}nji7L89{56bX?>(&p~iQ?U$FU5nOpps9!X8uU*%_)8j0f$;a$- z(^c|$gsnjM!3lvXI=A*BWTJhRp zk;z(|Zz!8q`QHd($yl{KJ&Uf2G7ikS9gc4poi&%0VJ@}CF%845u6b2gL zjSrbL`mgrp!sN0Jf4VYr_A3#{sj4FvGRzkuRgdM4NxJjckOi1!C(83lEJKX?qpxt# z{!W{x)>Ln)HPMVcT-s!P+~BF1DeCgVXdW@L=|edVkqP-C3!H`mDBx`8ABG#JF}S5=6hC<#3rZZOOV?dRlO-v_47Yyz|nYo+QGnc1$V4JUQNW zKgb4hSp1UnDoWkxvflz$ab-F1!WD}0R{}@K?stK{u&j;EoJ+4D*>w-^8_KYp` z?PX=X!c--2(6{b(drottEkK{(a6-rHBoW)>(Z$Avk`RN3ha@M12@gg?gOV`$g@y*r zp*vP>@P9%7^PCMD{S${4G*rgv;zawzIUD{iek%NL2{v8$Xvi$4JV3VEaE$5GxpKM2;R~o>u-Rn#jJO(~W6d#-Ve3OWHlekM@Wh z<*$qTh54Vzw1^UuQUA#<;km!3TVpd3JS0PbEa&qeP}TAI(0~VqV_sG&Ix+S-byBOl zfNbt&64>_rQ;_T*{2pxWACF?rL*972q&XA~d{Fe%5q;$U*t#ihR0%s;Y+yDG5Z;$%)5laSEL)y5qWJl?hVlhQ;C~YM20o-@ z7bG{pOXTpxq+*VQC+aR*{zrC`vN{YS^z+x$jH0K};~1xT|1oEh15ZVrOo{N?CwPjLESpUfwZldN%?Xs%rH`W;C{MrsU#c=z_()hKXo^v;{&CgEV*E^;=OczqU> zLyk7=UxRN{uMp=5h^oGaUj~MhNXtpI_fx zYM!6m+b2d3c{j~jPEuoqe%S+JCn$h_^}Hgn$bX(xopK^>%us;*qfg-~Y2Uarc(+k{$PcT$*IpL6)hzS|J1*8)XIRskoMjgE7Zh zFT1$okS<&3n^+OFs(qVlm`stuwKkePn|f(TT&4=xk-aW zfX*882ciIV_Rm(d)@H4n4i`cYDu1c7k;CdNDgp!d6uPqCZJBK5_cKpl2fis=Y;L=j zfuE(eGMQ#99;2BrIiK*gow?uMBiBep^1m|^E5FHL@~*Y0NaYQF`)cc7**e-GD0sH> z?B=IxTRFPfQ1^F<#j#Zrd1HwUjPV0u zF3^~((B$f0zve-&8hr7;an~^#m0#{%yi2}i6Rfz80e-J8Ts{fZf2?ovZC#4bk&UBf z$|btX^#bNiUE5Cu=Jvl$&C)r-ji`h%OBGnRXPD0CiLr@vW0+JjZxvT7NjnLktE z)Rz4?=q3qL9Q8$IC`K^8QVSX7Zms5oK)=Bi8!zcuoOBmI3xo3=>wgtqGEAu9Bm(Wl zMSYJqgY1ZioC9cZ4fK?pIQbonTqwCZP3o46x>t0r)db%*Kj#fEhK&!>QygmjQOo1T zrhRMeiSs@Xh^1p3M1rE*6Z5~4nF5|`ilhN{@!WHA!c)JoVWcYGzPX;5u_?XOLc&$r zjxs_ec~YqOU>lN=$8#92ft(G0A3MFp`wcGJ@GIeRkP>>5Ch~tgFD61RMh`D5nxf4? zFAhCHv@wT(07FeqgeMsakReKEz~RJ`8Oj~01H(n0T|9R`5IPB2p1Pc!0{#|% zYWS?Dk?=q3a?s+R{r$2rPp(sHMgE2hVL#JC9Vd|o+qI=i;6!xxZ@Y5kmCav z2E^nE6U(?yb76*%^OB!B{wMq3L*^*OtVpn%EW>(?Or;xYk#c;THTHsJ!)5br=%mwr z;9^5UE{8xs2#v@~iEAJ)(_RXHvm^AaB~?fLUqS3H8=U42A2&7C+is4JEvKKT%<;x+Z*n1NxV>W4G5Zob z$2kmx75MZ#a~p2t(I-k%H+-BZE*sN2?{jX1SF6DnHwdhsL~1>%293$Ja4< zuAz&@(FVEnA{eVhd|!swIMiZ6d#mvN2|4Mlp~jf&+=!U z>&K)}^7V*#l==B*(kAmSWmCaK9;F{?U)Qc*7wUUxkR`@$##Qvpz4NBX+VlKFgskOVXn>@!MIJYmTPH98h7Mw%*$(OV z57?TooISei%JLxcd%o?cA=X-8om6h_1U4%n_-EAQWDof{Tl|tMz88gmu$$lzYH`v^%^#Zw{jqXNzOJy6bd{_L^$33+?qi|ieN*aM z$WT%~Pd3e4ppTtk3;zOH*LrwlLX$Y@J92Fe*3WDtyEwC4j~j+JQ>R;sF>gCx@g4Z& zBFht@%~Pk_Yb)8eR*fWoOs!;S;~bXFu+9^}lZ**7x8Ka7a|m#&u^-sWIUnCeX<18;A@fl*lEgBQGy6!ABfkLT#ccu#X(VZ|jcki)x3IDu>OR zWP&7BsPl0*N$H29?q3#YZ+N@d{w34@rX&Ox z_G*kv$v8^>-LifaO!!yp9SXe2^1rQjAS%u`ki+sLaW~?17XR+xbzB$$LT6B0pa$)U zs5srdy#Abq6(yq*n_qy`o+?pvogwc#!e#CxV%}vE1=8fOC?VfG;&ww4iPmLHOKN@a zCRGTyz(a%QQri|PKC(2*y`A9iy!xc9!)cdwXWV%01_QcgLGQ)Z$=`}3BD;fL(aoI+ zq_4Zl+HGdMs&DJ1FM9F)4!^ol4TOm!{i4kSvKxkp8Nvn7ENCGiA8lF_3tr%{& zh@o~cT7(N11zYClJQs^$%dOKDiiXPz5c7{Q8k`A&2EP0#xTBm~g>oEL&xsK)sh71)cHXJN;;^~(e z>F)QzhY$;PjYX?hs&?^KxL%C0BA^A-A`#M9fNdOKu^V7oQ$zZxps8)%(_^3*|A%^P zz)97m%}GlvE#s4Qbhy15RywwyPHY^OrmXTedXp$I%J=u`>7yBd%tiH7wwIrU3iQnM z_FLzTbv7(I36s%eML)H_{xVHxjU<^qs4)IzJ(j`IFRj+)y1|Zi{zB;{akUs>T?@~IPTiZUw*m2}1$-)& z&TbcQQ9#37$un(q<|z{CL*tPL@C8#d_&d6$Jc=adQnQoHpPqY@T8ujIOB!pz*& z(82h%@S<1c^0UDrZV}Yj`w`|?c5ioh*OH%#)-GkK7KnvIN8|IM*VD5amLy6#g6qZk zjCHdmi0cI6Da_3a5EVoHygeV}>^kW#W&=77dnu=PtLA4yz|Fjslj1U3mh}J&9&_>n zwM`9OIsy~cuuPYYCbX5mtw0-{3KyIWuL-4ke&^YtPT)}{RJ)6Kj)BO-} zb;&~aWrDS+h)G)N#MB^6h?f`7eIfKLt2LM4YSj{db_N$Wi7bp&QaBXwGU9custYho zf8L6_{^3$m@hjBWAE{C-UfmQnBCXEne$e`%EI9dyYo%q_8_iCIp|sXJ3~~=*>X_HP z1Mu)m`+6%_Zo#I_CeZ7au*j+>nl9(vIZB?%qd?!nq0RG{v&U({)OD!`_Iz0@$nsGW z=wqc=tLLZgDmQw-^>||Dx31Gt#r8T(!>Ip3nbgu)Hq?5WH@nbutZC-e0?EX9#%;UV zto;x#dAL1NwLBNgU{#-yo#%ci?{o3-;Sb+z_XWJ*Yy)aP7AU+iPxi|d<2x8^q<3t2 zYsI7r$LOfq3}yGKL*bMTzvHM5|BAIq#drU}+nhBBxR>udn9kFFg*ju2%a#JOMua%F z<{h?<2Il}`dPV%GJ_fBwUfVyNz%WZ!DLAkChTPUpYYjl(4Cko*n0fjB_2n5dpL1)U zG$%SbMFWY$m*DA=@O<5_LxsM2A&J<}M6M80YTqrp9_d&ReyKoj2c1Vwpo1H3ER-W8 zwmKR3Tj_vIWU<@|M1OB=-k6w34Jija6aO&E=CAVjUaehjEy`5EkFD9XQj+1Ok4e|WW>sS^vw)jN;?_B1m!)yN1Jw~+v~(_RxobVN2v@+xWI>MI z%$@JDN0#a=L*E90T>!MUptbF`F8Gh#YqA(FbxU&ZPjn? zBsJU!Fc~Ee(b*1K%4LB+<)Ov4W95`KJjqqIX8hFE-7=<$=DZgogu;ehCxo1RA^lPM z#$4tH5CyEG4^PA+#RJuF&5vr$i&0sX$W}4>UzCfjm4(PUeSyA3eoj?GmUe_NrrlP7 zrjNE3*l9=!s$tczqriG{>*#%TX11on%*puQs*U`2!EP%Nm~}pYMWc)Fm5PK0sr=s0 zIAbi%A~^lUET7HU&`Z?1*F9f?-c0 zAE6?3ON~H3zn%4CJPo}1B>SRub7M!(T6zoY*y8lTft4KN?+67wA+yd71H$XaqCA5= zgv0O3PMjuk>I%}}8z+KG){&XZYvl$fZcX}A;+pJjY)o-yW71{#ta6_Fvs}E=KicG_ zCo&C=t{cjZThqYMAh)2t+ec*}(i!K2>p!rV2GFk)!Hc4^wJIfwM*b+sy*VmEnC2(8?kkENHi<1? zi6WGKi^4fvbF(sT=wO1mkoh6?I#Uu^6Embap`WD;4~f$uV-{bz4X>Sqr>wGDWw@vs zA$9`1Dg0AZ{BQlqRw78ikw|`YTnVF8;q~S|paQ28=tQ|MvF-0Wyp%3z*PRwDW=@KO zg1mcJrlZ$>RofHQ&j7SSsZe^2F`1Kn4m-J^9!u>GsGnCp%`G}8!3{-Ny*opD7^W_( zz03HL1VLTpmGMpYcBU0-d&7WO&BVrM!@lY6CrlA=MBMWn;VWy%Eo?;XV#zFH`Iwhe zUYzLt0pmk`R3%vG2V&2@pJEfNR7)d$d?oLlka40Q9-CM+hjdG$YErn}5Lsd6lYUu{WzbE*V#(Dy+-ZnYiSM*5)0bY|UE zS)wAc6?C%Z=RJ2}yDa*-MM)V{-k9O^4i;Z_ z6j1l6uv}Q?Kb#5LR)j6!Hv)0hND&MNlE*K<&!BBZuFr);hrJMpy zt0ZewP$b6;qk7$^xEo2&T5;+cc(4$xJSuu?^cAVg%<}RuU`hXg`cC#uH*& zUR9bu^rY*W$OC*jTOXIZuBWgyQXDg}oON=*3q;_lI#B@L!>zX^LeSsN0M{K?*AK+Y zhKQ`Vd1&s$NR!$6lq$bf%L;3XNQ`JCiBg7R5~KFNtd9pvJ8;|fw87q(&aOdH&-klt zp{!nvNqFRx^etd=IGrpPDootPX{X` zBI1-G6PUS7oV2tI#B)r~g=%UZ2Fs@eh~-Z;)+b^`*FJb^duKXdcn=6=8ZdYgu=%2j zQ^z&u;Nw4>BIkVExw!6gyu0P*MeucmLmE4r?3w&P$|8U;&S8D{oQrzgX#jlweDtV+ruf^V#P`GMf29wE)7&JJ_LDN z&fbhjjmZL8IRu@O?yAG+bsbcZT<8H^Dx&E@@trNU_gJn2cWL&|*SlZVJh%Vgt?c;oc z{QPXI%dqm}hzplGIe{NT2bAa0xgLZ!LG?hvNsg%oJk{D*n|p8C;<^>d$DBC;$s-?I~^xMC8XQ)D<*FLgq zH|>ZAS-RiOq~Dseu5iiP-yNdGPBsZxI4<<^xi})61M~W9F<~LxHgn)fD4)TO$1a7f zKA%j41O+YQeJ$q7bws-WqfrTaYwivedgnozdHL*eWqZwjdTV804|!EI`yYT650NKX zV!+E)URmwn_pEw@upG18Q`v=ZcHdm9RyI8ZwP}CTRp@#jYGc6o?z8KKxQEe>x)0*M zW)1DTnNX5t9w>vWzBHb-b)Q3j3w?SBDwKWsE8Cdov^oZd8<%4~*xc)x%{dsk;uo+<=={PFF6^FU>xsVvE+&Va)Po`2T%4;gtD zDCE%oTO8QC6WMk8c(wykSDJo1&g-g1=X8xnuR5bA|6S2TrI9-s z#xa_&O*59=3$#!FunnQe0L_YxcxdD?eFec&Lmh^s?UnZudVB`sSh zZ>BiWz^1-r!uwGvRN%=zl(ExKN*2Mu@tELP6!RKy{di4L{MX>D1-m4kr{d4E4=xOq zWu7-tR?A+a8l%p9m~`8sk4&A;TTr_xb-$Z1Jc2&|qEl~bpb>>16s{jOnydCkZVnys zt8mNwP`y)nI3#qSPZ&ac{)?6OJkNbmtV~cj7IV(#c_8$-uQ42n^7=I4xMH?Tj&lFK zo}m^foRtI$Y(?Xe_aqL&>5<7`*LW)j5h=1A*-V5hH|m5mdEu?{AJ5tm5#{f~)Y(Gh z4G~D?_X=%XK;!f?>jCHCxBW4|Z3Rj<9ZvP^p^*B;UA5PcH@NhK9steycJ##sEI+87 z<8Ch)E@O3hTUL*C6>VHfQ#O`hRfWu}(CDBak9xuGmrL>v#fvj0e#|Q6H=WoJ2DZyc zf`qfI^Vajm7kGEu9b9JXVPK0Hu*yyShfDhdinTr@%qG`!-^KO4Cbl}GlJ*DL5b03n zbdiJZONvD`@W^jVf(GCeq$7FEA_|U^GbP1N_!!X}gJgksQT9KO`T&a$5 z>}1lVDIUu=dQ`McDa=t&&0n>`;=zC%^hHa{-sFl62VIUWZrRs>p)8+sE_-P5Er%bC zN<2)NJvL`emRL^WZ+`JP`%S+muw$yOV=vq|X{JtXOL~<<>Pd^34}jo8RYfn7C+_7H z17;w&S->o&?y**}#1R0+!10j25`Lwnnf2c8ut69zzW_aCjf8=+t+u46wc?<-1-vNG zHLg{@jdmF~b@_IMK175BPBbeB31Ihwc*$;D$f|8=U@5kdiP{nV#v9CdIZ#K8c76V6fLRdy zX=Rb6{E7ZhWUz7x*XuVXz5xUt{R}TYX1-B}?K$6Vi!6|9*bc3H!m-a*$ab9I7u zIk8ST=`pxo{E_C`X-L!9LKgqG;PRppB6{I!d~&Pn2y=-p?>X1ohVynZ~kyU5tAx+ zRR|f@HQM5P@D)O8K&mixjMgga$MeP*w8VW;{AjJJb9*>H#h<6l5sU)s8Wg@9P10Nw z|0ipkc>Id9KYl^q1HA1B<2M9nzmoTHEj4u?L8FiSM53)A`2f-b_P(G1vQ|buKNU21 zp$21L;V@Y-&JVNQPV+@|DP}!TfDl07T2$fQm)ghdl5yrH5H_YNa#Dxx-iGw4BgB)Y zH!P=69y13XzkFYc4-qfhVN!4!La&Cd`kNddF|_~e{FDiCi$Md29`&WYR6eJ0p#H&t z^B=&~K47|B$t$2;j9kbJI(#hM6~F>8aU*^izQ7HAy1zluH|QwROCg-cO}%ur!@Nc@ ztA-^KFngJOSz7;Hvu`oPw#_q5j-xxNs7e3Im?IJhgqO@0pcshYB`Z$vBnQq>Md@sWy+ipU76 z4^AK4CTqGyLY+}OJ@-{#=MwTQC-;2w}Ar3wMhDtAkthM0W{m&ZqgNl~RJ-wA4`&QhOxL zau0O*-PpoeJir6X!)x5h@*UDhiz>tMnw$Sh#QPR z25Eh$qTtb6haobFUo8oH6pK1$1Ir>;t#QE@A3s`D{o%bK0cNKNb*h8!`JB!%xO zKcWnTHic4)+G{`89Uvg_BI>KjVb{nXThy$2T?a6R;-&`=eSP9Z-NC^5z3Mz7k_^jH ze2|$dZs1s{)sUYYlZzT^+c9xL!Oa3l62d!hSVt{EJo_cqy;#liN$|@z<1!0SsFsNt zBG!A{)qSi3cvp|b36p-mTVqSCi97$ul!2r~ya20O^>Vp&bp6YQxH9s2?ZWwH1Tj?` zn3v5zsrT@a0b$wINr02mvPSpL-=tXIx?#D|&G&;I@}V&5kNKbw7;L>p){bp&iV|%1 z3h;HyzG@lFpB=R$ekE(@b^KchWe}?#4j+nxd?={3UsY^zyUKC7Mbe*91+u$6Z3mRv>A-TJ@Ot(v;CNapR`AJ zbaCX6J%gP_(nwoxutxM{czrhlE%n|04($(u8ZOQ^yg6qjVByrPJ5Pu!PlR&4%hY$? zCL^O%5I{8GH0i12+TZ_3B{|R?MfJx%>slEEMhsmP^37MuB5ZU-LH3;Q$wywt#;s|+ zJFI(s(!08X9?i?~U&jljDz+HKU-;JCw#<=Shw3eOy;Xn5X?}RDNysAHfbVuirl2Qa zHG7DrvyD3H+@~_A_rBLb%!e*&yztJd;Dh)*A6-BXh zaPElYe^7XhnhuC(fK_h{U?(5Zvu<3-d%6l-XC$U7Ky)swIBI9NTrQaP0c~kRh%&MK zzt9Nlc(Z{rf`o5YW(@Pz3a_`0#yV^D+mBzS`wqum9%`;@JrWw;AxrxVj7Pp0 z0!sxUvD<7OYWfcS1?vU@7s<0~g#1>%kFrUB!X`-9Zf{{{gq+OjEqOH7ojh*5=)X=z zZer%HIV0|_B5FczTyQN<8_xRf(Sz|&AWsM_cuqI+8nhY;wcd4QbL*NJzNcmbIc(xm z=8Xmq=9J79aOg*5bpwW#jnwklO(J>}pjd~**DO9oFmUVUIydQ(i)XQ~!^aJRQurbkYexKq>P%Ql_c&Ja)Zi9DL>-&W5xi~}b z2PQa+hJTbuq0q@}I4pRwq?jGl?)OcoZJ_x$>5A&1z-u-c!3Vl~YmA-J}Lz%jsgBD}c`}T7lT6NVk=7XWBIl*?d9l%x?HyV&n%HjqWm8N5Q5PIZEl#jUV?Uii+ z=u3z6Nl^!Y6i`y|N(p#h+UoXIaYYLwfl zW!6Qz9lGOag2PyXkLZF&ofQ7~bkCTcJ7WlOgpnB-uZJK#M9MAT{1pCS0)twsf!OOs zV~2ul%AE6tcAYA)?yEd18;S1SG5Eug?snWtK6dIye~Q+PeYt~ zk<)i8%3l6tJWyJkZoiv$#@w9{sAKAu2=1z-99VDkAZgWs{+@hoR8-pI?9M?YS55d% zUR`P(l1(F=MZ%{KKVh!U+wr%+V~K8K=e&K+2Y{esao6+xDrje+JS`#Y%p{=4Ir?() zhJT)YYV+BkdzkX^905Gdmd$U|ptRG?)Gj!4tygsNv6U4^!UnhPRUcJ~BI(D7@%o7)=&SopfuL-)1J z(R#wF{6-YY+0hr0#m=vtMxL;@pbmpxHjQ!XUn`vE`JGMH^<99Y)l_O_VZwk?C8*J1 z)@FNb1_?H7xt8d8rNCnuKIkj4^QhM`R1Puj{wRSl`G|!{qZLQayV=QpH2*&m`SxEp zLe0&P43*qjGEznH_r86{r&FjUHWmv(=hEXx;p(nxzd%A+VG7Oh$-f7sKuNhVkn7Yz z3{hXF`|m@kh_MQ(=&gcrCOGM3Xv4$aAufAe<6LXrt+ZaK_<7r-=jHs`&3%0Xf#FNU zK(gdD<%ttMJ0HB-&^vE$XkRvX(uimNWmd@iKABkEgfN36PdK=#u}Ct1!&d*-`@)|m ztv-~A-+4VAlVWPI)6O);Tr}~WA#7k%a~#5XUHc26wHaucoO=&qQ=;zbq1@&1qUlc2 zTu^jdiWi<2A5_+^s`KUw8jZTtpgur>)nry5a6%fS7DMb!{~S%Rz36QE;N8}&_djBbQP78V$)ak0o<+pL z7>F`N&>}8|{4fKRj2uZclp`<%U2T9$I1a_E>g1|}xQApVtw0lgOAB)%XKB1mNs0vQ58X5pSkFyo6$Exhl8)r7o zQK`?{$l%VxxVym@=)T_Tg95lgmLlv&s8e4>2u@}wl0K)_z_Dl4nY91Zhqc>xtV{KO zhmQ;XQNF%_G<;TixZX~`b{K40bh$T};xxYamNngP1&&Ykf3;U4cn(^6muBxDk zT?A}5N$Mc_6q`5r6bY(LZ=@IPu}-6)rGY+!RbwT=s1}ll9{)!-1+SpB^YuLmPy1%H zQlrD4b>llqJ%dy)w(7iNM82ceEYWR?h8B1qg)Df2&Xc$JVkt{TTJtwqVPT7R3ViDP zqCdum@Ro1*-*h~U2=9D?h$e7fPNjgtV>R1mP5^hXrZ(%BSU_b=Fq?t~hvFc5e^rqp!Z!S+doi8A|#rigb2gX*mZbtP-lN@#$pXB2*VdK z`md*;KSH&j(|Q1lw&x82_J$VwtC`*sr~sEMVDLZP{?(hWQQ45-J@e=|9F*35qgE)k@L6LB@sPzr^jxFjP#8fiTHZEjz_QKjfFGwGOFh?LP9fi*_0s?}isUFFl=<;7VB)%ym zEZh^0SR3Z@FPAu44iNQhAncl+1ljmvq_Mn%LSh?|RK7t!(9y+t?z4NmokVN5dG#yf zNL1l29c!tLF|)e9p-9+a4npQEA*V9IFcOQqi@(v9A&0t$6^0#)O8DZL~dw=E)?NNuvSS!)n?_LY_@4b z)*JRvfqZ;k+tBCQ{#OYNrB(Ph|2|<0#RT>S`SXCmJ_(vg<=bdBk4N_=-lNUd)R|Rk zs_w3w>^HVx!;N2W{C?J+nV!coOc3(VrVJo9cEyU=m%58O;?w;4ay>OavyAPHGa@Zcbv4*&C~baXr-NNCyzGNg@c* z+n4M5eU{nmYL4=AbEoct=VviYME$xCeXndWf^yX5y5;Mgch)EIzlzIqzm< z-v(tQre|u3ng$JPWt*`o4Tw0LGpF3DBDg?93hHPN+2Z-US`my^O#pdJqSUN1jkMqa z&^35DU^H%XHHnOiLsEyApf@#bU`b<30*}M%bQ3GnCjB8e-~El^n{IC`4f^0EidXCN z?uq>6L_$KTbt^K!y3oSMr@9XWSWJ)Pe3|H#SJt`ozUB2yD{PjrV-t{%w<%ReNo2J&H5kkOFUXeXtL`iDLQJ?c&ZV+~tW*(wR$2u|$?wp{hP;lyp38y5rAFj#Cm zCU)Ywcv0BmvNHVPzC+-sUoRF=ID;?*F(N;R*5a0bn!bZu><9Rcod(gSc8JB~xv~@V zwTEDFwV=n~A&T{J1>Y>nLS+yHy)P=2+_30;{h{a1ExAq5n08Koi;Uatj?6(a_Q;g( zLpF0Cu@@1*>$bHGI~-$_{(d-b%<*zB>r5?oY?auHz=u!{ztn)+iu>J|7r&2Bv!rf< z%-wCHF`XbDbMj-hnOefBKzeZ7&H-L&s1H`_&PHH*;KjLJ*I1X?{L z<<~+<%k$Vyzre9@IH9b9WE8!giy(U#cGxmrj;n11ABNqj&Z)WO`Bo(#^SQwg)2RCq z-mM!5_FFBlXAL?SXQ^}5kIZof^`4mC$f!yWbgNpQbMseNUGD{^wI!G{D8YY$qNRMn z%*?;|Vqzz#o4NhMR8>*8Q>Q%E2hT(8g5G6tibk_?)w@(b)2SsTS?a1FWP}aRZM{G> zsX4 zmEDSyyXC9&D+5eM0*!_nS%n`;J{G#x6IrRMkd?a&$9rzM(ey6ALj?jvF&7Mibr3#P zf$8x5j~OiA(eq%7$yI#~#KuD`Q;2(hXu9+&x=mcj&WQF541AY4LQw)(eFV1dj)@bU zt$W%z;s7T1f*}G+1stOC&K;gEMclWEpCkF6woBk4E=U_7QY-iB!5L=&ccQ}d47+(E zJPE9SHA&TDc>mlau#1_rXJFvbAo{fK8ZAVaX`2tlNlS5^v#ftl2#{BZwf>8ZP!Rff z@KgblhIz)A2E5+|N+{RJOPqr3CKqTYPIKb=KfnZ7!J%k@V@pfJJ($7KJCuH~%g)F_ z-FVMy2ZjWvGJ)<=I|+=tv>JasnT%;5axyCZs4lkKMxEJ0X5v%0$&UIvCY%|VEs@5q z?8Kafu-j2l^s{DcWh^uJ(joYB_nPq>e~&j2Q$~B$)q`*WroZxjrOh-#6Xmr*vVFRj zYV5zQU_VCXOCOXSuC#XR2a0J19Si$J{nC@1fC-qDV_)wkCm6)R@ed1Wg1i6VJS6_7 z;Y8Jk2+$kdvvJD%$p4e`aVhUgGWVh*?_&0OcjL5yxleF|b^gMZ|0Tt)%PnBzRGr<> zohV%J=Yj3YnnSwet80fWv2GLG!mZ*F6%mba^oH|Z2%xgwj!^2tUVN@ z@vZNDfDxy}_;YN>5itzQe7Ds14T~l1fQC_$HnuS;0%aX`o17*tt}im!_H=fl@XWi? zW38J1#?I5zXS2$5WzFQdL4NGO_SEdD#kSe;E+GAmztb#9mpfui(DQPy^Tu`5(^G@E zZ|CUbgU%)H32VT{tp$-65x+ck)}GhW?vv8i!|j>@yVWi3n3oR!&DC%$Rmx}{{OSge zzfXKI5(*h#aut`hWRS*2a)^6bcw&3`p3fYvQ4Ly4qzj12LWWa~ zGf-rFw#&;7!%qxG6V~!u$x7PEr<#(LILPvzM%4(0a{oj|LJy(& zQ%+GwKlVWgu$H&++n8?zDTd#JSmm7@xoWE+@`PY*_ z$42)aJonVvxO-{ZRB%c%NWOb>*b|&ajiXmXsEo|Bck;fEojH@~!HG!BSGE+~JD~Ha zT2LVnl!-U@eXhMnv9%7)+SV|SH#UxJ(lU$emWtzR{Yh>iTlpbSyV(@$!`8&8R6$UGR>l!evEpw?p8XDlj6Z# zo*af^X_o?0?bhy=pD_kKBH!WlAa7?EA=%(gVC^&l6Rmz^0~V9Lo-9&OY|)cpXjGNX zG4VI-Mnavg#=CP!kzG7{T7UT@REWMv-Mn2J1BEsJN&@%&0Vk%F92S=GX77W)(*Adn zxi2Wu9fm?xitbHy{QK!^6}DGThg|IY-zvYg6apoRLq^k6#J%N({oSR)ef6f$$o}$3 z{xaC#2!h-IkYk1!J@`M_C}FP!a6icYR{1Ykp$GYRn+Vcd|IBz1l7N!v1Da;%g#qb6 z=`s+1iPqZ?L71V<5NsSm$Y`Kpgn3j{9@GC#@@?E8*73q^dXEYs!x-+jXZ`%2K8fMN zBEbg)L}Q8b3*!Gq7}SeiBRPw(!_yfniQV{@rViiRxK~&Fzq;=ig$jcCvIoD;|J61u z8QgA~o~ArAErMT6P5B>J28fUd>Gi`jEq3_4m!m;s`v{Xm;%0>K-SSVTbX6wl)xZ42 z{|xUg1Z?}&g;EFFRvMD=p&j_y@UINRzYRxdg_MQc)IVhk z8-_u|vow7pC@c+JIv<`X!@Eb*AA4-^R}7ym85KpJSI*&oPXv^C1Lkr3iP~jBZ`N)2 z$e+jCk5LK&g{8F+L;*ely9`baA+*Hj<-^RXyO@j=4teT7t_LUx14~31U3<6@4CnEJ zH^)of?Ay6-D0#%ei7F?Avk0^xNGbSe*KlR^^5cqd)mRkri8YR4K5(;kC^q@OIf}y! zk(k}(>F03WYOuIOu=0^^DJ9L}0SFJz9d){T7C(5|V=x#{19ySh?92fv=>J`p_mn`4 zyQ$dqS%bb%*HS!=!xaFdVr)cGJo zl+v$n4&ndx;QLKDBT8cXa}6B>lT({t78!j&IZ*J?*I9A+oz3vfVgcV)Ih{caupHt~ z00K=zW*Cf&6nKPapr{JB6egor=Cr-}+59?QZ?^uLQbXrxn4+q69I~ z`E_v*y)=^lq@JYOpU-HJ100|CJ1iC{jYJvvH zO)(m9Dh-Z<{ zD~0Hat#4nmNg~0~Z{bD=EwF0IYQ?Y$;|y5mKp1k@{G|Z?b_VpngE*V7?9ee^#IuD3sC>k}G>hf@ddEN*x9MZH7x+RB*UL9s*g)ha4XM-~Zu;;kZdYDAI|% zmA+QXVEzNVTERd+X>mERQV~7B{|8Ek BTK@n5 literal 0 HcmV?d00001 diff --git a/docs/source/docs/quick-start/index.md b/docs/source/docs/quick-start/index.md index e9cce5df1..4b9a97e3d 100644 --- a/docs/source/docs/quick-start/index.md +++ b/docs/source/docs/quick-start/index.md @@ -7,7 +7,7 @@ common-setups quick-install wiring networking -arducam-cameras +camera-matching camera-calibration quick-configure ``` diff --git a/docs/source/docs/troubleshooting/camera-troubleshooting.md b/docs/source/docs/troubleshooting/camera-troubleshooting.md index 6ec73b82f..955a45671 100644 --- a/docs/source/docs/troubleshooting/camera-troubleshooting.md +++ b/docs/source/docs/troubleshooting/camera-troubleshooting.md @@ -2,7 +2,7 @@ ## Pi Cameras -If you haven't yet, please refer to {ref}`the Pi CSI Camera Configuration page ` for information on updating {code}`config.txt` for your use case. If you've tried that, and things still aren't working, restart PhotonVision using the restart button in the settings tab, and press tilde (\`) in the web UI once connection is restored. This should show the most recent boot log. +If you haven't yet, please refer to {ref}`the Pi CSI Camera Configuration page ` for information on updating {code}`config.txt` for your use case. If you've tried that, and things still aren't working, restart PhotonVision using the restart button in the settings tab, and press tilde (\`) in the web UI once connection is restored. This should show the most recent boot log. | | Expected output | Bad | | ------------------------------- | ----------------------------------------------------- | ---------------------------------- | @@ -12,7 +12,7 @@ If you haven't yet, please refer to {ref}`the Pi CSI Camera Configuration page < If the driver isn't loaded, you may be using a non-official Pi image, or an image not new enough. Try updating to the most recent image available (one released for 2023) -- if that doesn't resolve the problem, {ref}`contact us` with your settings ZIP file and Pi version/camera version/config.txt file used. -If the camera is not detected, the most likely cause is either a config.txt file incorrectly set-up, or a ribbon cable attached backwards. Review the {ref}`picam configuration page `, and verify the ribbon cable is properly oriented at both ends, and that it is _fully_ inserted into the FFC connector. Then, {ref}`contact us` with your settings ZIP file and Pi version/camera version/config.txt file used. +If the camera is not detected, the most likely cause is either a config.txt file incorrectly set-up, or a ribbon cable attached backwards. Review the {ref}`picam configuration page `, and verify the ribbon cable is properly oriented at both ends, and that it is _fully_ inserted into the FFC connector. Then, {ref}`contact us` with your settings ZIP file and Pi version/camera version/config.txt file used. ## USB cameras @@ -27,7 +27,7 @@ USB cameras supported by CSCore require no libcamera driver initialization to wo On Linux devices (including Raspberry Pi), PhotonVision uses WPILib's CSCore to interact with video devices, which internally uses Video4Linux (v4l2). CSCore, and therefore Photon, requires that cameras attached have good v4l drivers for proper functionality. These should be built into the Linux kernel, and do not need to be installed manually. Valid picamera setup (from /boot/config.txt) can also be determined using these steps. The list-devices command will show all valid video devices detected, and list-formats the list of "video modes" each camera can be in. -- For picams: edit the config.txt file as described in the {ref}`picam configuration page ` +- For picams: edit the config.txt file as described in the {ref}`picam configuration page ` - SSH into your Pi: {code}`ssh pi@photonvision.local` and enter the username "pi" & password "raspberry" - run {code}`v4l2-ctl --list-devices` and {code}`v4l2-ctl --list-formats` diff --git a/docs/source/index.md b/docs/source/index.md index a8bbdc6de..6a6d01a4b 100644 --- a/docs/source/index.md +++ b/docs/source/index.md @@ -91,6 +91,7 @@ docs/description docs/quick-start/index docs/hardware/index docs/advanced-installation/index +docs/camera-specific-configuration/index ``` ```{toctree} From 09f8d1c2a516e41510b93558d122a8a0c7c33e11 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 16 Mar 2025 23:39:20 -0400 Subject: [PATCH 08/42] Delete unused classes and remove unused code --- .../dataflow/events/HTTPRequestEvent.java | 31 - .../common/networking/RoborioFinder.java | 118 ---- .../common/scripting/ScriptCommandType.java | 31 - .../common/util/MemoryManager.java | 84 --- .../common/util/NativeLibHelper.java | 40 -- .../common/util/ReflectionUtils.java | 58 -- .../common/util/file/FileUtils.java | 42 -- .../common/util/java/TriConsumer.java | 22 - .../common/util/math/IPUtils.java | 56 -- .../vision/calibration/JsonImageMat.java | 92 --- .../vision/frame/FrameConsumer.java | 22 - .../frame/consumer/DummyFrameConsumer.java | 28 - .../photonvision/vision/opencv/DualMat.java | 25 - .../vision/pipe/impl/BlurPipe.java | 64 -- .../pipe/impl/DrawCornerDetectionPipe.java | 48 -- .../vision/pipe/impl/ErodeDilatePipe.java | 61 -- .../pipe/impl/GPUAcceleratedHSVPipe.java | 551 ------------------ .../vision/processes/VisionModuleManager.java | 21 - 18 files changed, 1394 deletions(-) delete mode 100644 photon-core/src/main/java/org/photonvision/common/dataflow/events/HTTPRequestEvent.java delete mode 100644 photon-core/src/main/java/org/photonvision/common/networking/RoborioFinder.java delete mode 100644 photon-core/src/main/java/org/photonvision/common/scripting/ScriptCommandType.java delete mode 100644 photon-core/src/main/java/org/photonvision/common/util/MemoryManager.java delete mode 100644 photon-core/src/main/java/org/photonvision/common/util/NativeLibHelper.java delete mode 100644 photon-core/src/main/java/org/photonvision/common/util/ReflectionUtils.java delete mode 100644 photon-core/src/main/java/org/photonvision/common/util/java/TriConsumer.java delete mode 100644 photon-core/src/main/java/org/photonvision/common/util/math/IPUtils.java delete mode 100644 photon-core/src/main/java/org/photonvision/vision/calibration/JsonImageMat.java delete mode 100644 photon-core/src/main/java/org/photonvision/vision/frame/FrameConsumer.java delete mode 100644 photon-core/src/main/java/org/photonvision/vision/frame/consumer/DummyFrameConsumer.java delete mode 100644 photon-core/src/main/java/org/photonvision/vision/opencv/DualMat.java delete mode 100644 photon-core/src/main/java/org/photonvision/vision/pipe/impl/BlurPipe.java delete mode 100644 photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCornerDetectionPipe.java delete mode 100644 photon-core/src/main/java/org/photonvision/vision/pipe/impl/ErodeDilatePipe.java delete mode 100644 photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/events/HTTPRequestEvent.java b/photon-core/src/main/java/org/photonvision/common/dataflow/events/HTTPRequestEvent.java deleted file mode 100644 index 5843ba1cc..000000000 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/events/HTTPRequestEvent.java +++ /dev/null @@ -1,31 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.common.dataflow.events; - -import org.photonvision.common.dataflow.DataChangeDestination; -import org.photonvision.common.dataflow.DataChangeSource; - -public class HTTPRequestEvent extends DataChangeEvent { - public HTTPRequestEvent( - DataChangeSource sourceType, - DataChangeDestination destType, - String propertyName, - T newValue) { - super(sourceType, destType, propertyName, newValue); - } -} diff --git a/photon-core/src/main/java/org/photonvision/common/networking/RoborioFinder.java b/photon-core/src/main/java/org/photonvision/common/networking/RoborioFinder.java deleted file mode 100644 index 605480e29..000000000 --- a/photon-core/src/main/java/org/photonvision/common/networking/RoborioFinder.java +++ /dev/null @@ -1,118 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.common.networking; - -import edu.wpi.first.cscore.CameraServerJNI; -import java.io.IOException; -import java.net.InetAddress; -import java.net.UnknownHostException; -import java.util.ArrayList; -import java.util.Arrays; -import java.util.HashMap; -import java.util.List; -import org.photonvision.common.dataflow.DataChangeService; -import org.photonvision.common.dataflow.events.OutgoingUIEvent; -import org.photonvision.common.logging.LogGroup; -import org.photonvision.common.logging.Logger; - -public class RoborioFinder { - private static RoborioFinder instance; - private static final Logger logger = new Logger(RoborioFinder.class, LogGroup.General); - - public static RoborioFinder getInstance() { - if (instance == null) instance = new RoborioFinder(); - return instance; - } - - public void findRios() { - HashMap map = new HashMap<>(); - var subMap = new HashMap(); - // Separate from the above so we don't hold stuff up - System.setProperty("java.net.preferIPv4Stack", "true"); - subMap.put( - "deviceIps", - Arrays.stream(CameraServerJNI.getNetworkInterfaces()) - .filter(it -> !it.equals("0.0.0.0")) - .toArray()); - logger.info("Searching for rios"); - List possibleRioList = new ArrayList<>(); - for (var ip : CameraServerJNI.getNetworkInterfaces()) { - logger.info("Trying " + ip); - var possibleRioAddr = getPossibleRioAddress(ip); - if (possibleRioAddr != null) { - logger.info("Maybe found " + ip); - searchForHost(possibleRioList, possibleRioAddr); - } else { - logger.info("Didn't match RIO IP"); - } - } - - // String name = - // "roboRIO-" - // + - // ConfigManager.getInstance().getConfig().getNetworkConfig().teamNumber - // + "-FRC.local"; - // searchForHost(possibleRioList, name); - // name = - // "roboRIO-" - // + - // ConfigManager.getInstance().getConfig().getNetworkConfig().teamNumber - // + "-FRC.lan"; - // searchForHost(possibleRioList, name); - // name = - // "roboRIO-" - // + - // ConfigManager.getInstance().getConfig().getNetworkConfig().teamNumber - // + "-FRC.frc-field.local"; - // searchForHost(possibleRioList, name); - // subMap.put("possibleRios", possibleRioList.toArray()); - - subMap.put("possibleRios", possibleRioList.toArray()); - map.put("networkInfo", subMap); - DataChangeService.getInstance().publishEvent(new OutgoingUIEvent<>("deviceIpInfo", map)); - } - - String getPossibleRioAddress(String ip) { - try { - InetAddress addr = InetAddress.getByName(ip); - var address = addr.getAddress(); - if (address[0] != (byte) (10 & 0xff)) return null; - address[3] = (byte) (2 & 0xff); - return InetAddress.getByAddress(address).getHostAddress(); - } catch (UnknownHostException e) { - e.printStackTrace(); - } - return null; - } - - void searchForHost(List list, String hostname) { - try { - logger.info("Looking up " + hostname); - InetAddress testAddr = InetAddress.getByName(hostname); - logger.info("Pinging " + hostname); - var canContact = testAddr.isReachable(500); - if (canContact) { - logger.info("Was able to connect to " + hostname); - if (!list.contains(hostname)) list.add(hostname); - } else { - logger.info("Unable to reach " + hostname); - } - } catch (IOException ignored) { - } - } -} diff --git a/photon-core/src/main/java/org/photonvision/common/scripting/ScriptCommandType.java b/photon-core/src/main/java/org/photonvision/common/scripting/ScriptCommandType.java deleted file mode 100644 index debc05c1b..000000000 --- a/photon-core/src/main/java/org/photonvision/common/scripting/ScriptCommandType.java +++ /dev/null @@ -1,31 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.common.scripting; - -public enum ScriptCommandType { - kDefault(""), - kBashScript("bash"), - kPythonScript("python"), - kPython3Script("python3"); - - public final String value; - - ScriptCommandType(String value) { - this.value = value; - } -} diff --git a/photon-core/src/main/java/org/photonvision/common/util/MemoryManager.java b/photon-core/src/main/java/org/photonvision/common/util/MemoryManager.java deleted file mode 100644 index d84536e0a..000000000 --- a/photon-core/src/main/java/org/photonvision/common/util/MemoryManager.java +++ /dev/null @@ -1,84 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.common.util; - -public class MemoryManager { - private static final long MEGABYTE_FACTOR = 1024L * 1024L; - - private int collectionThreshold; - private long collectionPeriodMillis = -1; - - private double lastUsedMb = 0; - private long lastCollectionMillis = 0; - - public MemoryManager(int collectionThreshold) { - this.collectionThreshold = collectionThreshold; - } - - public MemoryManager(int collectionThreshold, long collectionPeriodMillis) { - this.collectionThreshold = collectionThreshold; - this.collectionPeriodMillis = collectionPeriodMillis; - } - - public void setCollectionThreshold(int collectionThreshold) { - this.collectionThreshold = collectionThreshold; - } - - public void setCollectionPeriodMillis(long collectionPeriodMillis) { - this.collectionPeriodMillis = collectionPeriodMillis; - } - - private static long getUsedMemory() { - return Runtime.getRuntime().totalMemory() - Runtime.getRuntime().freeMemory(); - } - - private static double getUsedMemoryMB() { - return ((double) getUsedMemory() / MEGABYTE_FACTOR); - } - - private void collect() { - System.gc(); - System.runFinalization(); - } - - public void run() { - run(false); - } - - public void run(boolean print) { - var usedMem = getUsedMemoryMB(); - - if (usedMem != lastUsedMb) { - lastUsedMb = usedMem; - if (print) System.out.printf("Memory usage: %.2fMB\n", usedMem); - } - - boolean collectionThresholdPassed = usedMem >= collectionThreshold; - boolean collectionPeriodPassed = - collectionPeriodMillis != -1 - && (System.currentTimeMillis() - lastCollectionMillis >= collectionPeriodMillis); - - if (collectionThresholdPassed || collectionPeriodPassed) { - collect(); - lastCollectionMillis = System.currentTimeMillis(); - if (print) { - System.out.printf("Garbage collected at %.2fMB\n", usedMem); - } - } - } -} diff --git a/photon-core/src/main/java/org/photonvision/common/util/NativeLibHelper.java b/photon-core/src/main/java/org/photonvision/common/util/NativeLibHelper.java deleted file mode 100644 index a8d7dd5ef..000000000 --- a/photon-core/src/main/java/org/photonvision/common/util/NativeLibHelper.java +++ /dev/null @@ -1,40 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.common.util; - -import java.nio.file.Path; -import java.nio.file.Paths; - -public class NativeLibHelper { - private static NativeLibHelper INSTANCE; - - public static NativeLibHelper getInstance() { - if (INSTANCE == null) { - INSTANCE = new NativeLibHelper(); - } - - return INSTANCE; - } - - public final Path NativeLibPath; - - private NativeLibHelper() { - String home = System.getProperty("user.home"); - NativeLibPath = Paths.get(home, ".pvlibs", "nativecache"); - } -} diff --git a/photon-core/src/main/java/org/photonvision/common/util/ReflectionUtils.java b/photon-core/src/main/java/org/photonvision/common/util/ReflectionUtils.java deleted file mode 100644 index cda97c3f8..000000000 --- a/photon-core/src/main/java/org/photonvision/common/util/ReflectionUtils.java +++ /dev/null @@ -1,58 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.common.util; - -public class ReflectionUtils { - public static StackTraceElement[] getFullStackTrace() { - return Thread.currentThread().getStackTrace(); - } - - public static StackTraceElement getNthCaller(int n) { - if (n < 0) n = 0; - return Thread.currentThread().getStackTrace()[n]; - } - - public static String getCallerClassName() { - StackTraceElement[] stElements = Thread.currentThread().getStackTrace(); - for (int i = 1; i < stElements.length; i++) { - StackTraceElement ste = stElements[i]; - if (!ste.getClassName().equals(ReflectionUtils.class.getName()) - && ste.getClassName().indexOf("java.lang.Thread") != 0) { - return ste.getClassName(); - } - } - return null; - } - - public static String getCallerCallerClassName() { - StackTraceElement[] stElements = Thread.currentThread().getStackTrace(); - String callerClassName = null; - for (int i = 1; i < stElements.length; i++) { - StackTraceElement ste = stElements[i]; - if (!ste.getClassName().equals(ReflectionUtils.class.getName()) - && ste.getClassName().indexOf("java.lang.Thread") != 0) { - if (callerClassName == null) { - callerClassName = ste.getClassName(); - } else if (!callerClassName.equals(ste.getClassName())) { - return ste.getClassName(); - } - } - } - return null; - } -} diff --git a/photon-core/src/main/java/org/photonvision/common/util/file/FileUtils.java b/photon-core/src/main/java/org/photonvision/common/util/file/FileUtils.java index 8dc72acbb..cdf31cb2f 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/file/FileUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/file/FileUtils.java @@ -17,19 +17,12 @@ package org.photonvision.common.util.file; -import java.io.File; import java.io.FileNotFoundException; import java.io.IOException; import java.nio.file.Files; import java.nio.file.NoSuchFileException; import java.nio.file.Path; -import java.nio.file.attribute.PosixFileAttributes; -import java.nio.file.attribute.PosixFilePermission; -import java.util.Arrays; import java.util.Comparator; -import java.util.HashSet; -import java.util.Set; -import org.photonvision.common.hardware.Platform; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; @@ -37,8 +30,6 @@ public class FileUtils { private FileUtils() {} private static final Logger logger = new Logger(FileUtils.class, LogGroup.General); - private static final Set allReadWriteExecutePerms = - new HashSet<>(Arrays.asList(PosixFilePermission.values())); public static boolean deleteDirectory(Path path) { try { @@ -109,37 +100,4 @@ public class FileUtils { boolean fileCopied = copyFile(src, dst); return fileDeleted && fileCopied; } - - public static void setFilePerms(Path path) throws IOException { - if (Platform.isLinux()) { - File thisFile = path.toFile(); - Set perms = - Files.readAttributes(path, PosixFileAttributes.class).permissions(); - if (!perms.equals(allReadWriteExecutePerms)) { - logger.info("Setting perms on" + path); - Files.setPosixFilePermissions(path, perms); - var theseFiles = thisFile.listFiles(); - if (thisFile.isDirectory() && theseFiles != null) { - for (File subfile : theseFiles) { - setFilePerms(subfile.toPath()); - } - } - } - } - } - - public static void setAllPerms(Path path) { - if (Platform.isLinux()) { - String command = String.format("chmod 777 -R %s", path.toString()); - try { - Process p = Runtime.getRuntime().exec(command); - p.waitFor(); - - } catch (Exception e) { - logger.error("Setting perms failed!", e); - } - } else { - logger.info("Cannot set directory permissions on Windows!"); - } - } } diff --git a/photon-core/src/main/java/org/photonvision/common/util/java/TriConsumer.java b/photon-core/src/main/java/org/photonvision/common/util/java/TriConsumer.java deleted file mode 100644 index 6f1dc67fb..000000000 --- a/photon-core/src/main/java/org/photonvision/common/util/java/TriConsumer.java +++ /dev/null @@ -1,22 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.common.util.java; - -public interface TriConsumer { - void accept(T t, U u, V v); -} diff --git a/photon-core/src/main/java/org/photonvision/common/util/math/IPUtils.java b/photon-core/src/main/java/org/photonvision/common/util/math/IPUtils.java deleted file mode 100644 index f4127e782..000000000 --- a/photon-core/src/main/java/org/photonvision/common/util/math/IPUtils.java +++ /dev/null @@ -1,56 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.common.util.math; - -import java.util.ArrayList; -import java.util.List; - -public class IPUtils { - public static boolean isValidIPV4(final String ip) { - String PATTERN = - "^((0|1\\d?\\d?|2[0-4]?\\d?|25[0-5]?|[3-9]\\d?)\\.){3}(0|1\\d?\\d?|2[0-4]?\\d?|25[0-5]?|[3-9]\\d?)$"; - - return ip.matches(PATTERN); - } - - public static List getDigitBytes(int num) { - List digits = new ArrayList<>(); - collectDigitBytes(num, digits); - return digits; - } - - private static void collectDigitBytes(int num, List digits) { - if (num / 10 > 0) { - collectDigitBytes(num / 10, digits); - } - digits.add((byte) (num % 10)); - } - - public static List getDigits(int num) { - List digits = new ArrayList<>(); - collectDigits(num, digits); - return digits; - } - - private static void collectDigits(int num, List digits) { - if (num / 10 > 0) { - collectDigits(num / 10, digits); - } - digits.add(num % 10); - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/calibration/JsonImageMat.java b/photon-core/src/main/java/org/photonvision/vision/calibration/JsonImageMat.java deleted file mode 100644 index 241004cca..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/calibration/JsonImageMat.java +++ /dev/null @@ -1,92 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.vision.calibration; - -import com.fasterxml.jackson.annotation.JsonIgnore; -import com.fasterxml.jackson.annotation.JsonProperty; -import java.util.Base64; -import org.opencv.core.Mat; -import org.opencv.core.MatOfByte; -import org.opencv.imgcodecs.Imgcodecs; -import org.photonvision.vision.opencv.Releasable; - -/** JSON-serializable image. Data is stored as base64-encoded PNG data. */ -public class JsonImageMat implements Releasable { - public final int rows; - public final int cols; - public final int type; - - // We store image data as a base64-encoded PNG inside a Java string. This lets us serialize it - // without too much overhead and still use JSON. - public final String data; - - // Cached matrices to avoid object recreation - @JsonIgnore private Mat wrappedMat = null; - - public JsonImageMat(Mat mat) { - this.rows = mat.rows(); - this.cols = mat.cols(); - this.type = mat.type(); - - // Convert from Mat -> png byte array -> base64 - var buf = new MatOfByte(); - Imgcodecs.imencode(".png", mat, buf); - data = Base64.getEncoder().encodeToString(buf.toArray()); - buf.release(); - } - - public JsonImageMat( - @JsonProperty("rows") int rows, - @JsonProperty("cols") int cols, - @JsonProperty("type") int type, - @JsonProperty("data") String data) { - this.rows = rows; - this.cols = cols; - this.type = type; - this.data = data; - } - - @JsonIgnore - public Mat getAsMat() { - if (wrappedMat == null) { - // Convert back from base64 string -> png -> Mat - var bytes = Base64.getDecoder().decode(data); - var pngData = new MatOfByte(bytes); - this.wrappedMat = Imgcodecs.imdecode(pngData, Imgcodecs.IMREAD_COLOR); - } - return this.wrappedMat; - } - - @Override - public void release() { - if (wrappedMat != null) wrappedMat.release(); - } - - @Override - public String toString() { - return "JsonImageMat [rows=" - + rows - + ", cols=" - + cols - + ", type=" - + type - + ", datalen=" - + data.length() - + "]"; - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/FrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/FrameConsumer.java deleted file mode 100644 index c22fe707e..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/frame/FrameConsumer.java +++ /dev/null @@ -1,22 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.vision.frame; - -import java.util.function.Consumer; - -public interface FrameConsumer extends Consumer {} diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/DummyFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/DummyFrameConsumer.java deleted file mode 100644 index 1e9449a35..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/DummyFrameConsumer.java +++ /dev/null @@ -1,28 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.vision.frame.consumer; - -import org.photonvision.vision.frame.Frame; -import org.photonvision.vision.frame.FrameConsumer; - -public class DummyFrameConsumer implements FrameConsumer { - @Override - public void accept(Frame frame) { - frame.release(); // lol ez - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/opencv/DualMat.java b/photon-core/src/main/java/org/photonvision/vision/opencv/DualMat.java deleted file mode 100644 index f2adb4a92..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/opencv/DualMat.java +++ /dev/null @@ -1,25 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.vision.opencv; - -import org.opencv.core.Mat; - -public class DualMat { - public Mat first; - public Mat second; -} diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/BlurPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/BlurPipe.java deleted file mode 100644 index 11eff2e21..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/BlurPipe.java +++ /dev/null @@ -1,64 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.vision.pipe.impl; - -import org.opencv.core.Mat; -import org.opencv.core.Size; -import org.opencv.imgproc.Imgproc; -import org.photonvision.vision.pipe.MutatingPipe; - -/** Represents a pipeline that blurs the image. */ -public class BlurPipe extends MutatingPipe { - /** - * Processes this pipe. - * - * @param in Input for pipe processing. - * @return The processed frame. - */ - @Override - protected Void process(Mat in) { - Imgproc.blur(in, in, params.getBlurSize()); - return null; - } - - public static class BlurParams { - // Default BlurImagePrams with zero blur. - public static BlurParams DEFAULT = new BlurParams(0); - - // Member to store the blur size. - private final int m_blurSize; - - /** - * Constructs a new BlurImageParams. - * - * @param blurSize The blur size. - */ - public BlurParams(int blurSize) { - m_blurSize = blurSize; - } - - /** - * Returns the blur size. - * - * @return The blur size. - */ - public Size getBlurSize() { - return new Size(m_blurSize, m_blurSize); - } - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCornerDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCornerDetectionPipe.java deleted file mode 100644 index 9ef05ad99..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCornerDetectionPipe.java +++ /dev/null @@ -1,48 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.vision.pipe.impl; - -import java.util.List; -import org.apache.commons.lang3.tuple.Pair; -import org.opencv.core.Mat; -import org.opencv.core.Scalar; -import org.opencv.imgproc.Imgproc; -import org.photonvision.vision.pipe.MutatingPipe; -import org.photonvision.vision.target.TrackedTarget; - -public class DrawCornerDetectionPipe - extends MutatingPipe>, DrawCornerDetectionPipe.DrawCornerParams> { - @Override - protected Void process(Pair> in) { - Mat image = in.getLeft(); - - for (var target : in.getRight()) { - var corners = target.getTargetCorners(); - for (var corner : corners) { - Imgproc.circle(image, corner, params.dotRadius, params.dotColor); - } - } - - return null; - } - - public static class DrawCornerParams { - int dotRadius; - Scalar dotColor; - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ErodeDilatePipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ErodeDilatePipe.java deleted file mode 100644 index 9d09a5d19..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ErodeDilatePipe.java +++ /dev/null @@ -1,61 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.vision.pipe.impl; - -import org.opencv.core.Mat; -import org.opencv.core.Size; -import org.opencv.imgproc.Imgproc; -import org.photonvision.vision.pipe.MutatingPipe; - -public class ErodeDilatePipe extends MutatingPipe { - @Override - protected Void process(Mat in) { - if (params.shouldErode()) { - Imgproc.erode(in, in, params.getKernel()); - } - if (params.shouldDilate()) { - Imgproc.dilate(in, in, params.getKernel()); - } - return null; - } - - public static class ErodeDilateParams { - private final boolean m_erode; - private final boolean m_dilate; - private final Mat m_kernel; - - public ErodeDilateParams(boolean erode, boolean dilate, int kernelSize) { - m_erode = erode; - m_dilate = dilate; - m_kernel = - Imgproc.getStructuringElement(Imgproc.MORPH_RECT, new Size(kernelSize, kernelSize)); - } - - public boolean shouldErode() { - return m_erode; - } - - public boolean shouldDilate() { - return m_dilate; - } - - public Mat getKernel() { - return m_kernel; - } - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java deleted file mode 100644 index 5b49faf64..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GPUAcceleratedHSVPipe.java +++ /dev/null @@ -1,551 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.vision.pipe.impl; - -import static com.jogamp.opengl.GL.*; -import static com.jogamp.opengl.GL2ES2.*; - -import com.jogamp.opengl.*; -import com.jogamp.opengl.util.GLBuffers; -import com.jogamp.opengl.util.texture.Texture; -import com.jogamp.opengl.util.texture.TextureData; -import java.nio.ByteBuffer; -import java.nio.FloatBuffer; -import java.nio.IntBuffer; -import jogamp.opengl.GLOffscreenAutoDrawableImpl; -import org.opencv.core.CvType; -import org.opencv.core.Mat; -import org.photonvision.common.logging.LogGroup; -import org.photonvision.common.logging.Logger; -import org.photonvision.vision.pipe.CVPipe; - -public class GPUAcceleratedHSVPipe extends CVPipe { - private static final String k_vertexShader = - String.join( - "\n", - "#version 100", - "", - "attribute vec4 position;", - "", - "void main() {", - " gl_Position = position;", - "}"); - private static final String k_fragmentShader = - String.join( - "\n", - "#version 100", - "", - "precision highp float;", - "precision highp int;", - "", - "uniform vec3 lowerThresh;", - "uniform vec3 upperThresh;", - "uniform vec2 resolution;", - "uniform sampler2D texture0;", - "", - "vec3 rgb2hsv(vec3 c) {", - " vec4 K = vec4(0.0, -1.0 / 3.0, 2.0 / 3.0, -1.0);", - " vec4 p = mix(vec4(c.bg, K.wz), vec4(c.gb, K.xy), step(c.b, c.g));", - " vec4 q = mix(vec4(p.xyw, c.r), vec4(c.r, p.yzx), step(p.x, c.r));", - "", - " float d = q.x - min(q.w, q.y);", - " float e = 1.0e-10;", - " return vec3(abs(q.z + (q.w - q.y) / (6.0 * d + e)), d / (q.x + e), q.x);", - "}", - "", - "bool inRange(vec3 hsv) {", - " bvec3 botBool = greaterThanEqual(hsv, lowerThresh);", - " bvec3 topBool = lessThanEqual(hsv, upperThresh);", - " return all(botBool) && all(topBool);", - "}", - "", - "void main() {", - " vec2 uv = gl_FragCoord.xy/resolution;", - // Important! We do this .bgr swizzle because the image comes in as BGR, but we pretend - // it's RGB for convenience+speed - " vec3 col = texture2D(texture0, uv).bgr;", - // Only the first value in the vec4 gets used for GL_RED, and only the last value gets - // used for GL_ALPHA - " gl_FragColor = inRange(rgb2hsv(col)) ? vec4(1.0, 0.0, 0.0, 1.0) : vec4(0.0, 0.0, 0.0, 0.0);", - "}"); - private static final int k_startingWidth = 1280, k_startingHeight = 720; - private static final float[] k_vertexPositions = { - // Set up a quad that covers the screen - -1f, +1f, +1f, +1f, -1f, -1f, +1f, -1f - }; - private static final int k_positionVertexAttribute = - 0; // ID for the vertex shader position variable - - public enum PBOMode { - NONE, - SINGLE_BUFFERED, - DOUBLE_BUFFERED - } - - private final IntBuffer vertexVBOIds = GLBuffers.newDirectIntBuffer(1), - unpackPBOIds = GLBuffers.newDirectIntBuffer(2), - packPBOIds = GLBuffers.newDirectIntBuffer(2); - - private final GL2ES2 gl; - private final GLProfile profile; - private final int outputFormat; - private final PBOMode pboMode; - private final GLOffscreenAutoDrawableImpl.FBOImpl drawable; - private final Texture texture; - // The texture uniform holds the image that's being processed - // The resolution uniform holds the current image resolution - // The lower and upper uniforms hold the lower and upper HSV limits for thresholding - private final int textureUniformId, resolutionUniformId, lowerUniformId, upperUniformId; - - private final Logger logger = new Logger(GPUAcceleratedHSVPipe.class, LogGroup.General); - - private byte[] inputBytes, outputBytes; - private Mat outputMat = new Mat(k_startingHeight, k_startingWidth, CvType.CV_8UC1); - private int previousWidth = -1, previousHeight = -1; - private int unpackIndex = 0, unpackNextIndex = 0, packIndex = 0, packNextIndex = 0; - - public GPUAcceleratedHSVPipe(PBOMode pboMode) { - this.pboMode = pboMode; - - // Set up GL profile and ask for specific capabilities - profile = GLProfile.get(pboMode == PBOMode.NONE ? GLProfile.GLES2 : GLProfile.GL4ES3); - final var capabilities = new GLCapabilities(profile); - capabilities.setHardwareAccelerated(true); - capabilities.setFBO(true); - capabilities.setDoubleBuffered(false); - capabilities.setOnscreen(false); - capabilities.setRedBits(8); - capabilities.setBlueBits(0); - capabilities.setGreenBits(0); - capabilities.setAlphaBits(0); - - // Set up the offscreen area we're going to draw to - final var factory = GLDrawableFactory.getFactory(profile); - drawable = - (GLOffscreenAutoDrawableImpl.FBOImpl) - factory.createOffscreenAutoDrawable( - factory.getDefaultDevice(), - capabilities, - new DefaultGLCapabilitiesChooser(), - k_startingWidth, - k_startingHeight); - drawable.display(); - drawable.getContext().makeCurrent(); - - // Get an OpenGL context; OpenGL ES 2.0 and OpenGL 2.0 are compatible with all the coprocs we - // care about but not compatible with PBOs. Open GL ES 3.0 and OpenGL 4.0 are compatible with - // select coprocs *and* PBOs - gl = pboMode == PBOMode.NONE ? drawable.getGL().getGLES2() : drawable.getGL().getGL4ES3(); - final int programId = gl.glCreateProgram(); - - if (pboMode == PBOMode.NONE && !gl.glGetString(GL_EXTENSIONS).contains("GL_EXT_texture_rg")) { - logger.warn( - "OpenGL ES 2.0 implementation does not have the 'GL_EXT_texture_rg' extension, falling back to GL_ALPHA instead of GL_RED output format"); - outputFormat = GL_ALPHA; - } else { - outputFormat = GL_RED; - } - - // JOGL creates a framebuffer color attachment that has RGB set as the format, which is not - // appropriate for us because we want a single-channel format - // We make ourown FBO color attachment to remedy this - // Detach and destroy the FBO color attachment that JOGL made for us - drawable.getFBObject(GL_FRONT).detachColorbuffer(gl, 0, true); - // Equivalent to calling glBindFramebuffer - drawable.getFBObject(GL_FRONT).bind(gl); - if (true) { // For now renderbuffers are disabled - // Create a color attachment texture to hold our rendered output - var colorBufferIds = GLBuffers.newDirectIntBuffer(1); - gl.glGenTextures(1, colorBufferIds); - gl.glBindTexture(GL_TEXTURE_2D, colorBufferIds.get(0)); - gl.glTexImage2D( - GL_TEXTURE_2D, - 0, - outputFormat == GL_RED ? GL_R8 : GL_ALPHA8, - k_startingWidth, - k_startingHeight, - 0, - outputFormat, - GL_UNSIGNED_BYTE, - null); - gl.glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MIN_FILTER, GL_LINEAR); - gl.glTexParameteri(GL_TEXTURE_2D, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - // Attach the texture to the framebuffer - gl.glBindTexture(GL_TEXTURE_2D, 0); - gl.glFramebufferTexture2D( - GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_TEXTURE_2D, colorBufferIds.get(0), 0); - // Cleanup - gl.glBindTexture(GL_TEXTURE_2D, 0); - } else { - // Create a color attachment texture to hold our rendered output - var renderBufferIds = GLBuffers.newDirectIntBuffer(1); - gl.glGenRenderbuffers(1, renderBufferIds); - gl.glBindRenderbuffer(GL_RENDERBUFFER, renderBufferIds.get(0)); - gl.glRenderbufferStorage( - GL_RENDERBUFFER, - outputFormat == GL_RED ? GL_R8 : GL_ALPHA8, - k_startingWidth, - k_startingHeight); - // Attach the texture to the framebuffer - gl.glFramebufferRenderbuffer( - GL_FRAMEBUFFER, GL_COLOR_ATTACHMENT0, GL_RENDERBUFFER, renderBufferIds.get(0)); - // Cleanup - gl.glBindRenderbuffer(GL_RENDERBUFFER, 0); - } - drawable.getFBObject(GL_FRONT).unbind(gl); - - // Check that the FBO is attached - int fboStatus = gl.glCheckFramebufferStatus(GL_FRAMEBUFFER); - if (fboStatus == GL_FRAMEBUFFER_UNSUPPORTED) { - throw new RuntimeException( - "GL implementation does not support rendering to internal format '" - + String.format("0x%08X", outputFormat == GL_RED ? GL_R8 : GL_ALPHA8) - + "' with type '" - + String.format("0x%08X", GL_UNSIGNED_BYTE) - + "'"); - } else if (fboStatus != GL_FRAMEBUFFER_COMPLETE) { - throw new RuntimeException( - "Framebuffer is not complete; framebuffer status is " - + String.format("0x%08X", fboStatus)); - } - - logger.debug( - "Created an OpenGL context with renderer '" - + gl.glGetString(GL_RENDERER) - + "', version '" - + gl.glGetString(GL.GL_VERSION) - + "', and profile '" - + profile - + "'"); - - var fmt = GLBuffers.newDirectIntBuffer(1); - gl.glGetIntegerv(GLES3.GL_IMPLEMENTATION_COLOR_READ_FORMAT, fmt); - var type = GLBuffers.newDirectIntBuffer(1); - gl.glGetIntegerv(GLES3.GL_IMPLEMENTATION_COLOR_READ_TYPE, type); - - // Tell OpenGL that the attribute in the vertex shader named position is bound to index 0 (the - // index for the generic position input) - gl.glBindAttribLocation(programId, 0, "position"); - - // Compile and set up our two shaders with our program - final int vertexId = createShader(gl, programId, k_vertexShader, GL_VERTEX_SHADER); - final int fragmentId = createShader(gl, programId, k_fragmentShader, GL_FRAGMENT_SHADER); - - // Link our program together and check for errors - gl.glLinkProgram(programId); - IntBuffer status = GLBuffers.newDirectIntBuffer(1); - gl.glGetProgramiv(programId, GL_LINK_STATUS, status); - if (status.get(0) == GL_FALSE) { - IntBuffer infoLogLength = GLBuffers.newDirectIntBuffer(1); - gl.glGetProgramiv(programId, GL_INFO_LOG_LENGTH, infoLogLength); - - ByteBuffer bufferInfoLog = GLBuffers.newDirectByteBuffer(infoLogLength.get(0)); - gl.glGetProgramInfoLog(programId, infoLogLength.get(0), null, bufferInfoLog); - byte[] bytes = new byte[infoLogLength.get(0)]; - bufferInfoLog.get(bytes); - String strInfoLog = new String(bytes); - - throw new RuntimeException("Linker failure: " + strInfoLog); - } - gl.glValidateProgram(programId); - - // Cleanup shaders that are now compiled in - gl.glDetachShader(programId, vertexId); - gl.glDetachShader(programId, fragmentId); - gl.glDeleteShader(vertexId); - gl.glDeleteShader(fragmentId); - - // Tell OpenGL to use our program - gl.glUseProgram(programId); - - // Set up our texture - texture = new Texture(GL_TEXTURE_2D); - texture.setTexParameteri(gl, GL_TEXTURE_MIN_FILTER, GL_LINEAR); - texture.setTexParameteri(gl, GL_TEXTURE_MAG_FILTER, GL_LINEAR); - texture.setTexParameteri(gl, GL_TEXTURE_WRAP_S, GL_CLAMP_TO_EDGE); - texture.setTexParameteri(gl, GL_TEXTURE_WRAP_T, GL_CLAMP_TO_EDGE); - - // Set up a uniform holding our image as a texture - textureUniformId = gl.glGetUniformLocation(programId, "texture0"); - gl.glUniform1i(textureUniformId, 0); - - // Set up a uniform to hold image resolution - resolutionUniformId = gl.glGetUniformLocation(programId, "resolution"); - - // Set up uniforms for the HSV thresholds - lowerUniformId = gl.glGetUniformLocation(programId, "lowerThresh"); - upperUniformId = gl.glGetUniformLocation(programId, "upperThresh"); - - // Set up a quad that covers the entire screen so that our fragment shader draws onto the entire - // screen - gl.glGenBuffers(1, vertexVBOIds); - - FloatBuffer vertexBuffer = GLBuffers.newDirectFloatBuffer(k_vertexPositions); - gl.glBindBuffer(GL_ARRAY_BUFFER, vertexVBOIds.get(0)); - gl.glBufferData( - GL_ARRAY_BUFFER, - (long) vertexBuffer.capacity() * Float.BYTES, - vertexBuffer, - GL_STATIC_DRAW); - - // Set up pixel unpack buffer (a PBO to transfer image data to the GPU) - if (pboMode != PBOMode.NONE) { - gl.glGenBuffers(2, unpackPBOIds); - - gl.glBindBuffer(GLES3.GL_PIXEL_UNPACK_BUFFER, unpackPBOIds.get(0)); - gl.glBufferData( - GLES3.GL_PIXEL_UNPACK_BUFFER, - k_startingHeight * k_startingWidth * 3, - null, - GLES3.GL_STREAM_DRAW); - if (pboMode == PBOMode.DOUBLE_BUFFERED) { - gl.glBindBuffer(GLES3.GL_PIXEL_UNPACK_BUFFER, unpackPBOIds.get(1)); - gl.glBufferData( - GLES3.GL_PIXEL_UNPACK_BUFFER, - k_startingHeight * k_startingWidth * 3, - null, - GLES3.GL_STREAM_DRAW); - } - gl.glBindBuffer(GLES3.GL_PIXEL_UNPACK_BUFFER, 0); - } - - // Set up pixel pack buffer (a PBO to transfer the processed image back from the GPU) - if (pboMode != PBOMode.NONE) { - gl.glGenBuffers(2, packPBOIds); - - gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(0)); - gl.glBufferData( - GLES3.GL_PIXEL_PACK_BUFFER, - k_startingHeight * k_startingWidth, - null, - GLES3.GL_STREAM_READ); - if (pboMode == PBOMode.DOUBLE_BUFFERED) { - gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(1)); - gl.glBufferData( - GLES3.GL_PIXEL_PACK_BUFFER, - k_startingHeight * k_startingWidth, - null, - GLES3.GL_STREAM_READ); - } - gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, 0); - } - } - - private static int createShader(GL2ES2 gl, int programId, String glslCode, int shaderType) { - int shaderId = gl.glCreateShader(shaderType); - if (shaderId == 0) throw new RuntimeException("Shader ID is zero"); - - IntBuffer length = GLBuffers.newDirectIntBuffer(new int[] {glslCode.length()}); - gl.glShaderSource(shaderId, 1, new String[] {glslCode}, length); - gl.glCompileShader(shaderId); - - IntBuffer intBuffer = IntBuffer.allocate(1); - gl.glGetShaderiv(shaderId, GL_COMPILE_STATUS, intBuffer); - - if (intBuffer.get(0) != 1) { - gl.glGetShaderiv(shaderId, GL_INFO_LOG_LENGTH, intBuffer); - int size = intBuffer.get(0); - if (size > 0) { - ByteBuffer byteBuffer = ByteBuffer.allocate(size); - gl.glGetShaderInfoLog(shaderId, size, intBuffer, byteBuffer); - System.err.println(new String(byteBuffer.array())); - } - throw new RuntimeException("Couldn't compile shader"); - } - - gl.glAttachShader(programId, shaderId); - - return shaderId; - } - - @Override - protected Mat process(Mat in) { - if (in.width() != previousWidth && in.height() != previousHeight) { - logger.debug("Resizing OpenGL viewport, byte buffers, and PBOs"); - - drawable.setSurfaceSize(in.width(), in.height()); - gl.glViewport(0, 0, in.width(), in.height()); - - previousWidth = in.width(); - previousHeight = in.height(); - - inputBytes = new byte[in.width() * in.height() * 3]; - - outputBytes = new byte[in.width() * in.height()]; - outputMat = new Mat(k_startingHeight, k_startingWidth, CvType.CV_8UC1); - - if (pboMode != PBOMode.NONE) { - gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(0)); - gl.glBufferData( - GLES3.GL_PIXEL_PACK_BUFFER, - (long) in.width() * in.height(), - null, - GLES3.GL_STREAM_READ); - - if (pboMode == PBOMode.DOUBLE_BUFFERED) { - gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(1)); - gl.glBufferData( - GLES3.GL_PIXEL_PACK_BUFFER, - (long) in.width() * in.height(), - null, - GLES3.GL_STREAM_READ); - } - } - } - - if (pboMode == PBOMode.DOUBLE_BUFFERED) { - unpackIndex = (unpackIndex + 1) % 2; - unpackNextIndex = (unpackIndex + 1) % 2; - } - - // Reset the fullscreen quad - gl.glBindBuffer(GL_ARRAY_BUFFER, vertexVBOIds.get(0)); - gl.glEnableVertexAttribArray(k_positionVertexAttribute); - gl.glVertexAttribPointer(0, 2, GL_FLOAT, false, 0, 0); - gl.glBindBuffer(GL_ARRAY_BUFFER, 0); - - // Load and bind our image as a 2D texture - gl.glActiveTexture(GL_TEXTURE0); - texture.enable(gl); - texture.bind(gl); - - // Load our image into the texture - in.get(0, 0, inputBytes); - if (pboMode == PBOMode.NONE) { - ByteBuffer buf = ByteBuffer.wrap(inputBytes); - // (We're actually taking in BGR even though this says RGB; it's much easier and faster to - // switch it around in the fragment shader) - texture.updateImage( - gl, - new TextureData( - profile, - GL_RGB8, - in.width(), - in.height(), - 0, - GL_RGB, - GL_UNSIGNED_BYTE, - false, - false, - false, - buf, - null)); - } else { - // Bind the PBO to the texture - gl.glBindBuffer(GLES3.GL_PIXEL_UNPACK_BUFFER, unpackPBOIds.get(unpackIndex)); - - // Copy pixels from the PBO to the texture object - gl.glTexSubImage2D( - GLES3.GL_TEXTURE_2D, - 0, - 0, - 0, - in.width(), - in.height(), - GLES3.GL_RGB8, - GLES3.GL_UNSIGNED_BYTE, - 0); - - // Bind (potentially) another PBO to update the texture source - gl.glBindBuffer(GLES3.GL_PIXEL_UNPACK_BUFFER, unpackPBOIds.get(unpackNextIndex)); - - // This call with a nullptr for the data arg tells OpenGL *not* to wait to be in sync with the - // GPU - // This causes the previous data in the PBO to be discarded - gl.glBufferData( - GLES3.GL_PIXEL_UNPACK_BUFFER, - (long) in.width() * in.height() * 3, - null, - GLES3.GL_STREAM_DRAW); - - // Map the buffer of GPU memory into a place that's accessible by us - var buf = - gl.glMapBufferRange( - GLES3.GL_PIXEL_UNPACK_BUFFER, - 0, - (long) in.width() * in.height() * 3, - GLES3.GL_MAP_WRITE_BIT); - buf.put(inputBytes); - - gl.glUnmapBuffer(GLES3.GL_PIXEL_UNPACK_BUFFER); - gl.glBindBuffer(GLES3.GL_PIXEL_UNPACK_BUFFER, 0); - } - - // Put values in a uniform holding the image resolution - gl.glUniform2f(resolutionUniformId, in.width(), in.height()); - - // Put values in threshold uniforms - var lowr = params.getHsvLower().val; - var upr = params.getHsvUpper().val; - gl.glUniform3f(lowerUniformId, (float) lowr[0], (float) lowr[1], (float) lowr[2]); - gl.glUniform3f(upperUniformId, (float) upr[0], (float) upr[1], (float) upr[2]); - - // Draw the fullscreen quad - gl.glDrawArrays(GL_TRIANGLE_STRIP, 0, k_vertexPositions.length); - - // Cleanup - texture.disable(gl); - gl.glDisableVertexAttribArray(k_positionVertexAttribute); - gl.glUseProgram(0); - - if (pboMode == PBOMode.NONE) { - return saveMatNoPBO(gl, in.width(), in.height()); - } else { - return saveMatPBO((GLES3) gl, in.width(), in.height(), pboMode == PBOMode.DOUBLE_BUFFERED); - } - } - - private Mat saveMatNoPBO(GL2ES2 gl, int width, int height) { - ByteBuffer buffer = GLBuffers.newDirectByteBuffer(width * height); - // We use GL_RED/GL_ALPHA to get things in a single-channel format - // Note that which pixel format you use is *very* important to performance - // E.g. GL_ALPHA is super slow in this case - gl.glReadPixels(0, 0, width, height, outputFormat, GL_UNSIGNED_BYTE, buffer); - - return new Mat(height, width, CvType.CV_8UC1, buffer); - } - - private Mat saveMatPBO(GLES3 gl, int width, int height, boolean doubleBuffered) { - if (doubleBuffered) { - packIndex = (packIndex + 1) % 2; - packNextIndex = (packIndex + 1) % 2; - } - - // Set the target framebuffer attachment to read - gl.glReadBuffer(GLES3.GL_COLOR_ATTACHMENT0); - - // Read pixels from the framebuffer to the PBO - gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(packIndex)); - // We use GL_RED (which is always supported in GLES3) to get things in a single-channel format - // Note that which pixel format you use is *very* important to performance - // E.g. GL_ALPHA is super slow in this case - gl.glReadPixels(0, 0, width, height, GLES3.GL_RED, GLES3.GL_UNSIGNED_BYTE, 0); - - // Map the PBO into the CPU's memory - gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, packPBOIds.get(packNextIndex)); - var buf = - gl.glMapBufferRange( - GLES3.GL_PIXEL_PACK_BUFFER, 0, (long) width * height, GLES3.GL_MAP_READ_BIT); - buf.get(outputBytes); - outputMat.put(0, 0, outputBytes); - gl.glUnmapBuffer(GLES3.GL_PIXEL_PACK_BUFFER); - gl.glBindBuffer(GLES3.GL_PIXEL_PACK_BUFFER, 0); - - return outputMat; - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java index fc6818a36..35c727eba 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java @@ -19,7 +19,6 @@ package org.photonvision.vision.processes; import java.util.*; import java.util.stream.Collectors; -import org.photonvision.common.dataflow.websocket.UICameraConfiguration; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; @@ -83,24 +82,4 @@ public class VisionModuleManager { return idx; } - - public static class UiVmmState { - public final List visionModules; - - UiVmmState(List _v) { - this.visionModules = _v; - } - } - - public synchronized UiVmmState getState() { - return new UiVmmState( - this.visionModules.stream() - .map(VisionModule::toUICameraConfig) - .map( - it -> { - it.calibrations = null; - return it; - }) - .collect(Collectors.toList())); - } } From 1fb02a477d8e6106628d4a768fe3843b71ad217f Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 16 Mar 2025 23:40:32 -0400 Subject: [PATCH 09/42] Make HardwareConfig a record --- .../common/configuration/HardwareConfig.java | 197 +++++------------- .../websocket/UIPhotonConfiguration.java | 6 +- .../common/hardware/GPIO/CustomGPIO.java | 6 +- .../common/hardware/HardwareManager.java | 16 +- .../hardware/metrics/cmds/FileCmds.java | 18 +- .../USBCameras/GenericUSBCameraSettables.java | 2 +- .../vision/camera/csi/LibcameraGpuSource.java | 2 +- .../vision/processes/VisionModule.java | 2 +- .../hardware/HardwareConfigTest.java | 8 +- 9 files changed, 79 insertions(+), 178 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/HardwareConfig.java b/photon-core/src/main/java/org/photonvision/common/configuration/HardwareConfig.java index 2c8323f15..7d008f94f 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/HardwareConfig.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/HardwareConfig.java @@ -23,109 +23,59 @@ import java.util.Collections; import java.util.List; @JsonIgnoreProperties(ignoreUnknown = true) -public class HardwareConfig { - public final String deviceName; - public final String deviceLogoPath; - public final String supportURL; +public record HardwareConfig( + String deviceName, + String deviceLogoPath, + String supportURL, + // LED control - // LED control - public final ArrayList ledPins; - public final String ledSetCommand; - public final boolean ledsCanDim; - public final ArrayList ledBrightnessRange; - public final String ledDimCommand; - public final String ledBlinkCommand; - public final ArrayList statusRGBPins; + ArrayList ledPins, + String ledSetCommand, + boolean ledsCanDim, + ArrayList ledBrightnessRange, + String ledDimCommand, + String ledBlinkCommand, + ArrayList statusRGBPins, + // Metrics - // Metrics - public final String cpuTempCommand; - public final String cpuMemoryCommand; - public final String cpuUtilCommand; - public final String cpuThrottleReasonCmd; - public final String cpuUptimeCommand; - public final String gpuMemoryCommand; - public final String ramUtilCommand; - public final String gpuMemUsageCommand; - public final String diskUsageCommand; - - // Device stuff - public final String restartHardwareCommand; - public final double vendorFOV; // -1 for unmanaged - public final List blacklistedResIndices; // this happens before the defaults are applied + String cpuTempCommand, + String cpuMemoryCommand, + String cpuUtilCommand, + String cpuThrottleReasonCmd, + String cpuUptimeCommand, + String gpuMemoryCommand, + String ramUtilCommand, + String gpuMemUsageCommand, + String diskUsageCommand, + // Device stuff + String restartHardwareCommand, + double vendorFOV, // -1 for unmanaged + List blacklistedResIndices) { // this happens before the defaults are applied) public HardwareConfig() { - deviceName = ""; - deviceLogoPath = ""; - supportURL = ""; - ledPins = new ArrayList<>(); - ledSetCommand = ""; - ledsCanDim = false; - ledBrightnessRange = new ArrayList<>(); - statusRGBPins = new ArrayList<>(); - ledDimCommand = ""; - - cpuTempCommand = ""; - cpuMemoryCommand = ""; - cpuUtilCommand = ""; - cpuThrottleReasonCmd = ""; - cpuUptimeCommand = ""; - gpuMemoryCommand = ""; - ramUtilCommand = ""; - ledBlinkCommand = ""; - gpuMemUsageCommand = ""; - diskUsageCommand = ""; - - restartHardwareCommand = ""; - vendorFOV = -1; - blacklistedResIndices = Collections.emptyList(); - } - - @SuppressWarnings("unused") - public HardwareConfig( - String deviceName, - String deviceLogoPath, - String supportURL, - ArrayList ledPins, - String ledSetCommand, - boolean ledsCanDim, - ArrayList ledBrightnessRange, - String ledDimCommand, - String ledBlinkCommand, - ArrayList statusRGBPins, - String cpuTempCommand, - String cpuMemoryCommand, - String cpuUtilCommand, - String cpuThrottleReasonCmd, - String cpuUptimeCommand, - String gpuMemoryCommand, - String ramUtilCommand, - String gpuMemUsageCommand, - String diskUsageCommand, - String restartHardwareCommand, - double vendorFOV, - List blacklistedResIndices) { - this.deviceName = deviceName; - this.deviceLogoPath = deviceLogoPath; - this.supportURL = supportURL; - this.ledPins = ledPins; - this.ledSetCommand = ledSetCommand; - this.ledsCanDim = ledsCanDim; - this.ledBrightnessRange = ledBrightnessRange; - this.ledDimCommand = ledDimCommand; - this.ledBlinkCommand = ledBlinkCommand; - this.statusRGBPins = statusRGBPins; - this.cpuTempCommand = cpuTempCommand; - this.cpuMemoryCommand = cpuMemoryCommand; - this.cpuUtilCommand = cpuUtilCommand; - this.cpuThrottleReasonCmd = cpuThrottleReasonCmd; - this.cpuUptimeCommand = cpuUptimeCommand; - this.gpuMemoryCommand = gpuMemoryCommand; - this.ramUtilCommand = ramUtilCommand; - this.gpuMemUsageCommand = gpuMemUsageCommand; - this.diskUsageCommand = diskUsageCommand; - this.restartHardwareCommand = restartHardwareCommand; - this.vendorFOV = vendorFOV; - this.blacklistedResIndices = blacklistedResIndices; + this( + "", // deviceName + "", // deviceLogoPath + "", // supportURL + new ArrayList<>(), // ledPins + "", // ledSetCommand + false, // ledsCanDim + new ArrayList<>(), // ledBrightnessRange + "", // ledDimCommand + "", // ledBlinkCommand + new ArrayList<>(), // statusRGBPins + "", // cpuTempCommand + "", // cpuMemoryCommand + "", // cpuUtilCommand + "", // cpuThrottleReasonCmd + "", // cpuUptimeCommand + "", // gpuMemoryCommand + "", // ramUtilCommand + "", // gpuMemUsageCommand + "", // diskUsageCommand + "", // restartHardwareCommand + -1, // vendorFOV + Collections.emptyList()); // blacklistedResIndices } /** @@ -150,53 +100,4 @@ public class HardwareConfig { || gpuMemUsageCommand != "" || diskUsageCommand != ""; } - - @Override - public String toString() { - return "HardwareConfig [deviceName=" - + deviceName - + ", deviceLogoPath=" - + deviceLogoPath - + ", supportURL=" - + supportURL - + ", ledPins=" - + ledPins - + ", ledSetCommand=" - + ledSetCommand - + ", ledsCanDim=" - + ledsCanDim - + ", ledBrightnessRange=" - + ledBrightnessRange - + ", ledDimCommand=" - + ledDimCommand - + ", ledBlinkCommand=" - + ledBlinkCommand - + ", statusRGBPins=" - + statusRGBPins - + ", cpuTempCommand=" - + cpuTempCommand - + ", cpuMemoryCommand=" - + cpuMemoryCommand - + ", cpuUtilCommand=" - + cpuUtilCommand - + ", cpuThrottleReasonCmd=" - + cpuThrottleReasonCmd - + ", cpuUptimeCommand=" - + cpuUptimeCommand - + ", gpuMemoryCommand=" - + gpuMemoryCommand - + ", ramUtilCommand=" - + ramUtilCommand - + ", gpuMemUsageCommand=" - + gpuMemUsageCommand - + ", diskUsageCommand=" - + diskUsageCommand - + ", restartHardwareCommand=" - + restartHardwareCommand - + ", vendorFOV=" - + vendorFOV - + ", blacklistedResIndices=" - + blacklistedResIndices - + "]"; - } } diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java index 97b609f3d..50ec04576 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java @@ -49,7 +49,7 @@ public class UIPhotonConfiguration { NetworkManager.getInstance().networkingIsDisabled), new UILightingConfig( c.getHardwareSettings().ledBrightnessPercentage, - !c.getHardwareConfig().ledPins.isEmpty()), + !c.getHardwareConfig().ledPins().isEmpty()), new UIGeneralSettings( PhotonVersion.versionString, // TODO add support for other types of GPU accel @@ -57,9 +57,9 @@ public class UIPhotonConfiguration { MrCalJNILoader.getInstance().isLoaded(), NeuralNetworkModelManager.getInstance().getModels(), NeuralNetworkModelManager.getInstance().getSupportedBackends(), - c.getHardwareConfig().deviceName.isEmpty() + c.getHardwareConfig().deviceName().isEmpty() ? Platform.getHardwareModel() - : c.getHardwareConfig().deviceName, + : c.getHardwareConfig().deviceName(), Platform.getPlatformName()), c.getApriltagFieldLayout()), VisionSourceManager.getInstance().getVisionModules().stream() diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/CustomGPIO.java b/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/CustomGPIO.java index f67beb97c..36c9d28af 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/CustomGPIO.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/GPIO/CustomGPIO.java @@ -92,8 +92,8 @@ public class CustomGPIO extends GPIOBase { public static void setConfig(HardwareConfig config) { if (Platform.isRaspberryPi()) return; - commands.replace("setState", config.ledSetCommand); - commands.replace("dim", config.ledDimCommand); - commands.replace("blink", config.ledBlinkCommand); + commands.replace("setState", config.ledSetCommand()); + commands.replace("dim", config.ledDimCommand()); + commands.replace("blink", config.ledBlinkCommand()); } } diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/HardwareManager.java b/photon-core/src/main/java/org/photonvision/common/hardware/HardwareManager.java index 2c9a95615..e1a217031 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/HardwareManager.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/HardwareManager.java @@ -94,22 +94,22 @@ public class HardwareManager { } statusLED = - hardwareConfig.statusRGBPins.size() == 3 - ? new StatusLED(hardwareConfig.statusRGBPins) + hardwareConfig.statusRGBPins().size() == 3 + ? new StatusLED(hardwareConfig.statusRGBPins()) : null; if (statusLED != null) { TimedTaskManager.getInstance().addTask("StatusLEDUpdate", this::statusLEDUpdate, 150); } - var hasBrightnessRange = hardwareConfig.ledBrightnessRange.size() == 2; + var hasBrightnessRange = hardwareConfig.ledBrightnessRange().size() == 2; visionLED = - hardwareConfig.ledPins.isEmpty() + hardwareConfig.ledPins().isEmpty() ? null : new VisionLED( - hardwareConfig.ledPins, - hasBrightnessRange ? hardwareConfig.ledBrightnessRange.get(0) : 0, - hasBrightnessRange ? hardwareConfig.ledBrightnessRange.get(1) : 100, + hardwareConfig.ledPins(), + hasBrightnessRange ? hardwareConfig.ledBrightnessRange().get(0) : 0, + hasBrightnessRange ? hardwareConfig.ledBrightnessRange().get(1) : 100, pigpioSocket, ledModeState::set); @@ -158,7 +158,7 @@ public class HardwareManager { } } try { - return shellExec.executeBashCommand(hardwareConfig.restartHardwareCommand) == 0; + return shellExec.executeBashCommand(hardwareConfig.restartHardwareCommand()) == 0; } catch (IOException e) { logger.error("Could not restart device!", e); return false; diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/FileCmds.java b/photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/FileCmds.java index 7a2746903..bda20e0af 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/FileCmds.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/metrics/cmds/FileCmds.java @@ -22,17 +22,17 @@ import org.photonvision.common.configuration.HardwareConfig; public class FileCmds extends CmdBase { @Override public void initCmds(HardwareConfig config) { - cpuMemoryCommand = config.cpuMemoryCommand; - cpuTemperatureCommand = config.cpuTempCommand; - cpuUtilizationCommand = config.cpuUtilCommand; - cpuThrottleReasonCmd = config.cpuThrottleReasonCmd; - cpuUptimeCommand = config.cpuUptimeCommand; + cpuMemoryCommand = config.cpuMemoryCommand(); + cpuTemperatureCommand = config.cpuTempCommand(); + cpuUtilizationCommand = config.cpuUtilCommand(); + cpuThrottleReasonCmd = config.cpuThrottleReasonCmd(); + cpuUptimeCommand = config.cpuUptimeCommand(); - gpuMemoryCommand = config.gpuMemoryCommand; - gpuMemUsageCommand = config.gpuMemUsageCommand; + gpuMemoryCommand = config.gpuMemoryCommand(); + gpuMemUsageCommand = config.gpuMemUsageCommand(); - diskUsageCommand = config.diskUsageCommand; + diskUsageCommand = config.diskUsageCommand(); - ramUsageCommand = config.ramUtilCommand; + ramUsageCommand = config.ramUtilCommand(); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java index dcfea72c5..158b2bf43 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java @@ -308,7 +308,7 @@ public class GenericUSBCameraSettables extends VisionSourceSettables { // On vendor cameras, respect blacklisted indices var indexBlacklist = - ConfigManager.getInstance().getConfig().getHardwareConfig().blacklistedResIndices; + ConfigManager.getInstance().getConfig().getHardwareConfig().blacklistedResIndices(); for (int badIdx : indexBlacklist) { sortedList.remove(badIdx); } diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSource.java index 28449e9ac..6fa1223db 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSource.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/csi/LibcameraGpuSource.java @@ -100,7 +100,7 @@ public class LibcameraGpuSource extends VisionSource { @Override public boolean hasLEDs() { - return (ConfigManager.getInstance().getConfig().getHardwareConfig().ledPins.size() > 0); + return (ConfigManager.getInstance().getConfig().getHardwareConfig().ledPins().size() > 0); } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java index 34e9976ec..1c013fb8b 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModule.java @@ -160,7 +160,7 @@ public class VisionModule { // Set vendor FOV if (isVendorCamera()) { - var fov = ConfigManager.getInstance().getConfig().getHardwareConfig().vendorFOV; + var fov = ConfigManager.getInstance().getConfig().getHardwareConfig().vendorFOV(); logger.info("Setting FOV of vendor camera to " + fov); visionSource.getSettables().setFOV(fov); } diff --git a/photon-core/src/test/java/org/photonvision/hardware/HardwareConfigTest.java b/photon-core/src/test/java/org/photonvision/hardware/HardwareConfigTest.java index 9cd13e5dd..b9b088e84 100644 --- a/photon-core/src/test/java/org/photonvision/hardware/HardwareConfigTest.java +++ b/photon-core/src/test/java/org/photonvision/hardware/HardwareConfigTest.java @@ -34,11 +34,11 @@ public class HardwareConfigTest { System.out.println("Loading Hardware configs..."); var config = new ObjectMapper().readValue(TestUtils.getHardwareConfigJson(), HardwareConfig.class); - assertEquals(config.deviceName, "PhotonVision"); - assertEquals(config.deviceLogoPath, "photonvision.png"); - assertEquals(config.supportURL, "https://support.photonvision.com"); + assertEquals(config.deviceName(), "PhotonVision"); + assertEquals(config.deviceLogoPath(), "photonvision.png"); + assertEquals(config.supportURL(), "https://support.photonvision.com"); Assertions.assertArrayEquals( - config.ledPins.stream().mapToInt(i -> i).toArray(), new int[] {2, 13}); + config.ledPins().stream().mapToInt(i -> i).toArray(), new int[] {2, 13}); CustomGPIO.setConfig(config); } catch (IOException e) { From 20e2fe46ba7b0aeeac6a4561acb8a2a177ea7c7f Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 14 Apr 2025 18:43:53 -0400 Subject: [PATCH 10/42] Make NMDeviceInfo a record --- .../common/networking/NetworkManager.java | 11 ++++---- .../common/networking/NetworkUtils.java | 28 ++++++------------- 2 files changed, 15 insertions(+), 24 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/networking/NetworkManager.java b/photon-core/src/main/java/org/photonvision/common/networking/NetworkManager.java index f358c1cd8..0abf4c3e3 100644 --- a/photon-core/src/main/java/org/photonvision/common/networking/NetworkManager.java +++ b/photon-core/src/main/java/org/photonvision/common/networking/NetworkManager.java @@ -77,21 +77,22 @@ public class NetworkManager { var ethernetDevices = NetworkUtils.getAllWiredInterfaces(); for (NMDeviceInfo deviceInfo : ethernetDevices) { activeConnections.put( - deviceInfo.devName, NetworkUtils.getActiveConnection(deviceInfo.devName)); - monitorDevice(deviceInfo.devName, 5000); + deviceInfo.devName(), NetworkUtils.getActiveConnection(deviceInfo.devName())); + monitorDevice(deviceInfo.devName(), 5000); } var physicalDevices = NetworkUtils.getAllActiveWiredInterfaces(); var config = ConfigManager.getInstance().getConfig().getNetworkConfig(); - if (physicalDevices.stream().noneMatch(it -> (it.devName.equals(config.networkManagerIface)))) { + if (physicalDevices.stream() + .noneMatch(it -> (it.devName().equals(config.networkManagerIface)))) { try { // if the configured interface isn't in the list of available ones, select one that is var iFace = physicalDevices.stream().findFirst().orElseThrow(); logger.warn( "The configured interface doesn't match any available interface. Applying configuration to " - + iFace.devName); + + iFace.devName()); // update NetworkConfig with found interface - config.networkManagerIface = iFace.devName; + config.networkManagerIface = iFace.devName(); ConfigManager.getInstance().requestSave(); } catch (NoSuchElementException e) { // if there are no available interfaces, go with the one from settings diff --git a/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java b/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java index fc7b31735..f34d91f9a 100644 --- a/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java @@ -53,26 +53,16 @@ public class NetworkUtils { } } - public static class NMDeviceInfo { + /** + * Contains data about network devices retrieved from "nmcli device show" + * + * @param connName The human-readable name used by "nmcli con" + * @param devName The underlying device name, used by dhclient + * @param nmType The NetworkManager device type + */ + public static record NMDeviceInfo(String connName, String devName, NMType nmType) { public NMDeviceInfo(String c, String d, String type) { - connName = c; - devName = d; - nmType = NMType.typeForString(type); - } - - public final String connName; // Human-readable name used by "nmcli con" - public final String devName; // underlying device, used by dhclient - public final NMType nmType; - - @Override - public String toString() { - return "NMDeviceInfo [connName=" - + connName - + ", devName=" - + devName - + ", nmType=" - + nmType - + "]"; + this(c, d, NMType.typeForString(type)); } } From a42aed1e7f4141173b377cbdd768452b8a8885d8 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 30 Mar 2025 01:43:03 -0400 Subject: [PATCH 11/42] Make pipe params into records --- .../frame/provider/CpuImageProcessor.java | 2 +- .../provider/LibcameraGpuFrameProvider.java | 14 +-- .../vision/objects/Letterbox.java | 5 +- .../pipe/impl/AprilTagDetectionPipe.java | 15 ++- .../impl/AprilTagDetectionPipeParams.java | 62 ---------- .../pipe/impl/AprilTagPoseEstimatorPipe.java | 45 ++----- .../pipe/impl/ArucoPoseEstimatorPipe.java | 22 ++-- .../pipe/impl/Collect2dTargetsPipe.java | 42 ++----- .../vision/pipe/impl/CornerDetectionPipe.java | 36 ++---- .../vision/pipe/impl/Draw2dCrosshairPipe.java | 95 ++++++++------- .../vision/pipe/impl/DrawCalibrationPipe.java | 15 +-- .../vision/pipe/impl/FilterContoursPipe.java | 67 +++-------- .../pipe/impl/FilterObjectDetectionsPipe.java | 45 ++----- .../vision/pipe/impl/FilterShapesPipe.java | 48 +++----- .../pipe/impl/FindBoardCornersPipe.java | 112 +++++------------- .../vision/pipe/impl/FindCirclesPipe.java | 78 ++++++------ .../vision/pipe/impl/FindPolygonPipe.java | 16 ++- .../vision/pipe/impl/GroupContoursPipe.java | 28 +---- .../vision/pipe/impl/HSVPipe.java | 42 ++----- .../vision/pipe/impl/MultiTargetPNPPipe.java | 34 ++---- .../pipe/impl/NeuralNetworkPipeResult.java | 12 +- .../vision/pipe/impl/ObjectDetectionPipe.java | 15 +-- .../vision/pipe/impl/ResizeImagePipe.java | 16 +-- .../vision/pipe/impl/RotateImagePipe.java | 12 +- .../vision/pipe/impl/SolvePNPPipe.java | 30 ++--- .../vision/pipe/impl/SortContoursPipe.java | 37 ++---- .../vision/pipe/impl/SpeckleRejectPipe.java | 14 +-- .../vision/pipeline/AprilTagPipeline.java | 2 +- .../pipeline/ObjectDetectionPipeline.java | 7 +- .../vision/target/PotentialTarget.java | 6 +- 30 files changed, 292 insertions(+), 682 deletions(-) delete mode 100644 photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java index 0ceb96c19..1a9e13e60 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/CpuImageProcessor.java @@ -100,7 +100,7 @@ public abstract class CpuImageProcessor extends FrameProvider { m_processType, input.captureTimestamp, input.staticProps != null - ? input.staticProps.rotate(m_rImagePipe.getParams().rotation) + ? input.staticProps.rotate(m_rImagePipe.getParams().rotation()) : input.staticProps); } diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java b/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java index 6a354257b..2fa04fba2 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/provider/LibcameraGpuFrameProvider.java @@ -121,13 +121,13 @@ public class LibcameraGpuFrameProvider extends FrameProvider { public void requestHsvSettings(HSVParams params) { LibCameraJNI.setThresholds( settables.r_ptr, - params.getHsvLower().val[0] / 180.0, - params.getHsvLower().val[1] / 255.0, - params.getHsvLower().val[2] / 255.0, - params.getHsvUpper().val[0] / 180.0, - params.getHsvUpper().val[1] / 255.0, - params.getHsvUpper().val[2] / 255.0, - params.getHueInverted()); + params.hsvLower().val[0] / 180.0, + params.hsvLower().val[1] / 255.0, + params.hsvLower().val[2] / 255.0, + params.hsvUpper().val[0] / 180.0, + params.hsvUpper().val[1] / 255.0, + params.hsvUpper().val[2] / 255.0, + params.hueInverted()); } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/objects/Letterbox.java b/photon-core/src/main/java/org/photonvision/vision/objects/Letterbox.java index bbbae5269..51cf48915 100644 --- a/photon-core/src/main/java/org/photonvision/vision/objects/Letterbox.java +++ b/photon-core/src/main/java/org/photonvision/vision/objects/Letterbox.java @@ -90,14 +90,15 @@ public class Letterbox { for (var t : unscaled) { var scale = 1.0 / this.scale; - var boundingBox = t.bbox; + var boundingBox = t.bbox(); double x = (boundingBox.x - this.dx) * scale; double y = (boundingBox.y - this.dy) * scale; double width = boundingBox.width * scale; double height = boundingBox.height * scale; ret.add( - new NeuralNetworkPipeResult(new Rect2d(x, y, width, height), t.classIdx, t.confidence)); + new NeuralNetworkPipeResult( + new Rect2d(x, y, width, height), t.classIdx(), t.confidence())); } return ret; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipe.java index e4737ce95..01e237c41 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipe.java @@ -20,12 +20,14 @@ package org.photonvision.vision.pipe.impl; import edu.wpi.first.apriltag.AprilTagDetection; import edu.wpi.first.apriltag.AprilTagDetector; import java.util.List; +import org.photonvision.vision.apriltag.AprilTagFamily; import org.photonvision.vision.opencv.CVMat; import org.photonvision.vision.opencv.Releasable; import org.photonvision.vision.pipe.CVPipe; public class AprilTagDetectionPipe - extends CVPipe, AprilTagDetectionPipeParams> + extends CVPipe< + CVMat, List, AprilTagDetectionPipe.AprilTagDetectionPipeParams> implements Releasable { private AprilTagDetector m_detector = new AprilTagDetector(); @@ -58,11 +60,11 @@ public class AprilTagDetectionPipe @Override public void setParams(AprilTagDetectionPipeParams newParams) { if (this.params == null || !this.params.equals(newParams)) { - m_detector.setConfig(newParams.detectorParams); - m_detector.setQuadThresholdParameters(newParams.quadParams); + m_detector.setConfig(newParams.detectorParams()); + m_detector.setQuadThresholdParameters(newParams.quadParams()); m_detector.clearFamilies(); - m_detector.addFamily(newParams.family.getNativeName()); + m_detector.addFamily(newParams.family().getNativeName()); } super.setParams(newParams); @@ -73,4 +75,9 @@ public class AprilTagDetectionPipe m_detector.close(); m_detector = null; } + + public static record AprilTagDetectionPipeParams( + AprilTagFamily family, + AprilTagDetector.Config detectorParams, + AprilTagDetector.QuadThresholdParameters quadParams) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java deleted file mode 100644 index 773a0d299..000000000 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagDetectionPipeParams.java +++ /dev/null @@ -1,62 +0,0 @@ -/* - * Copyright (C) Photon Vision. - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - */ - -package org.photonvision.vision.pipe.impl; - -import edu.wpi.first.apriltag.AprilTagDetector; -import org.photonvision.vision.apriltag.AprilTagFamily; - -public class AprilTagDetectionPipeParams { - public final AprilTagFamily family; - public final AprilTagDetector.Config detectorParams; - public final AprilTagDetector.QuadThresholdParameters quadParams; - - public AprilTagDetectionPipeParams( - AprilTagFamily tagFamily, - AprilTagDetector.Config config, - AprilTagDetector.QuadThresholdParameters quadParams) { - this.family = tagFamily; - this.detectorParams = config; - this.quadParams = quadParams; - } - - @Override - public int hashCode() { - final int prime = 31; - int result = 1; - result = prime * result + ((family == null) ? 0 : family.hashCode()); - result = prime * result + ((detectorParams == null) ? 0 : detectorParams.hashCode()); - result = prime * result + ((quadParams == null) ? 0 : quadParams.hashCode()); - return result; - } - - @Override - public boolean equals(Object obj) { - if (this == obj) return true; - if (obj == null) return false; - if (getClass() != obj.getClass()) return false; - AprilTagDetectionPipeParams other = (AprilTagDetectionPipeParams) obj; - if (family != other.family) return false; - if (detectorParams == null) { - if (other.detectorParams != null) return false; - } else if (!detectorParams.equals(other.detectorParams)) return false; - if (quadParams == null) { - if (other.quadParams != null) return false; - } else if (!quadParams.equals(other.quadParams)) return false; - return true; - } -} diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java index 3ddc2f3de..f2c713799 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/AprilTagPoseEstimatorPipe.java @@ -57,8 +57,8 @@ public class AprilTagPoseEstimatorPipe Calib3d.undistortImagePoints( temp, temp, - params.calibration.getCameraIntrinsicsMat(), - params.calibration.getDistCoeffsMat()); + params.calibration().getCameraIntrinsicsMat(), + params.calibration().getDistCoeffsMat()); // Save out undistorted corners corners = temp.toArray(); @@ -82,13 +82,13 @@ public class AprilTagPoseEstimatorPipe in.getCenterY(), fixedCorners); - return m_poseEstimator.estimateOrthogonalIteration(corrected, params.nIters); + return m_poseEstimator.estimateOrthogonalIteration(corrected, params.nIters()); } @Override public void setParams(AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams newParams) { - if (this.params == null || !this.params.equals(newParams)) { - m_poseEstimator.setConfig(newParams.config); + if (this.params == null || !this.params.config().equals(newParams.config())) { + m_poseEstimator.setConfig(newParams.config()); } super.setParams(newParams); @@ -99,37 +99,6 @@ public class AprilTagPoseEstimatorPipe temp.release(); } - public static class AprilTagPoseEstimatorPipeParams { - final AprilTagPoseEstimator.Config config; - final CameraCalibrationCoefficients calibration; - final int nIters; - - public AprilTagPoseEstimatorPipeParams( - Config config, CameraCalibrationCoefficients cal, int nIters) { - this.config = config; - this.nIters = nIters; - this.calibration = cal; - } - - @Override - public int hashCode() { - final int prime = 31; - int result = 1; - result = prime * result + ((config == null) ? 0 : config.hashCode()); - result = prime * result + nIters; - return result; - } - - @Override - public boolean equals(Object obj) { - if (this == obj) return true; - if (obj == null) return false; - if (getClass() != obj.getClass()) return false; - AprilTagPoseEstimatorPipeParams other = (AprilTagPoseEstimatorPipeParams) obj; - if (config == null) { - if (other.config != null) return false; - } else if (!config.equals(other.config)) return false; - return nIters == other.nIters; - } - } + public static record AprilTagPoseEstimatorPipeParams( + Config config, CameraCalibrationCoefficients calibration, int nIters) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoPoseEstimatorPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoPoseEstimatorPipe.java index ff9a89319..f036bfbfd 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoPoseEstimatorPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoPoseEstimatorPipe.java @@ -86,8 +86,8 @@ public class ArucoPoseEstimatorPipe Calib3d.solvePnPGeneric( objectPoints, imagePoints, - params.calibration.getCameraIntrinsicsMat(), - params.calibration.getDistCoeffsMat(), + params.calibration().getCameraIntrinsicsMat(), + params.calibration().getDistCoeffsMat(), rvecs, tvecs, false, @@ -120,8 +120,8 @@ public class ArucoPoseEstimatorPipe @Override public void setParams(ArucoPoseEstimatorPipe.ArucoPoseEstimatorPipeParams newParams) { // exact equality check OK here, the number shouldn't change - if (this.params == null || this.params.tagSize != newParams.tagSize) { - var tagSize = newParams.tagSize; + if (this.params == null || this.params.tagSize() != newParams.tagSize()) { + var tagSize = newParams.tagSize(); // This order is relevant for SOLVEPNP_IPPE_SQUARE // The expected 2d correspondences with a tag facing the camera would be (BR, BL, TL, TR) @@ -147,15 +147,7 @@ public class ArucoPoseEstimatorPipe reprojectionErrors.release(); } - public static class ArucoPoseEstimatorPipeParams { - final CameraCalibrationCoefficients calibration; - final double tagSize; - - // object vertices defined by tag size - - public ArucoPoseEstimatorPipeParams(CameraCalibrationCoefficients cal, double tagSize) { - this.calibration = cal; - this.tagSize = tagSize; - } - } + // object vertices defined by tag size + public static record ArucoPoseEstimatorPipeParams( + CameraCalibrationCoefficients calibration, double tagSize) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Collect2dTargetsPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Collect2dTargetsPipe.java index d5e4bda99..836e04fc7 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Collect2dTargetsPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Collect2dTargetsPipe.java @@ -41,12 +41,12 @@ public class Collect2dTargetsPipe var calculationParams = new TrackedTarget.TargetCalculationParameters( - params.targetOrientation == TargetOrientation.Landscape, - params.targetOffsetPointEdge, - params.robotOffsetPointMode, - params.robotOffsetSinglePoint, - params.dualOffsetValues, - params.frameStaticProperties); + params.targetOrientation() == TargetOrientation.Landscape, + params.targetOffsetPointEdge(), + params.robotOffsetPointMode(), + params.robotOffsetSinglePoint(), + params.dualOffsetValues(), + params.frameStaticProperties()); for (PotentialTarget target : in) { targets.add(new TrackedTarget(target, calculationParams, target.shape)); @@ -55,27 +55,11 @@ public class Collect2dTargetsPipe return targets; } - public static class Collect2dTargetsParams { - private final RobotOffsetPointMode robotOffsetPointMode; - private final Point robotOffsetSinglePoint; - private final DualOffsetValues dualOffsetValues; - private final TargetOffsetPointEdge targetOffsetPointEdge; - private final TargetOrientation targetOrientation; - private final FrameStaticProperties frameStaticProperties; - - public Collect2dTargetsParams( - RobotOffsetPointMode robotOffsetPointMode, - Point robotOffsetSinglePoint, - DualOffsetValues dualOffsetValues, - TargetOffsetPointEdge targetOffsetPointEdge, - TargetOrientation orientation, - FrameStaticProperties frameStaticProperties) { - this.frameStaticProperties = frameStaticProperties; - this.robotOffsetPointMode = robotOffsetPointMode; - this.robotOffsetSinglePoint = robotOffsetSinglePoint; - this.dualOffsetValues = dualOffsetValues; - this.targetOffsetPointEdge = targetOffsetPointEdge; - targetOrientation = orientation; - } - } + public static record Collect2dTargetsParams( + RobotOffsetPointMode robotOffsetPointMode, + Point robotOffsetSinglePoint, + DualOffsetValues dualOffsetValues, + TargetOffsetPointEdge targetOffsetPointEdge, + TargetOrientation targetOrientation, + FrameStaticProperties frameStaticProperties) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java index 660a11203..def6aeda1 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java @@ -121,12 +121,12 @@ public class CornerDetectionPipe var isOpen = !convexHull && target.hasSubContours(); var peri = Imgproc.arcLength(targetContour, true); Imgproc.approxPolyDP( - targetContour, polyOutput, params.accuracyPercentage / 600.0 * peri, !isOpen); + targetContour, polyOutput, params.accuracyPercentage() / 600.0 * peri, !isOpen); // we must have at least 4 corners for this strategy to work. // If we are looking for an exact side count that is handled here too. var pointList = new ArrayList<>(polyOutput.toList()); - if (pointList.size() < 4 || (params.exactSideCount && params.sideCount != pointList.size())) + if (pointList.size() < 4 || (params.exactSideCount() && params.sideCount() != pointList.size())) return null; target.setApproximateBoundingPolygon(polyOutput); @@ -177,29 +177,15 @@ public class CornerDetectionPipe return List.of(bl, br, tr, tl); } - public static class CornerDetectionPipeParameters { - private final DetectionStrategy cornerDetectionStrategy; - - private final boolean calculateConvexHulls; - private final boolean exactSideCount; - private final int sideCount; - - /** This number can be changed to change how "accurate" our approximate polygon must be. */ - private final double accuracyPercentage; - - public CornerDetectionPipeParameters( - DetectionStrategy cornerDetectionStrategy, - boolean calculateConvexHulls, - boolean exactSideCount, - int sideCount, - double accuracyPercentage) { - this.cornerDetectionStrategy = cornerDetectionStrategy; - this.calculateConvexHulls = calculateConvexHulls; - this.exactSideCount = exactSideCount; - this.sideCount = sideCount; - this.accuracyPercentage = accuracyPercentage; - } - } + /** + * @param accuracyPercentage Represents how "accurate" our approximate polygon must be. + */ + public static record CornerDetectionPipeParameters( + DetectionStrategy cornerDetectionStrategy, + boolean calculateConvexHulls, + boolean exactSideCount, + int sideCount, + double accuracyPercentage) {} public enum DetectionStrategy { APPROX_POLY_DP_AND_EXTREME_CORNERS diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java index fb22c6615..b7a3335af 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java @@ -38,21 +38,22 @@ public class Draw2dCrosshairPipe Pair>, Draw2dCrosshairPipe.Draw2dCrosshairParams> { @Override protected Void process(Pair> in) { - if (!params.shouldDraw) return null; + if (!params.shouldDraw()) return null; var image = in.getLeft(); - if (params.showCrosshair) { - double x = params.frameStaticProperties.centerX; - double y = params.frameStaticProperties.centerY; - double scale = params.frameStaticProperties.imageWidth / (double) params.divisor.value / 32.0; + if (params.showCrosshair()) { + double x = params.frameStaticProperties().centerX; + double y = params.frameStaticProperties().centerY; + double scale = + params.frameStaticProperties().imageWidth / (double) params.divisor().value / 32.0; - switch (params.robotOffsetPointMode) { + switch (params.robotOffsetPointMode()) { case None -> {} case Single -> { - if (params.singleOffsetPoint.x != 0 && params.singleOffsetPoint.y != 0) { - x = params.singleOffsetPoint.x; - y = params.singleOffsetPoint.y; + if (params.singleOffsetPoint().x != 0 && params.singleOffsetPoint().y != 0) { + x = params.singleOffsetPoint().x; + y = params.singleOffsetPoint().y; } } case Dual -> { @@ -61,7 +62,7 @@ public class Draw2dCrosshairPipe if (target != null) { var area = target.getArea(); var offsetCrosshair = - TargetCalculations.calculateDualOffsetCrosshair(params.dualOffsetValues, area); + TargetCalculations.calculateDualOffsetCrosshair(params.dualOffsetValues(), area); x = offsetCrosshair.x; y = offsetCrosshair.y; } @@ -69,45 +70,30 @@ public class Draw2dCrosshairPipe } } - x /= (double) params.divisor.value; - y /= (double) params.divisor.value; + x /= (double) params.divisor().value; + y /= (double) params.divisor().value; Point xMax = new Point(x + scale, y); Point xMin = new Point(x - scale, y); Point yMax = new Point(x, y + scale); Point yMin = new Point(x, y - scale); - Imgproc.line(image, xMax, xMin, ColorHelper.colorToScalar(params.crosshairColor)); - Imgproc.line(image, yMax, yMin, ColorHelper.colorToScalar(params.crosshairColor)); + Imgproc.line(image, xMax, xMin, ColorHelper.colorToScalar(params.crosshairColor())); + Imgproc.line(image, yMax, yMin, ColorHelper.colorToScalar(params.crosshairColor())); } return null; } - public static class Draw2dCrosshairParams { - public boolean showCrosshair = true; - public Color crosshairColor = Color.GREEN; - - public final boolean shouldDraw; - public final FrameStaticProperties frameStaticProperties; - public final ImageRotationMode rotMode; - public final RobotOffsetPointMode robotOffsetPointMode; - public final Point singleOffsetPoint; - public final DualOffsetValues dualOffsetValues; - private final FrameDivisor divisor; - - public Draw2dCrosshairParams( - FrameStaticProperties frameStaticProperties, - FrameDivisor divisor, - ImageRotationMode rotMode) { - shouldDraw = true; - this.frameStaticProperties = frameStaticProperties; - this.rotMode = rotMode; - robotOffsetPointMode = RobotOffsetPointMode.None; - singleOffsetPoint = new Point(); - dualOffsetValues = new DualOffsetValues(); - this.divisor = divisor; - } - + public static record Draw2dCrosshairParams( + boolean shouldDraw, + RobotOffsetPointMode robotOffsetPointMode, + Point singleOffsetPoint, + DualOffsetValues dualOffsetValues, + FrameStaticProperties frameStaticProperties, + FrameDivisor divisor, + ImageRotationMode rotMode, + boolean showCrosshair, + Color crosshairColor) { public Draw2dCrosshairParams( boolean shouldDraw, RobotOffsetPointMode robotOffsetPointMode, @@ -116,13 +102,30 @@ public class Draw2dCrosshairPipe FrameStaticProperties frameStaticProperties, FrameDivisor divisor, ImageRotationMode rotMode) { - this.shouldDraw = shouldDraw; - this.frameStaticProperties = frameStaticProperties; - this.robotOffsetPointMode = robotOffsetPointMode; - this.singleOffsetPoint = singleOffsetPoint; - this.dualOffsetValues = dualOffsetValues; - this.divisor = divisor; - this.rotMode = rotMode; + this( + shouldDraw, + robotOffsetPointMode, + singleOffsetPoint, + dualOffsetValues, + frameStaticProperties, + divisor, + rotMode, + true, + Color.GREEN); + } + + public Draw2dCrosshairParams( + FrameStaticProperties frameStaticProperties, + FrameDivisor divisor, + ImageRotationMode rotMode) { + this( + true, + RobotOffsetPointMode.None, + new Point(), + new DualOffsetValues(), + frameStaticProperties, + divisor, + rotMode); } } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java index 925000aa7..7005d66e8 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java @@ -43,7 +43,7 @@ public class DrawCalibrationPipe @Override protected Void process(Pair> in) { - if (!params.drawAllSnapshots) return null; + if (!params.drawAllSnapshots()) return null; var image = in.getLeft(); @@ -65,7 +65,8 @@ public class DrawCalibrationPipe c = new Point( - c.x / params.divisor.value.doubleValue(), c.y / params.divisor.value.doubleValue()); + c.x / params.divisor().value.doubleValue(), + c.y / params.divisor().value.doubleValue()); var r2 = r / Math.sqrt(2); var color = chessboardColors[i % chessboardColors.length]; @@ -82,13 +83,5 @@ public class DrawCalibrationPipe return null; } - public static class DrawCalibrationPipeParams { - private final FrameDivisor divisor; - public boolean drawAllSnapshots; - - public DrawCalibrationPipeParams(FrameDivisor divisor, boolean drawSnapshots) { - this.divisor = divisor; - this.drawAllSnapshots = drawSnapshots; - } - } + public static record DrawCalibrationPipeParams(FrameDivisor divisor, boolean drawAllSnapshots) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java index 1e7616c44..12f2ac913 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java @@ -38,7 +38,7 @@ public class FilterContoursPipe } // we need the whole list for outlier rejection - rejectOutliers(m_filteredContours, params.xTol, params.yTol); + rejectOutliers(m_filteredContours, params.xTol(), params.yTol()); return m_filteredContours; } @@ -81,66 +81,31 @@ public class FilterContoursPipe // Area Filtering. double areaPercentage = - minAreaRect.size.area() / params.getFrameStaticProperties().imageArea * 100.0; - double minAreaPercentage = params.getArea().getFirst(); - double maxAreaPercentage = params.getArea().getSecond(); + minAreaRect.size.area() / params.frameStaticProperties().imageArea * 100.0; + double minAreaPercentage = params.area().getFirst(); + double maxAreaPercentage = params.area().getSecond(); if (areaPercentage < minAreaPercentage || areaPercentage > maxAreaPercentage) return; // Fullness Filtering. double contourArea = contour.getArea(); - double minFullness = params.getFullness().getFirst() * minAreaRect.size.area() / 100.0; - double maxFullness = params.getFullness().getSecond() * minAreaRect.size.area() / 100.0; + double minFullness = params.fullness().getFirst() * minAreaRect.size.area() / 100.0; + double maxFullness = params.fullness().getSecond() * minAreaRect.size.area() / 100.0; if (contourArea <= minFullness || contourArea >= maxFullness) return; // Aspect Ratio Filtering. double aspectRatio = - TargetCalculations.getAspectRatio(contour.getMinAreaRect(), params.isLandscape); - if (aspectRatio < params.getRatio().getFirst() || aspectRatio > params.getRatio().getSecond()) - return; + TargetCalculations.getAspectRatio(contour.getMinAreaRect(), params.isLandscape()); + if (aspectRatio < params.ratio().getFirst() || aspectRatio > params.ratio().getSecond()) return; m_filteredContours.add(contour); } - public static class FilterContoursParams { - private final DoubleCouple m_area; - private final DoubleCouple m_ratio; - private final DoubleCouple m_fullness; - private final FrameStaticProperties m_frameStaticProperties; - private final double xTol; // IQR tolerance for x - private final double yTol; // IQR tolerance for x - public final boolean isLandscape; - - public FilterContoursParams( - DoubleCouple area, - DoubleCouple ratio, - DoubleCouple extent, - FrameStaticProperties camProperties, - double xTol, - double yTol, - boolean isLandscape) { - this.m_area = area; - this.m_ratio = ratio; - this.m_fullness = extent; - this.m_frameStaticProperties = camProperties; - this.xTol = xTol; - this.yTol = yTol; - this.isLandscape = isLandscape; - } - - public DoubleCouple getArea() { - return m_area; - } - - public DoubleCouple getRatio() { - return m_ratio; - } - - public DoubleCouple getFullness() { - return m_fullness; - } - - public FrameStaticProperties getFrameStaticProperties() { - return m_frameStaticProperties; - } - } + public static record FilterContoursParams( + DoubleCouple area, + DoubleCouple ratio, + DoubleCouple fullness, + FrameStaticProperties frameStaticProperties, + double xTol, // IQR tolerance for x + double yTol, // IQR tolerance for y + boolean isLandscape) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterObjectDetectionsPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterObjectDetectionsPipe.java index d22556668..03479dc51 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterObjectDetectionsPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterObjectDetectionsPipe.java @@ -41,49 +41,24 @@ public class FilterObjectDetectionsPipe } private void filterContour(NeuralNetworkPipeResult contour) { - var boc = contour.bbox; + var boc = contour.bbox(); // Area filtering - double areaPercentage = boc.area() / params.getFrameStaticProperties().imageArea * 100.0; - double minAreaPercentage = params.getArea().getFirst(); - double maxAreaPercentage = params.getArea().getSecond(); + double areaPercentage = boc.area() / params.frameStaticProperties().imageArea * 100.0; + double minAreaPercentage = params.area().getFirst(); + double maxAreaPercentage = params.area().getSecond(); if (areaPercentage < minAreaPercentage || areaPercentage > maxAreaPercentage) return; // Aspect ratio filtering; much simpler since always axis-aligned double aspectRatio = boc.width / boc.height; - if (aspectRatio < params.getRatio().getFirst() || aspectRatio > params.getRatio().getSecond()) - return; + if (aspectRatio < params.ratio().getFirst() || aspectRatio > params.ratio().getSecond()) return; m_filteredContours.add(contour); } - public static class FilterContoursParams { - private final DoubleCouple m_area; - private final DoubleCouple m_ratio; - private final FrameStaticProperties m_frameStaticProperties; - public final boolean isLandscape; - - public FilterContoursParams( - DoubleCouple area, - DoubleCouple ratio, - FrameStaticProperties camProperties, - boolean isLandscape) { - this.m_area = area; - this.m_ratio = ratio; - this.m_frameStaticProperties = camProperties; - this.isLandscape = isLandscape; - } - - public DoubleCouple getArea() { - return m_area; - } - - public DoubleCouple getRatio() { - return m_ratio; - } - - public FrameStaticProperties getFrameStaticProperties() { - return m_frameStaticProperties; - } - } + public static record FilterContoursParams( + DoubleCouple area, + DoubleCouple ratio, + FrameStaticProperties frameStaticProperties, + boolean isLandscape) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterShapesPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterShapesPipe.java index 1802d6971..4f2489a92 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterShapesPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterShapesPipe.java @@ -48,40 +48,20 @@ public class FilterShapesPipe } private boolean shouldRemove(CVShape shape) { - return shape.shape != params.desiredShape - || shape.contour.getArea() / params.getFrameStaticProperties().imageArea * 100.0 - > params.maxArea - || shape.contour.getArea() / params.getFrameStaticProperties().imageArea * 100.0 - < params.minArea - || shape.contour.getPerimeter() > params.maxPeri - || shape.contour.getPerimeter() < params.minPeri; + return shape.shape != params.desiredShape() + || shape.contour.getArea() / params.frameStaticProperties().imageArea * 100.0 + > params.maxArea() + || shape.contour.getArea() / params.frameStaticProperties().imageArea * 100.0 + < params.minArea() + || shape.contour.getPerimeter() > params.maxPeri() + || shape.contour.getPerimeter() < params.minPeri(); } - public static class FilterShapesPipeParams { - private final ContourShape desiredShape; - private final FrameStaticProperties frameStaticProperties; - private final double minArea; - private final double maxArea; - private final double minPeri; - private final double maxPeri; - - public FilterShapesPipeParams( - ContourShape desiredShape, - double minArea, - double maxArea, - double minPeri, - double maxPeri, - FrameStaticProperties frameStaticProperties) { - this.desiredShape = desiredShape; - this.minArea = minArea; - this.maxArea = maxArea; - this.minPeri = minPeri; - this.maxPeri = maxPeri; - this.frameStaticProperties = frameStaticProperties; - } - - public FrameStaticProperties getFrameStaticProperties() { - return frameStaticProperties; - } - } + public static record FilterShapesPipeParams( + ContourShape desiredShape, + double minArea, + double maxArea, + double minPeri, + double maxPeri, + FrameStaticProperties frameStaticProperties) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java index a85c57a3e..93a5511bb 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java @@ -91,30 +91,30 @@ public class FindBoardCornersPipe * number of corners. */ this.patternSize = - params.type == UICalibrationData.BoardType.CHESSBOARD - ? new Size(params.boardWidth - 1, params.boardHeight - 1) - : new Size(params.boardWidth, params.boardHeight); + params.type() == UICalibrationData.BoardType.CHESSBOARD + ? new Size(params.boardWidth() - 1, params.boardHeight() - 1) + : new Size(params.boardWidth(), params.boardHeight()); // Chessboard and dot board have different 3D points to project as a dot board // has alternating // dots per column - if (params.type == UICalibrationData.BoardType.CHESSBOARD) { + if (params.type() == UICalibrationData.BoardType.CHESSBOARD) { // Here we can create an NxN grid since a chessboard is rectangular for (int heightIdx = 0; heightIdx < patternSize.height; heightIdx++) { for (int widthIdx = 0; widthIdx < patternSize.width; widthIdx++) { - double boardYCoord = heightIdx * params.gridSize; - double boardXCoord = widthIdx * params.gridSize; + double boardYCoord = heightIdx * params.gridSize(); + double boardXCoord = widthIdx * params.gridSize(); objectPoints.push_back(new MatOfPoint3f(new Point3(boardXCoord, boardYCoord, 0.0))); } } - } else if (params.type == UICalibrationData.BoardType.CHARUCOBOARD) { + } else if (params.type() == UICalibrationData.BoardType.CHARUCOBOARD) { board = new CharucoBoard( - new Size(params.boardWidth, params.boardHeight), - (float) params.gridSize, - (float) params.markerSize, - Objdetect.getPredefinedDictionary(params.tagFamily.getValue())); - board.setLegacyPattern(params.useOldPattern); + new Size(params.boardWidth(), params.boardHeight()), + (float) params.gridSize(), + (float) params.markerSize(), + Objdetect.getPredefinedDictionary(params.tagFamily().getValue())); + board.setLegacyPattern(params.useOldPattern()); detector = new CharucoDetector(board); detector.getDetectorParameters().set_adaptiveThreshConstant(10); detector.getDetectorParameters().set_adaptiveThreshWinSizeMin(11); @@ -122,7 +122,7 @@ public class FindBoardCornersPipe detector.getDetectorParameters().set_adaptiveThreshWinSizeMax(91); } else { - logger.error("Can't create pattern for unknown board type " + params.type); + logger.error("Can't create pattern for unknown board type " + params.type()); } } @@ -145,7 +145,7 @@ public class FindBoardCornersPipe * @return */ private double getFindCornersScaleFactor(Mat inFrame) { - return 1.0 / params.divisor.value; + return 1.0 / params.divisor().value; } /** @@ -185,8 +185,8 @@ public class FindBoardCornersPipe * @return the size to scale the input mat to */ private Size getFindCornersImgSize(Mat in) { - int width = in.cols() / params.divisor.value; - int height = in.rows() / params.divisor.value; + int width = in.cols() / params.divisor().value; + int height = in.rows() / params.divisor().value; return new Size(width, height); } @@ -222,7 +222,7 @@ public class FindBoardCornersPipe */ private Size getWindowSize(MatOfPoint2f inPoints) { double windowHalfWidth = 11; // Dot board uses fixed-size window half-width - if (params.type == UICalibrationData.BoardType.CHESSBOARD) { + if (params.type() == UICalibrationData.BoardType.CHESSBOARD) { // Chessboard uses a dynamic sized window based on how far apart the corners are windowHalfWidth = Math.floor(getApproxMinSpacing(inPoints) * 0.50); windowHalfWidth = Math.max(1, windowHalfWidth); @@ -254,7 +254,7 @@ public class FindBoardCornersPipe // Get the size of the inFrame this.imageSize = new Size(inFrame.width(), inFrame.height()); - if (params.type == UICalibrationData.BoardType.CHARUCOBOARD) { + if (params.type() == UICalibrationData.BoardType.CHARUCOBOARD) { Mat objPoints = new Mat(); // 3 dimensional currentObjectPoints, the physical target ChArUco Board Mat imgPoints = @@ -295,10 +295,10 @@ public class FindBoardCornersPipe // for each backend { Point[] boardCorners = - new Point[(this.params.boardHeight - 1) * (this.params.boardWidth - 1)]; + new Point[(this.params.boardHeight() - 1) * (this.params.boardWidth() - 1)]; Point3[] objectPoints = - new Point3[(this.params.boardHeight - 1) * (this.params.boardWidth - 1)]; - levels = new float[(this.params.boardHeight - 1) * (this.params.boardWidth - 1)]; + new Point3[(this.params.boardHeight() - 1) * (this.params.boardWidth() - 1)]; + levels = new float[(this.params.boardHeight() - 1) * (this.params.boardWidth() - 1)]; for (int i = 0; i < detectedIds.total(); i++) { int id = (int) detectedIds.get(i, 0)[0]; @@ -329,7 +329,7 @@ public class FindBoardCornersPipe // this since we // don't need that copy. See: // https://github.com/opencv/opencv/blob/a8ec6586118c3f8e8f48549a85f2da7a5b78bcc9/modules/imgproc/src/resize.cpp#L4185 - if (params.divisor != FrameDivisor.NONE) { + if (params.divisor() != FrameDivisor.NONE) { Imgproc.resize(inFrame, smallerInFrame, getFindCornersImgSize(inFrame)); } else { smallerInFrame = inFrame; @@ -371,65 +371,15 @@ public class FindBoardCornersPipe return new FindBoardCornersPipeResult(inFrame.size(), objPts, outBoardCorners, outLevels); } - public static class FindCornersPipeParams { - final int boardHeight; - final int boardWidth; - final UICalibrationData.BoardType type; - final double gridSize; - final double markerSize; - final FrameDivisor divisor; - final UICalibrationData.TagFamily tagFamily; - final boolean useOldPattern; - - public FindCornersPipeParams( - int boardHeight, - int boardWidth, - UICalibrationData.BoardType type, - UICalibrationData.TagFamily tagFamily, - double gridSize, - double markerSize, - FrameDivisor divisor, - boolean useOldPattern) { - this.boardHeight = boardHeight; - this.boardWidth = boardWidth; - this.tagFamily = tagFamily; - this.type = type; - this.gridSize = gridSize; // meter - this.markerSize = markerSize; // meter - this.divisor = divisor; - this.useOldPattern = useOldPattern; - } - - @Override - public int hashCode() { - final int prime = 31; - int result = 1; - result = prime * result + boardHeight; - result = prime * result + boardWidth; - result = prime * result + ((type == null) ? 0 : type.hashCode()); - long temp; - temp = Double.doubleToLongBits(gridSize); - result = prime * result + (int) (temp ^ (temp >>> 32)); - result = prime * result + ((divisor == null) ? 0 : divisor.hashCode()); - return result; - } - - @Override - public boolean equals(Object obj) { - if (this == obj) return true; - if (obj == null) return false; - if (getClass() != obj.getClass()) return false; - FindCornersPipeParams other = (FindCornersPipeParams) obj; - if (boardHeight != other.boardHeight) return false; - if (boardWidth != other.boardWidth) return false; - if (tagFamily != other.tagFamily) return false; - if (useOldPattern != other.useOldPattern) return false; - if (type != other.type) return false; - if (Double.doubleToLongBits(gridSize) != Double.doubleToLongBits(other.gridSize)) - return false; - return divisor == other.divisor; - } - } + public static record FindCornersPipeParams( + int boardHeight, + int boardWidth, + UICalibrationData.BoardType type, + UICalibrationData.TagFamily tagFamily, + double gridSize, // meters + double markerSize, // meters + FrameDivisor divisor, + boolean useOldPattern) {} public static class FindBoardCornersPipeResult implements Releasable { public Size size; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java index 07ec9ecd8..6631a032e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java @@ -49,9 +49,9 @@ public class FindCirclesPipe circles.release(); List output = new ArrayList<>(); - var diag = params.diagonalLengthPx; - var minRadius = (int) (params.minRadius * diag / 100.0); - var maxRadius = (int) (params.maxRadius * diag / 100.0); + var diag = params.diagonalLengthPx(); + var minRadius = (int) (params.minRadius() * diag / 100.0); + var maxRadius = (int) (params.maxRadius() * diag / 100.0); Imgproc.HoughCircles( in.getLeft(), @@ -65,9 +65,9 @@ public class FindCirclesPipe unless some small very circles need to be detected. */ 1.0, - params.minDist, - params.maxCannyThresh, - Math.max(1.0, params.accuracy), + params.minDist(), + params.maxCannyThresh(), + Math.max(1.0, params.accuracy()), minRadius, maxRadius); // Great, we now found the center point of the circle, and it's radius, but we have no idea what @@ -91,8 +91,8 @@ public class FindCirclesPipe // NOTE: This means that the centroid of the contour must be within the "allowable // threshold" // of the center of the circle - if (Math.abs(x_center - (mu.m10 / mu.m00)) <= params.allowableThreshold - && Math.abs(y_center - (mu.m01 / mu.m00)) <= params.allowableThreshold) { + if (Math.abs(x_center - (mu.m10 / mu.m00)) <= params.allowableThreshold() + && Math.abs(y_center - (mu.m01 / mu.m00)) <= params.allowableThreshold()) { // If it is, then add it to the output array output.add(new CVShape(contour, new Point(c[0], c[1]), c[2])); unmatchedContours.remove(contour); @@ -107,41 +107,29 @@ public class FindCirclesPipe return output; } - public static class FindCirclePipeParams { - private final int allowableThreshold; - private final int minRadius; - private final int maxRadius; - private final int minDist; - private final int maxCannyThresh; - private final int accuracy; - private final double diagonalLengthPx; - - /* - * @params minDist - Minimum distance between the centers of the detected circles. - * If the parameter is too small, multiple neighbor circles may be falsely detected in addition to a true one. If it is too large, some circles may be missed. - * - * @param maxCannyThresh -First method-specific parameter. In case of #HOUGH_GRADIENT and #HOUGH_GRADIENT_ALT, it is the higher threshold of the two passed to the Canny edge detector (the lower one is twice smaller). - * Note that #HOUGH_GRADIENT_ALT uses #Scharr algorithm to compute image derivatives, so the threshold value should normally be higher, such as 300 or normally exposed and contrasty images. - * - * - * @param allowableThreshold - When finding the corresponding contour, this is used to see how close a center should be to a contour for it to be considered THAT contour. - * Should be increased with lower resolutions and decreased with higher resolution - * */ - public FindCirclePipeParams( - int allowableThreshold, - int minRadius, - int minDist, - int maxRadius, - int maxCannyThresh, - int accuracy, - double diagonalLengthPx) { - this.allowableThreshold = allowableThreshold; - this.minRadius = minRadius; - this.maxRadius = maxRadius; - this.minDist = minDist; - this.maxCannyThresh = maxCannyThresh; - this.accuracy = accuracy; - this.diagonalLengthPx = diagonalLengthPx; - } - } + /** + * @param allowableThreshold When finding the corresponding contour, this is used to see how close + * a center should be to a contour for it to be considered THAT contour. Should be increased + * with lower resolutions and decreased with higher resolution + * @param minRadius Minimum circle radius, [0, 100] + * @param minDist Minimum distance between the centers of the detected circles. If the parameter + * is too small, multiple neighbor circles may be falsely detected in addition to a true one. + * If it is too large, some circles may be missed. + * @param maxRadius Maximum circle radius, [0, 100] + * @param maxCannyThresh First method-specific parameter. In case of #HOUGH_GRADIENT and + * #HOUGH_GRADIENT_ALT, it is the higher threshold of the two passed to the Canny edge + * detector (the lower one is twice smaller). Note that #HOUGH_GRADIENT_ALT uses #Scharr + * algorithm to compute image derivatives, so the threshold value should normally be higher, + * such as 300 or normally exposed and contrasty images. + * @param accuracy Circle accuracy, [1, 100] + * @param diagonalLengthPx The diagonal length of the image in pixels + */ + public static record FindCirclePipeParams( + int allowableThreshold, + int minRadius, + int minDist, + int maxRadius, + int maxCannyThresh, + int accuracy, + double diagonalLengthPx) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java index 4cfc15259..fd32a9152 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindPolygonPipe.java @@ -56,19 +56,17 @@ public class FindPolygonPipe private int getCorners(Contour contour) { var approx = contour.getApproxPolyDp( - (100 - params.accuracyPercentage) / 100.0 * Imgproc.arcLength(contour.getMat2f(), true), + (100 - params.accuracyPercentage()) + / 100.0 + * Imgproc.arcLength(contour.getMat2f(), true), true); // The height of the resultant approximation is the number of vertices return (int) approx.size().height; } - public static class FindPolygonPipeParams { - private final double accuracyPercentage; - - // Should be a value between 0-100 - public FindPolygonPipeParams(double accuracyPercentage) { - this.accuracyPercentage = accuracyPercentage; - } - } + /** + * @param accuracyPercentage Accuracy percentage, 0-100 + */ + public static record FindPolygonPipeParams(double accuracyPercentage) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GroupContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GroupContoursPipe.java index 7711467dd..184215beb 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GroupContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GroupContoursPipe.java @@ -38,14 +38,14 @@ public class GroupContoursPipe m_targets.clear(); - if (params.getGroup() == ContourGroupingMode.Single) { + if (params.group() == ContourGroupingMode.Single) { for (var contour : input) { m_targets.add(new PotentialTarget(contour)); } } // Check if we have at least 2 targets for 2 or more // This will only ever return 1 contour! - else if (params.getGroup() == ContourGroupingMode.TwoOrMore + else if (params.group() == ContourGroupingMode.TwoOrMore && input.size() >= ContourGroupingMode.TwoOrMore.count) { // Just blob everything together Contour groupedContour = Contour.combineContourList(input); @@ -53,7 +53,7 @@ public class GroupContoursPipe m_targets.add(new PotentialTarget(groupedContour, input)); } } else { - int groupingCount = params.getGroup().count; + int groupingCount = params.group().count; if (input.size() >= groupingCount) { input.sort(Contour.SortByMomentsX); @@ -73,7 +73,7 @@ public class GroupContoursPipe // FYI: This method only takes 2 contours! Contour groupedContour = Contour.groupContoursByIntersection( - groupingSet.get(0), groupingSet.get(1), params.getIntersection()); + groupingSet.get(0), groupingSet.get(1), params.intersection()); if (groupedContour != null) { m_targets.add(new PotentialTarget(groupedContour, groupingSet)); @@ -88,22 +88,6 @@ public class GroupContoursPipe return m_targets; } - public static class GroupContoursParams { - private final ContourGroupingMode m_group; - private final ContourIntersectionDirection m_intersection; - - public GroupContoursParams( - ContourGroupingMode group, ContourIntersectionDirection intersectionDirection) { - m_group = group; - m_intersection = intersectionDirection; - } - - public ContourGroupingMode getGroup() { - return m_group; - } - - public ContourIntersectionDirection getIntersection() { - return m_intersection; - } - } + public static record GroupContoursParams( + ContourGroupingMode group, ContourIntersectionDirection intersection) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java index e0ba36ce0..e58a20f89 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/HSVPipe.java @@ -32,24 +32,24 @@ public class HSVPipe extends CVPipe { // rather than copying. Free performance! Imgproc.cvtColor(in, outputMat, Imgproc.COLOR_BGR2HSV, 3); - if (params.getHueInverted()) { + if (params.hueInverted()) { // In Java code we do this by taking an image thresholded // from [0, minHue] and ORing it with [maxHue, 180] // we want hue from the end of the slider to max hue - Scalar firstLower = params.getHsvLower().clone(); - Scalar firstUpper = params.getHsvUpper().clone(); - firstLower.val[0] = params.getHsvUpper().val[0]; + Scalar firstLower = params.hsvLower().clone(); + Scalar firstUpper = params.hsvUpper().clone(); + firstLower.val[0] = params.hsvUpper().val[0]; firstUpper.val[0] = 180; var lowerThresholdMat = new Mat(); Core.inRange(outputMat, firstLower, firstUpper, lowerThresholdMat); // We want hue from 0 to the start of the slider - var secondLower = params.getHsvLower().clone(); - var secondUpper = params.getHsvUpper().clone(); + var secondLower = params.hsvLower().clone(); + var secondUpper = params.hsvUpper().clone(); secondLower.val[0] = 0; - secondUpper.val[0] = params.getHsvLower().val[0]; + secondUpper.val[0] = params.hsvLower().val[0]; // Now that the output mat's been used by the first inRange, it's fine to mutate it Core.inRange(outputMat, secondLower, secondUpper, outputMat); @@ -60,35 +60,19 @@ public class HSVPipe extends CVPipe { lowerThresholdMat.release(); } else { - Core.inRange(outputMat, params.getHsvLower(), params.getHsvUpper(), outputMat); + Core.inRange(outputMat, params.hsvLower(), params.hsvUpper(), outputMat); } return outputMat; } - public static class HSVParams { - private final Scalar m_hsvLower; - private final Scalar m_hsvUpper; - private final boolean m_hueInverted; - + public static record HSVParams(Scalar hsvLower, Scalar hsvUpper, boolean hueInverted) { public HSVParams( IntegerCouple hue, IntegerCouple saturation, IntegerCouple value, boolean hueInverted) { - m_hsvLower = new Scalar(hue.getFirst(), saturation.getFirst(), value.getFirst()); - m_hsvUpper = new Scalar(hue.getSecond(), saturation.getSecond(), value.getSecond()); - - this.m_hueInverted = hueInverted; - } - - public Scalar getHsvLower() { - return m_hsvLower; - } - - public Scalar getHsvUpper() { - return m_hsvUpper; - } - - public boolean getHueInverted() { - return m_hueInverted; + this( + new Scalar(hue.getFirst(), saturation.getFirst(), value.getFirst()), + new Scalar(hue.getSecond(), saturation.getSecond(), value.getSecond()), + hueInverted); } } } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/MultiTargetPNPPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/MultiTargetPNPPipe.java index d0c338db1..b795da581 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/MultiTargetPNPPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/MultiTargetPNPPipe.java @@ -43,9 +43,9 @@ public class MultiTargetPNPPipe @Override protected Optional process(List targetList) { if (params == null - || params.cameraCoefficients == null - || params.cameraCoefficients.getCameraIntrinsicsMat() == null - || params.cameraCoefficients.getDistCoeffsMat() == null) { + || params.cameraCoefficients() == null + || params.cameraCoefficients().getCameraIntrinsicsMat() == null + || params.cameraCoefficients().getDistCoeffsMat() == null) { if (!hasWarned) { logger.warn( "Cannot perform solvePNP an uncalibrated camera! Please calibrate this resolution..."); @@ -62,7 +62,7 @@ public class MultiTargetPNPPipe var tagIDsUsed = new ArrayList(); for (var target : targetList) { int id = target.getFiducialId(); - if (params.atfl.getTagPose(id).isPresent()) tagIDsUsed.add((short) id); + if (params.atfl().getTagPose(id).isPresent()) tagIDsUsed.add((short) id); } // Only run with multiple targets @@ -72,11 +72,11 @@ public class MultiTargetPNPPipe var estimatedPose = VisionEstimation.estimateCamPosePNP( - params.cameraCoefficients.cameraIntrinsics.getAsWpilibMat(), - params.cameraCoefficients.distCoeffs.getAsWpilibMat(), + params.cameraCoefficients().cameraIntrinsics.getAsWpilibMat(), + params.cameraCoefficients().distCoeffs.getAsWpilibMat(), TrackedTarget.simpleFromTrackedTargets(targetList), - params.atfl, - params.targetModel); + params.atfl(), + params.targetModel()); if (estimatedPose.isPresent()) { return Optional.of(new MultiTargetPNPResult(estimatedPose.get(), tagIDsUsed)); @@ -85,18 +85,8 @@ public class MultiTargetPNPPipe } } - public static class MultiTargetPNPPipeParams { - private final CameraCalibrationCoefficients cameraCoefficients; - private final AprilTagFieldLayout atfl; - private final TargetModel targetModel; - - public MultiTargetPNPPipeParams( - CameraCalibrationCoefficients cameraCoefficients, - AprilTagFieldLayout atfl, - TargetModel targetModel) { - this.cameraCoefficients = cameraCoefficients; - this.atfl = atfl; - this.targetModel = targetModel; - } - } + public static record MultiTargetPNPPipeParams( + CameraCalibrationCoefficients cameraCoefficients, + AprilTagFieldLayout atfl, + TargetModel targetModel) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/NeuralNetworkPipeResult.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/NeuralNetworkPipeResult.java index 4fce74955..40a56e8d3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/NeuralNetworkPipeResult.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/NeuralNetworkPipeResult.java @@ -19,14 +19,4 @@ package org.photonvision.vision.pipe.impl; import org.opencv.core.Rect2d; -public class NeuralNetworkPipeResult { - public NeuralNetworkPipeResult(Rect2d boundingBox, int classIdx, double confidence) { - bbox = boundingBox; - this.classIdx = classIdx; - this.confidence = confidence; - } - - public final int classIdx; - public final Rect2d bbox; - public final double confidence; -} +public record NeuralNetworkPipeResult(Rect2d bbox, int classIdx, double confidence) {} diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ObjectDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ObjectDetectionPipe.java index fad36a5b8..079ee7926 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ObjectDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ObjectDetectionPipe.java @@ -42,9 +42,9 @@ public class ObjectDetectionPipe @Override protected List process(CVMat in) { // Check if the model has changed - if (detector.getModel() != params.model) { + if (detector.getModel() != params.model()) { detector.release(); - detector = params.model.load(); + detector = params.model().load(); } Mat frame = in.getMat(); @@ -52,17 +52,10 @@ public class ObjectDetectionPipe return List.of(); } - return detector.detect(in.getMat(), params.nms, params.confidence); + return detector.detect(in.getMat(), params.nms(), params.confidence()); } - public static class ObjectDetectionPipeParams { - public double confidence; - public double nms; - public int max_detections; - public Model model; - - public ObjectDetectionPipeParams() {} - } + public static record ObjectDetectionPipeParams(double confidence, double nms, Model model) {} public List getClassNames() { return detector.getClasses(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ResizeImagePipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ResizeImagePipe.java index 3d9c03043..7a65b2709 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ResizeImagePipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ResizeImagePipe.java @@ -32,22 +32,12 @@ public class ResizeImagePipe extends MutatingPipe process(List targetList) { - if (params.cameraCoefficients == null - || params.cameraCoefficients.getCameraIntrinsicsMat() == null - || params.cameraCoefficients.getDistCoeffsMat() == null) { + if (params.cameraCoefficients() == null + || params.cameraCoefficients().getCameraIntrinsicsMat() == null + || params.cameraCoefficients().getDistCoeffsMat() == null) { if (!hasWarned) { logger.warn( "Cannot perform solvePNP an uncalibrated camera! Please calibrate this resolution..."); @@ -65,9 +65,9 @@ public class SolvePNPPipe var corners = target.getTargetCorners(); if (corners == null || corners.isEmpty() - || params.cameraCoefficients == null - || params.cameraCoefficients.getCameraIntrinsicsMat() == null - || params.cameraCoefficients.getDistCoeffsMat() == null) { + || params.cameraCoefficients() == null + || params.cameraCoefficients().getCameraIntrinsicsMat() == null + || params.cameraCoefficients().getDistCoeffsMat() == null) { return; } this.imagePoints.fromList(corners); @@ -76,10 +76,10 @@ public class SolvePNPPipe var tVec = new Mat(); try { Calib3d.solvePnP( - params.targetModel.getRealWorldTargetCoordinates(), + params.targetModel().getRealWorldTargetCoordinates(), imagePoints, - params.cameraCoefficients.getCameraIntrinsicsMat(), - params.cameraCoefficients.getDistCoeffsMat(), + params.cameraCoefficients().getCameraIntrinsicsMat(), + params.cameraCoefficients().getDistCoeffsMat(), rVec, tVec); } catch (Exception e) { @@ -103,14 +103,6 @@ public class SolvePNPPipe target.setAltCameraToTarget3d(new Transform3d()); } - public static class SolvePNPPipeParams { - private final CameraCalibrationCoefficients cameraCoefficients; - private final TargetModel targetModel; - - public SolvePNPPipeParams( - CameraCalibrationCoefficients cameraCoefficients, TargetModel targetModel) { - this.cameraCoefficients = cameraCoefficients; - this.targetModel = targetModel; - } - } + public static record SolvePNPPipeParams( + CameraCalibrationCoefficients cameraCoefficients, TargetModel targetModel) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java index b084c75c4..e9abc1ae9 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java @@ -39,46 +39,23 @@ public class SortContoursPipe if (!in.isEmpty()) { m_sortedContours.addAll(in); - if (params.getSortMode() != ContourSortMode.Centermost) { - m_sortedContours.sort(params.getSortMode().getComparator()); + if (params.sortMode() != ContourSortMode.Centermost) { + m_sortedContours.sort(params.sortMode().getComparator()); } else { // we need knowledge of camera properties to calculate this distance -- do it ourselves m_sortedContours.sort(Comparator.comparingDouble(this::calcSquareCenterDistance)); } } - return new ArrayList<>( - m_sortedContours.subList(0, Math.min(in.size(), params.getMaxTargets()))); + return new ArrayList<>(m_sortedContours.subList(0, Math.min(in.size(), params.maxTargets()))); } private double calcSquareCenterDistance(PotentialTarget tgt) { return Math.sqrt( - Math.pow(params.getCamProperties().centerX - tgt.getMinAreaRect().center.x, 2) - + Math.pow(params.getCamProperties().centerY - tgt.getMinAreaRect().center.y, 2)); + Math.pow(params.frameStaticProperties().centerX - tgt.getMinAreaRect().center.x, 2) + + Math.pow(params.frameStaticProperties().centerY - tgt.getMinAreaRect().center.y, 2)); } - public static class SortContoursParams { - private final ContourSortMode m_sortMode; - private final int m_maxTargets; - private final FrameStaticProperties m_frameStaticProperties; - - public SortContoursParams( - ContourSortMode sortMode, int maxTargets, FrameStaticProperties camProperties) { - m_sortMode = sortMode; - m_maxTargets = maxTargets; - m_frameStaticProperties = camProperties; - } - - public ContourSortMode getSortMode() { - return m_sortMode; - } - - public FrameStaticProperties getCamProperties() { - return m_frameStaticProperties; - } - - public int getMaxTargets() { - return m_maxTargets; - } - } + public static record SortContoursParams( + ContourSortMode sortMode, int maxTargets, FrameStaticProperties frameStaticProperties) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java index 4f4c5ce54..8f0a79cd6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SpeckleRejectPipe.java @@ -40,7 +40,7 @@ public class SpeckleRejectPipe } averageArea /= in.size(); - double minAllowedArea = params.getMinPercentOfAvg() / 100.0 * averageArea; + double minAllowedArea = params.minPercentOfAvg() / 100.0 * averageArea; for (Contour c : in) { if (c.getArea() >= minAllowedArea) { m_despeckledContours.add(c); @@ -53,15 +53,5 @@ public class SpeckleRejectPipe return m_despeckledContours; } - public static class SpeckleRejectParams { - private final double m_minPercentOfAvg; - - public SpeckleRejectParams(double minPercentOfAvg) { - m_minPercentOfAvg = minPercentOfAvg; - } - - public double getMinPercentOfAvg() { - return m_minPercentOfAvg; - } - } + public static record SpeckleRejectParams(double minPercentOfAvg) {} } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java index 5cc9cc98f..f5cd52c26 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java @@ -38,7 +38,7 @@ import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameThresholdType; import org.photonvision.vision.pipe.CVPipe.CVPipeResult; import org.photonvision.vision.pipe.impl.AprilTagDetectionPipe; -import org.photonvision.vision.pipe.impl.AprilTagDetectionPipeParams; +import org.photonvision.vision.pipe.impl.AprilTagDetectionPipe.AprilTagDetectionPipeParams; import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe; import org.photonvision.vision.pipe.impl.AprilTagPoseEstimatorPipe.AprilTagPoseEstimatorPipeParams; import org.photonvision.vision.pipe.impl.CalculateFPSPipe; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java index 684fdd024..c0e9fa424 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java @@ -56,9 +56,6 @@ public class ObjectDetectionPipeline @Override protected void setPipeParamsImpl() { - var params = new ObjectDetectionPipeParams(); - params.confidence = settings.confidence; - params.nms = settings.nms; Optional selectedModel = NeuralNetworkModelManager.getInstance().getModel(settings.model); @@ -71,8 +68,8 @@ public class ObjectDetectionPipeline if (selectedModel.isEmpty()) { selectedModel = Optional.of(NullModel.getInstance()); } - - params.model = selectedModel.get(); + var params = + new ObjectDetectionPipeParams(settings.confidence, settings.nms, selectedModel.get()); objectDetectorPipe.setParams(params); diff --git a/photon-core/src/main/java/org/photonvision/vision/target/PotentialTarget.java b/photon-core/src/main/java/org/photonvision/vision/target/PotentialTarget.java index 520f1d454..a7c00e62e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/target/PotentialTarget.java +++ b/photon-core/src/main/java/org/photonvision/vision/target/PotentialTarget.java @@ -56,11 +56,11 @@ public class PotentialTarget implements Releasable { } public PotentialTarget(NeuralNetworkPipeResult det) { - this.shape = new CVShape(new Contour(det.bbox), ContourShape.Quadrilateral); + this.shape = new CVShape(new Contour(det.bbox()), ContourShape.Quadrilateral); this.m_mainContour = this.shape.getContour(); m_subContours = List.of(); - this.clsId = det.classIdx; - this.confidence = det.confidence; + this.clsId = det.classIdx(); + this.confidence = det.confidence(); } public PotentialTarget(CVShape cvShape) { From 4ffd1fc600a30592f4586f66abadefef1286c463 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 16 Mar 2025 23:41:35 -0400 Subject: [PATCH 12/42] Use nicer array syntax --- .../networktables/NTDataPublisher.java | 4 +- .../vision/pipe/impl/ArucoDetectionPipe.java | 13 +++--- .../vision/pipe/impl/DrawCalibrationPipe.java | 15 ++++--- .../vision/pipeline/PipelineProfiler.java | 25 ++++++----- .../vision/target/TrackedTarget.java | 42 ++++++++----------- .../pipeline/CalibrationRotationPipeTest.java | 4 +- .../java/org/photonvision/PhotonCamera.java | 2 +- .../simulation/SimCameraProperties.java | 32 +++++++------- .../estimation/VisionEstimation.java | 13 +++--- .../test/java/ConstrainedSolvepnpTest.java | 9 ++-- 10 files changed, 72 insertions(+), 87 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java index a3a8971f9..92275a643 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/networktables/NTDataPublisher.java @@ -205,8 +205,8 @@ public class NTDataPublisher implements CVPipelineResultConsumer { ts.cameraIntrinsicsPublisher.accept(fsp.cameraCalibration.getIntrinsicsArr()); ts.cameraDistortionPublisher.accept(fsp.cameraCalibration.getDistCoeffsArr()); } else { - ts.cameraIntrinsicsPublisher.accept(new double[] {}); - ts.cameraDistortionPublisher.accept(new double[] {}); + ts.cameraIntrinsicsPublisher.accept(new double[0]); + ts.cameraDistortionPublisher.accept(new double[0]); } ts.heartbeatPublisher.set(acceptedResult.sequenceID); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipe.java index 82dfd31c3..a360dd7c3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/ArucoDetectionPipe.java @@ -59,13 +59,12 @@ public class ArucoDetectionPipe for (var detection : detections) { double[] xCorners = detection.getXCorners(); double[] yCorners = detection.getYCorners(); - Point[] cornerPoints = - new Point[] { - new Point(xCorners[0], yCorners[0]), - new Point(xCorners[1], yCorners[1]), - new Point(xCorners[2], yCorners[2]), - new Point(xCorners[3], yCorners[3]) - }; + Point[] cornerPoints = { + new Point(xCorners[0], yCorners[0]), + new Point(xCorners[1], yCorners[1]), + new Point(xCorners[2], yCorners[2]), + new Point(xCorners[3], yCorners[3]) + }; double bltr = Math.hypot( cornerPoints[2].x - cornerPoints[0].x, cornerPoints[2].y - cornerPoints[0].y); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java index 7005d66e8..c9112f445 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java @@ -32,14 +32,13 @@ import org.photonvision.vision.target.TrackedTarget; public class DrawCalibrationPipe extends MutatingPipe< Pair>, DrawCalibrationPipe.DrawCalibrationPipeParams> { - Scalar[] chessboardColors = - new Scalar[] { - ColorHelper.colorToScalar(Color.RED, 0.4), - ColorHelper.colorToScalar(Color.ORANGE, 0.4), - ColorHelper.colorToScalar(Color.GREEN, 0.4), - ColorHelper.colorToScalar(Color.BLUE, 0.4), - ColorHelper.colorToScalar(Color.MAGENTA, 0.4), - }; + Scalar[] chessboardColors = { + ColorHelper.colorToScalar(Color.RED, 0.4), + ColorHelper.colorToScalar(Color.ORANGE, 0.4), + ColorHelper.colorToScalar(Color.GREEN, 0.4), + ColorHelper.colorToScalar(Color.BLUE, 0.4), + ColorHelper.colorToScalar(Color.MAGENTA, 0.4), + }; @Override protected Void process(Pair> in) { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/PipelineProfiler.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/PipelineProfiler.java index 57c94b064..8d3fb88e5 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/PipelineProfiler.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/PipelineProfiler.java @@ -37,19 +37,18 @@ public class PipelineProfiler { * output) 14 - draw2dTargetsPipe (on input) 15 - draw2dTargetsPipe (on output) 16 - * draw3dTargetsPipe (OPTIONAL, on input) 17 - draw3dTargetsPipe (OPTIONAL, on output) */ - private static final String[] ReflectivePipeNames = - new String[] { - "RotateImage", - "HSV", - "FindContours", - "SpeckleReject", - "FilterContours", - "GroupContours", - "SortContours", - "Collect2dTargets", - "CornerDetection", - "SolvePNP", - }; + private static final String[] ReflectivePipeNames = { + "RotateImage", + "HSV", + "FindContours", + "SpeckleReject", + "FilterContours", + "GroupContours", + "SortContours", + "Collect2dTargets", + "CornerDetection", + "SolvePNP", + }; public static final int ReflectivePipeCount = ReflectivePipeNames.length; diff --git a/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java b/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java index ee31696cf..1c5e22c05 100644 --- a/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java +++ b/photon-core/src/main/java/org/photonvision/vision/target/TrackedTarget.java @@ -122,11 +122,9 @@ public class TrackedTarget implements Releasable { tvec.put( 0, 0, - new double[] { - bestPose.getTranslation().getX(), - bestPose.getTranslation().getY(), - bestPose.getTranslation().getZ() - }); + bestPose.getTranslation().getX(), + bestPose.getTranslation().getY(), + bestPose.getTranslation().getZ()); setCameraRelativeTvec(tvec); // Opencv expects a 3d vector with norm = angle and direction = axis @@ -136,13 +134,12 @@ public class TrackedTarget implements Releasable { } double[] corners = tagDetection.getCorners(); - Point[] cornerPoints = - new Point[] { - new Point(corners[0], corners[1]), - new Point(corners[2], corners[3]), - new Point(corners[4], corners[5]), - new Point(corners[6], corners[7]) - }; + Point[] cornerPoints = { + new Point(corners[0], corners[1]), + new Point(corners[2], corners[3]), + new Point(corners[4], corners[5]), + new Point(corners[6], corners[7]) + }; m_targetCorners = List.of(cornerPoints); MatOfPoint contourMat = new MatOfPoint(cornerPoints); m_approximateBoundingPolygon = new MatOfPoint2f(cornerPoints); @@ -198,13 +195,12 @@ public class TrackedTarget implements Releasable { double[] xCorners = result.getXCorners(); double[] yCorners = result.getYCorners(); - Point[] cornerPoints = - new Point[] { - new Point(xCorners[0], yCorners[0]), - new Point(xCorners[1], yCorners[1]), - new Point(xCorners[2], yCorners[2]), - new Point(xCorners[3], yCorners[3]) - }; + Point[] cornerPoints = { + new Point(xCorners[0], yCorners[0]), + new Point(xCorners[1], yCorners[1]), + new Point(xCorners[2], yCorners[2]), + new Point(xCorners[3], yCorners[3]) + }; m_targetCorners = List.of(cornerPoints); MatOfPoint contourMat = new MatOfPoint(cornerPoints); m_approximateBoundingPolygon = new MatOfPoint2f(cornerPoints); @@ -236,11 +232,9 @@ public class TrackedTarget implements Releasable { tvec.put( 0, 0, - new double[] { - bestPose.getTranslation().getX(), - bestPose.getTranslation().getY(), - bestPose.getTranslation().getZ() - }); + bestPose.getTranslation().getX(), + bestPose.getTranslation().getY(), + bestPose.getTranslation().getZ()); setCameraRelativeTvec(tvec); var rvec = new Mat(3, 1, CvType.CV_64FC1); diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java index 296e70481..8e9f52c2b 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java @@ -123,7 +123,7 @@ public class CalibrationRotationPipeTest { 0.09625562194891251, -0.1860797479660746 }), - new double[] {}, + new double[0], List.of(), new Size(), 1, @@ -288,7 +288,7 @@ public class CalibrationRotationPipeTest { 0.04625562194891251, -0.0860797479660746 }), - new double[] {}, + new double[0], List.of(), new Size(), 1, diff --git a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java index a60ec848f..4ca7c3077 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java @@ -138,7 +138,7 @@ public class PhotonCamera implements AutoCloseable { .getRawTopic("rawBytes") .subscribe( PhotonPipelineResult.photonStruct.getTypeString(), - new byte[] {}, + new byte[0], PubSubOption.periodic(0.01), PubSubOption.sendAll(true), PubSubOption.pollStorage(20)); diff --git a/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java b/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java index f9b7f8a46..eb6414145 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java @@ -202,24 +202,20 @@ public class SimCameraProperties { this.distCoeffs = distCoeffs; // left, right, up, and down view planes - var p = - new Translation3d[] { - new Translation3d( - 1, - new Rotation3d(0, 0, getPixelYaw(0).plus(new Rotation2d(-Math.PI / 2)).getRadians())), - new Translation3d( - 1, - new Rotation3d( - 0, 0, getPixelYaw(resWidth).plus(new Rotation2d(Math.PI / 2)).getRadians())), - new Translation3d( - 1, - new Rotation3d( - 0, getPixelPitch(0).plus(new Rotation2d(Math.PI / 2)).getRadians(), 0)), - new Translation3d( - 1, - new Rotation3d( - 0, getPixelPitch(resHeight).plus(new Rotation2d(-Math.PI / 2)).getRadians(), 0)) - }; + Translation3d[] p = { + new Translation3d( + 1, new Rotation3d(0, 0, getPixelYaw(0).plus(new Rotation2d(-Math.PI / 2)).getRadians())), + new Translation3d( + 1, + new Rotation3d( + 0, 0, getPixelYaw(resWidth).plus(new Rotation2d(Math.PI / 2)).getRadians())), + new Translation3d( + 1, new Rotation3d(0, getPixelPitch(0).plus(new Rotation2d(Math.PI / 2)).getRadians(), 0)), + new Translation3d( + 1, + new Rotation3d( + 0, getPixelPitch(resHeight).plus(new Rotation2d(-Math.PI / 2)).getRadians(), 0)) + }; viewplanes.clear(); for (Translation3d translation3d : p) { viewplanes.add( diff --git a/photon-targeting/src/main/java/org/photonvision/estimation/VisionEstimation.java b/photon-targeting/src/main/java/org/photonvision/estimation/VisionEstimation.java index 6031ec337..afd3f4c3a 100644 --- a/photon-targeting/src/main/java/org/photonvision/estimation/VisionEstimation.java +++ b/photon-targeting/src/main/java/org/photonvision/estimation/VisionEstimation.java @@ -248,13 +248,12 @@ public class VisionEstimation { } // fx fy cx cy - double[] cameraCal = - new double[] { - cameraMatrix.get(0, 0), - cameraMatrix.get(1, 1), - cameraMatrix.get(0, 2), - cameraMatrix.get(1, 2), - }; + double[] cameraCal = { + cameraMatrix.get(0, 0), + cameraMatrix.get(1, 1), + cameraMatrix.get(0, 2), + cameraMatrix.get(1, 2), + }; var guess2 = robotPoseSeed.toPose2d(); diff --git a/photon-targeting/src/test/java/ConstrainedSolvepnpTest.java b/photon-targeting/src/test/java/ConstrainedSolvepnpTest.java index fd7c1f1eb..40acdf2a9 100644 --- a/photon-targeting/src/test/java/ConstrainedSolvepnpTest.java +++ b/photon-targeting/src/test/java/ConstrainedSolvepnpTest.java @@ -50,10 +50,9 @@ public class ConstrainedSolvepnpTest { @Test public void smoketest() { - double[] cameraCal = - new double[] { - 600, 600, 300, 150, - }; + double[] cameraCal = { + 600, 600, 300, 150, + }; var field2points = MatBuilder.fill( @@ -86,7 +85,7 @@ public class ConstrainedSolvepnpTest { MatBuilder.fill(Nat.N4(), Nat.N4(), 0, 0, 1, 0, -1, 0, 0, 0, 0, -1, 0, 0, 0, 0, 0, 1); // Initial guess for optimization - double[] x_guess = new double[] {0.2, 0.1, -.05}; + double[] x_guess = {0.2, 0.1, -.05}; var ret = ConstrainedSolvepnpJni.do_optimization( From b86217a59a7fe4a3f007a6f0f2eaeaaa0d305e68 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 16 Mar 2025 23:42:03 -0400 Subject: [PATCH 13/42] Use text blocks --- .../common/configuration/DatabaseSchema.java | 23 +-- .../java/org/photonvision/PhotonCamera.java | 157 ++++++++++-------- 2 files changed, 101 insertions(+), 79 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/DatabaseSchema.java b/photon-core/src/main/java/org/photonvision/common/configuration/DatabaseSchema.java index d55c3494d..ccb7e6d72 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/DatabaseSchema.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/DatabaseSchema.java @@ -27,16 +27,19 @@ package org.photonvision.common.configuration; public final class DatabaseSchema { public static final String[] migrations = { // #1 - initial schema - "CREATE TABLE IF NOT EXISTS global (\n" - + " filename TINYTEXT PRIMARY KEY,\n" - + " contents mediumtext NOT NULL\n" - + ");" - + "CREATE TABLE IF NOT EXISTS cameras (\n" - + " unique_name TINYTEXT PRIMARY KEY,\n" - + " config_json text NOT NULL,\n" - + " drivermode_json text NOT NULL,\n" - + " pipeline_jsons mediumtext NOT NULL\n" - + ");", + // spotless:off + """ + CREATE TABLE IF NOT EXISTS global ( + filename TINYTEXT PRIMARY KEY, + contents mediumtext NOT NULL + ); + CREATE TABLE IF NOT EXISTS cameras ( + unique_name TINYTEXT PRIMARY KEY, + config_json text NOT NULL, + drivermode_json text NOT NULL, + pipeline_jsons mediumtext NOT NULL + );""", + // spotless:on // #2 - add column otherpaths_json "ALTER TABLE cameras ADD COLUMN otherpaths_json TEXT NOT NULL DEFAULT '[]';", // add future migrations here diff --git a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java index 4ca7c3077..00b04b753 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java @@ -175,65 +175,77 @@ public class PhotonCamera implements AutoCloseable { } public static void verifyDependencies() { + // spotless:off if (!WPILibVersion.Version.equals(PhotonVersion.wpilibTargetVersion)) { - String bfw = - "\n\n\n\n\n" - + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n" - + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" - + ">>> \n" - + ">>> You are running an incompatible version \n" - + ">>> of PhotonVision ! \n" - + ">>> \n" - + ">>> PhotonLib " - + PhotonVersion.versionString - + " is built for WPILib " - + PhotonVersion.wpilibTargetVersion - + "\n" - + ">>> but you are using WPILib " - + WPILibVersion.Version - + ">>> \n" - + ">>> This is neither tested nor supported. \n" - + ">>> You MUST update PhotonVision, \n" - + ">>> PhotonLib, or both. \n" - + ">>> Verify the output of `./gradlew dependencies` \n" - + ">>> \n" - + ">>> Your code will now crash. \n" - + ">>> We hope your day gets better. \n" - + ">>> \n" - + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" - + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n"; + String bfw = """ + + + + + >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\s + >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\s + >>> \s + >>> You are running an incompatible version \s + >>> of PhotonVision ! \s + >>> \s + >>> PhotonLib """ + + PhotonVersion.versionString + + " is built for WPILib " + + PhotonVersion.wpilibTargetVersion + + "\n" + + ">>> but you are using WPILib " + + WPILibVersion.Version + + """ + >>> \s + >>> This is neither tested nor supported. \s + >>> You MUST update PhotonVision, \s + >>> PhotonLib, or both. \s + >>> Verify the output of `./gradlew dependencies` + >>> \s + >>> Your code will now crash. \s + >>> We hope your day gets better. \s + >>> \s + >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\s + >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\s + """; DriverStation.reportWarning(bfw, false); DriverStation.reportError(bfw, false); throw new UnsupportedOperationException(bfw); } if (!Core.VERSION.equals(PhotonVersion.opencvTargetVersion)) { - String bfw = - "\n\n\n\n\n" - + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n" - + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" - + ">>> \n" - + ">>> You are running an incompatible version \n" - + ">>> of PhotonVision ! \n" - + ">>> \n" - + ">>> PhotonLib " - + PhotonVersion.versionString - + " is built for OpenCV " - + PhotonVersion.opencvTargetVersion - + "\n" - + ">>> but you are using OpenCV " - + Core.VERSION - + ">>> \n" - + ">>> This is neither tested nor supported. \n" - + ">>> You MUST update PhotonVision, \n" - + ">>> PhotonLib, or both. \n" - + ">>> Verify the output of `./gradlew dependencies` \n" - + ">>> \n" - + ">>> Your code will now crash. \n" - + ">>> We hope your day gets better. \n" - + ">>> \n" - + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" - + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n"; + String bfw = """ + + + + + >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\s + >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\s + >>> \s + >>> You are running an incompatible version \s + >>> of PhotonVision ! \s + >>> \s + >>> PhotonLib """ + + PhotonVersion.versionString + + " is built for OpenCV " + + PhotonVersion.opencvTargetVersion + + "\n" + + ">>> but you are using OpenCV " + + Core.VERSION + + """ + >>> \s + >>> This is neither tested nor supported. \s + >>> You MUST update PhotonVision, \s + >>> PhotonLib, or both. \s + >>> Verify the output of `./gradlew dependencies` + >>> \s + >>> Your code will now crash. \s + >>> We hope your day gets better. \s + >>> \s + >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\s + >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\s + """; + // spotless:on DriverStation.reportWarning(bfw, false); DriverStation.reportError(bfw, false); @@ -533,23 +545,30 @@ public class PhotonCamera implements AutoCloseable { // Error on a verified version mismatch // But stay silent otherwise - String bfw = - "\n\n\n\n\n" - + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n" - + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" - + ">>> \n" - + ">>> You are running an incompatible version \n" - + ">>> of PhotonVision on your coprocessor! \n" - + ">>> \n" - + ">>> This is neither tested nor supported. \n" - + ">>> You MUST update PhotonVision, \n" - + ">>> PhotonLib, or both. \n" - + ">>> \n" - + ">>> Your code will now crash. \n" - + ">>> We hope your day gets better. \n" - + ">>> \n" - + ">>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n" - + ">>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>\n"; + // spotless:off + String bfw = """ + + + + + + >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! + >>> \s + >>> You are running an incompatible version \s + >>> of PhotonVision on your coprocessor! \s + >>> \s + >>> This is neither tested nor supported. \s + >>> You MUST update PhotonVision, \s + >>> PhotonLib, or both. \s + >>> \s + >>> Your code will now crash. \s + >>> We hope your day gets better. \s + >>> \s + >>> !!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!!! + >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> + """; + // spotless:on DriverStation.reportWarning(bfw, false); var versionMismatchMessage = From c45c2a0a1f94749a24dcf77261bcd1736286cba9 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Tue, 18 Mar 2025 02:44:07 -0400 Subject: [PATCH 14/42] Refactor how AprilTag images are made in sim --- .../org/photonvision/simulation/VideoSimUtil.java | 13 ++----------- 1 file changed, 2 insertions(+), 11 deletions(-) diff --git a/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java b/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java index 325a2ab2c..89face676 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java @@ -39,7 +39,6 @@ import java.util.Map; import org.opencv.core.Core; import org.opencv.core.CvType; import org.opencv.core.Mat; -import org.opencv.core.MatOfByte; import org.opencv.core.MatOfPoint; import org.opencv.core.MatOfPoint2f; import org.opencv.core.Point; @@ -103,16 +102,8 @@ public class VideoSimUtil { */ private static Mat get36h11TagImage(int id) { RawFrame frame = AprilTag.generate36h11AprilTagImage(id); - - var buf = frame.getData(); - byte[] arr = new byte[buf.remaining()]; - buf.get(arr); - // frame.close(); - - var mat = new MatOfByte(arr).reshape(1, 10).submat(new Rect(0, 0, 10, 10)); - mat.dump(); - - return mat; + return new Mat( + frame.getHeight(), frame.getWidth(), CvType.CV_8UC1, frame.getData(), frame.getStride()); } /** Gets the points representing the marker(black square) corners. */ From 8a2c9f2ae052e43c04f31f2cc86b5b64aaccfaa8 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Thu, 20 Mar 2025 01:32:14 -0400 Subject: [PATCH 15/42] Refactor FileSaveFrameConsumer to close objects and let Java handle paths --- .../frame/consumer/FileSaveFrameConsumer.java | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java index d12f491fd..dce9366a5 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/FileSaveFrameConsumer.java @@ -103,19 +103,17 @@ public class FileSaveFrameConsumer implements Consumer { + matchData; // Check if the Unique Camera directory exists and create it if it doesn't - String cameraPath = FILE_PATH + File.separator + this.cameraUniqueName; - var cameraDir = new File(cameraPath); + var cameraDir = new File(FILE_PATH, this.cameraUniqueName); if (!cameraDir.exists()) { cameraDir.mkdir(); } - - String saveFilePath = cameraPath + File.separator + fileName + FILE_EXTENSION; + var saveFilePath = cameraDir.toPath().resolve(fileName + FILE_EXTENSION); logger.info("Saving image to: " + saveFilePath); if (image == null || image.getMat() == null || image.getMat().empty()) { - Imgcodecs.imwrite(saveFilePath, StaticFrames.LOST_MAT); + Imgcodecs.imwrite(saveFilePath.toString(), StaticFrames.LOST_MAT); } else { - Imgcodecs.imwrite(saveFilePath, image.getMat()); + Imgcodecs.imwrite(saveFilePath.toString(), image.getMat()); } savedImagesCount++; @@ -178,6 +176,9 @@ public class FileSaveFrameConsumer implements Consumer { } public void close() { - // troododfa;lkjadsf;lkfdsaj otgooadflsk;j + saveFrameEntry.close(); + ntEventName.close(); + ntMatchNum.close(); + ntMatchType.close(); } } From ed7fc6bbcc11ccbb66b52bcfdafb038f42c986f0 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 14 Apr 2025 18:43:36 -0400 Subject: [PATCH 16/42] Use WPILib Pair and drop dependency on Apache Commons Pair This allowed us to drop a few Apache Commons dependencies, which is good for reducing JAR size and the number of things we need to pull in. --- .../photonvision/common/logging/Logger.java | 5 ++-- .../vision/pipe/impl/Draw2dCrosshairPipe.java | 8 +++--- .../vision/pipe/impl/Draw2dTargetsPipe.java | 28 +++++++++---------- .../vision/pipe/impl/Draw3dTargetsPipe.java | 22 +++++++-------- .../vision/pipe/impl/DrawCalibrationPipe.java | 6 ++-- .../pipe/impl/FindBoardCornersPipe.java | 6 ++-- .../vision/pipe/impl/FindCirclesPipe.java | 6 ++-- .../vision/pipeline/Calibrate3dPipeline.java | 2 +- .../vision/pipeline/ColoredShapePipeline.java | 2 +- .../vision/pipeline/DriverModePipeline.java | 2 +- .../vision/pipeline/OutputStreamPipeline.java | 2 +- .../VisionModuleChangeSubscriber.java | 6 ++-- .../server/DataSocketHandler.java | 2 +- shared/common.gradle | 2 -- 14 files changed, 48 insertions(+), 51 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/logging/Logger.java b/photon-core/src/main/java/org/photonvision/common/logging/Logger.java index 7bba651b5..8bad35796 100644 --- a/photon-core/src/main/java/org/photonvision/common/logging/Logger.java +++ b/photon-core/src/main/java/org/photonvision/common/logging/Logger.java @@ -17,14 +17,13 @@ package org.photonvision.common.logging; +import edu.wpi.first.math.Pair; import java.io.*; import java.nio.file.Path; import java.text.ParseException; import java.text.SimpleDateFormat; import java.util.*; import java.util.function.Supplier; -import org.apache.commons.lang3.tuple.Pair; -// import org.photonvision.common.configuration.ConfigManager; import org.photonvision.common.configuration.PathManager; import org.photonvision.common.dataflow.DataChangeService; import org.photonvision.common.dataflow.events.OutgoingUIEvent; @@ -194,7 +193,7 @@ public class Logger { connected = true; synchronized (uiBacklog) { for (var message : uiBacklog) { - uiLogAppender.log(message.getLeft(), message.getRight()); + uiLogAppender.log(message.getFirst(), message.getSecond()); } uiBacklog.clear(); } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java index b7a3335af..ed416b167 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dCrosshairPipe.java @@ -17,9 +17,9 @@ package org.photonvision.vision.pipe.impl; +import edu.wpi.first.math.Pair; import java.awt.*; import java.util.List; -import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Mat; import org.opencv.core.Point; import org.opencv.imgproc.Imgproc; @@ -40,7 +40,7 @@ public class Draw2dCrosshairPipe protected Void process(Pair> in) { if (!params.shouldDraw()) return null; - var image = in.getLeft(); + var image = in.getFirst(); if (params.showCrosshair()) { double x = params.frameStaticProperties().centerX; @@ -57,8 +57,8 @@ public class Draw2dCrosshairPipe } } case Dual -> { - if (!in.getRight().isEmpty()) { - var target = in.getRight().get(0); + if (!in.getSecond().isEmpty()) { + var target = in.getSecond().get(0); if (target != null) { var area = target.getArea(); var offsetCrosshair = diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java index 3365a5cf3..93caa4169 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw2dTargetsPipe.java @@ -17,9 +17,9 @@ package org.photonvision.vision.pipe.impl; +import edu.wpi.first.math.Pair; import java.awt.*; import java.util.List; -import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.*; import org.opencv.core.Point; import org.opencv.imgproc.Imgproc; @@ -39,15 +39,15 @@ public class Draw2dTargetsPipe @Override protected Void process(Pair> in) { - var imRows = in.getLeft().rows(); - var imCols = in.getLeft().cols(); + var imRows = in.getFirst().rows(); + var imCols = in.getFirst().cols(); var imageSize = Math.sqrt(imRows * imCols); var textSize = params.kPixelsToText * imageSize; var thickness = params.kPixelsToThickness * imageSize; if (!params.shouldDraw) return null; - if (!in.getRight().isEmpty() + if (!in.getSecond().isEmpty() && (params.showCentroid || params.showMaximumBox || params.showRotatedBox @@ -58,7 +58,7 @@ public class Draw2dTargetsPipe var circleColor = ColorHelper.colorToScalar(params.circleColor); var shapeColour = ColorHelper.colorToScalar(params.shapeOutlineColour); - for (int i = 0; i < (params.showMultipleTargets ? in.getRight().size() : 1); i++) { + for (int i = 0; i < (params.showMultipleTargets ? in.getSecond().size() : 1); i++) { Point[] vertices = new Point[4]; MatOfPoint contour = new MatOfPoint(); @@ -66,7 +66,7 @@ public class Draw2dTargetsPipe break; } - TrackedTarget target = in.getRight().get(i); + TrackedTarget target = in.getSecond().get(i); RotatedRect r = target.getMinAreaRect(); if (r == null) continue; @@ -77,14 +77,14 @@ public class Draw2dTargetsPipe if (params.shouldShowRotatedBox(target.getShape())) { Imgproc.drawContours( - in.getLeft(), + in.getFirst(), List.of(contour), 0, rotatedBoxColour, (int) Math.ceil(imageSize * params.kPixelsToBoxThickness)); } else if (params.shouldShowCircle(target.getShape())) { Imgproc.circle( - in.getLeft(), + in.getFirst(), target.getShape().center, (int) target.getShape().radius, circleColor, @@ -101,7 +101,7 @@ public class Draw2dTargetsPipe mat.fromArray(poly.toArray()); divideMat(mat, mat); Imgproc.drawContours( - in.getLeft(), + in.getFirst(), List.of(mat), -1, ColorHelper.colorToScalar(params.rotatedBoxColor), @@ -113,7 +113,7 @@ public class Draw2dTargetsPipe if (params.showMaximumBox) { Rect box = Imgproc.boundingRect(contour); Imgproc.rectangle( - in.getLeft(), + in.getFirst(), new Point(box.x, box.y), new Point(box.x + box.width, box.y + box.height), maximumBoxColour, @@ -123,7 +123,7 @@ public class Draw2dTargetsPipe if (params.showShape) { divideMat(target.m_mainContour.mat, tempMat); Imgproc.drawContours( - in.getLeft(), + in.getFirst(), List.of(tempMat), -1, shapeColour, @@ -142,7 +142,7 @@ public class Draw2dTargetsPipe var contourNumber = String.valueOf(id == -1 ? i : id); Imgproc.putText( - in.getLeft(), + in.getFirst(), contourNumber, textPos, 0, @@ -163,13 +163,13 @@ public class Draw2dTargetsPipe Point yMin = new Point(x, y - crosshairRadius); Imgproc.line( - in.getLeft(), + in.getFirst(), xMax, xMin, centroidColour, (int) Math.ceil(imageSize * params.kPixelsToBoxThickness)); Imgproc.line( - in.getLeft(), + in.getFirst(), yMax, yMin, centroidColour, diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java index e3e24d188..c5183b66e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Draw3dTargetsPipe.java @@ -17,9 +17,9 @@ package org.photonvision.vision.pipe.impl; +import edu.wpi.first.math.Pair; import java.awt.*; import java.util.List; -import org.apache.commons.lang3.tuple.Pair; import org.opencv.calib3d.Calib3d; import org.opencv.core.*; import org.opencv.core.Point; @@ -47,7 +47,7 @@ public class Draw3dTargetsPipe return null; } - for (var target : in.getRight()) { + for (var target : in.getSecond()) { // draw convex hull if (params.shouldDrawHull(target)) { var pointMat = new MatOfPoint(); @@ -59,14 +59,14 @@ public class Draw3dTargetsPipe continue; } Imgproc.drawContours( - in.getLeft(), List.of(pointMat), -1, ColorHelper.colorToScalar(Color.green), 1); + in.getFirst(), List.of(pointMat), -1, ColorHelper.colorToScalar(Color.green), 1); // draw approximate polygon var poly = target.getApproximateBoundingPolygon(); if (poly != null) { divideMat2f(poly, pointMat); Imgproc.drawContours( - in.getLeft(), List.of(pointMat), -1, ColorHelper.colorToScalar(Color.blue), 2); + in.getFirst(), List.of(pointMat), -1, ColorHelper.colorToScalar(Color.blue), 2); } pointMat.release(); } @@ -126,7 +126,7 @@ public class Draw3dTargetsPipe // floor, then pillars, then top for (int i = 0; i < bottomPoints.size(); i++) { Imgproc.line( - in.getLeft(), + in.getFirst(), bottomPoints.get(i), bottomPoints.get((i + 1) % (bottomPoints.size())), ColorHelper.colorToScalar(Color.green), @@ -167,21 +167,21 @@ public class Draw3dTargetsPipe // XYZ is RGB // y-axis = green Imgproc.line( - in.getLeft(), + in.getFirst(), axisPoints.get(0), axisPoints.get(2), ColorHelper.colorToScalar(Color.GREEN), 3); // z-axis = blue Imgproc.line( - in.getLeft(), + in.getFirst(), axisPoints.get(0), axisPoints.get(3), ColorHelper.colorToScalar(Color.BLUE), 3); // x-axis = red Imgproc.line( - in.getLeft(), + in.getFirst(), axisPoints.get(0), axisPoints.get(1), ColorHelper.colorToScalar(Color.RED), @@ -190,7 +190,7 @@ public class Draw3dTargetsPipe // box edges perpendicular to tag for (int i = 0; i < bottomPoints.size(); i++) { Imgproc.line( - in.getLeft(), + in.getFirst(), bottomPoints.get(i), topPoints.get(i), ColorHelper.colorToScalar(Color.blue), @@ -199,7 +199,7 @@ public class Draw3dTargetsPipe // box edges parallel to tag for (int i = 0; i < topPoints.size(); i++) { Imgproc.line( - in.getLeft(), + in.getFirst(), topPoints.get(i), topPoints.get((i + 1) % (bottomPoints.size())), ColorHelper.colorToScalar(Color.orange), @@ -219,7 +219,7 @@ public class Draw3dTargetsPipe var y = corner.y / (double) params.divisor.value; Imgproc.circle( - in.getLeft(), + in.getFirst(), new Point(x, y), params.radius, ColorHelper.colorToScalar(params.color), diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java index c9112f445..5f6b83a17 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/DrawCalibrationPipe.java @@ -17,9 +17,9 @@ package org.photonvision.vision.pipe.impl; +import edu.wpi.first.math.Pair; import java.awt.Color; import java.util.List; -import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Mat; import org.opencv.core.Point; import org.opencv.core.Scalar; @@ -44,7 +44,7 @@ public class DrawCalibrationPipe protected Void process(Pair> in) { if (!params.drawAllSnapshots()) return null; - var image = in.getLeft(); + var image = in.getFirst(); var imgSz = image.size(); var diag = Math.hypot(imgSz.width, imgSz.height); @@ -55,7 +55,7 @@ public class DrawCalibrationPipe int thickness = (int) Math.max(diag * 1.0 / 600.0, 1); int i = 0; - for (var target : in.getRight()) { + for (var target : in.getSecond()) { for (var c : target.getTargetCorners()) { if (c.x < 0 || c.y < 0) { // Skip if the corner is less than zero diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java index 93a5511bb..357782a21 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java @@ -17,10 +17,10 @@ package org.photonvision.vision.pipe.impl; +import edu.wpi.first.math.Pair; import java.util.ArrayList; import java.util.Arrays; import java.util.List; -import org.apache.commons.lang3.tuple.Pair; import org.opencv.calib3d.Calib3d; import org.opencv.core.*; import org.opencv.imgproc.Imgproc; @@ -244,8 +244,8 @@ public class FindBoardCornersPipe var objPts = new MatOfPoint3f(); var outBoardCorners = new MatOfPoint2f(); - var inFrame = in.getLeft(); - var outFrame = in.getRight(); + var inFrame = in.getFirst(); + var outFrame = in.getSecond(); // Convert the inFrame too grayscale to increase contrast Imgproc.cvtColor(inFrame, inFrame, Imgproc.COLOR_BGR2GRAY); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java index 6631a032e..08277f0d2 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindCirclesPipe.java @@ -17,9 +17,9 @@ package org.photonvision.vision.pipe.impl; +import edu.wpi.first.math.Pair; import java.util.ArrayList; import java.util.List; -import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Mat; import org.opencv.core.Point; import org.opencv.imgproc.Imgproc; @@ -54,7 +54,7 @@ public class FindCirclesPipe var maxRadius = (int) (params.maxRadius() * diag / 100.0); Imgproc.HoughCircles( - in.getLeft(), + in.getFirst(), circles, // Detection method, see #HoughModes. The available methods are #HOUGH_GRADIENT and // #HOUGH_GRADIENT_ALT. @@ -76,7 +76,7 @@ public class FindCirclesPipe // only match against them // This does mean that contours closer than allowableThreshold aren't matched to anything if // there's a 'better' option - var unmatchedContours = in.getRight(); + var unmatchedContours = in.getSecond(); for (int x = 0; x < circles.cols(); x++) { // Grab the current circle we are looking at double[] c = circles.get(0, x); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java index ec4f1e609..d951bdaba 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java @@ -17,12 +17,12 @@ package org.photonvision.vision.pipeline; +import edu.wpi.first.math.Pair; import edu.wpi.first.math.util.Units; import java.nio.file.Path; import java.util.ArrayList; import java.util.List; import java.util.stream.Collectors; -import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Mat; import org.opencv.core.Point; import org.photonvision.common.dataflow.DataChangeService; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java index cefcddce1..9a66708b4 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java @@ -17,10 +17,10 @@ package org.photonvision.vision.pipeline; +import edu.wpi.first.math.Pair; import java.util.Arrays; import java.util.List; import java.util.stream.Collectors; -import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Point; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameThresholdType; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/DriverModePipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/DriverModePipeline.java index 856c03579..7d87c9a28 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/DriverModePipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/DriverModePipeline.java @@ -17,8 +17,8 @@ package org.photonvision.vision.pipeline; +import edu.wpi.first.math.Pair; import java.util.List; -import org.apache.commons.lang3.tuple.Pair; import org.photonvision.common.util.math.MathUtils; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameThresholdType; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java index da2c40097..fb4d6ba4f 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java @@ -17,8 +17,8 @@ package org.photonvision.vision.pipeline; +import edu.wpi.first.math.Pair; import java.util.List; -import org.apache.commons.lang3.tuple.Pair; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameStaticProperties; import org.photonvision.vision.opencv.DualOffsetValues; diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java index d40e0d75b..dfbe2808e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java @@ -17,11 +17,11 @@ package org.photonvision.vision.processes; +import edu.wpi.first.math.Pair; import java.util.ArrayList; import java.util.List; import java.util.Map; import java.util.concurrent.locks.ReentrantLock; -import org.apache.commons.lang3.tuple.Pair; import org.opencv.core.Point; import org.photonvision.common.dataflow.DataChangeSubscriber; import org.photonvision.common.dataflow.events.DataChangeEvent; @@ -173,8 +173,8 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { } public void newPipelineInfo(Pair typeName) { - var type = typeName.getRight(); - var name = typeName.getLeft(); + var type = typeName.getSecond(); + var name = typeName.getFirst(); logger.info("Adding a " + type + " pipeline with name " + name); diff --git a/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java b/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java index 67243f4a3..dc7a6b5c8 100644 --- a/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java @@ -20,6 +20,7 @@ package org.photonvision.server; import com.fasterxml.jackson.core.JsonProcessingException; import com.fasterxml.jackson.core.type.TypeReference; import com.fasterxml.jackson.databind.ObjectMapper; +import edu.wpi.first.math.Pair; import io.javalin.websocket.WsBinaryMessageContext; import io.javalin.websocket.WsCloseContext; import io.javalin.websocket.WsConnectContext; @@ -33,7 +34,6 @@ import java.util.HashMap; import java.util.List; import java.util.Map; import java.util.concurrent.CopyOnWriteArrayList; -import org.apache.commons.lang3.tuple.Pair; import org.msgpack.jackson.dataformat.MessagePackFactory; import org.photonvision.common.dataflow.DataChangeDestination; import org.photonvision.common.dataflow.DataChangeService; diff --git a/shared/common.gradle b/shared/common.gradle index 62aa78dae..6a0cf794c 100644 --- a/shared/common.gradle +++ b/shared/common.gradle @@ -44,8 +44,6 @@ dependencies { implementation "commons-io:commons-io:2.11.0" implementation "commons-cli:commons-cli:1.5.0" - implementation "org.apache.commons:commons-lang3:3.12.0" - implementation "org.apache.commons:commons-collections4:4.4" implementation "org.apache.commons:commons-exec:1.3" testImplementation 'org.junit.jupiter:junit-jupiter-api:5.10.0' From 75dee20d770198541736ee2b828c2ded0e93a58c Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Thu, 27 Mar 2025 08:22:39 -0400 Subject: [PATCH 17/42] Move various printTestResults methods to TestUtils printTestResults was duplicated a lot, so it has been moved to TestUtils for maintainability. --- .../photonvision/common/util/TestUtils.java | 19 ++++++++++++++++++ .../vision/pipeline/AprilTagTest.java | 18 ++--------------- .../vision/pipeline/ArucoPipelineTest.java | 16 +-------------- .../vision/pipeline/CirclePNPTest.java | 18 ++--------------- .../pipeline/ColoredShapePipelineTest.java | 15 ++++---------- .../pipeline/ReflectivePipelineTest.java | 13 +++--------- .../vision/pipeline/SolvePNPTest.java | 20 +++---------------- .../processes/VisionModuleManagerTest.java | 9 +-------- 8 files changed, 35 insertions(+), 93 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java index ca1298905..bf189ff29 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java @@ -24,10 +24,13 @@ import java.awt.HeadlessException; import java.io.File; import java.io.IOException; import java.nio.file.Path; +import java.util.stream.Collectors; import org.opencv.core.Mat; import org.opencv.highgui.HighGui; import org.photonvision.jni.WpilibLoader; import org.photonvision.vision.calibration.CameraCalibrationCoefficients; +import org.photonvision.vision.pipeline.result.CVPipelineResult; +import org.photonvision.vision.target.TrackedTarget; public class TestUtils { public static boolean loadLibraries() { @@ -372,6 +375,22 @@ public class TestUtils { showImage(frame, DefaultTimeoutMillis); } + public static void printTestResults(CVPipelineResult pipelineResult) { + double fps = 1000 / pipelineResult.getLatencyMillis(); + System.out.print( + "Pipeline ran in " + pipelineResult.getLatencyMillis() + "ms (" + fps + " fps), "); + System.out.println("Found " + pipelineResult.targets.size() + " valid targets"); + } + + public static void printTestResultsWithLocation(CVPipelineResult pipelineResult) { + printTestResults(pipelineResult); + System.out.println( + "Found targets at " + + pipelineResult.targets.stream() + .map(TrackedTarget::getBestCameraToTarget3d) + .collect(Collectors.toList())); + } + public static Path getTestMode2023ImagePath() { return getResourcesFolderPath(true) .resolve("testimages") diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java index 24bffd6d5..94f1db534 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java @@ -18,7 +18,6 @@ package org.photonvision.vision.pipeline; import edu.wpi.first.math.geometry.Translation3d; -import java.util.stream.Collectors; import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; @@ -29,7 +28,6 @@ import org.photonvision.vision.camera.QuirkyCamera; import org.photonvision.vision.frame.provider.FileFrameProvider; import org.photonvision.vision.pipeline.result.CVPipelineResult; import org.photonvision.vision.target.TargetModel; -import org.photonvision.vision.target.TrackedTarget; public class AprilTagTest { @BeforeEach @@ -59,7 +57,7 @@ public class AprilTagTest { CVPipelineResult pipelineResult; pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResultsWithLocation(pipelineResult); // Draw on input var outputPipe = new OutputStreamPipeline(); @@ -124,7 +122,7 @@ public class AprilTagTest { CVPipelineResult pipelineResult; pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResultsWithLocation(pipelineResult); // Draw on input var outputPipe = new OutputStreamPipeline(); @@ -140,16 +138,4 @@ public class AprilTagTest { Assertions.assertEquals(2, pose.getTranslation().getY(), 0.2); Assertions.assertEquals(0.0, pose.getTranslation().getZ(), 0.2); } - - private static void printTestResults(CVPipelineResult pipelineResult) { - double fps = 1000 / pipelineResult.getLatencyMillis(); - System.out.println( - "Pipeline ran in " + pipelineResult.getLatencyMillis() + "ms (" + fps + " " + "fps)"); - System.out.println("Found " + pipelineResult.targets.size() + " valid targets"); - System.out.println( - "Found targets at " - + pipelineResult.targets.stream() - .map(TrackedTarget::getBestCameraToTarget3d) - .collect(Collectors.toList())); - } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java index 8a7a4af46..1c4ee4cef 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java @@ -18,7 +18,6 @@ package org.photonvision.vision.pipeline; import edu.wpi.first.math.geometry.Translation3d; -import java.util.stream.Collectors; import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; @@ -29,7 +28,6 @@ import org.photonvision.vision.camera.QuirkyCamera; import org.photonvision.vision.frame.provider.FileFrameProvider; import org.photonvision.vision.pipeline.result.CVPipelineResult; import org.photonvision.vision.target.TargetModel; -import org.photonvision.vision.target.TrackedTarget; public class ArucoPipelineTest { @BeforeEach @@ -59,7 +57,7 @@ public class ArucoPipelineTest { CVPipelineResult pipelineResult; pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResultsWithLocation(pipelineResult); // Draw on input var outputPipe = new OutputStreamPipeline(); @@ -102,16 +100,4 @@ public class ArucoPipelineTest { // The object's Z axis should be (0, 0, 1) Assertions.assertEquals(1, new Translation3d(0, 0, 1).rotateBy(pose.getRotation()).getZ(), 0.1); } - - private static void printTestResults(CVPipelineResult pipelineResult) { - double fps = 1000 / pipelineResult.getLatencyMillis(); - System.out.println( - "Pipeline ran in " + pipelineResult.getLatencyMillis() + "ms (" + fps + " " + "fps)"); - System.out.println("Found " + pipelineResult.targets.size() + " valid targets"); - System.out.println( - "Found targets at " - + pipelineResult.targets.stream() - .map(TrackedTarget::getBestCameraToTarget3d) - .collect(Collectors.toList())); - } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java index 9a4d392ad..35f02fc90 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/CirclePNPTest.java @@ -20,7 +20,6 @@ package org.photonvision.vision.pipeline; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertNotNull; -import java.util.stream.Collectors; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; import org.photonvision.common.util.TestUtils; @@ -34,7 +33,6 @@ import org.photonvision.vision.opencv.ContourIntersectionDirection; import org.photonvision.vision.opencv.ContourShape; import org.photonvision.vision.pipeline.result.CVPipelineResult; import org.photonvision.vision.target.TargetModel; -import org.photonvision.vision.target.TrackedTarget; public class CirclePNPTest { private static final String LIFECAM_240P_CAL_FILE = "lifecam240p.json"; @@ -111,7 +109,7 @@ public class CirclePNPTest { frameProvider.requestFrameThresholdType(pipeline.getThresholdType()); CVPipelineResult pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResultsWithLocation(pipelineResult); TestUtils.showImage( pipelineResult.inputAndOutputFrame.colorImage.getMat(), "Pipeline output", 999999); @@ -123,7 +121,7 @@ public class CirclePNPTest { while (true) { CVPipelineResult pipelineResult = pipeline.run(frame, QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResultsWithLocation(pipelineResult); int preRelease = CVMat.getMatCount(); pipelineResult.release(); int postRelease = CVMat.getMatCount(); @@ -151,16 +149,4 @@ public class CirclePNPTest { continuouslyRunPipeline(frameProvider.get(), settings); } - - private static void printTestResults(CVPipelineResult pipelineResult) { - double fps = 1000 / pipelineResult.getLatencyMillis(); - System.out.println( - "Pipeline ran in " + pipelineResult.getLatencyMillis() + "ms (" + fps + " " + "fps)"); - System.out.println("Found " + pipelineResult.targets.size() + " valid targets"); - System.out.println( - "Found targets at " - + pipelineResult.targets.stream() - .map(TrackedTarget::getBestCameraToTarget3d) - .collect(Collectors.toList())); - } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/ColoredShapePipelineTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/ColoredShapePipelineTest.java index b89618562..0e33c0fa3 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/ColoredShapePipelineTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/ColoredShapePipelineTest.java @@ -35,7 +35,7 @@ public class ColoredShapePipelineTest { TestUtils.showImage( colouredShapePipelineResult.inputAndOutputFrame.processedImage.getMat(), "Pipeline output: Triangle."); - printTestResults(colouredShapePipelineResult); + TestUtils.printTestResults(colouredShapePipelineResult); } public static void testQuadrilateralDetection( @@ -46,7 +46,7 @@ public class ColoredShapePipelineTest { TestUtils.showImage( colouredShapePipelineResult.inputAndOutputFrame.processedImage.getMat(), "Pipeline output: Quadrilateral."); - printTestResults(colouredShapePipelineResult); + TestUtils.printTestResults(colouredShapePipelineResult); } public static void testCustomShapeDetection( @@ -57,7 +57,7 @@ public class ColoredShapePipelineTest { TestUtils.showImage( colouredShapePipelineResult.inputAndOutputFrame.processedImage.getMat(), "Pipeline output: Custom."); - printTestResults(colouredShapePipelineResult); + TestUtils.printTestResults(colouredShapePipelineResult); } @Test @@ -69,7 +69,7 @@ public class ColoredShapePipelineTest { TestUtils.showImage( colouredShapePipelineResult.inputAndOutputFrame.processedImage.getMat(), "Pipeline output: Circle."); - printTestResults(colouredShapePipelineResult); + TestUtils.printTestResults(colouredShapePipelineResult); } @Test @@ -115,11 +115,4 @@ public class ColoredShapePipelineTest { // testCircleShapeDetection(pipeline, settings, frameProvider.get()); // testPowercellDetection(settings, pipeline); } - - private static void printTestResults(CVPipelineResult pipelineResult) { - double fps = 1000 / pipelineResult.getLatencyMillis(); - System.out.print( - "Pipeline ran in " + pipelineResult.getLatencyMillis() + "ms (" + fps + " fps), "); - System.out.println("Found " + pipelineResult.targets.size() + " valid targets"); - } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java index 0817cf37d..04ab24434 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java @@ -60,7 +60,7 @@ public class ReflectivePipelineTest { CVPipelineResult pipelineResult; pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResults(pipelineResult); Assertions.assertTrue(pipelineResult.hasTargets()); Assertions.assertEquals(2, pipelineResult.targets.size(), "Target count wrong!"); @@ -84,7 +84,7 @@ public class ReflectivePipelineTest { TestUtils.WPI2020Image.FOV); CVPipelineResult pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResults(pipelineResult); TestUtils.showImage( pipelineResult.inputAndOutputFrame.processedImage.getMat(), "Pipeline output"); @@ -95,7 +95,7 @@ public class ReflectivePipelineTest { while (true) { CVPipelineResult pipelineResult = pipeline.run(frame, QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResults(pipelineResult); int preRelease = CVMat.getMatCount(); pipelineResult.release(); int postRelease = CVMat.getMatCount(); @@ -123,11 +123,4 @@ public class ReflectivePipelineTest { continuouslyRunPipeline(frameProvider.get(), settings); } - - private static void printTestResults(CVPipelineResult pipelineResult) { - double fps = 1000 / pipelineResult.getLatencyMillis(); - System.out.print( - "Pipeline ran in " + pipelineResult.getLatencyMillis() + "ms (" + fps + " fps), "); - System.out.println("Found " + pipelineResult.targets.size() + " valid targets"); - } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/SolvePNPTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/SolvePNPTest.java index b205a7f9d..fad273df4 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/SolvePNPTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/SolvePNPTest.java @@ -24,7 +24,6 @@ import static org.junit.jupiter.api.Assertions.assertTrue; import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.util.Units; -import java.util.stream.Collectors; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; import org.photonvision.common.util.TestUtils; @@ -38,7 +37,6 @@ import org.photonvision.vision.opencv.ContourIntersectionDirection; import org.photonvision.vision.pipe.impl.HSVPipe; import org.photonvision.vision.pipeline.result.CVPipelineResult; import org.photonvision.vision.target.TargetModel; -import org.photonvision.vision.target.TrackedTarget; public class SolvePNPTest { private static final String LIFECAM_240P_CAL_FILE = "lifecam240p.json"; @@ -113,7 +111,7 @@ public class SolvePNPTest { frameProvider.requestHsvSettings(hsvParams); CVPipelineResult pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResultsWithLocation(pipelineResult); // Draw on input var outputPipe = new OutputStreamPipeline(); @@ -168,7 +166,7 @@ public class SolvePNPTest { frameProvider.requestHsvSettings(hsvParams); CVPipelineResult pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResultsWithLocation(pipelineResult); // Draw on input var outputPipe = new OutputStreamPipeline(); @@ -204,7 +202,7 @@ public class SolvePNPTest { while (true) { CVPipelineResult pipelineResult = pipeline.run(frame, QuirkyCamera.DefaultCamera); - printTestResults(pipelineResult); + TestUtils.printTestResultsWithLocation(pipelineResult); int preRelease = CVMat.getMatCount(); pipelineResult.release(); int postRelease = CVMat.getMatCount(); @@ -232,16 +230,4 @@ public class SolvePNPTest { continuouslyRunPipeline(frameProvider.get(), settings); } - - private static void printTestResults(CVPipelineResult pipelineResult) { - double fps = 1000 / pipelineResult.getLatencyMillis(); - System.out.println( - "Pipeline ran in " + pipelineResult.getLatencyMillis() + "ms (" + fps + " " + "fps)"); - System.out.println("Found " + pipelineResult.targets.size() + " valid targets"); - System.out.println( - "Found targets at " - + pipelineResult.targets.stream() - .map(TrackedTarget::getBestCameraToTarget3d) - .collect(Collectors.toList())); - } } diff --git a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java index 465cc9bc6..9a9195796 100644 --- a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java @@ -190,7 +190,7 @@ public class VisionModuleManagerTest { sleep(1500); Assertions.assertNotNull(module0DataConsumer.result); - printTestResults(module0DataConsumer.result); + TestUtils.printTestResults(module0DataConsumer.result); } @Test @@ -253,13 +253,6 @@ public class VisionModuleManagerTest { assertTrue(idxs.contains(4)); } - private static void printTestResults(CVPipelineResult pipelineResult) { - double fps = 1000 / pipelineResult.getLatencyMillis(); - System.out.print( - "Pipeline ran in " + pipelineResult.getLatencyMillis() + "ms (" + fps + " fps), "); - System.out.println("Found " + pipelineResult.targets.size() + " valid targets"); - } - private void sleep(int millis) { try { Thread.sleep(millis); From 23d5e5b34f43500a4ffb64ad6a624fdf478c1760 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 30 Mar 2025 00:15:32 -0400 Subject: [PATCH 18/42] Remove blacklistedResIndices from HardwareConfig Matt says this was for mmal, and we use libcamera now, so this is unnecessary now. Also, the filtering logic that used blacklistedResIndices was completely broken. --- .../photonvision/common/configuration/HardwareConfig.java | 8 ++------ .../camera/USBCameras/GenericUSBCameraSettables.java | 8 -------- 2 files changed, 2 insertions(+), 14 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/HardwareConfig.java b/photon-core/src/main/java/org/photonvision/common/configuration/HardwareConfig.java index 7d008f94f..be053241a 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/HardwareConfig.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/HardwareConfig.java @@ -19,8 +19,6 @@ package org.photonvision.common.configuration; import com.fasterxml.jackson.annotation.JsonIgnoreProperties; import java.util.ArrayList; -import java.util.Collections; -import java.util.List; @JsonIgnoreProperties(ignoreUnknown = true) public record HardwareConfig( @@ -49,8 +47,7 @@ public record HardwareConfig( String diskUsageCommand, // Device stuff String restartHardwareCommand, - double vendorFOV, // -1 for unmanaged - List blacklistedResIndices) { // this happens before the defaults are applied) + double vendorFOV) { // -1 for unmanaged public HardwareConfig() { this( @@ -74,8 +71,7 @@ public record HardwareConfig( "", // gpuMemUsageCommand "", // diskUsageCommand "", // restartHardwareCommand - -1, // vendorFOV - Collections.emptyList()); // blacklistedResIndices + -1); // vendorFOV } /** diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java index 158b2bf43..417dfde24 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java @@ -31,7 +31,6 @@ import java.util.List; import java.util.Optional; import java.util.stream.Collectors; import org.photonvision.common.configuration.CameraConfiguration; -import org.photonvision.common.configuration.ConfigManager; import org.photonvision.vision.camera.CameraQuirk; import org.photonvision.vision.processes.VisionSourceSettables; @@ -306,13 +305,6 @@ public class GenericUSBCameraSettables extends VisionSourceSettables { .collect(Collectors.toList()); Collections.reverse(sortedList); - // On vendor cameras, respect blacklisted indices - var indexBlacklist = - ConfigManager.getInstance().getConfig().getHardwareConfig().blacklistedResIndices(); - for (int badIdx : indexBlacklist) { - sortedList.remove(badIdx); - } - for (VideoMode videoMode : sortedList) { videoModes.put(sortedList.indexOf(videoMode), videoMode); } From 38ee450117e50870f30d3aae4d94e550f23e695c Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Thu, 27 Mar 2025 08:17:07 -0400 Subject: [PATCH 19/42] Use toList instead of collect(Collectors.toList()) when the list is definitely never modified --- .../configuration/LegacyConfigProvider.java | 7 ++--- .../configuration/SqlConfigProvider.java | 2 +- .../websocket/UIPhotonConfiguration.java | 3 +-- .../common/networking/NetworkUtils.java | 26 +++++++++++++------ .../photonvision/common/util/TestUtils.java | 5 +--- .../UICameraCalibrationCoefficients.java | 5 ++-- .../USBCameras/GenericUSBCameraSettables.java | 7 ++--- .../vision/pipe/impl/Calibrate3dPipe.java | 15 +++++------ .../vision/pipe/impl/FindContoursPipe.java | 3 +-- .../vision/pipeline/Calibrate3dPipeline.java | 5 +--- .../vision/pipeline/ColoredShapePipeline.java | 3 +-- .../pipeline/ObjectDetectionPipeline.java | 5 +--- .../result/CalibrationPipelineResult.java | 3 +-- .../vision/processes/VisionModuleManager.java | 5 +--- .../pipeline/CalibrationRotationPipeTest.java | 9 +++---- .../processes/VisionModuleManagerTest.java | 8 ++---- .../java/org/photonvision/PhotonCamera.java | 3 +-- .../simulation/VisionSystemSim.java | 6 +---- 18 files changed, 47 insertions(+), 73 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java b/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java index 6c2dca8cc..f82e6f914 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/LegacyConfigProvider.java @@ -32,7 +32,6 @@ import java.time.LocalDateTime; import java.time.format.DateTimeFormatter; import java.time.temporal.TemporalAccessor; import java.util.*; -import java.util.stream.Collectors; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; import org.photonvision.common.util.file.FileUtils; @@ -280,9 +279,7 @@ class LegacyConfigProvider extends ConfigProvider { HashMap loadedConfigurations = new HashMap<>(); try { var subdirectories = - Files.list(camerasFolder.toPath()) - .filter(f -> f.toFile().isDirectory()) - .collect(Collectors.toList()); + Files.list(camerasFolder.toPath()).filter(f -> f.toFile().isDirectory()).toList(); for (var subdir : subdirectories) { var cameraConfigPath = Path.of(subdir.toString(), "config.json"); @@ -348,7 +345,7 @@ class LegacyConfigProvider extends ConfigProvider { return null; }) .filter(Objects::nonNull) - .collect(Collectors.toList()) + .toList() : Collections.emptyList(); loadedConfig.driveModeSettings = driverMode; diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java index d2808bb3c..bae7c4ced 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/SqlConfigProvider.java @@ -398,7 +398,7 @@ public class SqlConfigProvider extends ConfigProvider { } }) .filter(Objects::nonNull) - .collect(Collectors.toList()); + .toList(); statement.setString(4, JacksonUtils.serializeToString(settings)); statement.executeUpdate(); diff --git a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java index 50ec04576..4d5758bf7 100644 --- a/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java +++ b/photon-core/src/main/java/org/photonvision/common/dataflow/websocket/UIPhotonConfiguration.java @@ -18,7 +18,6 @@ package org.photonvision.common.dataflow.websocket; import java.util.List; -import java.util.stream.Collectors; import org.photonvision.PhotonVersion; import org.photonvision.common.configuration.NeuralNetworkModelManager; import org.photonvision.common.configuration.PhotonConfiguration; @@ -64,6 +63,6 @@ public class UIPhotonConfiguration { c.getApriltagFieldLayout()), VisionSourceManager.getInstance().getVisionModules().stream() .map(VisionModule::toUICameraConfig) - .collect(Collectors.toList())); + .toList()); } } diff --git a/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java b/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java index f34d91f9a..fa24c4e66 100644 --- a/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/networking/NetworkUtils.java @@ -23,7 +23,6 @@ import java.util.ArrayList; import java.util.List; import java.util.regex.Matcher; import java.util.regex.Pattern; -import java.util.stream.Collectors; import org.photonvision.common.hardware.Platform; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; @@ -108,24 +107,35 @@ public class NetworkUtils { return ret; } + /** + * Returns an immutable list of active network interfaces. + * + * @return The list. + */ public static List getAllActiveInterfaces() { // Seems like if an interface exists but isn't actually connected, the connection name will be // an empty string. Check here and only return connections with non-empty names - return getAllInterfaces().stream() - .filter(it -> !it.connName.trim().isEmpty()) - .collect(Collectors.toList()); + return getAllInterfaces().stream().filter(it -> !it.connName.trim().isEmpty()).toList(); } + /** + * Returns an immutable list of all wired network interfaces. + * + * @return The list. + */ public static List getAllWiredInterfaces() { return getAllInterfaces().stream() .filter(it -> it.nmType.equals(NMType.NMTYPE_ETHERNET)) - .collect(Collectors.toList()); + .toList(); } + /** + * Returns an immutable list of all wired and active network interfaces. + * + * @return The list. + */ public static List getAllActiveWiredInterfaces() { - return getAllWiredInterfaces().stream() - .filter(it -> !it.connName.isBlank()) - .collect(Collectors.toList()); + return getAllWiredInterfaces().stream().filter(it -> !it.connName.isBlank()).toList(); } public static NMDeviceInfo getNMinfoForConnName(String connName) { diff --git a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java index bf189ff29..44e7e33ce 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java @@ -24,7 +24,6 @@ import java.awt.HeadlessException; import java.io.File; import java.io.IOException; import java.nio.file.Path; -import java.util.stream.Collectors; import org.opencv.core.Mat; import org.opencv.highgui.HighGui; import org.photonvision.jni.WpilibLoader; @@ -386,9 +385,7 @@ public class TestUtils { printTestResults(pipelineResult); System.out.println( "Found targets at " - + pipelineResult.targets.stream() - .map(TrackedTarget::getBestCameraToTarget3d) - .collect(Collectors.toList())); + + pipelineResult.targets.stream().map(TrackedTarget::getBestCameraToTarget3d).toList()); } public static Path getTestMode2023ImagePath() { diff --git a/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java b/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java index 14cbfa51e..c02d48d15 100644 --- a/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java +++ b/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java @@ -18,11 +18,12 @@ package org.photonvision.vision.calibration; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Size; public class UICameraCalibrationCoefficients extends CameraCalibrationCoefficients { public int numSnapshots; + + /** Immutable list of mean errors. */ public List meanErrors; public UICameraCalibrationCoefficients( @@ -54,6 +55,6 @@ public class UICameraCalibrationCoefficients extends CameraCalibrationCoefficien .mapToDouble(it -> Math.sqrt(it.x * it.x + it.y * it.y)) .average() .orElse(0)) - .collect(Collectors.toList()); + .toList(); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java index 417dfde24..a14218fa6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java @@ -25,11 +25,9 @@ import edu.wpi.first.math.MathUtil; import edu.wpi.first.util.PixelFormat; import java.util.ArrayList; import java.util.Arrays; -import java.util.Collections; import java.util.HashMap; import java.util.List; import java.util.Optional; -import java.util.stream.Collectors; import org.photonvision.common.configuration.CameraConfiguration; import org.photonvision.vision.camera.CameraQuirk; import org.photonvision.vision.processes.VisionSourceSettables; @@ -301,9 +299,8 @@ public class GenericUSBCameraSettables extends VisionSourceSettables { var sortedList = videoModesList.stream() .distinct() // remove redundant video mode entries - .sorted(((a, b) -> (b.width + b.height) - (a.width + a.height))) - .collect(Collectors.toList()); - Collections.reverse(sortedList); + .sorted(((a, b) -> (a.width + a.height) - (b.width + b.height))) + .toList(); for (VideoMode videoMode : sortedList) { videoModes.put(sortedList.indexOf(videoMode), videoMode); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java index 428a64362..bfa96c5a3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/Calibrate3dPipe.java @@ -89,7 +89,7 @@ public class Calibrate3dPipe && it.imagePoints != null && it.objectPoints != null && it.size != null) - .collect(Collectors.toList()); + .toList(); CameraCalibrationCoefficients ret; var start = System.nanoTime(); @@ -134,11 +134,9 @@ public class Calibrate3dPipe double fxGuess, double fyGuess, Path imageSavePath) { - List objPointsIn = - in.stream().map(it -> it.objectPoints).collect(Collectors.toList()); - List imgPointsIn = - in.stream().map(it -> it.imagePoints).collect(Collectors.toList()); - List levelsArr = in.stream().map(it -> it.levels).collect(Collectors.toList()); + List objPointsIn = in.stream().map(it -> it.objectPoints).toList(); + List imgPointsIn = in.stream().map(it -> it.imagePoints).toList(); + List levelsArr = in.stream().map(it -> it.levels).toList(); if (objPointsIn.size() != imgPointsIn.size() || objPointsIn.size() != levelsArr.size()) { logger.error("objpts.size != imgpts.size"); @@ -223,10 +221,9 @@ public class Calibrate3dPipe double fyGuess, Path imageSavePath) { List corner_locations = - in.stream().map(it -> it.imagePoints).map(MatOfPoint2f::new).collect(Collectors.toList()); + in.stream().map(it -> it.imagePoints).map(MatOfPoint2f::new).toList(); - List levels = - in.stream().map(it -> it.levels).map(MatOfFloat::new).collect(Collectors.toList()); + List levels = in.stream().map(it -> it.levels).map(MatOfFloat::new).toList(); int imageWidth = (int) in.get(0).size.width; int imageHeight = (int) in.get(0).size.height; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java index d5564d63f..3181a637b 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindContoursPipe.java @@ -19,7 +19,6 @@ package org.photonvision.vision.pipe.impl; import java.util.ArrayList; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Mat; import org.opencv.core.MatOfPoint; import org.opencv.imgproc.Imgproc; @@ -40,7 +39,7 @@ public class FindContoursPipe Imgproc.findContours( in, m_foundContours, new Mat(), Imgproc.RETR_EXTERNAL, Imgproc.CHAIN_APPROX_TC89_KCOS); - return m_foundContours.stream().map(Contour::new).collect(Collectors.toList()); + return m_foundContours.stream().map(Contour::new).toList(); } public static class FindContoursParams {} diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java index d951bdaba..399869df1 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/Calibrate3dPipeline.java @@ -22,7 +22,6 @@ import edu.wpi.first.math.util.Units; import java.nio.file.Path; import java.util.ArrayList; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Mat; import org.opencv.core.Point; import org.photonvision.common.dataflow.DataChangeService; @@ -166,9 +165,7 @@ public class Calibrate3dPipeline } List> getCornersList() { - return foundCornersList.stream() - .map(it -> it.imagePoints.toList()) - .collect(Collectors.toList()); + return foundCornersList.stream().map(it -> it.imagePoints.toList()).toList(); } public boolean hasEnough() { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java index 9a66708b4..fd1753f1a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ColoredShapePipeline.java @@ -20,7 +20,6 @@ package org.photonvision.vision.pipeline; import edu.wpi.first.math.Pair; import java.util.Arrays; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Point; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameThresholdType; @@ -199,7 +198,7 @@ public class ColoredShapePipeline sortContoursPipe.run( filterShapeResult.output.stream() .map(shape -> new PotentialTarget(shape.getContour(), shape)) - .collect(Collectors.toList())); + .toList()); sumPipeNanosElapsed += sortContoursResult.nanosElapsed; CVPipeResult> collect2dTargetsResult = diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java index c0e9fa424..640c66759 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ObjectDetectionPipeline.java @@ -19,7 +19,6 @@ package org.photonvision.vision.pipeline; import java.util.List; import java.util.Optional; -import java.util.stream.Collectors; import org.photonvision.common.configuration.NeuralNetworkModelManager; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.frame.FrameThresholdType; @@ -127,9 +126,7 @@ public class ObjectDetectionPipeline CVPipeResult> sortContoursResult = sortContoursPipe.run( - filterContoursResult.output.stream() - .map(shape -> new PotentialTarget(shape)) - .collect(Collectors.toList())); + filterContoursResult.output.stream().map(shape -> new PotentialTarget(shape)).toList()); sumPipeNanosElapsed += sortContoursResult.nanosElapsed; CVPipeResult> collect2dTargetsResult = diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CalibrationPipelineResult.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CalibrationPipelineResult.java index a06bd8443..acf895c50 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CalibrationPipelineResult.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/result/CalibrationPipelineResult.java @@ -18,14 +18,13 @@ package org.photonvision.vision.pipeline.result; import java.util.List; -import java.util.stream.Collectors; import org.opencv.core.Point; import org.photonvision.vision.frame.Frame; import org.photonvision.vision.target.TrackedTarget; public class CalibrationPipelineResult extends CVPipelineResult { private static List cornersToTarget(List> corners) { - return corners.stream().map(TrackedTarget::new).collect(Collectors.toList()); + return corners.stream().map(TrackedTarget::new).toList(); } public CalibrationPipelineResult( diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java index 35c727eba..7eb3c8621 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleManager.java @@ -18,7 +18,6 @@ package org.photonvision.vision.processes; import java.util.*; -import java.util.stream.Collectors; import org.photonvision.common.logging.LogGroup; import org.photonvision.common.logging.Logger; @@ -67,9 +66,7 @@ public class VisionModuleManager { // Big list, which should contain every vision source (currently loaded plus the new ones being // added) List bigList = - this.getModules().stream() - .map(it -> it.getCameraConfiguration().streamIndex) - .collect(Collectors.toList()); + this.getModules().stream().map(it -> it.getCameraConfiguration().streamIndex).toList(); int idx = 0; while (bigList.contains(idx)) { diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java index 8e9f52c2b..1d7b9faa4 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java @@ -23,7 +23,6 @@ import static org.junit.jupiter.api.Assertions.assertEquals; import java.io.IOException; import java.util.Arrays; import java.util.List; -import java.util.stream.Collectors; import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Test; @@ -151,13 +150,13 @@ public class CalibrationRotationPipeTest { var rotatedDistortedPoints = distortedOriginalPoints.stream() .map(it -> rot.rotatePoint(it, frameProps.imageWidth, frameProps.imageHeight)) - .collect(Collectors.toList()); + .toList(); // Now let's instead rotate then distort var rotatedOriginalPoints = Arrays.stream(originalPoints) .map(it -> rot.rotatePoint(it, frameProps.imageWidth, frameProps.imageHeight)) - .collect(Collectors.toList()); + .toList(); var distortedRotatedPoints = OpenCVHelp.distortPoints( @@ -310,9 +309,7 @@ public class CalibrationRotationPipeTest { // rotate and try again var rotAngle = ImageRotationMode.DEG_90_CCW; var rotatedDistortedPoints = - distortedCorners.stream() - .map(it -> rotAngle.rotatePoint(it, 1280, 720)) - .collect(Collectors.toList()); + distortedCorners.stream().map(it -> rotAngle.rotatePoint(it, 1280, 720)).toList(); pipe.setParams( new SolvePNPPipeParams( coeffs.rotateCoefficients(rotAngle), TargetModel.kAprilTag6p5in_36h11)); diff --git a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java index 9a9195796..32d8ec762 100644 --- a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java @@ -25,7 +25,6 @@ import java.io.IOException; import java.util.Arrays; import java.util.HashMap; import java.util.List; -import java.util.stream.Collectors; import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Test; @@ -233,15 +232,12 @@ public class VisionModuleManagerTest { var modules = List.of(testSource, testSource2, testSource3, usbSimulation, usbSimulation2).stream() .map(vmm::addSource) - .collect(Collectors.toList()); + .toList(); System.out.println( Arrays.toString( modules.stream().map(it -> it.getCameraConfiguration().streamIndex).toArray())); - var idxs = - modules.stream() - .map(it -> it.getCameraConfiguration().streamIndex) - .collect(Collectors.toList()); + var idxs = modules.stream().map(it -> it.getCameraConfiguration().streamIndex).toList(); assertTrue(usbSimulation.equals(usbSimulation)); assertTrue(!usbSimulation.equals(usbSimulation2)); diff --git a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java index 00b04b753..198c38732 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonCamera.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonCamera.java @@ -50,7 +50,6 @@ import java.util.ArrayList; import java.util.Arrays; import java.util.List; import java.util.Optional; -import java.util.stream.Collectors; import org.opencv.core.Core; import org.photonvision.common.hardware.VisionLEDMode; import org.photonvision.common.networktables.PacketSubscriber; @@ -594,6 +593,6 @@ public class PhotonCamera implements AutoCloseable { it -> { return rootPhotonTable.getSubTable(it).getEntry("rawBytes").exists(); }) - .collect(Collectors.toList()); + .toList(); } } diff --git a/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java b/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java index b61b93946..7aa7ff1c2 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/VisionSystemSim.java @@ -41,7 +41,6 @@ import java.util.List; import java.util.Map; import java.util.Optional; import java.util.Set; -import java.util.stream.Collectors; import org.photonvision.PhotonCamera; import org.photonvision.estimation.TargetModel; @@ -357,10 +356,7 @@ public class VisionSystemSim { entry -> dbgField .getObject(entry.getKey()) - .setPoses( - entry.getValue().stream() - .map(t -> t.getPose().toPose2d()) - .collect(Collectors.toList()))); + .setPoses(entry.getValue().stream().map(t -> t.getPose().toPose2d()).toList())); if (robotPoseMeters == null) return; From e514071094ce8e2f9035dd02726e266d41729130 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 30 Mar 2025 01:30:43 -0400 Subject: [PATCH 20/42] Use Math.hypot instead of Math.sqrt(a^2 + b^2) --- .../vision/calibration/UICameraCalibrationCoefficients.java | 2 +- .../photonvision/vision/pipe/impl/CornerDetectionPipe.java | 4 +--- .../photonvision/vision/pipe/impl/FindBoardCornersPipe.java | 4 +--- .../org/photonvision/vision/pipe/impl/SortContoursPipe.java | 6 +++--- .../org/photonvision/simulation/SimCameraProperties.java | 2 +- 5 files changed, 7 insertions(+), 11 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java b/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java index c02d48d15..123b1063d 100644 --- a/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java +++ b/photon-core/src/main/java/org/photonvision/vision/calibration/UICameraCalibrationCoefficients.java @@ -52,7 +52,7 @@ public class UICameraCalibrationCoefficients extends CameraCalibrationCoefficien .map( it2 -> it2.reprojectionErrors.stream() - .mapToDouble(it -> Math.sqrt(it.x * it.x + it.y * it.y)) + .mapToDouble(it -> Math.hypot(it.x, it.y)) .average() .orElse(0)) .toList(); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java index def6aeda1..5508154b0 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java @@ -85,9 +85,7 @@ public class CornerDetectionPipe * @return The straight line distance between them. */ private static double distanceBetween(Point a, Point b) { - double xDelta = a.x - b.x; - double yDelta = a.y - b.y; - return Math.sqrt(xDelta * xDelta + yDelta * yDelta); + return Math.hypot(a.x - b.x, a.y - b.y); } /** diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java index 357782a21..fb2dd3b8b 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java @@ -170,9 +170,7 @@ public class FindBoardCornersPipe // +1 idx Neighbor distance double[] startPoint = inPoints.get(pointIdx, 0); double[] endPoint = inPoints.get(pointIdx + 1, 0); - double deltaX = startPoint[0] - endPoint[0]; - double deltaY = startPoint[1] - endPoint[1]; - double distToNext = Math.sqrt(deltaX * deltaX + deltaY * deltaY); + double distToNext = Math.hypot(startPoint[0] - endPoint[0], startPoint[1] - endPoint[1]); minSpacing = Math.min(distToNext, minSpacing); } diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java index e9abc1ae9..8be3116bd 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/SortContoursPipe.java @@ -51,9 +51,9 @@ public class SortContoursPipe } private double calcSquareCenterDistance(PotentialTarget tgt) { - return Math.sqrt( - Math.pow(params.frameStaticProperties().centerX - tgt.getMinAreaRect().center.x, 2) - + Math.pow(params.frameStaticProperties().centerY - tgt.getMinAreaRect().center.y, 2)); + return Math.hypot( + params.frameStaticProperties().centerX - tgt.getMinAreaRect().center.x, + params.frameStaticProperties().centerY - tgt.getMinAreaRect().center.y); } public static record SortContoursParams( diff --git a/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java b/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java index eb6414145..7e806e159 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/SimCameraProperties.java @@ -171,7 +171,7 @@ public class SimCameraProperties { DriverStation.reportError( "Requested invalid FOV! Clamping between (1, 179) degrees...", false); } - double resDiag = Math.sqrt(resWidth * resWidth + resHeight * resHeight); + double resDiag = Math.hypot(resWidth, resHeight); double diagRatio = Math.tan(fovDiag.getRadians() / 2); var fovWidth = new Rotation2d(Math.atan(diagRatio * (resWidth / resDiag)) * 2); var fovHeight = new Rotation2d(Math.atan(diagRatio * (resHeight / resDiag)) * 2); From 89c0cc3a0188994895f5d83bd5327d07768afeb1 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 30 Mar 2025 20:25:11 -0400 Subject: [PATCH 21/42] Remove unnecessary assignment In places like pipelines or DataSocketHandler, objects were being instantiated and assigned to a variable, but were then passed into a method, never to be used again. For pipelines especially, that style of code wasn't always consistently used, and other pipelines skipped assignment and instantiated objects in the method call. Make everything consistent by always instantiating in the method call. GenericUSBCameraSettables also had an unnecessary assignment, and that was cleaned up too for readability. --- .../USBCameras/GenericUSBCameraSettables.java | 6 +- .../vision/pipeline/AprilTagPipeline.java | 4 +- .../vision/pipeline/ArucoPipeline.java | 11 +- .../vision/pipeline/Calibrate3dPipeline.java | 14 +- .../vision/pipeline/ColoredShapePipeline.java | 58 ++--- .../vision/pipeline/DriverModePipeline.java | 7 +- .../pipeline/ObjectDetectionPipeline.java | 21 +- .../vision/pipeline/OutputStreamPipeline.java | 35 ++- .../vision/pipeline/ReflectivePipeline.java | 38 ++- .../server/DataSocketHandler.java | 233 ++++++++---------- 10 files changed, 179 insertions(+), 248 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java index a14218fa6..bfe05e24a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java @@ -271,11 +271,7 @@ public class GenericUSBCameraSettables extends VisionSourceSettables { videoModes = new HashMap<>(); List videoModesList = new ArrayList<>(); try { - VideoMode[] modes; - - modes = camera.enumerateVideoModes(); - - for (VideoMode videoMode : modes) { + for (VideoMode videoMode : camera.enumerateVideoModes()) { // Filter grey modes if (videoMode.pixelFormat == PixelFormat.kGray || videoMode.pixelFormat == PixelFormat.kUnknown) { diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java index f5cd52c26..3e98f7e9e 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/AprilTagPipeline.java @@ -134,8 +134,8 @@ public class AprilTagPipeline extends CVPipeline> tagDetectionPipeResult; - tagDetectionPipeResult = aprilTagDetectionPipe.run(frame.processedImage); + CVPipeResult> tagDetectionPipeResult = + aprilTagDetectionPipe.run(frame.processedImage); sumPipeNanosElapsed += tagDetectionPipeResult.nanosElapsed; List detections = tagDetectionPipeResult.output; diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java index 8395054a1..b0a4505a6 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/ArucoPipeline.java @@ -145,8 +145,8 @@ public class ArucoPipeline extends CVPipeline> tagDetectionPipeResult; - tagDetectionPipeResult = arucoDetectionPipe.run(frame.processedImage); + CVPipeResult> tagDetectionPipeResult = + arucoDetectionPipe.run(frame.processedImage); sumPipeNanosElapsed += tagDetectionPipeResult.nanosElapsed; // If we want to debug the thresholding steps, draw the first step to the color image @@ -163,14 +163,13 @@ public class ArucoPipeline extends CVPipeline { - // TODO: what is this event? - var data = (Boolean) entryValue; - var dmIsDriverEvent = - new IncomingWebSocketEvent( - DataChangeDestination.DCD_ACTIVEMODULE, - "isDriverMode", - data, - cameraUniqueName, - context); - - dcService.publishEvents(dmIsDriverEvent); - } - case SMT_CHANGECAMERANAME -> { - var ccnEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "cameraNickname", - (String) entryValue, - cameraUniqueName, - context); - dcService.publishEvent(ccnEvent); - } - case SMT_CHANGEPIPELINENAME -> { - var cpnEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "pipelineName", - (String) entryValue, - cameraUniqueName, - context); - dcService.publishEvent(cpnEvent); - } + case SMT_DRIVERMODE -> // TODO: what is this event? + dcService.publishEvents( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "isDriverMode", + (Boolean) entryValue, + cameraUniqueName, + context)); + case SMT_CHANGECAMERANAME -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "cameraNickname", + (String) entryValue, + cameraUniqueName, + context)); + case SMT_CHANGEPIPELINENAME -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "pipelineName", + (String) entryValue, + cameraUniqueName, + context)); case SMT_ADDNEWPIPELINE -> { // HashMap data = (HashMap) entryValue; // var type = (PipelineType) data.get("pipelineType"); @@ -168,109 +159,90 @@ public class DataSocketHandler { var name = (String) arr.get(0); var type = PipelineType.values()[(Integer) arr.get(1) + 2]; - var newPipelineEvent = + dcService.publishEvent( new IncomingWebSocketEvent<>( DataChangeDestination.DCD_ACTIVEMODULE, "newPipelineInfo", Pair.of(name, type), cameraUniqueName, - context); - dcService.publishEvent(newPipelineEvent); - } - case SMT_CHANGEBRIGHTNESS -> { - HardwareManager.getInstance() - .setBrightnessPercent(Integer.parseInt(entryValue.toString())); + context)); } + case SMT_CHANGEBRIGHTNESS -> + HardwareManager.getInstance() + .setBrightnessPercent(Integer.parseInt(entryValue.toString())); case SMT_DUPLICATEPIPELINE -> { var pipeIndex = (Integer) entryValue; logger.info("Duplicating pipe@index" + pipeIndex + " for camera " + cameraUniqueName); - var newPipelineEvent = + dcService.publishEvent( new IncomingWebSocketEvent<>( DataChangeDestination.DCD_ACTIVEMODULE, "duplicatePipeline", pipeIndex, cameraUniqueName, - context); - dcService.publishEvent(newPipelineEvent); - } - case SMT_DELETECURRENTPIPELINE -> { - var deleteCurrentPipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "deleteCurrPipeline", - 0, - cameraUniqueName, - context); - dcService.publishEvent(deleteCurrentPipelineEvent); - } - case SMT_ROBOTOFFSETPOINT -> { - var robotOffsetPointEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "robotOffsetPoint", - (Integer) entryValue, - cameraUniqueName, - null); - dcService.publishEvent(robotOffsetPointEvent); - } - case SMT_CURRENTCAMERA -> { - var changeCurrentCameraEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_OTHER, "changeUICamera", (Integer) entryValue); - dcService.publishEvent(changeCurrentCameraEvent); - } - case SMT_CURRENTPIPELINE -> { - var changePipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "changePipeline", - (Integer) entryValue, - cameraUniqueName, - context); - dcService.publishEvent(changePipelineEvent); - } - case SMT_STARTPNPCALIBRATION -> { - var changePipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "startCalibration", - (Map) entryValue, - cameraUniqueName, - context); - dcService.publishEvent(changePipelineEvent); - } - case SMT_SAVEINPUTSNAPSHOT -> { - var takeInputSnapshotEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "saveInputSnapshot", - 0, - cameraUniqueName, - context); - dcService.publishEvent(takeInputSnapshotEvent); - } - case SMT_SAVEOUTPUTSNAPSHOT -> { - var takeOutputSnapshotEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "saveOutputSnapshot", - 0, - cameraUniqueName, - context); - dcService.publishEvent(takeOutputSnapshotEvent); - } - case SMT_TAKECALIBRATIONSNAPSHOT -> { - var takeCalSnapshotEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "takeCalSnapshot", - 0, - cameraUniqueName, - context); - dcService.publishEvent(takeCalSnapshotEvent); + context)); } + case SMT_DELETECURRENTPIPELINE -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "deleteCurrPipeline", + 0, + cameraUniqueName, + context)); + case SMT_ROBOTOFFSETPOINT -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "robotOffsetPoint", + (Integer) entryValue, + cameraUniqueName, + null)); + case SMT_CURRENTCAMERA -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_OTHER, "changeUICamera", (Integer) entryValue)); + case SMT_CURRENTPIPELINE -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "changePipeline", + (Integer) entryValue, + cameraUniqueName, + context)); + case SMT_STARTPNPCALIBRATION -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "startCalibration", + (Map) entryValue, + cameraUniqueName, + context)); + case SMT_SAVEINPUTSNAPSHOT -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "saveInputSnapshot", + 0, + cameraUniqueName, + context)); + case SMT_SAVEOUTPUTSNAPSHOT -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "saveOutputSnapshot", + 0, + cameraUniqueName, + context)); + case SMT_TAKECALIBRATIONSNAPSHOT -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "takeCalSnapshot", + 0, + cameraUniqueName, + context)); case SMT_PIPELINESETTINGCHANGE -> { HashMap data = (HashMap) entryValue; @@ -280,29 +252,26 @@ public class DataSocketHandler { if (dataEntry.getKey().equals("cameraUniqueName")) { continue; } - var pipelineSettingChangeEvent = + dcService.publishEvent( new IncomingWebSocketEvent( DataChangeDestination.DCD_ACTIVEPIPELINESETTINGS, dataEntry.getKey(), dataEntry.getValue(), cameraIndex2, - context); - dcService.publishEvent(pipelineSettingChangeEvent); + context)); } } else { logger.warn("Unknown message for PSC: " + data.keySet().iterator().next()); } } - case SMT_CHANGEPIPELINETYPE -> { - var changePipelineEvent = - new IncomingWebSocketEvent<>( - DataChangeDestination.DCD_ACTIVEMODULE, - "changePipelineType", - (Integer) entryValue, - cameraUniqueName, - context); - dcService.publishEvent(changePipelineEvent); - } + case SMT_CHANGEPIPELINETYPE -> + dcService.publishEvent( + new IncomingWebSocketEvent<>( + DataChangeDestination.DCD_ACTIVEMODULE, + "changePipelineType", + (Integer) entryValue, + cameraUniqueName, + context)); } } catch (Exception e) { logger.error("Failed to parse message!", e); From 7f7d80bc3bee06dd7211f943186661c1197de7cf Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 31 Mar 2025 17:53:11 -0400 Subject: [PATCH 22/42] Refactor switch case --- .../common/hardware/VisionLED.java | 8 +- .../vision/processes/PipelineManager.java | 107 +++++++----------- .../VisionModuleChangeSubscriber.java | 87 +++++++------- .../vision/target/TargetCalculations.java | 20 ++-- 4 files changed, 91 insertions(+), 131 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java b/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java index 52fb48a97..2a1af5086 100644 --- a/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java +++ b/photon-core/src/main/java/org/photonvision/common/hardware/VisionLED.java @@ -136,10 +136,10 @@ public class VisionLED { if (newLedModeRaw != currentLedMode.value) { VisionLEDMode newLedMode = switch (newLedModeRaw) { - case -1 -> newLedMode = VisionLEDMode.kDefault; - case 0 -> newLedMode = VisionLEDMode.kOff; - case 1 -> newLedMode = VisionLEDMode.kOn; - case 2 -> newLedMode = VisionLEDMode.kBlink; + case -1 -> VisionLEDMode.kDefault; + case 0 -> VisionLEDMode.kOff; + case 1 -> VisionLEDMode.kOn; + case 2 -> VisionLEDMode.kBlink; default -> { logger.warn("User supplied invalid LED mode, falling back to Default"); yield VisionLEDMode.kDefault; diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java index 85adb4cbd..9d8b6cc32 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/PipelineManager.java @@ -90,19 +90,16 @@ public class PipelineManager { * @return The gotten settings of the pipeline whose index was provided. */ public CVPipelineSettings getPipelineSettings(int index) { - if (index < 0) { - switch (index) { - case DRIVERMODE_INDEX: - return driverModePipeline.getSettings(); - case CAL_3D_INDEX: - return calibration3dPipeline.getSettings(); + return switch (index) { + case DRIVERMODE_INDEX -> driverModePipeline.getSettings(); + case CAL_3D_INDEX -> calibration3dPipeline.getSettings(); + default -> { + for (var setting : userPipelineSettings) { + if (setting.pipelineIndex == index) yield setting; + } + yield null; } - } - - for (var setting : userPipelineSettings) { - if (setting.pipelineIndex == index) return setting; - } - return null; + }; } /** @@ -112,19 +109,16 @@ public class PipelineManager { * @return the nickname of the pipeline whose index was provided. */ public String getPipelineNickname(int index) { - if (index < 0) { - switch (index) { - case DRIVERMODE_INDEX: - return driverModePipeline.getSettings().pipelineNickname; - case CAL_3D_INDEX: - return calibration3dPipeline.getSettings().pipelineNickname; + return switch (index) { + case DRIVERMODE_INDEX -> driverModePipeline.getSettings().pipelineNickname; + case CAL_3D_INDEX -> calibration3dPipeline.getSettings().pipelineNickname; + default -> { + for (var setting : userPipelineSettings) { + if (setting.pipelineIndex == index) yield setting.pipelineNickname; + } + yield null; } - } - - for (var setting : userPipelineSettings) { - if (setting.pipelineIndex == index) return setting.pipelineNickname; - } - return null; + }; } /** @@ -156,17 +150,12 @@ public class PipelineManager { */ public CVPipeline getCurrentPipeline() { updatePipelineFromRequested(); - if (currentPipelineIndex < 0) { - switch (currentPipelineIndex) { - case CAL_3D_INDEX: - return calibration3dPipeline; - case DRIVERMODE_INDEX: - return driverModePipeline; - } - } - - // Just return the current user pipeline, we're not on aa built-in one - return currentUserPipeline; + return switch (currentPipelineIndex) { + case CAL_3D_INDEX -> calibration3dPipeline; + case DRIVERMODE_INDEX -> driverModePipeline; + // Just return the current user pipeline, we're not on a built-in one + default -> currentUserPipeline; + }; } /** @@ -339,40 +328,22 @@ public class PipelineManager { } private CVPipelineSettings createSettingsForType(PipelineType type, String nickname) { - switch (type) { - case Reflective -> { - var added = new ReflectivePipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - case ColoredShape -> { - var added = new ColoredShapePipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - case AprilTag -> { - var added = new AprilTagPipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - case Aruco -> { - var added = new ArucoPipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - case ObjectDetection -> { - var added = new ObjectDetectionPipelineSettings(); - added.pipelineNickname = nickname; - return added; - } - case Calib3d, DriverMode -> { - logger.error("Got invalid pipeline type: " + type); - return null; - } + CVPipelineSettings settings = + switch (type) { + case Reflective -> new ReflectivePipelineSettings(); + case ColoredShape -> new ColoredShapePipelineSettings(); + case AprilTag -> new AprilTagPipelineSettings(); + case Aruco -> new ArucoPipelineSettings(); + case ObjectDetection -> new ObjectDetectionPipelineSettings(); + case Calib3d, DriverMode -> { + logger.error("Got invalid pipeline type: " + type); + yield null; + } + }; + if (settings != null) { + settings.pipelineNickname = nickname; } - - // This can never happen, this is here to satisfy the compiler. - throw new IllegalStateException("Got impossible pipeline type: " + type); + return settings; } private void addPipelineInternal(CVPipelineSettings settings) { diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java index dfbe2808e..55b173736 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java @@ -89,12 +89,8 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { var newPropValue = change.getNewPropValue(); var currentSettings = change.getCurrentSettings(); var originContext = change.getOriginContext(); - boolean handled = true; switch (propName) { - case "pipelineName" -> { - newPipelineNickname((String) newPropValue); - continue; - } + case "pipelineName" -> newPipelineNickname((String) newPropValue); case "newPipelineInfo" -> newPipelineInfo((Pair) newPropValue); case "deleteCurrPipeline" -> deleteCurrPipeline(); case "changePipeline" -> changePipeline((Integer) newPropValue); @@ -120,45 +116,43 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { parentModule.saveAndBroadcastAll(); } case "isDriverMode" -> parentModule.setDriverMode((Boolean) newPropValue); - default -> handled = false; - } - - // special case for camera settables - if (propName.startsWith("camera")) { - var propMethodName = "set" + propName.replace("camera", ""); - var methods = parentModule.visionSource.getSettables().getClass().getMethods(); - for (var method : methods) { - if (method.getName().equalsIgnoreCase(propMethodName)) { - try { - method.invoke(parentModule.visionSource.getSettables(), newPropValue); - } catch (Exception e) { - logger.error("Failed to invoke camera settable method: " + method.getName(), e); + default -> { + // special case for camera settables + if (propName.startsWith("camera")) { + var propMethodName = "set" + propName.replace("camera", ""); + var methods = parentModule.visionSource.getSettables().getClass().getMethods(); + for (var method : methods) { + if (method.getName().equalsIgnoreCase(propMethodName)) { + try { + method.invoke(parentModule.visionSource.getSettables(), newPropValue); + } catch (Exception e) { + logger.error("Failed to invoke camera settable method: " + method.getName(), e); + } + } } } + + try { + setProperty(currentSettings, propName, newPropValue); + logger.trace("Set prop " + propName + " to value " + newPropValue); + } catch (NoSuchFieldException | IllegalAccessException e) { + logger.error( + "Could not set prop " + + propName + + " with value " + + newPropValue + + " on " + + currentSettings + + " | " + + e.getClass().getSimpleName(), + e); + } catch (Exception e) { + logger.error("Unknown exception when setting PSC prop!", e); + } + + parentModule.saveAndBroadcastSelective(originContext, propName, newPropValue); } } - - if (!handled) { - try { - setProperty(currentSettings, propName, newPropValue); - logger.trace("Set prop " + propName + " to value " + newPropValue); - } catch (NoSuchFieldException | IllegalAccessException e) { - logger.error( - "Could not set prop " - + propName - + " with value " - + newPropValue - + " on " - + currentSettings - + " | " - + e.getClass().getSimpleName(), - e); - } catch (Exception e) { - logger.error("Unknown exception when setting PSC prop!", e); - } - } - - parentModule.saveAndBroadcastSelective(originContext, propName, newPropValue); } getSettingChanges().clear(); } finally { @@ -230,9 +224,8 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { switch (offsetOperation) { case CLEAR -> curAdvSettings.offsetSinglePoint = new Point(); case TAKE_SINGLE -> curAdvSettings.offsetSinglePoint = newPoint; - case TAKE_FIRST_DUAL, TAKE_SECOND_DUAL -> { - logger.warn("Dual point operation in single point mode"); - } + case TAKE_FIRST_DUAL, TAKE_SECOND_DUAL -> + logger.warn("Dual point operation in single point mode"); } } case Dual -> { @@ -253,14 +246,10 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { curAdvSettings.offsetDualPointB = newPoint; curAdvSettings.offsetDualPointBArea = latestTarget.getArea(); } - case TAKE_SINGLE -> { - logger.warn("Single point operation in dual point mode"); - } + case TAKE_SINGLE -> logger.warn("Single point operation in dual point mode"); } } - case None -> { - logger.warn("Robot offset point operation requested, but no offset mode set"); - } + case None -> logger.warn("Robot offset point operation requested, but no offset mode set"); } } diff --git a/photon-core/src/main/java/org/photonvision/vision/target/TargetCalculations.java b/photon-core/src/main/java/org/photonvision/vision/target/TargetCalculations.java index 22c92ae2c..1cdcd31f5 100644 --- a/photon-core/src/main/java/org/photonvision/vision/target/TargetCalculations.java +++ b/photon-core/src/main/java/org/photonvision/vision/target/TargetCalculations.java @@ -134,17 +134,16 @@ public class TargetCalculations { Point camCenterPoint, DualOffsetValues dualOffsetValues, RobotOffsetPointMode offsetMode) { - switch (offsetMode) { - case None: - default: - return camCenterPoint; - case Single: + return switch (offsetMode) { + case None -> camCenterPoint; + case Single -> { if (offsetPoint.x == 0 && offsetPoint.y == 0) { - return camCenterPoint; + yield camCenterPoint; } else { - return offsetPoint; + yield offsetPoint; } - case Dual: + } + case Dual -> { var resultPoint = new Point(); var lineValues = dualOffsetValues.getLineValues(); var offsetSlope = lineValues.getFirst(); @@ -152,8 +151,9 @@ public class TargetCalculations { resultPoint.x = (offsetPoint.x - offsetIntercept) / offsetSlope; resultPoint.y = (offsetPoint.y * offsetSlope) + offsetIntercept; - return resultPoint; - } + yield resultPoint; + } + }; } public static double getAspectRatio(RotatedRect rect, boolean isLandscape) { From 3ed8d3a4f36513c7a5d26403b4a463b62553b6fb Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 31 Mar 2025 18:03:33 -0400 Subject: [PATCH 23/42] Refactor instanceof --- .../photonvision/vision/camera/PVCameraInfo.java | 15 +++------------ .../vision/camera/USBCameras/USBCameraSource.java | 8 ++++---- .../vision/pipeline/OutputStreamPipeline.java | 5 ++--- 3 files changed, 9 insertions(+), 19 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java b/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java index 023394ee2..9728569cb 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java @@ -123,10 +123,7 @@ public sealed interface PVCameraInfo { public boolean equals(Object obj) { if (this == obj) return true; if (obj == null) return false; - if (obj instanceof PVCameraInfo info) { - return equals(info); - } - return false; + return obj instanceof PVCameraInfo info && equals(info); } @Override @@ -192,10 +189,7 @@ public sealed interface PVCameraInfo { public boolean equals(Object obj) { if (this == obj) return true; if (obj == null) return false; - if (obj instanceof PVCameraInfo info) { - return equals(info); - } - return false; + return obj instanceof PVCameraInfo info && equals(info); } @Override @@ -252,10 +246,7 @@ public sealed interface PVCameraInfo { public boolean equals(Object obj) { if (this == obj) return true; if (obj == null) return false; - if (obj instanceof PVFileCameraInfo info) { - return equals(info); - } - return false; + return obj instanceof PVFileCameraInfo info && equals(info); } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/USBCameraSource.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/USBCameraSource.java index ab7bf5bc7..b0a4dde81 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/USBCameraSource.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/USBCameraSource.java @@ -71,12 +71,12 @@ public class USBCameraSource extends VisionSource { // yes to me... if (getCameraConfiguration().cameraQuirks == null) { int vid = - (config.matchedCameraInfo instanceof PVUsbCameraInfo) - ? ((PVUsbCameraInfo) config.matchedCameraInfo).vendorId + (config.matchedCameraInfo instanceof PVUsbCameraInfo cameraInfo) + ? cameraInfo.vendorId : -1; int pid = - (config.matchedCameraInfo instanceof PVUsbCameraInfo) - ? ((PVUsbCameraInfo) config.matchedCameraInfo).productId + (config.matchedCameraInfo instanceof PVUsbCameraInfo cameraInfo) + ? cameraInfo.productId : -1; getCameraConfiguration().cameraQuirks = diff --git a/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java b/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java index 70cb7e996..366ef1a0a 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipeline/OutputStreamPipeline.java @@ -107,11 +107,10 @@ public class OutputStreamPipeline { resizeImagePipe.setParams( new ResizeImagePipe.ResizeImageParams(settings.streamingFrameDivisor)); - if (settings instanceof Calibration3dPipelineSettings) { + if (settings instanceof Calibration3dPipelineSettings pipelineSettings) { drawCalibrationPipe.setParams( new DrawCalibrationPipe.DrawCalibrationPipeParams( - settings.streamingFrameDivisor, - ((Calibration3dPipelineSettings) settings).drawAllSnapshots)); + pipelineSettings.streamingFrameDivisor, pipelineSettings.drawAllSnapshots)); } } From 0dfca8c04f6d9a232b9b96231c92b463a9f4fcdc Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 7 Apr 2025 08:01:35 -0400 Subject: [PATCH 24/42] Always statically import JUnit Assertions --- .../common/configuration/ConfigTest.java | 21 +++++----- .../configuration/NetworkConfigTest.java | 10 +++-- .../common/util/LogFileManagementTest.java | 15 ++++--- .../common/util/TimedTaskManagerTest.java | 5 ++- .../hardware/HardwareConfigTest.java | 5 +-- .../photonvision/vision/QuirkyCameraTest.java | 7 ++-- .../vision/pipeline/AprilTagTest.java | 39 +++++++++---------- .../vision/pipeline/ArucoPipelineTest.java | 33 ++++++++-------- .../pipeline/CalibrationRotationPipeTest.java | 16 +++----- .../vision/pipeline/PipelineProfilerTest.java | 8 ++-- .../pipeline/ReflectivePipelineTest.java | 8 ++-- .../vision/processes/PipelineManagerTest.java | 5 ++- .../processes/VisionModuleManagerTest.java | 4 +- .../vision/target/TargetCalculationsTest.java | 9 ++--- .../org/photonvision/PhotonCameraTest.java | 3 +- .../java/org/photonvision/PhotonUtilTest.java | 17 ++++---- .../org/photonvision/PhotonVersionTest.java | 13 ++++--- .../org/photonvision/VisionSystemSimTest.java | 4 +- 18 files changed, 115 insertions(+), 107 deletions(-) diff --git a/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java b/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java index 8f5c333a8..95262912a 100644 --- a/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java +++ b/photon-core/src/test/java/org/photonvision/common/configuration/ConfigTest.java @@ -17,6 +17,9 @@ package org.photonvision.common.configuration; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertTrue; + import java.io.File; import java.io.FileWriter; import java.io.IOException; @@ -87,9 +90,9 @@ public class ConfigTest { Path.of(configMgr.configDirectoryFile.toString(), "cameras", "TestCamera") .toAbsolutePath() .toString()); - Assertions.assertTrue(camConfDir.exists(), "TestCamera config folder not found!"); + assertTrue(camConfDir.exists(), "TestCamera config folder not found!"); - Assertions.assertTrue( + assertTrue( Files.exists(Path.of(configMgr.configDirectoryFile.toString(), "networkSettings.json")), "networkSettings.json file not found!"); } @@ -104,17 +107,17 @@ public class ConfigTest { var apriltagPipelineSettings = configMgr.getConfig().getCameraConfigurations().get("TestCamera").pipelineSettings.get(2); - Assertions.assertEquals(REFLECTIVE_PIPELINE_SETTINGS, reflectivePipelineSettings); - Assertions.assertEquals(COLORED_SHAPE_PIPELINE_SETTINGS, coloredShapePipelineSettings); - Assertions.assertEquals(APRIL_TAG_PIPELINE_SETTINGS, apriltagPipelineSettings); + assertEquals(REFLECTIVE_PIPELINE_SETTINGS, reflectivePipelineSettings); + assertEquals(COLORED_SHAPE_PIPELINE_SETTINGS, coloredShapePipelineSettings); + assertEquals(APRIL_TAG_PIPELINE_SETTINGS, apriltagPipelineSettings); - Assertions.assertTrue( + assertTrue( reflectivePipelineSettings instanceof ReflectivePipelineSettings, "Config loaded pipeline settings for index 0 not of expected type ReflectivePipelineSettings!"); - Assertions.assertTrue( + assertTrue( coloredShapePipelineSettings instanceof ColoredShapePipelineSettings, "Config loaded pipeline settings for index 1 not of expected type ColoredShapePipelineSettings!"); - Assertions.assertTrue( + assertTrue( apriltagPipelineSettings instanceof AprilTagPipelineSettings, "Config loaded pipeline settings for index 2 not of expected type AprilTagPipelineSettings!"); } @@ -184,7 +187,7 @@ public class ConfigTest { AprilTagPipelineSettings settings = (AprilTagPipelineSettings) JacksonUtils.deserialize(tempFile.toPath(), CVPipelineSettings.class); - Assertions.assertEquals(TargetModel.kAprilTag6in_16h5, settings.targetModel); + assertEquals(TargetModel.kAprilTag6in_16h5, settings.targetModel); tempFile.delete(); } diff --git a/photon-core/src/test/java/org/photonvision/common/configuration/NetworkConfigTest.java b/photon-core/src/test/java/org/photonvision/common/configuration/NetworkConfigTest.java index 7c9d6d6f4..0cc3c027c 100644 --- a/photon-core/src/test/java/org/photonvision/common/configuration/NetworkConfigTest.java +++ b/photon-core/src/test/java/org/photonvision/common/configuration/NetworkConfigTest.java @@ -17,11 +17,13 @@ package org.photonvision.common.configuration; +import static org.junit.jupiter.api.Assertions.assertDoesNotThrow; +import static org.junit.jupiter.api.Assertions.assertEquals; + import com.fasterxml.jackson.databind.ObjectMapper; import java.io.File; import java.io.IOException; import java.nio.file.Path; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; public class NetworkConfigTest { @@ -30,7 +32,7 @@ public class NetworkConfigTest { var mapper = new ObjectMapper(); var path = Path.of("netTest.json"); mapper.writeValue(path.toFile(), new NetworkConfig()); - Assertions.assertDoesNotThrow(() -> mapper.readValue(path.toFile(), NetworkConfig.class)); + assertDoesNotThrow(() -> mapper.readValue(path.toFile(), NetworkConfig.class)); new File("netTest.json").delete(); } @@ -40,13 +42,13 @@ public class NetworkConfigTest { var folder = Path.of("test-resources/network-old-team-number"); var configMgr = new ConfigManager(folder, new LegacyConfigProvider(folder)); configMgr.load(); - Assertions.assertEquals("9999", configMgr.getConfig().getNetworkConfig().ntServerAddress); + assertEquals("9999", configMgr.getConfig().getNetworkConfig().ntServerAddress); } { var folder = Path.of("test-resources/network-new-team-number"); var configMgr = new ConfigManager(folder, new LegacyConfigProvider(folder)); configMgr.load(); - Assertions.assertEquals("9999", configMgr.getConfig().getNetworkConfig().ntServerAddress); + assertEquals("9999", configMgr.getConfig().getNetworkConfig().ntServerAddress); } } } diff --git a/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java b/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java index e83487464..9f96b59bd 100644 --- a/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java +++ b/photon-core/src/test/java/org/photonvision/common/util/LogFileManagementTest.java @@ -17,6 +17,11 @@ package org.photonvision.common.util; +import static org.junit.jupiter.api.Assertions.assertDoesNotThrow; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertTrue; +import static org.junit.jupiter.api.Assertions.fail; + import java.io.File; import java.io.FileWriter; import java.io.IOException; @@ -26,7 +31,6 @@ import java.time.LocalDateTime; import java.time.ZoneOffset; import org.apache.commons.io.FileUtils; import org.apache.commons.io.filefilter.WildcardFileFilter; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; import org.photonvision.common.configuration.ConfigManager; import org.photonvision.common.logging.Logger; @@ -39,7 +43,7 @@ public class LogFileManagementTest { String testDir = ConfigManager.getInstance().getLogsDir().toString() + "/test"; - Assertions.assertDoesNotThrow(() -> Files.createDirectories(Path.of(testDir))); + assertDoesNotThrow(() -> Files.createDirectories(Path.of(testDir))); // Create a bunch of log files with dummy contents. for (int fileIdx = 0; fileIdx < Logger.MAX_LOGS_TO_KEEP + 5; fileIdx++) { @@ -52,20 +56,19 @@ public class LogFileManagementTest { testLogWriter.write("Test log contents created for testing purposes only"); testLogWriter.close(); } catch (IOException e) { - Assertions.fail("Could not create test files"); + fail("Could not create test files"); } } // Confirm new log files were created - Assertions.assertTrue( + assertTrue( Logger.MAX_LOGS_TO_KEEP + 5 <= countLogFiles(testDir), "Not enough log files discovered"); // Run the log cleanup routine Logger.cleanLogs(Path.of(testDir)); // Confirm we deleted log files - Assertions.assertEquals( - Logger.MAX_LOGS_TO_KEEP, countLogFiles(testDir), "Not enough log files deleted"); + assertEquals(Logger.MAX_LOGS_TO_KEEP, countLogFiles(testDir), "Not enough log files deleted"); // Clean uptest directory org.photonvision.common.util.file.FileUtils.deleteDirectory(Path.of(testDir)); diff --git a/photon-core/src/test/java/org/photonvision/common/util/TimedTaskManagerTest.java b/photon-core/src/test/java/org/photonvision/common/util/TimedTaskManagerTest.java index 7b7567d67..5039ebd99 100644 --- a/photon-core/src/test/java/org/photonvision/common/util/TimedTaskManagerTest.java +++ b/photon-core/src/test/java/org/photonvision/common/util/TimedTaskManagerTest.java @@ -17,8 +17,9 @@ package org.photonvision.common.util; +import static org.junit.jupiter.api.Assertions.assertEquals; + import java.util.concurrent.atomic.AtomicInteger; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; public class TimedTaskManagerTest { @@ -27,6 +28,6 @@ public class TimedTaskManagerTest { AtomicInteger i = new AtomicInteger(); TimedTaskManager.getInstance().addTask("TaskManagerTest", i::getAndIncrement, 2); Thread.sleep(400); - Assertions.assertEquals(200, i.get(), 15); + assertEquals(200, i.get(), 15); } } diff --git a/photon-core/src/test/java/org/photonvision/hardware/HardwareConfigTest.java b/photon-core/src/test/java/org/photonvision/hardware/HardwareConfigTest.java index b9b088e84..67822816b 100644 --- a/photon-core/src/test/java/org/photonvision/hardware/HardwareConfigTest.java +++ b/photon-core/src/test/java/org/photonvision/hardware/HardwareConfigTest.java @@ -17,11 +17,11 @@ package org.photonvision.hardware; +import static org.junit.jupiter.api.Assertions.assertArrayEquals; import static org.junit.jupiter.api.Assertions.assertEquals; import com.fasterxml.jackson.databind.ObjectMapper; import java.io.IOException; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; import org.photonvision.common.configuration.HardwareConfig; import org.photonvision.common.hardware.GPIO.CustomGPIO; @@ -37,8 +37,7 @@ public class HardwareConfigTest { assertEquals(config.deviceName(), "PhotonVision"); assertEquals(config.deviceLogoPath(), "photonvision.png"); assertEquals(config.supportURL(), "https://support.photonvision.com"); - Assertions.assertArrayEquals( - config.ledPins().stream().mapToInt(i -> i).toArray(), new int[] {2, 13}); + assertArrayEquals(config.ledPins().stream().mapToInt(i -> i).toArray(), new int[] {2, 13}); CustomGPIO.setConfig(config); } catch (IOException e) { diff --git a/photon-core/src/test/java/org/photonvision/vision/QuirkyCameraTest.java b/photon-core/src/test/java/org/photonvision/vision/QuirkyCameraTest.java index 927a2cf27..e9126bf28 100644 --- a/photon-core/src/test/java/org/photonvision/vision/QuirkyCameraTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/QuirkyCameraTest.java @@ -17,8 +17,9 @@ package org.photonvision.vision; +import static org.junit.jupiter.api.Assertions.assertEquals; + import java.util.HashMap; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; import org.photonvision.vision.camera.CameraQuirk; import org.photonvision.vision.camera.QuirkyCamera; @@ -35,7 +36,7 @@ public class QuirkyCameraTest { } QuirkyCamera psEye = QuirkyCamera.getQuirkyCamera(0x1415, 0x2000); - Assertions.assertEquals(psEye.quirks, ps3EyeQuirks); + assertEquals(psEye.quirks, ps3EyeQuirks); } @Test @@ -46,6 +47,6 @@ public class QuirkyCameraTest { } QuirkyCamera quirkless = QuirkyCamera.getQuirkyCamera(1234, 8888); - Assertions.assertEquals(quirkless.quirks, noQuirks); + assertEquals(quirkless.quirks, noQuirks); } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java index 94f1db534..7a1fa9648 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/AprilTagTest.java @@ -17,8 +17,9 @@ package org.photonvision.vision.pipeline; +import static org.junit.jupiter.api.Assertions.assertEquals; + import edu.wpi.first.math.geometry.Translation3d; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; import org.photonvision.common.configuration.ConfigManager; @@ -72,33 +73,31 @@ public class AprilTagTest { // Test corner order var corners = target.getTargetCorners(); - Assertions.assertEquals(260, corners.get(0).x, 10); - Assertions.assertEquals(245, corners.get(0).y, 10); - Assertions.assertEquals(315, corners.get(1).x, 10); - Assertions.assertEquals(245, corners.get(1).y, 10); - Assertions.assertEquals(315, corners.get(2).x, 10); - Assertions.assertEquals(190, corners.get(2).y, 10); - Assertions.assertEquals(260, corners.get(3).x, 10); - Assertions.assertEquals(190, corners.get(3).y, 10); + assertEquals(260, corners.get(0).x, 10); + assertEquals(245, corners.get(0).y, 10); + assertEquals(315, corners.get(1).x, 10); + assertEquals(245, corners.get(1).y, 10); + assertEquals(315, corners.get(2).x, 10); + assertEquals(190, corners.get(2).y, 10); + assertEquals(260, corners.get(3).x, 10); + assertEquals(190, corners.get(3).y, 10); var pose = target.getBestCameraToTarget3d(); // Test pose estimate translation - Assertions.assertEquals(2, pose.getTranslation().getX(), 0.2); - Assertions.assertEquals(0.1, pose.getTranslation().getY(), 0.2); - Assertions.assertEquals(0.0, pose.getTranslation().getZ(), 0.2); + assertEquals(2, pose.getTranslation().getX(), 0.2); + assertEquals(0.1, pose.getTranslation().getY(), 0.2); + assertEquals(0.0, pose.getTranslation().getZ(), 0.2); // Test pose estimate rotation // We expect the object axes to be in NWU, with the x-axis coming out of the tag // This visible tag is facing the camera almost parallel, so in world space: // The object's X axis should be (-1, 0, 0) - Assertions.assertEquals( - -1, new Translation3d(1, 0, 0).rotateBy(pose.getRotation()).getX(), 0.1); + assertEquals(-1, new Translation3d(1, 0, 0).rotateBy(pose.getRotation()).getX(), 0.1); // The object's Y axis should be (0, -1, 0) - Assertions.assertEquals( - -1, new Translation3d(0, 1, 0).rotateBy(pose.getRotation()).getY(), 0.1); + assertEquals(-1, new Translation3d(0, 1, 0).rotateBy(pose.getRotation()).getY(), 0.1); // The object's Z axis should be (0, 0, 1) - Assertions.assertEquals(1, new Translation3d(0, 0, 1).rotateBy(pose.getRotation()).getZ(), 0.1); + assertEquals(1, new Translation3d(0, 0, 1).rotateBy(pose.getRotation()).getZ(), 0.1); } @Test @@ -134,8 +133,8 @@ public class AprilTagTest { // these numbers are not *accurate*, but they are known and expected var pose = pipelineResult.targets.get(0).getBestCameraToTarget3d(); - Assertions.assertEquals(4.14, pose.getTranslation().getX(), 0.2); - Assertions.assertEquals(2, pose.getTranslation().getY(), 0.2); - Assertions.assertEquals(0.0, pose.getTranslation().getZ(), 0.2); + assertEquals(4.14, pose.getTranslation().getX(), 0.2); + assertEquals(2, pose.getTranslation().getY(), 0.2); + assertEquals(0.0, pose.getTranslation().getZ(), 0.2); } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java index 1c4ee4cef..a145b503e 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/ArucoPipelineTest.java @@ -17,8 +17,9 @@ package org.photonvision.vision.pipeline; +import static org.junit.jupiter.api.Assertions.assertEquals; + import edu.wpi.first.math.geometry.Translation3d; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; import org.photonvision.common.configuration.ConfigManager; @@ -72,32 +73,30 @@ public class ArucoPipelineTest { // Test corner order var corners = target.getTargetCorners(); - Assertions.assertEquals(260, corners.get(0).x, 10); - Assertions.assertEquals(245, corners.get(0).y, 10); - Assertions.assertEquals(315, corners.get(1).x, 10); - Assertions.assertEquals(245, corners.get(1).y, 10); - Assertions.assertEquals(315, corners.get(2).x, 10); - Assertions.assertEquals(190, corners.get(2).y, 10); - Assertions.assertEquals(260, corners.get(3).x, 10); - Assertions.assertEquals(190, corners.get(3).y, 10); + assertEquals(260, corners.get(0).x, 10); + assertEquals(245, corners.get(0).y, 10); + assertEquals(315, corners.get(1).x, 10); + assertEquals(245, corners.get(1).y, 10); + assertEquals(315, corners.get(2).x, 10); + assertEquals(190, corners.get(2).y, 10); + assertEquals(260, corners.get(3).x, 10); + assertEquals(190, corners.get(3).y, 10); var pose = target.getBestCameraToTarget3d(); // Test pose estimate translation - Assertions.assertEquals(2, pose.getTranslation().getX(), 0.2); - Assertions.assertEquals(0.1, pose.getTranslation().getY(), 0.2); - Assertions.assertEquals(0.0, pose.getTranslation().getZ(), 0.2); + assertEquals(2, pose.getTranslation().getX(), 0.2); + assertEquals(0.1, pose.getTranslation().getY(), 0.2); + assertEquals(0.0, pose.getTranslation().getZ(), 0.2); // Test pose estimate rotation // We expect the object axes to be in NWU, with the x-axis coming out of the tag // This visible tag is facing the camera almost parallel, so in world space: // The object's X axis should be (-1, 0, 0) - Assertions.assertEquals( - -1, new Translation3d(1, 0, 0).rotateBy(pose.getRotation()).getX(), 0.1); + assertEquals(-1, new Translation3d(1, 0, 0).rotateBy(pose.getRotation()).getX(), 0.1); // The object's Y axis should be (0, -1, 0) - Assertions.assertEquals( - -1, new Translation3d(0, 1, 0).rotateBy(pose.getRotation()).getY(), 0.1); + assertEquals(-1, new Translation3d(0, 1, 0).rotateBy(pose.getRotation()).getY(), 0.1); // The object's Z axis should be (0, 0, 1) - Assertions.assertEquals(1, new Translation3d(0, 0, 1).rotateBy(pose.getRotation()).getZ(), 0.1); + assertEquals(1, new Translation3d(0, 0, 1).rotateBy(pose.getRotation()).getZ(), 0.1); } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java index 1d7b9faa4..53283228b 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/CalibrationRotationPipeTest.java @@ -23,7 +23,6 @@ import static org.junit.jupiter.api.Assertions.assertEquals; import java.io.IOException; import java.util.Arrays; import java.util.List; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Test; import org.junitpioneer.jupiter.cartesian.CartesianTest; @@ -324,14 +323,11 @@ public class CalibrationRotationPipeTest { System.out.println("Base: " + pose_base); System.out.println("rot-unrot: " + pose_unrotated); - Assertions.assertEquals(pose_base.getX(), pose_unrotated.getX(), 0.01); - Assertions.assertEquals(pose_base.getY(), pose_unrotated.getY(), 0.01); - Assertions.assertEquals(pose_base.getZ(), pose_unrotated.getZ(), 0.01); - Assertions.assertEquals( - pose_base.getRotation().getX(), pose_unrotated.getRotation().getX(), 0.01); - Assertions.assertEquals( - pose_base.getRotation().getY(), pose_unrotated.getRotation().getY(), 0.01); - Assertions.assertEquals( - pose_base.getRotation().getZ(), pose_unrotated.getRotation().getZ(), 0.01); + assertEquals(pose_base.getX(), pose_unrotated.getX(), 0.01); + assertEquals(pose_base.getY(), pose_unrotated.getY(), 0.01); + assertEquals(pose_base.getZ(), pose_unrotated.getZ(), 0.01); + assertEquals(pose_base.getRotation().getX(), pose_unrotated.getRotation().getX(), 0.01); + assertEquals(pose_base.getRotation().getY(), pose_unrotated.getRotation().getY(), 0.01); + assertEquals(pose_base.getRotation().getZ(), pose_unrotated.getRotation().getZ(), 0.01); } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/PipelineProfilerTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/PipelineProfilerTest.java index dbabd15e6..e7cb30d11 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/PipelineProfilerTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/PipelineProfilerTest.java @@ -17,7 +17,9 @@ package org.photonvision.vision.pipeline; -import org.junit.jupiter.api.Assertions; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertTrue; + import org.junit.jupiter.api.Test; public class PipelineProfilerTest { @@ -35,7 +37,7 @@ public class PipelineProfilerTest { System.out.println(validResult); - Assertions.assertEquals("Invalid data", invalidResult); - Assertions.assertTrue(validResult.contains("Total: 45.0ms")); + assertEquals("Invalid data", invalidResult); + assertTrue(validResult.contains("Total: 45.0ms")); } } diff --git a/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java b/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java index 04ab24434..5e10b56b1 100644 --- a/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/pipeline/ReflectivePipelineTest.java @@ -17,7 +17,9 @@ package org.photonvision.vision.pipeline; -import org.junit.jupiter.api.Assertions; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertTrue; + import org.junit.jupiter.api.Test; import org.photonvision.common.util.TestUtils; import org.photonvision.vision.camera.QuirkyCamera; @@ -62,8 +64,8 @@ public class ReflectivePipelineTest { pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera); TestUtils.printTestResults(pipelineResult); - Assertions.assertTrue(pipelineResult.hasTargets()); - Assertions.assertEquals(2, pipelineResult.targets.size(), "Target count wrong!"); + assertTrue(pipelineResult.hasTargets()); + assertEquals(2, pipelineResult.targets.size(), "Target count wrong!"); TestUtils.showImage(pipelineResult.inputAndOutputFrame.colorImage.getMat(), "Pipeline output"); } diff --git a/photon-core/src/test/java/org/photonvision/vision/processes/PipelineManagerTest.java b/photon-core/src/test/java/org/photonvision/vision/processes/PipelineManagerTest.java index b90de65ae..3d229bdfe 100644 --- a/photon-core/src/test/java/org/photonvision/vision/processes/PipelineManagerTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/processes/PipelineManagerTest.java @@ -17,9 +17,10 @@ package org.photonvision.vision.processes; +import static org.junit.jupiter.api.Assertions.assertEquals; + import java.util.ArrayList; import java.util.List; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Test; import org.photonvision.common.configuration.ConfigManager; @@ -62,7 +63,7 @@ public class PipelineManagerTest { for (int i = 2; i < 15; i++) { expected.add("Another (" + i + ")"); } - Assertions.assertEquals(expected, nicks); + assertEquals(expected, nicks); } @Test diff --git a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java index 32d8ec762..d71866677 100644 --- a/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/processes/VisionModuleManagerTest.java @@ -17,6 +17,7 @@ package org.photonvision.vision.processes; +import static org.junit.jupiter.api.Assertions.assertNotNull; import static org.junit.jupiter.api.Assertions.assertTrue; import static org.junit.jupiter.api.Assertions.fail; @@ -25,7 +26,6 @@ import java.io.IOException; import java.util.Arrays; import java.util.HashMap; import java.util.List; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Test; import org.photonvision.common.configuration.CameraConfiguration; @@ -188,7 +188,7 @@ public class VisionModuleManagerTest { sleep(1500); - Assertions.assertNotNull(module0DataConsumer.result); + assertNotNull(module0DataConsumer.result); TestUtils.printTestResults(module0DataConsumer.result); } diff --git a/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java b/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java index 340b8c993..c6aad210c 100644 --- a/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java +++ b/photon-core/src/test/java/org/photonvision/vision/target/TargetCalculationsTest.java @@ -24,7 +24,6 @@ import edu.wpi.first.math.geometry.Rotation3d; import edu.wpi.first.math.geometry.Translation3d; import java.util.List; import java.util.stream.Stream; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.Test; import org.junit.jupiter.params.ParameterizedTest; @@ -316,9 +315,9 @@ public class TargetCalculationsTest { Point crosshairPointOutside = TargetCalculations.calculateDualOffsetCrosshair(dualOffsetValues, 1); - Assertions.assertEquals(expectedHalfway.x, crosshairPointHalfway.x); - Assertions.assertEquals(expectedHalfway.y, crosshairPointHalfway.y); - Assertions.assertEquals(expectedOutside.x, crosshairPointOutside.x); - Assertions.assertEquals(expectedOutside.y, crosshairPointOutside.y); + assertEquals(expectedHalfway.x, crosshairPointHalfway.x); + assertEquals(expectedHalfway.y, crosshairPointHalfway.y); + assertEquals(expectedOutside.x, crosshairPointOutside.x); + assertEquals(expectedOutside.y, crosshairPointOutside.y); } } diff --git a/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java b/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java index c25955480..2f8e6c57d 100644 --- a/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java +++ b/photon-lib/src/test/java/org/photonvision/PhotonCameraTest.java @@ -46,7 +46,6 @@ import java.util.List; import java.util.Optional; import java.util.stream.Stream; import org.junit.jupiter.api.AfterEach; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; @@ -95,7 +94,7 @@ class PhotonCameraTest { @Test public void testEmpty() { - Assertions.assertDoesNotThrow( + assertDoesNotThrow( () -> { var packet = new Packet(1); var ret = new PhotonPipelineResult(); diff --git a/photon-lib/src/test/java/org/photonvision/PhotonUtilTest.java b/photon-lib/src/test/java/org/photonvision/PhotonUtilTest.java index bbc70cf85..fbb632a91 100644 --- a/photon-lib/src/test/java/org/photonvision/PhotonUtilTest.java +++ b/photon-lib/src/test/java/org/photonvision/PhotonUtilTest.java @@ -24,9 +24,10 @@ package org.photonvision; +import static org.junit.jupiter.api.Assertions.assertEquals; + import edu.wpi.first.math.geometry.*; import edu.wpi.first.math.util.Units; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; class PhotonUtilTest { @@ -40,7 +41,7 @@ class PhotonUtilTest { var dist = PhotonUtils.calculateDistanceToTargetMeters(camHeight, targetHeight, camPitch, targetPitch); - Assertions.assertEquals(3.464, dist, 0.01); + assertEquals(3.464, dist, 0.01); camHeight = 1; targetHeight = 2; @@ -49,7 +50,7 @@ class PhotonUtilTest { dist = PhotonUtils.calculateDistanceToTargetMeters(camHeight, targetHeight, camPitch, targetPitch); - Assertions.assertEquals(5.671, dist, 0.01); + assertEquals(5.671, dist, 0.01); } @Test @@ -75,9 +76,9 @@ class PhotonUtilTest { fieldToTarget, cameraToRobot); - Assertions.assertEquals(-3.464, fieldToRobot.getX(), 0.1); - Assertions.assertEquals(0, fieldToRobot.getY(), 0.1); - Assertions.assertEquals(0, fieldToRobot.getRotation().getDegrees(), 0.1); + assertEquals(-3.464, fieldToRobot.getX(), 0.1); + assertEquals(0, fieldToRobot.getY(), 0.1); + assertEquals(0, fieldToRobot.getRotation().getDegrees(), 0.1); } @Test @@ -94,8 +95,8 @@ class PhotonUtilTest { new Translation2d(Units.inchesToMeters(324), Units.inchesToMeters(162)), new Rotation2d()); var currentPose = new Pose2d(0, 0, Rotation2d.fromDegrees(0)); - Assertions.assertEquals(4.0, fieldToRobot.getX()); - Assertions.assertEquals( + assertEquals(4.0, fieldToRobot.getX()); + assertEquals( Math.toDegrees(Math.atan2((Units.inchesToMeters(162)), (Units.inchesToMeters(324)))), PhotonUtils.getYawToPose(currentPose, targetPose).getDegrees()); } diff --git a/photon-lib/src/test/java/org/photonvision/PhotonVersionTest.java b/photon-lib/src/test/java/org/photonvision/PhotonVersionTest.java index 216a0536a..f21c8957f 100644 --- a/photon-lib/src/test/java/org/photonvision/PhotonVersionTest.java +++ b/photon-lib/src/test/java/org/photonvision/PhotonVersionTest.java @@ -25,10 +25,11 @@ package org.photonvision; import static org.junit.jupiter.api.Assertions.assertDoesNotThrow; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; import java.util.regex.Matcher; import java.util.regex.Pattern; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.Test; public class PhotonVersionTest { @@ -52,11 +53,11 @@ public class PhotonVersionTest { @Test public void testVersion() { - Assertions.assertTrue(versionMatches("v2021.1.6", "v2021.1.6")); - Assertions.assertTrue(versionMatches("dev-v2021.1.6", "v2021.1.6")); - Assertions.assertTrue(versionMatches("dev-v2021.1.6-5-gca49ea50", "v2021.1.6")); - Assertions.assertFalse(versionMatches("", "v2021.1.6")); - Assertions.assertFalse(versionMatches("v2021.1.6", "")); + assertTrue(versionMatches("v2021.1.6", "v2021.1.6")); + assertTrue(versionMatches("dev-v2021.1.6", "v2021.1.6")); + assertTrue(versionMatches("dev-v2021.1.6-5-gca49ea50", "v2021.1.6")); + assertFalse(versionMatches("", "v2021.1.6")); + assertFalse(versionMatches("v2021.1.6", "")); } @Test diff --git a/photon-lib/src/test/java/org/photonvision/VisionSystemSimTest.java b/photon-lib/src/test/java/org/photonvision/VisionSystemSimTest.java index d4c324965..9ba79d463 100644 --- a/photon-lib/src/test/java/org/photonvision/VisionSystemSimTest.java +++ b/photon-lib/src/test/java/org/photonvision/VisionSystemSimTest.java @@ -24,6 +24,7 @@ package org.photonvision; +import static org.junit.jupiter.api.Assertions.assertDoesNotThrow; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertFalse; import static org.junit.jupiter.api.Assertions.assertTrue; @@ -50,7 +51,6 @@ import java.util.ArrayList; import java.util.List; import java.util.stream.Stream; import org.junit.jupiter.api.AfterEach; -import org.junit.jupiter.api.Assertions; import org.junit.jupiter.api.BeforeAll; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; @@ -111,7 +111,7 @@ class VisionSystemSimTest { @Test public void testEmpty() { - Assertions.assertDoesNotThrow( + assertDoesNotThrow( () -> { var sysUnderTest = new VisionSystemSim("Test"); sysUnderTest.addVisionTargets( From a4295275ed5479c164276076d5fc51a69dd3fc49 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 13 Apr 2025 18:08:00 -0400 Subject: [PATCH 25/42] Use Timer object to calculate FPS --- .../vision/pipe/impl/CalculateFPSPipe.java | 13 +++---------- 1 file changed, 3 insertions(+), 10 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java index b840e6602..f1814a031 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java @@ -24,19 +24,12 @@ import org.photonvision.vision.pipe.CVPipe; public class CalculateFPSPipe extends CVPipe { private final LinearFilter fpsFilter = LinearFilter.movingAverage(20); - - // roll my own Timer, since this is so trivial - double lastTime = -1; + private final Timer timer = new Timer(); @Override protected Integer process(Void in) { - if (lastTime < 0) { - lastTime = Timer.getFPGATimestamp(); - } - - var now = Timer.getFPGATimestamp(); - var dtSeconds = now - lastTime; - lastTime = now; + var dtSeconds = timer.get(); + timer.reset(); // If < 1 uS between ticks, something is probably wrong int fps; From 1bb861545b678d703e02e2dafc8ed44609963bce Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 14 Apr 2025 16:55:21 -0400 Subject: [PATCH 26/42] Use CameraServer directly instead of duplicating its functionality --- .../frame/consumer/MJPGFrameConsumer.java | 95 +------------------ 1 file changed, 3 insertions(+), 92 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java index 189a8107b..b99dc23f3 100644 --- a/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java +++ b/photon-core/src/main/java/org/photonvision/vision/frame/consumer/MJPGFrameConsumer.java @@ -17,11 +17,9 @@ package org.photonvision.vision.frame.consumer; +import edu.wpi.first.cameraserver.CameraServer; import edu.wpi.first.cscore.*; -import edu.wpi.first.networktables.NetworkTable; -import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.util.PixelFormat; -import java.util.ArrayList; import org.photonvision.common.util.math.MathUtils; import org.photonvision.vision.frame.StaticFrames; import org.photonvision.vision.opencv.CVMat; @@ -34,59 +32,13 @@ public class MJPGFrameConsumer implements AutoCloseable { private CvSource cvSource; private MjpegServer mjpegServer; - private VideoListener listener; - - private final NetworkTable table; - public MJPGFrameConsumer(String sourceName, int width, int height, int port) { this.cvSource = new CvSource(sourceName, PixelFormat.kMJPEG, width, height, 30); - this.table = - NetworkTableInstance.getDefault().getTable("/CameraPublisher").getSubTable(sourceName); this.mjpegServer = new MjpegServer("serve_" + cvSource.getName(), port); mjpegServer.setSource(cvSource); mjpegServer.setCompression(75); - - listener = - new VideoListener( - event -> { - if (event.kind == VideoEvent.Kind.kNetworkInterfacesChanged) { - table.getEntry("source").setString("cv:"); - table.getEntry("streams"); - table.getEntry("connected").setBoolean(true); - table.getEntry("mode").setString(videoModeToString(cvSource.getVideoMode())); - table.getEntry("modes").setStringArray(getSourceModeValues(cvSource.getHandle())); - updateStreamValues(); - } - }, - 0x4fff, - true); - } - - private synchronized void updateStreamValues() { - // Get port - int port = mjpegServer.getPort(); - - // Generate values - var addresses = CameraServerJNI.getNetworkInterfaces(); - ArrayList values = new ArrayList<>(addresses.length + 1); - String listenAddress = CameraServerJNI.getMjpegServerListenAddress(mjpegServer.getHandle()); - if (!listenAddress.isEmpty()) { - // If a listen address is specified, only use that - values.add(makeStreamValue(listenAddress, port)); - } else { - // Otherwise generate for hostname and all interface addresses - values.add(makeStreamValue(CameraServerJNI.getHostname() + ".local", port)); - for (String addr : addresses) { - if ("127.0.0.1".equals(addr)) { - continue; // ignore localhost - } - values.add(makeStreamValue(addr, port)); - } - } - - String[] streamAddresses = values.toArray(new String[0]); - table.getEntry("streams").setStringArray(streamAddresses); + CameraServer.addServer(mjpegServer); } public MJPGFrameConsumer(String name, int port) { @@ -106,53 +58,12 @@ public class MJPGFrameConsumer implements AutoCloseable { } } - public int getCurrentStreamPort() { - return mjpegServer.getPort(); - } - - private static String makeStreamValue(String address, int port) { - return "mjpg:http://" + address + ":" + port + "/?action=stream"; - } - - private static String[] getSourceModeValues(int sourceHandle) { - VideoMode[] modes = CameraServerJNI.enumerateSourceVideoModes(sourceHandle); - String[] modeStrings = new String[modes.length]; - for (int i = 0; i < modes.length; i++) { - modeStrings[i] = videoModeToString(modes[i]); - } - return modeStrings; - } - - private static String videoModeToString(VideoMode mode) { - return mode.width - + "x" - + mode.height - + " " - + pixelFormatToString(mode.pixelFormat) - + " " - + mode.fps - + " fps"; - } - - private static String pixelFormatToString(PixelFormat pixelFormat) { - return switch (pixelFormat) { - case kMJPEG -> "MJPEG"; - case kYUYV -> "YUYV"; - case kRGB565 -> "RGB565"; - case kBGR -> "BGR"; - case kGray -> "Gray"; - case kUYVY, kUnknown, kY16, kBGRA -> "Unknown"; - }; - } - @Override public void close() { - table.getEntry("connected").setBoolean(false); + CameraServer.removeServer(mjpegServer.getName()); mjpegServer.close(); cvSource.close(); - listener.close(); mjpegServer = null; cvSource = null; - listener = null; } } From 1b1f8029c800c943a1d5cee1243c479655c3caca Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 14 Apr 2025 19:58:56 -0400 Subject: [PATCH 27/42] Refactor QuirkyCamera QuirkyCamera was refactored to use EnumMap, since that seems to be more efficient. This also enables more concise copying of QuirkyCamera in getQuirkyCamera by just passing in the Map of the QuirkyCamera. Also, putAll was used instead of manually copying quirks in updateQuirks for conciseness. --- .../vision/camera/QuirkyCamera.java | 56 +++++++------------ 1 file changed, 19 insertions(+), 37 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java b/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java index 4f85879f0..c50059222 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/QuirkyCamera.java @@ -19,10 +19,9 @@ package org.photonvision.vision.camera; import com.fasterxml.jackson.annotation.JsonCreator; import com.fasterxml.jackson.annotation.JsonProperty; -import java.util.ArrayList; -import java.util.Arrays; -import java.util.HashMap; +import java.util.EnumMap; import java.util.List; +import java.util.Map; import java.util.Objects; public class QuirkyCamera { @@ -112,7 +111,7 @@ public class QuirkyCamera { public final String displayName; @JsonProperty("quirks") - public final HashMap quirks; + public final Map quirks; /** * Creates a QuirkyCamera that matches by USB VID/PID @@ -153,7 +152,7 @@ public class QuirkyCamera { this.baseName = baseName; this.displayName = displayName; - this.quirks = new HashMap<>(); + this.quirks = new EnumMap<>(CameraQuirk.class); // (1) Fill quirk map with the supplied Quirk list for (var q : quirks) { @@ -172,7 +171,7 @@ public class QuirkyCamera { @JsonProperty("usbVid") int usbVid, @JsonProperty("usbPid") int usbPid, @JsonProperty("displayName") String displayName, - @JsonProperty("quirks") HashMap quirks) { + @JsonProperty("quirks") Map quirks) { this.baseName = baseName; this.usbPid = usbPid; this.usbVid = usbVid; @@ -212,17 +211,7 @@ public class QuirkyCamera { // We have a quirky camera! // Copy the quirks from our predefined object and create // a QuirkyCamera object with the complete properties - List quirks = new ArrayList(); - for (var q : CameraQuirk.values()) { - if (qc.hasQuirk(q)) quirks.add(q); - } - QuirkyCamera c = - new QuirkyCamera( - usbVid, - usbPid, - baseName, - Arrays.copyOf(quirks.toArray(), quirks.size(), CameraQuirk[].class)); - return c; + return new QuirkyCamera(baseName, usbVid, usbPid, "", new EnumMap<>(qc.quirks)); } } return new QuirkyCamera(usbVid, usbPid, baseName); @@ -245,19 +234,17 @@ public class QuirkyCamera { @Override public String toString() { - String ret = - "QuirkyCamera [baseName=" - + baseName - + ", displayName=" - + displayName - + ", usbVid=" - + usbVid - + ", usbPid=" - + usbPid - + ", quirks=" - + quirks.toString() - + "]"; - return ret; + return "QuirkyCamera [baseName=" + + baseName + + ", displayName=" + + displayName + + ", usbVid=" + + usbVid + + ", usbPid=" + + usbPid + + ", quirks=" + + quirks.toString() + + "]"; } @Override @@ -270,12 +257,7 @@ public class QuirkyCamera { * * @param quirksToChange map of true/false for quirks we should change */ - public void updateQuirks(HashMap quirksToChange) { - for (var q : quirksToChange.entrySet()) { - var quirk = q.getKey(); - var hasQuirk = q.getValue(); - - this.quirks.put(quirk, hasQuirk); - } + public void updateQuirks(Map quirksToChange) { + quirks.putAll(quirksToChange); } } From ad1f51ba0668893eed2a0707b4c2f8c9e362f73d Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Mon, 14 Apr 2025 19:59:14 -0400 Subject: [PATCH 28/42] Miscellanous clean up --- .../photonvision/common/util/TestUtils.java | 10 +++--- .../vision/calibration/JsonMatOfDouble.java | 2 +- .../USBCameras/GenericUSBCameraSettables.java | 12 ++----- .../vision/pipe/impl/CornerDetectionPipe.java | 28 ++++++++-------- .../vision/pipe/impl/FilterContoursPipe.java | 4 +-- .../pipe/impl/FindBoardCornersPipe.java | 2 +- .../vision/pipe/impl/GrayscalePipe.java | 4 +-- .../vision/processes/VisionModule.java | 14 ++++---- .../VisionModuleChangeSubscriber.java | 33 +++++++++---------- .../server/DataSocketHandler.java | 15 ++++----- .../photonvision/server/RequestHandler.java | 10 +++--- .../src/test/java/jni/FileLoggerTest.java | 2 +- 12 files changed, 60 insertions(+), 76 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java index 44e7e33ce..cf29d613b 100644 --- a/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java +++ b/photon-core/src/main/java/org/photonvision/common/util/TestUtils.java @@ -52,7 +52,7 @@ public class TestUtils { kRocketPanelAngleDark48in(1.2192), kRocketPanelAngleDark60in(1.524); - public static double FOV = 68.5; + public static final double FOV = 68.5; public final double distanceMeters; public final Path path; @@ -90,7 +90,7 @@ public class TestUtils { kRedLoading_084in(2.1336), kRedLoading_108in(2.7432); - public static double FOV = 68.5; + public static final double FOV = 68.5; public final double distanceMeters; public final Path path; @@ -110,7 +110,7 @@ public class TestUtils { kBackAmpZone_117in, kSpeakerCenter_143in; - public static double FOV = 68.5; + public static final double FOV = 68.5; public final Path path; @@ -129,7 +129,7 @@ public class TestUtils { k162_36_Straight, k383_60_Angle2; - public static double FOV = 68.5; + public static final double FOV = 68.5; public final Translation2d approxPose; public final Path path; @@ -156,7 +156,7 @@ public class TestUtils { kTerminal12ft6in(Units.feetToMeters(12.5)), kTerminal22ft6in(Units.feetToMeters(22.5)); - public static double FOV = 68.5; + public static final double FOV = 68.5; public final double distanceMeters; public final Path path; diff --git a/photon-core/src/main/java/org/photonvision/vision/calibration/JsonMatOfDouble.java b/photon-core/src/main/java/org/photonvision/vision/calibration/JsonMatOfDouble.java index 6bae04aaf..ff463e198 100644 --- a/photon-core/src/main/java/org/photonvision/vision/calibration/JsonMatOfDouble.java +++ b/photon-core/src/main/java/org/photonvision/vision/calibration/JsonMatOfDouble.java @@ -110,7 +110,7 @@ public class JsonMatOfDouble implements Releasable { if (wpilibMat == null) { wpilibMat = new Matrix(new SimpleMatrix(rows, cols, true, data)); } - return (Matrix) wpilibMat; + return wpilibMat; } @Override diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java index bfe05e24a..7d923bad8 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/USBCameras/GenericUSBCameraSettables.java @@ -100,12 +100,6 @@ public class GenericUSBCameraSettables extends VisionSourceSettables { // first. var autoExpProp = findProperty("exposure_auto", "auto_exposure"); - if (expProp.isPresent()) { - exposureAbsProp = expProp.get(); - this.minExposure = exposureAbsProp.getMin(); - this.maxExposure = exposureAbsProp.getMax(); - } - if (autoExpProp.isPresent()) { autoExposureProp = autoExpProp.get(); } @@ -278,10 +272,8 @@ public class GenericUSBCameraSettables extends VisionSourceSettables { continue; } - if (configuration.cameraQuirks.hasQuirk(CameraQuirk.FPSCap100)) { - if (videoMode.fps > 100) { - continue; - } + if (configuration.cameraQuirks.hasQuirk(CameraQuirk.FPSCap100) && videoMode.fps > 100) { + continue; } videoModesList.add(videoMode); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java index 5508154b0..82f563555 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CornerDetectionPipe.java @@ -62,19 +62,18 @@ public class CornerDetectionPipe // find the bl/br/tr/tl corners // first, min by left/right - var list_ = Arrays.asList(points); - list_.sort(leftRightComparator); + Arrays.sort(points, leftRightComparator); // of this, we now have left and right // sort to get top and bottom - var left = new ArrayList<>(List.of(list_.get(0), list_.get(1))); - left.sort(verticalComparator); - var right = new ArrayList<>(List.of(list_.get(2), list_.get(3))); - right.sort(verticalComparator); + Point[] left = {points[0], points[1]}; + Arrays.sort(left, verticalComparator); + Point[] right = {points[2], points[3]}; + Arrays.sort(right, verticalComparator); - var tl = left.get(0); - var bl = left.get(1); - var tr = right.get(0); - var br = right.get(1); + var tl = left[0]; + var bl = left[1]; + var tr = right[0]; + var br = right[1]; return List.of(bl, br, tr, tl); } @@ -140,11 +139,9 @@ public class CornerDetectionPipe // top left and top right are the poly corners closest to the bounding box tl and tr pointList.sort(compareDistToTl); - var tl = pointList.get(0); - pointList.remove(tl); + var tl = pointList.remove(0); pointList.sort(compareDistToTr); - var tr = pointList.get(0); - pointList.remove(tr); + var tr = pointList.remove(0); // at this point we look for points on the left/right of the center of the remaining points // and maximize their distance from the center of the min area rectangle @@ -160,12 +157,13 @@ public class CornerDetectionPipe for (var p : pointList) { if (p.y > target.m_mainContour.getBoundingRect().y - + target.m_mainContour.getBoundingRect().height / 2.0) + + target.m_mainContour.getBoundingRect().height / 2.0) { if (p.x < averageXCoordinate) { leftList.add(p); } else { rightList.add(p); } + } } if (leftList.isEmpty() || rightList.isEmpty()) return null; leftList.sort(compareCenterDist); diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java index 12f2ac913..37ee97733 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FilterContoursPipe.java @@ -67,9 +67,7 @@ public class FilterContoursPipe double x = c.getCenterPoint().x; double y = c.getCenterPoint().y; - if (Math.abs(x - meanX) > stdDevX * xTol) { - it.remove(); - } else if (Math.abs(y - meanY) > stdDevY * yTol) { + if (Math.abs(x - meanX) > stdDevX * xTol || Math.abs(y - meanY) > stdDevY * yTol) { it.remove(); } // Otherwise we're good! Keep it in diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java index fb2dd3b8b..1d670cb78 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/FindBoardCornersPipe.java @@ -54,7 +54,7 @@ public class FindBoardCornersPipe // Since we return results in real-time, we want to ensure it goes as fast as // possible // and fails as fast as possible. - final int findChessboardFlags = + static final int findChessboardFlags = Calib3d.CALIB_CB_NORMALIZE_IMAGE | Calib3d.CALIB_CB_ADAPTIVE_THRESH | Calib3d.CALIB_CB_FILTER_QUADS diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GrayscalePipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GrayscalePipe.java index 04b1bf774..97b95b195 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GrayscalePipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/GrayscalePipe.java @@ -32,7 +32,5 @@ public class GrayscalePipe extends CVPipe>(); var videoModes = visionSource.getSettables().getAllVideoModes(); - for (var k : videoModes.keySet()) { + for (var k : videoModes.entrySet()) { var internalMap = new HashMap(); - internalMap.put("width", videoModes.get(k).width); - internalMap.put("height", videoModes.get(k).height); - internalMap.put("fps", videoModes.get(k).fps); + internalMap.put("width", k.getValue().width); + internalMap.put("height", k.getValue().height); + internalMap.put("fps", k.getValue().fps); internalMap.put( "pixelFormat", - ((videoModes.get(k) instanceof LibcameraGpuSource.FPSRatedVideoMode) + ((k.getValue() instanceof LibcameraGpuSource.FPSRatedVideoMode) ? "kPicam" - : videoModes.get(k).pixelFormat.toString()) + : k.getValue().pixelFormat.toString()) .substring(1)); // Remove the k prefix - temp.put(k, internalMap); + temp.put(k.getKey(), internalMap); } if (videoModes.size() == 0) { diff --git a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java index 55b173736..7a5da5331 100644 --- a/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java +++ b/photon-core/src/main/java/org/photonvision/vision/processes/VisionModuleChangeSubscriber.java @@ -55,23 +55,22 @@ public class VisionModuleChangeSubscriber extends DataChangeSubscriber { @Override public void onDataChangeEvent(DataChangeEvent event) { - if (event instanceof IncomingWebSocketEvent wsEvent) { - // Camera index -1 means a "multicast event" (i.e. the event is received by all cameras) - if (wsEvent.cameraUniqueName != null - && wsEvent.cameraUniqueName.equals(parentModule.uniqueName())) { - logger.trace("Got PSC event - propName: " + wsEvent.propertyName); - changeListLock.lock(); - try { - getSettingChanges() - .add( - new VisionModuleChange( - wsEvent.propertyName, - wsEvent.data, - parentModule.pipelineManager.getCurrentPipeline().getSettings(), - wsEvent.originContext)); - } finally { - changeListLock.unlock(); - } + // Camera index -1 means a "multicast event" (i.e. the event is received by all cameras) + if (event instanceof IncomingWebSocketEvent wsEvent + && wsEvent.cameraUniqueName != null + && wsEvent.cameraUniqueName.equals(parentModule.uniqueName())) { + logger.trace("Got PSC event - propName: " + wsEvent.propertyName); + changeListLock.lock(); + try { + getSettingChanges() + .add( + new VisionModuleChange( + wsEvent.propertyName, + wsEvent.data, + parentModule.pipelineManager.getCurrentPipeline().getSettings(), + wsEvent.originContext)); + } finally { + changeListLock.unlock(); } } } diff --git a/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java b/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java index 9108abeba..848c7a447 100644 --- a/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/DataSocketHandler.java @@ -112,14 +112,13 @@ public class DataSocketHandler { var socketMessageType = DataSocketMessageType.fromEntryKey(entryKey); logger.trace( - () -> - "Got WS message: [" - + socketMessageType - + "] ==> [" - + entryKey - + "], [" - + entryValue - + "]"); + "Got WS message: [" + + socketMessageType + + "] ==> [" + + entryKey + + "], [" + + entryValue + + "]"); if (socketMessageType == null) { logger.warn("Got unknown socket message type: " + entryKey); diff --git a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java index 6becc0000..f734f38ef 100644 --- a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java @@ -641,7 +641,7 @@ public class RequestHandler { } public static void onCalibrationSnapshotRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); String cameraUniqueName = ctx.queryParam("cameraUniqueName"); var width = Integer.parseInt(ctx.queryParam("width")); @@ -695,7 +695,7 @@ public class RequestHandler { } public static void onCalibrationExportRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); String cameraUniqueName = ctx.queryParam("cameraUniqueName"); var width = Integer.parseInt(ctx.queryParam("width")); @@ -900,7 +900,7 @@ public class RequestHandler { } public static void onActivateMatchedCameraRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); String cameraUniqueName = ctx.queryParam("cameraUniqueName"); @@ -914,7 +914,7 @@ public class RequestHandler { } public static void onAssignUnmatchedCameraRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); PVCameraInfo camera; try { @@ -934,7 +934,7 @@ public class RequestHandler { } public static void onUnassignCameraRequest(Context ctx) { - logger.info(ctx.queryString().toString()); + logger.info(ctx.queryString()); String cameraUniqueName = ctx.queryParam("cameraUniqueName"); diff --git a/photon-targeting/src/test/java/jni/FileLoggerTest.java b/photon-targeting/src/test/java/jni/FileLoggerTest.java index 157ee9f1e..f974825b3 100644 --- a/photon-targeting/src/test/java/jni/FileLoggerTest.java +++ b/photon-targeting/src/test/java/jni/FileLoggerTest.java @@ -15,7 +15,7 @@ * along with this program. If not, see . */ -package wpiutil_extras; +package jni; import static org.junit.jupiter.api.Assertions.fail; import static org.junit.jupiter.api.Assumptions.assumeTrue; From 3ea910084543f4d5f73073d09faaba3bae13da08 Mon Sep 17 00:00:00 2001 From: Matt Morley Date: Sat, 19 Apr 2025 17:37:31 -0700 Subject: [PATCH 29/42] Add docs about robot modes (#1924) ## Description Adds docs about the new logging added in 1923 ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [x] If this PR changes behavior or adds a feature, user documentation is updated - [ ] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [ ] If this PR touches configuration, this is backwards compatible with settings back to v2024.3.1 - [ ] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [ ] If this PR addresses a bug, a regression test for it is added --- docs/source/docs/troubleshooting/logging.md | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/docs/source/docs/troubleshooting/logging.md b/docs/source/docs/troubleshooting/logging.md index ddf275a60..bf1eea0fa 100644 --- a/docs/source/docs/troubleshooting/logging.md +++ b/docs/source/docs/troubleshooting/logging.md @@ -20,3 +20,21 @@ Logs are stored inside the {code}`photonvision_config/logs` directory. Exporting Your browser does not support the video tag. ``` + +Robot mode transitions are also recorded in program logs. These transition messages look something like the two shown below, and show the contents of the [HAL Control Word](https://github.wpilib.org/allwpilib/docs/release/java/edu/wpi/first/hal/ControlWord.html) that the robot was in previously, and what it is now in. This includes: +- Enabled state +- Robot state (autonomous vs teleoperated) +- If the robot e-stop is active + +If the robot is connected to the FMS at an event, we will additionally print out: +- Event name +- Match type +- Driver station position + + +``` +[2025-04-19 19:52:08] [NetworkTables - NTDriverStation] [INFO] ROBOT TRANSITIONED MODES! From NtControlWord[m_enabled=true, m_autonomous=false, m_test=false, m_emergencyStop=false, m_fmsAttached=true, m_dsAttached=true] to NtControlWord[m_enabled=true, m_autonomous=false, m_test=true, m_emergencyStop=false, m_fmsAttached=true, m_dsAttached=true] + +[2025-04-19 19:52:09] [NetworkTables - NTDriverStation] [INFO] ROBOT TRANSITIONED MODES! From NtControlWord[m_enabled=true, m_autonomous=false, m_test=true, m_emergencyStop=false, m_fmsAttached=true, m_dsAttached=true] to NtControlWord[m_enabled=false, m_autonomous=false, m_test=false, m_emergencyStop=false, m_fmsAttached=false, m_dsAttached=false] +[2025-04-19 19:52:19] [NetworkTables - NTDriverStation] [INFO] ROBOT TRANSITIONED MODES! From NtControlWord[m_enabled=false, m_autonomous=false, m_test=false, m_emergencyStop=false, m_fmsAttached=false, m_dsAttached=false] to NtControlWord[m_enabled=true, m_autonomous=true, m_test=false, m_emergencyStop=false, m_fmsAttached=true, m_dsAttached=true] +``` From 5349cae9651af31d188d7794d2a6ad81f42a7474 Mon Sep 17 00:00:00 2001 From: Alan <40917647+alaninnovates@users.noreply.github.com> Date: Sat, 19 Apr 2025 21:24:22 -0700 Subject: [PATCH 30/42] [docs] Minor documentation changes (#1922) --- docs/source/docs/description.md | 2 +- docs/source/docs/quick-start/networking.md | 2 +- docs/source/docs/quick-start/wiring.md | 6 +++++- 3 files changed, 7 insertions(+), 3 deletions(-) diff --git a/docs/source/docs/description.md b/docs/source/docs/description.md index 35e6e74b0..e0f501c9d 100644 --- a/docs/source/docs/description.md +++ b/docs/source/docs/description.md @@ -11,7 +11,7 @@ PhotonVision has a myriad of advantages over similar solutions, including: ### Affordable -Compared to alternatives, PhotonVision is much cheaper to use (at the cost of your coprocessor and camera) compared to alternatives that cost \$400. This allows your team to save money while still being competitive. +PhotonVision offers a more affordable solution to vision, with costs being from your coprocessor(s) and camera(s). Teams may choose to run multiple cameras from one coprocessor. This makes it a great solution for teams with limited budgets. ### Easy to Use User Interface diff --git a/docs/source/docs/quick-start/networking.md b/docs/source/docs/quick-start/networking.md index 37ec600de..6b52059a6 100644 --- a/docs/source/docs/quick-start/networking.md +++ b/docs/source/docs/quick-start/networking.md @@ -54,13 +54,13 @@ Only use a static IP when connected to the **robot radio**, and never when testi 5. Change your IP to Static. 6. Set your coprocessor's IP address to “10.TE.AM.11”. More information on IP format can be found [here](https://docs.wpilib.org/en/stable/docs/networking/networking-introduction/ip-configurations.html#on-the-field-static-configuration). 7. Click the “Save” button. -8. Set your roboRIO to the following static IP address: “10.TE.AM.2”. This can be done via the [roboRIO web dashboard](https://docs.wpilib.org/en/stable/docs/software/roborio-info/roborio-web-dashboard.html#roborio-web-dashboard). Power-cycle your robot and then you will now be access the PhotonVision dashboard at `10.TE.AM.11:5800`. ```{image} images/static.png :alt: Correctly set static IP ``` + The "team number" field will accept (in addition to a team number) an IP address or hostname. This is useful for testing PhotonVision on the same computer as a simulated robot program; you can set the team number to "localhost", and PhotonVision will send data to the network tables in the simulated robot. diff --git a/docs/source/docs/quick-start/wiring.md b/docs/source/docs/quick-start/wiring.md index 001e6bf87..26dc43bf3 100644 --- a/docs/source/docs/quick-start/wiring.md +++ b/docs/source/docs/quick-start/wiring.md @@ -78,7 +78,11 @@ This diagram shows how to use the recommended regulator to power a coprocessor. Pigtails can be purchased from many sources we recommend [(USB C)](https://ctr-electronics.com/products/usb-type-c-wire-breakout?_pos=19&_sid=bf06b6a6b&_ss=r) [(Micro USB)](https://ctr-electronics.com/products/usb-micro-power-wire-breakout?pr_prod_strat=e5_desc&pr_rec_id=10bf36ce7&pr_rec_pid=7863771070637&pr_ref_pid=7863771103405&pr_seq=uniform) -## Coprocessor with Passive POE (Pi with SnakeEyes and Limelight) +## Limelight + +Follow the wiring instructions located in the [Limelight Documentation](https://docs.limelightvision.io/) for your Limelight model. + +## Coprocessor with Passive POE (Pi with SnakeEyes) 1. Plug the [passive POE injector](https://www.revrobotics.com/rev-11-1210/) into the coprocessor and wire it to PDP/PDH (NOT the VRM). 2. Add a breaker to relevant slot in your PDP/PDH From 7bbfe6f05bfc6a2b22d42b85937f39803d34d337 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Sun, 20 Apr 2025 12:35:27 +0000 Subject: [PATCH 31/42] Clean up build (#1926) --- build.gradle | 1 - photon-core/build.gradle | 6 ------ photon-docs/build.gradle | 25 ++----------------------- shared/common.gradle | 34 ---------------------------------- shared/config.gradle | 26 -------------------------- 5 files changed, 2 insertions(+), 90 deletions(-) diff --git a/build.gradle b/build.gradle index 90ac4a7b0..3ec1fd50b 100644 --- a/build.gradle +++ b/build.gradle @@ -37,7 +37,6 @@ ext { wpimathVersion = wpilibVersion openCVYear = "2025" openCVversion = "4.10.0-3" - joglVersion = "2.4.0" javalinVersion = "5.6.2" libcameraDriverVersion = "v2025.0.3" rknnVersion = "dev-v2025.0.0-1-g33b6263" diff --git a/photon-core/build.gradle b/photon-core/build.gradle index 0f94fbec5..7faefdc9a 100644 --- a/photon-core/build.gradle +++ b/photon-core/build.gradle @@ -26,12 +26,6 @@ nativeConfig.dependencies.add wpilibTools.deps.wpilib("hal") nativeConfig.dependencies.add wpilibTools.deps.wpilibOpenCv("frc" + openCVYear, wpi.versions.opencvVersion.get()) dependencies { - // JOGL stuff (currently we only distribute for aarch64, which is Pi 4) - implementation "org.jogamp.gluegen:gluegen-rt:$joglVersion" - implementation "org.jogamp.jogl:jogl-all:$joglVersion" - implementation "org.jogamp.gluegen:gluegen-rt:$joglVersion:natives-linux-aarch64" - implementation "org.jogamp.jogl:jogl-all:$joglVersion:natives-linux-aarch64" - // Zip implementation 'org.zeroturnaround:zt-zip:1.14' diff --git a/photon-docs/build.gradle b/photon-docs/build.gradle index e99e6c697..ff46e79e8 100644 --- a/photon-docs/build.gradle +++ b/photon-docs/build.gradle @@ -132,29 +132,8 @@ task generateJavaDocs(type: Javadoc) { title = "PhotonVision $pubVersion" ext.entryPoint = "$destinationDir/index.html" - if (JavaVersion.current().isJava8Compatible() && project.hasProperty('docWarningsAsErrors')) { - // Treat javadoc warnings as errors. - // - // The second argument '-quiet' is a hack. The one parameter - // addStringOption() doesn't work, so we add '-quiet', which is added - // anyway by gradle. See https://github.com/gradle/gradle/issues/2354. - // - // See JDK-8200363 (https://bugs.openjdk.java.net/browse/JDK-8200363) - // for information about the nonstandard -Xwerror option. JDK 15+ has - // -Werror. - options.addStringOption('Xwerror', '-quiet') - } - - if (JavaVersion.current().isJava11Compatible()) { - if (!JavaVersion.current().isJava12Compatible()) { - options.addBooleanOption('-no-module-directories', true) - } - doLast { - // This is a work-around for https://bugs.openjdk.java.net/browse/JDK-8211194. Can be removed once that issue is fixed on JDK's side - // Since JDK 11, package-list is missing from javadoc output files and superseded by element-list file, but a lot of external tools still need it - // Here we generate this file manually - new File(destinationDir, 'package-list').text = new File(destinationDir, 'element-list').text - } + if (project.hasProperty('docWarningsAsErrors')) { + options.addBooleanOption('Werror', true) } } diff --git a/shared/common.gradle b/shared/common.gradle index 6a0cf794c..9f3386c2c 100644 --- a/shared/common.gradle +++ b/shared/common.gradle @@ -68,40 +68,6 @@ tasks.register('testHeadless', Test) { workingDir = "../" } -tasks.register('generateJavaDocs', Javadoc) { - source = sourceSets.main.allJava - classpath = sourceSets.main.compileClasspath - destinationDir = file("${projectDir}/build/docs") - - options.addBooleanOption("Xdoclint:html,missing,reference,syntax", true) - options.addBooleanOption('html5', true) - - if (JavaVersion.current().isJava8Compatible() && project.hasProperty('docWarningsAsErrors')) { - // Treat javadoc warnings as errors. - // - // The second argument '-quiet' is a hack. The one parameter - // addStringOption() doesn't work, so we add '-quiet', which is added - // anyway by gradle. See https://github.com/gradle/gradle/issues/2354. - // - // See JDK-8200363 (https://bugs.openjdk.java.net/browse/JDK-8200363) - // for information about the nonstandard -Xwerror option. JDK 15+ has - // -Werror. - options.addStringOption('Xwerror', '-quiet') - } - - if (JavaVersion.current().isJava11Compatible()) { - if (!JavaVersion.current().isJava12Compatible()) { - options.addBooleanOption('-no-module-directories', true) - } - doLast { - // This is a work-around for https://bugs.openjdk.java.net/browse/JDK-8211194. Can be removed once that issue is fixed on JDK's side - // Since JDK 11, package-list is missing from javadoc output files and superseded by element-list file, but a lot of external tools still need it - // Here we generate this file manually - new File(destinationDir, 'package-list').text = new File(destinationDir, 'element-list').text - } - } -} - jacoco { toolVersion = "0.8.10" reportsDirectory = layout.buildDirectory.dir('customJacocoReportDir') diff --git a/shared/config.gradle b/shared/config.gradle index 1178f8372..307aa9712 100644 --- a/shared/config.gradle +++ b/shared/config.gradle @@ -135,32 +135,6 @@ ext.createComponentZipTasks = { components, names, base, type, project, func -> return taskList } -ext.createAllCombined = { list, name, base, type, project -> - def outputsFolder = file("$project.buildDir/outputs") - - def task = project.tasks.create(base + "-all", type) { - description = "Creates component archive for all classifiers" - destinationDirectory = outputsFolder - classifier = "all" - archiveBaseName = base - duplicatesStrategy = 'exclude' - - list.each { - if (it.name.endsWith('debug')) return - from project.zipTree(it.archiveFile) - dependsOn it - } - } - - project.build.dependsOn task - - project.artifacts { - task - } - - return task -} - // Create the standard ZIP format for the dependencies. ext.includeStandardZipFormat = { task, value -> value.each { binary -> From c15c62698a0b3cf957d6d63b11c0b6d82a55a3aa Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Tue, 22 Apr 2025 00:04:26 +0000 Subject: [PATCH 32/42] Revert "Use Timer object to calculate FPS" (#1928) This reverts commit a4295275ed5479c164276076d5fc51a69dd3fc49. ## Description This commit broke the FPS counter because I forgot to start the timer. I could just use `restart`, and then it would only be wrong for the very first pipeline run, but that's a hack, and frankly, the old way was fine. ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [ ] If this PR changes behavior or adds a feature, user documentation is updated - [ ] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [ ] If this PR touches configuration, this is backwards compatible with settings back to v2024.3.1 - [ ] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [ ] If this PR addresses a bug, a regression test for it is added --- .../vision/pipe/impl/CalculateFPSPipe.java | 13 ++++++++++--- 1 file changed, 10 insertions(+), 3 deletions(-) diff --git a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java index f1814a031..b840e6602 100644 --- a/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java +++ b/photon-core/src/main/java/org/photonvision/vision/pipe/impl/CalculateFPSPipe.java @@ -24,12 +24,19 @@ import org.photonvision.vision.pipe.CVPipe; public class CalculateFPSPipe extends CVPipe { private final LinearFilter fpsFilter = LinearFilter.movingAverage(20); - private final Timer timer = new Timer(); + + // roll my own Timer, since this is so trivial + double lastTime = -1; @Override protected Integer process(Void in) { - var dtSeconds = timer.get(); - timer.reset(); + if (lastTime < 0) { + lastTime = Timer.getFPGATimestamp(); + } + + var now = Timer.getFPGATimestamp(); + var dtSeconds = now - lastTime; + lastTime = now; // If < 1 uS between ticks, something is probably wrong int fps; From 0c9502d8b917c08be2e4bb1bad4246dc96668527 Mon Sep 17 00:00:00 2001 From: Matt Morley Date: Tue, 22 Apr 2025 07:53:24 -0700 Subject: [PATCH 33/42] Add leading zero to log file date/time (#1925) ## Description WAS: Logs did not have a leading zero, meaning that alphabetical and temporal sort were not the same IS: Logs now have leading zeros added. This means that alphabetical sort works properly. ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [ ] If this PR changes behavior or adds a feature, user documentation is updated - [ ] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [ ] If this PR touches configuration, this is backwards compatible with settings back to v2024.3.1 - [ ] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [ ] If this PR addresses a bug, a regression test for it is added --------- Co-authored-by: Craig Schardt --- docs/source/docs/troubleshooting/logging.md | 2 +- .../common/configuration/PathManager.java | 4 +- .../common/configuration/PathManagerTest.java | 85 +++++++++++++++++++ 3 files changed, 88 insertions(+), 3 deletions(-) create mode 100644 photon-core/src/test/java/org/photonvision/common/configuration/PathManagerTest.java diff --git a/docs/source/docs/troubleshooting/logging.md b/docs/source/docs/troubleshooting/logging.md index bf1eea0fa..4c05488e4 100644 --- a/docs/source/docs/troubleshooting/logging.md +++ b/docs/source/docs/troubleshooting/logging.md @@ -28,7 +28,7 @@ Robot mode transitions are also recorded in program logs. These transition messa If the robot is connected to the FMS at an event, we will additionally print out: - Event name -- Match type +- Match type and number - Driver station position diff --git a/photon-core/src/main/java/org/photonvision/common/configuration/PathManager.java b/photon-core/src/main/java/org/photonvision/common/configuration/PathManager.java index 0a57d13d0..3f9d5795e 100644 --- a/photon-core/src/main/java/org/photonvision/common/configuration/PathManager.java +++ b/photon-core/src/main/java/org/photonvision/common/configuration/PathManager.java @@ -53,9 +53,9 @@ public class PathManager { public static final String LOG_PREFIX = "photonvision-"; public static final String LOG_EXT = ".log"; - public static final String LOG_DATE_TIME_FORMAT = "yyyy-M-d_hh-mm-ss"; + public static final String LOG_DATE_TIME_FORMAT = "yyyy-MM-dd_HH-mm-ss"; - public String taToLogFname(TemporalAccessor date) { + public static String taToLogFname(TemporalAccessor date) { var dateString = DateTimeFormatter.ofPattern(LOG_DATE_TIME_FORMAT).format(date); return LOG_PREFIX + dateString + LOG_EXT; } diff --git a/photon-core/src/test/java/org/photonvision/common/configuration/PathManagerTest.java b/photon-core/src/test/java/org/photonvision/common/configuration/PathManagerTest.java new file mode 100644 index 000000000..f81408cf8 --- /dev/null +++ b/photon-core/src/test/java/org/photonvision/common/configuration/PathManagerTest.java @@ -0,0 +1,85 @@ +/* + * Copyright (C) Photon Vision. + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + */ + +package org.photonvision.common.configuration; + +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertTrue; + +import java.time.LocalDateTime; +import java.time.Month; +import java.time.ZoneId; +import java.time.ZonedDateTime; +import org.junit.jupiter.api.Test; + +public class PathManagerTest { + @Test + public void testNamingFormat_LeadingZeros_And24HourUTC() { + // GIVEN: a LocalDateTime with single-digit month, day, hour, minute, second + LocalDateTime dt = LocalDateTime.of(2024, 1, 2, 3, 4, 5); + + // WHEN: taToLogFname is called + String fname = PathManager.taToLogFname(dt); + + // THEN: the returned name has leading zeros in all date and time parts + assertTrue( + fname.matches("^photonvision-2024-01-02_03-04-05\\.log$"), + "Filename should match the expected pattern with leading zeros"); + + // THEN: time is in 24-hour format (03 not 03AM or 3PM), already shown implicitly + assertTrue(fname.contains("_03-04-05"), "Time should be in 24-hour format with leading zeros"); + } + + @Test + public void testNamingFormat_OtherDate_CheckPattern() { + // GIVEN: another date and time + LocalDateTime dt = LocalDateTime.of(2023, 12, 31, 23, 59, 59); + + // WHEN: taToLogFname is called + String fname = PathManager.taToLogFname(dt); + + // THEN: the returned name correctly formats the entire timestamp + assertEquals("photonvision-2023-12-31_23-59-59.log", fname); + } + + @Test + public void testNamingFormat_WithZonedDateTime_ConvertsToUTC() { + // GIVEN: a UTC ZonedDateTime at 7:08:09 on June 3, 2024 + ZonedDateTime utcDateTime = + ZonedDateTime.of(2024, Month.JUNE.getValue(), 3, 7, 8, 9, 0, ZoneId.of("UTC")); + + // WHEN: taToLogFname is called + String fname = PathManager.taToLogFname(utcDateTime); + + // THEN: it is formatted in UTC, with leading zeros, 24-hour + assertEquals("photonvision-2024-06-03_07-08-09.log", fname); + } + + @Test + public void testNamingFormat_WithNonUtcZoneTime_FormatsActualFieldsNotConverted() { + // GIVEN: a ZonedDateTime for 20:17:16 America/New_York (should use the provided fields, not + // convert to UTC) + ZonedDateTime nyTime = + ZonedDateTime.of(2024, 6, 3, 20, 17, 16, 0, ZoneId.of("America/New_York")); + + // WHEN: taToLogFname is called + String fname = PathManager.taToLogFname(nyTime); + + // THEN: asserts that fields from the zoned time are respected as is + assertEquals("photonvision-2024-06-03_20-17-16.log", fname); + } +} From 99b4dc8725637a48d40be6dc71e0c1eb381c4365 Mon Sep 17 00:00:00 2001 From: Maximilian McDiarmid <76010421+fakevoxel@users.noreply.github.com> Date: Tue, 22 Apr 2025 16:27:53 -0400 Subject: [PATCH 34/42] Updates to object detection documentation (#1930) ## Description Added a warning about non-quantized custom models not being supported, and a note about not being able to delete models from the GUI once they're uploaded to the coprocessor. --------- Co-authored-by: Sam Freund --- .../source/docs/objectDetection/about-object-detection.md | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/docs/source/docs/objectDetection/about-object-detection.md b/docs/source/docs/objectDetection/about-object-detection.md index 40ee828ae..a155a2f98 100644 --- a/docs/source/docs/objectDetection/about-object-detection.md +++ b/docs/source/docs/objectDetection/about-object-detection.md @@ -47,9 +47,17 @@ Before beginning, it is necessary to install the [rknn-toolkit2](https://github. PhotonVision currently ONLY supports 640x640 Ultralytics YOLOv5, YOLOv8, and YOLOv11 models trained and converted to `.rknn` format for RK3588 CPUs! Other models require different post-processing code and will NOT work. The model conversion process is also highly particular. Proceed with care. ::: +:::{warning} +Non-quantized models are not supported! If you have the option, make sure quantization is enabled when exporting to .rknn format. This will represent the weights and activations of the model as 8-bit integers, instead of 32-bit floats which PhotonVision doesn't support. Quantized models are also much faster. +::: + In the settings, under `Device Control`, there's an option to upload a new object detection model. Naming convention should be `name-verticalResolution-horizontalResolution-yolovXXX`. The `name` should only include alphanumeric characters, periods, and underscores. Additionally, the labels file ought to have the same name as the RKNN file, with `-labels` appended to the end. For example, if the RKNN file is named `Algae_1.03.2025-640-640-yolov5s.rknn`, the labels file should be named `Algae_1.03.2025-640-640-yolov5s-labels.txt`. + +:::{note} +Currently there is no way to delete custom models in the GUI, though this is a planned feature. To do this, you have to SSH into the coprocessor and delete the files manually from `/opt/photonvision/photonvision_config/models`. +::: From c1b0c8a831cc7984a1f8d6e8ec6f42b35e7a485f Mon Sep 17 00:00:00 2001 From: Bryce Roethel Date: Sat, 26 Apr 2025 00:57:27 -0400 Subject: [PATCH 35/42] [photon-lib] Add PhotonPoseEstimator.resetHeadingData() (#1933) --- .../java/org/photonvision/PhotonPoseEstimator.java | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java index a389d5931..1675ad3d1 100644 --- a/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java +++ b/photon-lib/src/main/java/org/photonvision/PhotonPoseEstimator.java @@ -336,6 +336,19 @@ public class PhotonPoseEstimator { headingBuffer.addSample(timestampSeconds, heading); } + /** + * Clears all heading data in the buffer, and adds a new seed. Useful for preventing estimates + * from utilizing heading data provided prior to a pose or rotation reset. + * + * @param timestampSeconds timestamp of the robot heading data. + * @param heading Field-relative robot heading at given timestamp. Standard WPILIB field + * coordinates. + */ + public void resetHeadingData(double timestampSeconds, Rotation2d heading) { + headingBuffer.clear(); + addHeadingData(timestampSeconds, heading); + } + /** * @return The current transform from the center of the robot to the camera mount position */ From ae9f73130f4c1c2e71e67122a7693bf9cc2f7ed7 Mon Sep 17 00:00:00 2001 From: Nolan Brown Date: Tue, 29 Apr 2025 15:06:59 -0700 Subject: [PATCH 36/42] [photon-lib] Fix incorrect tag visualization transforms (#1899) ## Description Fixes #1239 Tag image corners used in `VideoSimUtil` did not match the expected corner order returned by the detection pipeline of [BL, BR, TR, TL], causing the tag image to appear flipped. ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [x] If this PR changes behavior or adds a feature, user documentation is updated - [ ] If this PR addresses a bug, a regression test for it is added --- .../java/org/photonvision/simulation/VideoSimUtil.java | 8 +++++--- .../main/native/include/photon/simulation/VideoSimUtil.h | 6 +++--- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java b/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java index 89face676..038d1f89e 100644 --- a/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java +++ b/photon-lib/src/main/java/org/photonvision/simulation/VideoSimUtil.java @@ -84,14 +84,16 @@ public class VideoSimUtil { * through a Mat, the point (0,0) actually represents the center of the top-left pixel and not the * actual top-left corner. * + *

Order of corners returned is: [BL, BR, TR, TL] + * * @param size Size of image */ public static Point[] getImageCorners(Size size) { return new Point[] { - new Point(-0.5, -0.5), - new Point(size.width - 0.5, -0.5), + new Point(-0.5, size.height - 0.5), new Point(size.width - 0.5, size.height - 0.5), - new Point(-0.5, size.height - 0.5) + new Point(size.width - 0.5, -0.5), + new Point(-0.5, -0.5) }; } diff --git a/photon-lib/src/main/native/include/photon/simulation/VideoSimUtil.h b/photon-lib/src/main/native/include/photon/simulation/VideoSimUtil.h index 9f86e1ca7..618f36e1b 100644 --- a/photon-lib/src/main/native/include/photon/simulation/VideoSimUtil.h +++ b/photon-lib/src/main/native/include/photon/simulation/VideoSimUtil.h @@ -76,10 +76,10 @@ static std::unordered_map LoadAprilTagImages() { static std::vector GetImageCorners(const cv::Size& size) { std::vector retVal{}; - retVal.emplace_back(cv::Point2f{-0.5f, -0.5f}); - retVal.emplace_back(cv::Point2f{size.width - 0.5f, -0.5f}); - retVal.emplace_back(cv::Point2f{size.width - 0.5f, size.height - 0.5f}); retVal.emplace_back(cv::Point2f{-0.5f, size.height - 0.5f}); + retVal.emplace_back(cv::Point2f{size.width - 0.5f, size.height - 0.5f}); + retVal.emplace_back(cv::Point2f{size.width - 0.5f, -0.5f}); + retVal.emplace_back(cv::Point2f{-0.5f, -0.5f}); return retVal; } From 73cd2ab62c1045a9198f62b6374991a91029c34b Mon Sep 17 00:00:00 2001 From: Sam Freund Date: Sun, 4 May 2025 00:15:32 -0500 Subject: [PATCH 37/42] Standardize API (#1942) ## Description closes #1941 Rewrite the API to use the payload method , and use records in the ``RequestHandler``. There's a couple places where this isn't the place, that's where the front end is making a get request, and so a payload doesn't make sense. This is meant to encourage more static typing. Additionally, fix some typos in params in ``CameraSettingsStore`` ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [x] If this PR changes behavior or adds a feature, user documentation is updated - [x] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [x] If this PR touches configuration, this is backwards compatible with settings back to v2024.3.1 - [x] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [x] If this PR addresses a bug, a regression test for it is added - [x] Everything changed got tested --------- Co-authored-by: Matt Morley --- .../stores/settings/CameraSettingsStore.ts | 25 ++- .../src/views/CameraMatchingView.vue | 100 +++++++-- .../vision/camera/PVCameraInfo.java | 2 + .../photonvision/server/RequestHandler.java | 203 ++++++++++-------- 4 files changed, 211 insertions(+), 119 deletions(-) diff --git a/photon-client/src/stores/settings/CameraSettingsStore.ts b/photon-client/src/stores/settings/CameraSettingsStore.ts index 4e5e1dc6c..e21b56f6d 100644 --- a/photon-client/src/stores/settings/CameraSettingsStore.ts +++ b/photon-client/src/stores/settings/CameraSettingsStore.ts @@ -155,7 +155,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { * Update the configurable camera settings. * * @param data camera settings to save. - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. */ updateCameraSettings( data: CameraSettingsChangeRequest, @@ -163,9 +163,8 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { ) { // The camera settings endpoint doesn't actually require all data, instead, it needs key data such as the FOV const payload = { - settings: { - ...data - }, + fov: data.fov, + quirksToChange: data.quirksToChange, cameraUniqueName: cameraUniqueName }; return axios.post("/settings/camera", payload); @@ -175,7 +174,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { * * @param newPipelineName the name of the new pipeline. * @param pipelineType the type of the new pipeline. Cannot be {@link WebsocketPipelineType.Calib3d} or {@link WebsocketPipelineType.DriverMode}. - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. */ createNewPipeline( newPipelineName: string, @@ -193,7 +192,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { * * @param settings settings to modify. The type of the settings should match the currently selected pipeline type. * @param updateStore whether or not to update the store. This is useful if the input field already models the store reference. - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. */ changeCurrentPipelineSetting( settings: ActiveConfigurablePipelineSettings, @@ -224,7 +223,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { * * @param newName the new nickname for the camera. * @param updateStore whether or not to update the store. This is useful if the input field already models the store reference. - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. */ changeCurrentPipelineNickname( newName: string, @@ -244,7 +243,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { * Modify the Pipeline type of the currently selected pipeline of the provided camera. This overwrites the current pipeline's settings when the backend resets the current pipeline settings. * * @param type the pipeline type to set. Cannot be {@link WebsocketPipelineType.Calib3d} or {@link WebsocketPipelineType.DriverMode}. - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. */ changeCurrentPipelineType( type: Exclude, @@ -261,7 +260,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { * * @param index pipeline index to set. * @param updateStore whether or not to update the store. This is useful if the input field already models the store reference. - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. */ changeCurrentPipelineIndex( index: number, @@ -293,7 +292,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { /** * Change the currently selected pipeline of the provided camera. * - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. */ deleteCurrentPipeline(cameraUniqueName: string = useStateStore().currentCameraUniqueName) { const payload = { @@ -306,7 +305,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { * Duplicate the pipeline at the provided index. * * @param pipelineIndex index of the pipeline to duplicate. - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. */ duplicatePipeline(pipelineIndex: number, cameraUniqueName: string = useStateStore().currentCameraUniqueName) { const payload = { @@ -335,7 +334,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { * * @param newName the new nickname of the camera. * @param updateStore whether or not to update the store. This is useful if the input field already models the store reference. - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. * @return HTTP request promise to the backend */ changeCameraNickname( @@ -356,7 +355,7 @@ export const useCameraSettingsStore = defineStore("cameraSettings", { * Start the 3D calibration process for the provided camera. * * @param calibrationInitData initialization calibration data. - * @param cameraUniqueNamendex the unique name of the camera. + * @param cameraUniqueName the unique name of the camera. */ startPnPCalibration( calibrationInitData: { diff --git a/photon-client/src/views/CameraMatchingView.vue b/photon-client/src/views/CameraMatchingView.vue index 082ab1285..999a89c19 100644 --- a/photon-client/src/views/CameraMatchingView.vue +++ b/photon-client/src/views/CameraMatchingView.vue @@ -23,36 +23,106 @@ const activatingModule = ref(false); const activateModule = (moduleUniqueName: string) => { if (activatingModule.value) return; activatingModule.value = true; - const url = new URL(`http://${host}/api/utils/activateMatchedCamera`); - url.searchParams.set("cameraUniqueName", moduleUniqueName); - fetch(url.toString(), { - method: "POST" - }).finally(() => (activatingModule.value = false)); + axios + .post("/utils/activateMatchedCamera", { cameraUniqueName: moduleUniqueName }) + .then(() => { + useStateStore().showSnackbarMessage({ + message: "Camera activated successfully", + color: "success" + }); + }) + .catch((error) => { + if (error.response) { + useStateStore().showSnackbarMessage({ + message: "The backend is unable to fulfil the request to activate this camera.", + color: "error" + }); + } else if (error.request) { + useStateStore().showSnackbarMessage({ + message: "Error while trying to process the request! The backend didn't respond.", + color: "error" + }); + } else { + useStateStore().showSnackbarMessage({ + message: "An error occurred while trying to process the request.", + color: "error" + }); + } + }) + .finally(() => (activatingModule.value = false)); }; const assigningCamera = ref(false); const assignCamera = (cameraInfo: PVCameraInfo) => { if (assigningCamera.value) return; assigningCamera.value = true; - const url = new URL(`http://${host}/api/utils/assignUnmatchedCamera`); - url.searchParams.set("cameraInfo", JSON.stringify(cameraInfo)); - fetch(url.toString(), { - method: "POST" - }).finally(() => (assigningCamera.value = false)); + const payload = { + cameraInfo: cameraInfo + }; + + axios + .post("/utils/assignUnmatchedCamera", payload) + .then(() => { + useStateStore().showSnackbarMessage({ + message: "Unmatched camera assigned successfully", + color: "success" + }); + }) + .catch((error) => { + if (error.response) { + useStateStore().showSnackbarMessage({ + message: "The backend is unable to fulfil the request to assign this unmatched camera.", + color: "error" + }); + } else if (error.request) { + useStateStore().showSnackbarMessage({ + message: "Error while trying to process the request! The backend didn't respond.", + color: "error" + }); + } else { + useStateStore().showSnackbarMessage({ + message: "An error occurred while trying to process the request.", + color: "error" + }); + } + }) + .finally(() => (assigningCamera.value = false)); }; const deactivatingModule = ref(false); const deactivateModule = (cameraUniqueName: string) => { if (deactivatingModule.value) return; deactivatingModule.value = true; - const url = new URL(`http://${host}/api/utils/unassignCamera`); - url.searchParams.set("cameraUniqueName", cameraUniqueName); - fetch(url.toString(), { - method: "POST" - }).finally(() => (deactivatingModule.value = false)); + axios + .post("/utils/unassignCamera", { cameraUniqueName: cameraUniqueName }) + .then(() => { + useStateStore().showSnackbarMessage({ + message: "Camera deactivated successfully", + color: "success" + }); + }) + .catch((error) => { + if (error.response) { + useStateStore().showSnackbarMessage({ + message: "The backend is unable to fulfil the request to deactivate this camera.", + color: "error" + }); + } else if (error.request) { + useStateStore().showSnackbarMessage({ + message: "Error while trying to process the request! The backend didn't respond.", + color: "error" + }); + } else { + useStateStore().showSnackbarMessage({ + message: "An error occurred while trying to process the request.", + color: "error" + }); + } + }) + .finally(() => (deactivatingModule.value = false)); }; const deletingCamera = ref(false); diff --git a/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java b/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java index 9728569cb..d67bdfb34 100644 --- a/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java +++ b/photon-core/src/main/java/org/photonvision/vision/camera/PVCameraInfo.java @@ -19,6 +19,7 @@ package org.photonvision.vision.camera; import com.fasterxml.jackson.annotation.JsonCreator; import com.fasterxml.jackson.annotation.JsonGetter; +import com.fasterxml.jackson.annotation.JsonIgnoreProperties; import com.fasterxml.jackson.annotation.JsonProperty; import com.fasterxml.jackson.annotation.JsonSubTypes; import com.fasterxml.jackson.annotation.JsonTypeInfo; @@ -27,6 +28,7 @@ import edu.wpi.first.cscore.UsbCameraInfo; import java.util.Arrays; @JsonTypeInfo(use = JsonTypeInfo.Id.NAME, include = JsonTypeInfo.As.WRAPPER_OBJECT) +@JsonIgnoreProperties(ignoreUnknown = true) @JsonSubTypes({ @JsonSubTypes.Type(value = PVCameraInfo.PVUsbCameraInfo.class), @JsonSubTypes.Type(value = PVCameraInfo.PVCSICameraInfo.class), diff --git a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java index f734f38ef..6f7bd04c0 100644 --- a/photon-server/src/main/java/org/photonvision/server/RequestHandler.java +++ b/photon-server/src/main/java/org/photonvision/server/RequestHandler.java @@ -17,7 +17,6 @@ package org.photonvision.server; -import com.fasterxml.jackson.annotation.JsonProperty; import com.fasterxml.jackson.core.JsonProcessingException; import com.fasterxml.jackson.databind.ObjectMapper; import io.javalin.http.Context; @@ -51,7 +50,6 @@ import org.photonvision.common.logging.Logger; import org.photonvision.common.networking.NetworkManager; import org.photonvision.common.util.ShellExec; import org.photonvision.common.util.TimedTaskManager; -import org.photonvision.common.util.file.JacksonUtils; import org.photonvision.common.util.file.ProgramDirectoryUtilities; import org.photonvision.vision.calibration.CameraCalibrationCoefficients; import org.photonvision.vision.camera.CameraQuirk; @@ -68,6 +66,8 @@ public class RequestHandler { private static final ObjectMapper kObjectMapper = new ObjectMapper(); + private record CommonCameraUniqueName(String cameraUniqueName) {} + public static void onSettingsImportRequest(Context ctx) { var file = ctx.uploadedFile("data"); @@ -380,39 +380,38 @@ public class RequestHandler { NetworkTablesManager.getInstance().setConfig(config); } - public static class UICameraSettingsRequest { - @JsonProperty("fov") - double fov; - - @JsonProperty("quirksToChange") - HashMap quirksToChange; - } + private record CameraSettingsRequest( + double fov, HashMap quirksToChange, String cameraUniqueName) {} public static void onCameraSettingsRequest(Context ctx) { try { - var data = kObjectMapper.readTree(ctx.bodyInputStream()); + CameraSettingsRequest request = + kObjectMapper.readValue(ctx.body(), CameraSettingsRequest.class); + // Extract the settings from the request + double fov = request.fov; + HashMap quirksToChange = request.quirksToChange; + String cameraUniqueName = request.cameraUniqueName; - String cameraUniqueName = data.get("cameraUniqueName").asText(); - var settings = - JacksonUtils.deserialize(data.get("settings").toString(), UICameraSettingsRequest.class); - var fov = settings.fov; + if (cameraUniqueName == null || cameraUniqueName.isEmpty()) { + ctx.status(400).result("cameraUniqueName is required"); + logger.error("cameraUniqueName is missing in the request"); + return; + } logger.info("Changing camera FOV to: " + fov); - logger.info("Changing quirks to: " + settings.quirksToChange.toString()); + + logger.info("Changing quirks to: " + quirksToChange.toString()); var module = VisionSourceManager.getInstance().vmm.getModule(cameraUniqueName); - module.setFov(fov); - module.changeCameraQuirks(settings.quirksToChange); + module.setFov(fov); + module.changeCameraQuirks(quirksToChange); module.saveModule(); - ctx.status(200); - ctx.result("Successfully saved camera settings"); - logger.info("Successfully saved camera settings"); - } catch (NullPointerException | IOException e) { - ctx.status(400); - ctx.result("The provided camera settings were malformed"); - logger.error("The provided camera settings were malformed", e); + ctx.status(200).result("Camera settings updated successfully"); + } catch (Exception e) { + logger.error("Failed to process camera settings request", e); + ctx.status(500).result("Failed to process camera settings request"); } } @@ -474,20 +473,21 @@ public class RequestHandler { public static void onCalibrationEndRequest(Context ctx) { logger.info("Calibrating camera! This will take a long time..."); - String cameraUniqueName; - try { - cameraUniqueName = - kObjectMapper.readTree(ctx.bodyInputStream()).get("cameraUniqueName").asText(); + CommonCameraUniqueName request = + kObjectMapper.readValue(ctx.body(), CommonCameraUniqueName.class); var calData = - VisionSourceManager.getInstance().vmm.getModule(cameraUniqueName).endCalibration(); + VisionSourceManager.getInstance() + .vmm + .getModule(request.cameraUniqueName) + .endCalibration(); if (calData == null) { ctx.result("The calibration process failed"); ctx.status(500); logger.error( "The calibration process failed. Calibration data for module at cameraUniqueName (" - + cameraUniqueName + + request.cameraUniqueName + ") was null"); return; } @@ -509,20 +509,20 @@ public class RequestHandler { } } + private record DataCalibrationImportRequest( + String cameraUniqueName, CameraCalibrationCoefficients calibration) {} + public static void onDataCalibrationImportRequest(Context ctx) { try { - var data = kObjectMapper.readTree(ctx.bodyInputStream()); - - String cameraUniqueName = data.get("cameraUniqueName").asText(); - var coeffs = - kObjectMapper.convertValue(data.get("calibration"), CameraCalibrationCoefficients.class); + DataCalibrationImportRequest request = + kObjectMapper.readValue(ctx.body(), DataCalibrationImportRequest.class); var uploadCalibrationEvent = new IncomingWebSocketEvent<>( DataChangeDestination.DCD_ACTIVEMODULE, "calibrationUploaded", - coeffs, - cameraUniqueName, + request.calibration, + request.cameraUniqueName, null); DataChangeService.getInstance().publishEvent(uploadCalibrationEvent); @@ -612,26 +612,26 @@ public class RequestHandler { ctx.status(HardwareManager.getInstance().restartDevice() ? 204 : 500); } + private record CameraNicknameChangeRequest(String name, String cameraUniqueName) {} + public static void onCameraNicknameChangeRequest(Context ctx) { try { - var data = kObjectMapper.readTree(ctx.bodyInputStream()); + CameraNicknameChangeRequest request = + kObjectMapper.readValue(ctx.body(), CameraNicknameChangeRequest.class); - String name = data.get("name").asText(); - String cameraUniqueName = data.get("cameraUniqueName").asText(); - - VisionSourceManager.getInstance().vmm.getModule(cameraUniqueName).setCameraNickname(name); + VisionSourceManager.getInstance() + .vmm + .getModule(request.cameraUniqueName) + .setCameraNickname(request.name); ctx.status(200); - ctx.result("Successfully changed the camera name to: " + name); - logger.info("Successfully changed the camera name to: " + name); + ctx.result("Successfully changed the camera name to: " + request.name); + logger.info("Successfully changed the camera name to: " + request.name); } catch (JsonProcessingException e) { - ctx.status(400); - ctx.result("The provided nickname data was malformed"); - logger.error("The provided nickname data was malformed", e); - + ctx.status(400).result("Invalid JSON format"); + logger.error("Failed to process camera nickname change request", e); } catch (Exception e) { - ctx.status(500); - ctx.result("An error occurred while changing the camera's nickname"); - logger.error("An error occurred while changing the camera's nickname", e); + ctx.status(500).result("Failed to change camera nickname"); + logger.error("Unexpected error while changing camera nickname", e); } } @@ -641,12 +641,10 @@ public class RequestHandler { } public static void onCalibrationSnapshotRequest(Context ctx) { - logger.info(ctx.queryString()); - String cameraUniqueName = ctx.queryParam("cameraUniqueName"); var width = Integer.parseInt(ctx.queryParam("width")); var height = Integer.parseInt(ctx.queryParam("height")); - var observationIdx = Integer.parseInt(ctx.queryParam("snapshotIdx")); + Integer observationIdx = Integer.parseInt(ctx.queryParam("snapshotIdx")); CameraCalibrationCoefficients calList = VisionSourceManager.getInstance() @@ -695,8 +693,6 @@ public class RequestHandler { } public static void onCalibrationExportRequest(Context ctx) { - logger.info(ctx.queryString()); - String cameraUniqueName = ctx.queryParam("cameraUniqueName"); var width = Integer.parseInt(ctx.queryParam("width")); var height = Integer.parseInt(ctx.queryParam("height")); @@ -880,72 +876,97 @@ public class RequestHandler { public static void onNukeOneCamera(Context ctx) { try { - var payload = kObjectMapper.readTree(ctx.bodyInputStream()); - var name = payload.get("cameraUniqueName").asText(); - logger.warn("Deleting camera name " + name); + CommonCameraUniqueName request = + kObjectMapper.readValue(ctx.body(), CommonCameraUniqueName.class); - var cameraDir = ConfigManager.getInstance().getCalibrationImageSavePath(name).toFile(); + logger.warn("Deleting camera name " + request.cameraUniqueName); + + var cameraDir = + ConfigManager.getInstance() + .getCalibrationImageSavePath(request.cameraUniqueName) + .toFile(); if (cameraDir.exists()) { FileUtils.deleteDirectory(cameraDir); } - VisionSourceManager.getInstance().deleteVisionSource(name); + VisionSourceManager.getInstance().deleteVisionSource(request.cameraUniqueName); ctx.status(200); } catch (IOException e) { - // todo - logger.error("asdf", e); + logger.error("Failed to delete camera", e); ctx.status(500); + ctx.result("Failed to delete camera"); + return; } } public static void onActivateMatchedCameraRequest(Context ctx) { logger.info(ctx.queryString()); + try { + CommonCameraUniqueName request = + kObjectMapper.readValue(ctx.body(), CommonCameraUniqueName.class); - String cameraUniqueName = ctx.queryParam("cameraUniqueName"); - - if (VisionSourceManager.getInstance().reactivateDisabledCameraConfig(cameraUniqueName)) { - ctx.status(200); - } else { - ctx.status(403); + if (VisionSourceManager.getInstance() + .reactivateDisabledCameraConfig(request.cameraUniqueName)) { + ctx.status(200); + } else { + ctx.status(403); + } + } catch (IOException e) { + ctx.status(401); + logger.error("Failed to process activate matched camera request", e); + ctx.result("Failed to process activate matched camera request"); + return; } - - ctx.result("Successfully assigned camera with unique name: " + cameraUniqueName); } + private record AssignUnmatchedCamera(PVCameraInfo cameraInfo) {} + public static void onAssignUnmatchedCameraRequest(Context ctx) { logger.info(ctx.queryString()); - PVCameraInfo camera; try { - camera = JacksonUtils.deserialize(ctx.queryParam("cameraInfo"), PVCameraInfo.class); + AssignUnmatchedCamera request = + kObjectMapper.readValue(ctx.body(), AssignUnmatchedCamera.class); + + if (request.cameraInfo == null) { + ctx.status(400); + ctx.result("cameraInfo is required"); + logger.error("cameraInfo is missing in the request"); + return; + } + + if (VisionSourceManager.getInstance().assignUnmatchedCamera(request.cameraInfo)) { + ctx.status(200); + } else { + ctx.status(404); + } + + ctx.result("Successfully assigned camera: " + request.cameraInfo); } catch (IOException e) { ctx.status(401); + logger.error("Failed to process assign unmatched camera request", e); + ctx.result("Failed to process assign unmatched camera request"); return; } - - if (VisionSourceManager.getInstance().assignUnmatchedCamera(camera)) { - ctx.status(200); - } else { - ctx.status(404); - } - - ctx.result("Successfully assigned camera: " + camera); } public static void onUnassignCameraRequest(Context ctx) { logger.info(ctx.queryString()); + try { + CommonCameraUniqueName request = + kObjectMapper.readValue(ctx.body(), CommonCameraUniqueName.class); - String cameraUniqueName = ctx.queryParam("cameraUniqueName"); - - if (VisionSourceManager.getInstance().deactivateVisionSource(cameraUniqueName)) { - ctx.status(200); - } else { - ctx.status(403); + if (VisionSourceManager.getInstance().deactivateVisionSource(request.cameraUniqueName)) { + ctx.status(200); + } else { + ctx.status(403); + } + } catch (IOException e) { + ctx.status(401); + logger.error("Failed to process unassign camera request", e); + ctx.result("Failed to process unassign camera request"); + return; } - - ctx.status(200); - - ctx.result("Successfully assigned camera with unique name: " + cameraUniqueName); } } From 35c79b138c77e63dea51b570c5ed52999b851057 Mon Sep 17 00:00:00 2001 From: Sam Freund Date: Sun, 4 May 2025 00:26:15 -0500 Subject: [PATCH 38/42] Remove MacOS builds from releases (#1948) ## Description We don't support MacOS, so why have it in releases? Note: we still continue to build for MacOS, we just don't publish releases for it. --- .github/workflows/build.yml | 3 ++- docs/source/docs/contributing/building-photon.md | 6 ++++++ 2 files changed, 8 insertions(+), 1 deletion(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 09e06968b..6d1f8a6a1 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -557,7 +557,8 @@ jobs: rm: true files: | **/*.xz - **/*.jar + **/*linux*.jar + **/*win*.jar **/photonlib*.json **/photonlib*.zip if: github.event_name == 'push' diff --git a/docs/source/docs/contributing/building-photon.md b/docs/source/docs/contributing/building-photon.md index 10da7f643..4b99ec052 100644 --- a/docs/source/docs/contributing/building-photon.md +++ b/docs/source/docs/contributing/building-photon.md @@ -283,3 +283,9 @@ Using the [GitHub CLI](https://cli.github.com/), we can download artifacts from ``` ~/photonvision$ gh run download 11759699679 -n jar-Linux ``` + +#### MacOS Builds + +MacOS builds are not published to releases as MacOS is not an officially +supported platform. However, MacOS builds are still available from the MacOS +build action, which can be found [here](https://github.com/PhotonVision/photonvision/actions/workflows/build.yml). From 29f76bc1c34f136e3560ee6e5e73b564ba54f737 Mon Sep 17 00:00:00 2001 From: Sam Freund Date: Mon, 5 May 2025 18:43:25 -0500 Subject: [PATCH 39/42] Add question about method of powering to bug issue template (#1947) ## Description A common question is the way that people are powering their coprocs when we're trying to help debug. Therefore, it would be useful to know when people open a bug report. ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [x] If this PR changes behavior or adds a feature, user documentation is updated - [x] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [x] If this PR touches configuration, this is backwards compatible with settings back to v2024.3.1 - [x] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [x] If this PR addresses a bug, a regression test for it is added --------- Co-authored-by: Matt Morley --- .github/ISSUE_TEMPLATE/bug_report.md | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md index 5cdc15f84..57d3c80fb 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -22,6 +22,7 @@ If applicable, add screenshots to help explain your problem. Additionally, provi **Platform:** - Hardware Platform (ex. Raspberry Pi 4, Windows x64): + - How is it powered? (ex. Zinc-V, Pololu Buck Converter, Battery Bank): - Network Configuration (Connection between the Radio and any devices in between, such as a Network Switch): - PhotonVision Version: - Browser (with Version) (Chrome, Edge, Firefox, etc.): From bec80926606a233917b79abfd2223635ba3830e8 Mon Sep 17 00:00:00 2001 From: Graham Date: Tue, 6 May 2025 18:21:41 -0400 Subject: [PATCH 40/42] Vue 3 Upgrade (#1900) ## Description Upgrades to Vue 3 and necessary associated dependencies. Also fixes some issues with the layout and adds validation for object detection models. Closes #885, closes #1943, closes #1449. ## Meta Merge checklist: - [x] Pull Request title is [short, imperative summary](https://cbea.ms/git-commit/) of proposed changes - [x] The description documents the _what_ and _why_ - [ ] If this PR changes behavior or adds a feature, user documentation is updated - [ ] If this PR touches photon-serde, all messages have been regenerated and hashes have not changed unexpectedly - [ ] If this PR touches configuration, this is backwards compatible with settings back to v2024.3.1 - [ ] If this PR touches pipeline settings or anything related to data exchange, the frontend typing is updated - [ ] If this PR addresses a bug, a regression test for it is added --------- Co-authored-by: Matt M Co-authored-by: Gold856 <117957790+Gold856@users.noreply.github.com> Co-authored-by: samfreund --- photon-client/.eslintrc.json | 4 +- photon-client/package-lock.json | 1868 +++++++---------- photon-client/package.json | 18 +- photon-client/src/App.vue | 16 +- photon-client/src/assets/styles/settings.scss | 4 + .../src/assets/styles/variables.scss | 10 +- .../components/app/photon-camera-stream.vue | 2 +- .../components/app/photon-error-snackbar.vue | 2 +- .../src/components/app/photon-log-entry.vue | 8 +- .../src/components/app/photon-log-view.vue | 50 +- .../src/components/app/photon-sidebar.vue | 173 +- .../cameras/CameraCalibrationCard.vue | 78 +- .../cameras/CameraCalibrationInfoCard.vue | 49 +- .../components/cameras/CameraControlCard.vue | 43 +- .../components/cameras/CameraSettingsCard.vue | 19 +- .../src/components/cameras/CamerasView.vue | 33 +- .../components/common/pv-camera-info-card.vue | 4 +- .../common/pv-camera-match-card.vue | 4 +- .../src/components/common/pv-icon.vue | 13 +- .../src/components/common/pv-input.vue | 27 +- .../src/components/common/pv-number-input.vue | 19 +- .../src/components/common/pv-radio.vue | 22 +- .../src/components/common/pv-range-slider.vue | 32 +- .../src/components/common/pv-select.vue | 23 +- .../src/components/common/pv-slider.vue | 20 +- .../src/components/common/pv-switch.vue | 25 +- .../components/common/pv-tooltipped-label.vue | 6 +- .../dashboard/CameraAndPipelineSelectCard.vue | 49 +- .../src/components/dashboard/CamerasCard.vue | 18 +- .../components/dashboard/ConfigOptions.vue | 35 +- .../components/dashboard/StreamConfigCard.vue | 49 +- .../components/dashboard/tabs/AprilTagTab.vue | 30 +- .../components/dashboard/tabs/ArucoTab.vue | 32 +- .../components/dashboard/tabs/ContoursTab.vue | 72 +- .../components/dashboard/tabs/InputTab.vue | 50 +- .../components/dashboard/tabs/Map3DTab.vue | 2 +- .../dashboard/tabs/ObjectDetectionTab.vue | 37 +- .../components/dashboard/tabs/OutputTab.vue | 47 +- .../src/components/dashboard/tabs/PnPTab.vue | 15 +- .../components/dashboard/tabs/TargetsTab.vue | 105 +- .../dashboard/tabs/ThresholdTab.vue | 53 +- .../settings/ApriltagControlCard.vue | 8 +- .../components/settings/DeviceControlCard.vue | 59 +- .../components/settings/LEDControlCard.vue | 4 +- .../src/components/settings/MetricsCard.vue | 16 +- .../components/settings/NetworkingCard.vue | 22 +- .../settings/ObjectDetectionCard.vue | 62 +- photon-client/src/main.ts | 16 +- photon-client/src/plugins/vuetify.ts | 64 +- photon-client/src/router/index.ts | 11 +- .../src/views/CameraMatchingView.vue | 44 +- photon-client/src/views/DashboardView.vue | 4 +- photon-client/src/views/DocsView.vue | 2 +- photon-client/vite.config.ts | 26 +- 54 files changed, 1661 insertions(+), 1843 deletions(-) create mode 100644 photon-client/src/assets/styles/settings.scss diff --git a/photon-client/.eslintrc.json b/photon-client/.eslintrc.json index ca944a24c..325121f39 100644 --- a/photon-client/.eslintrc.json +++ b/photon-client/.eslintrc.json @@ -4,7 +4,9 @@ "plugin:vue/vue3-recommended", "eslint:recommended", "@vue/eslint-config-typescript", - "@vue/eslint-config-prettier/skip-formatting" + "@vue/eslint-config-prettier/skip-formatting", + "plugin:vuetify/base" + ], "rules": { "quotes": ["error", "double"], diff --git a/photon-client/package-lock.json b/photon-client/package-lock.json index 27cd3f7bb..490bdd2cf 100644 --- a/photon-client/package-lock.json +++ b/photon-client/package-lock.json @@ -11,35 +11,35 @@ "@fontsource/prompt": "^5.0.9", "@mdi/font": "^7.4.47", "@msgpack/msgpack": "^3.0.0-beta2", + "@vitejs/plugin-vue": "^5.2.3", "axios": "^1.6.3", "jspdf": "^2.5.1", "lodash": "^4.17.21", - "pinia": "^2.1.4", + "pinia": "^3.0.2", "three": "^0.160.0", - "vue": "^2.7.14", - "vue-router": "^3.6.5", + "vite-plugin-vuetify": "^2.1.1", + "vue": "^3.5.13", + "vue-router": "^4.5.0", "vue-virtual-scroll-list": "^2.3.5", - "vue2-helpers": "^2.1.1", - "vuetify": "^2.7.1" + "vue3-virtual-scroll-list": "^0.2.1", + "vuetify": "^3.8.1" }, "devDependencies": { "@rushstack/eslint-patch": "^1.3.2", "@types/node": "^18.19.45", "@types/three": "^0.160.0", - "@vitejs/plugin-vue2": "^2.3.1", "@vue/eslint-config-prettier": "^9.0.0", "@vue/eslint-config-typescript": "^12.0.0", "@vue/tsconfig": "^0.5.1", "deepmerge": "^4.3.1", "eslint": "^8.56.0", "eslint-plugin-vue": "^9.19.2", + "eslint-plugin-vuetify": "^2.5.2", "npm-run-all": "^4.1.5", "prettier": "3.2.2", - "sass": "~1.32", - "sass-loader": "^13.3.2", + "sass": "^1.86.3", "terser": "^5.14.2", "typescript": "^5.3.3", - "unplugin-vue-components": "^0.26.0", "vite": "^5.4.2" } }, @@ -52,19 +52,32 @@ "node": ">=0.10.0" } }, - "node_modules/@antfu/utils": { - "version": "0.7.7", - "resolved": "https://registry.npmjs.org/@antfu/utils/-/utils-0.7.7.tgz", - "integrity": "sha512-gFPqTG7otEJ8uP6wrhDv6mqwGWYZKNvAcCq6u9hOj0c+IKCEsY4L1oC9trPq2SaWIzAfHvqfBDxF591JkMf+kg==", - "dev": true, - "funding": { - "url": "https://github.com/sponsors/antfu" + "node_modules/@babel/helper-string-parser": { + "version": "7.25.9", + "resolved": "https://registry.npmjs.org/@babel/helper-string-parser/-/helper-string-parser-7.25.9.tgz", + "integrity": "sha512-4A/SCr/2KLd5jrtOMFzaKjVtAei3+2r/NChoBNoZ3EyP/+GlhoaEGoWOZUmFmoITP7zOJyHIMm+DYRd8o3PvHA==", + "license": "MIT", + "engines": { + "node": ">=6.9.0" + } + }, + "node_modules/@babel/helper-validator-identifier": { + "version": "7.25.9", + "resolved": "https://registry.npmjs.org/@babel/helper-validator-identifier/-/helper-validator-identifier-7.25.9.tgz", + "integrity": "sha512-Ed61U6XJc3CVRfkERJWDz4dJwKe7iLmmJsbOGu9wSloNSFttHV0I8g6UAgb7qnK5ly5bGLPd4oXZlxCdANBOWQ==", + "license": "MIT", + "engines": { + "node": ">=6.9.0" } }, "node_modules/@babel/parser": { - "version": "7.23.6", - "resolved": "https://registry.npmjs.org/@babel/parser/-/parser-7.23.6.tgz", - "integrity": "sha512-Z2uID7YJ7oNvAI20O9X0bblw7Qqs8Q2hFy0R9tAfnfLkp5MW0UH9eUvnDSnFwKZ0AvgS1ucqR4KzvVHgnke1VQ==", + "version": "7.27.0", + "resolved": "https://registry.npmjs.org/@babel/parser/-/parser-7.27.0.tgz", + "integrity": "sha512-iaepho73/2Pz7w2eMS0Q5f83+0RKI7i4xmiYeBmDzfRVbQtTOG7Ts0S4HzJVsTMGI9keU8rNfuZr8DKfSt7Yyg==", + "license": "MIT", + "dependencies": { + "@babel/types": "^7.27.0" + }, "bin": { "parser": "bin/babel-parser.js" }, @@ -83,6 +96,19 @@ "node": ">=6.9.0" } }, + "node_modules/@babel/types": { + "version": "7.27.0", + "resolved": "https://registry.npmjs.org/@babel/types/-/types-7.27.0.tgz", + "integrity": "sha512-H45s8fVLYjbhFH62dIJ3WtmJ6RSPt/3DRO0ZcT2SUiYiQyz3BLVb9ADEnLl91m74aQPS3AzzeajZHYOalWe3bg==", + "license": "MIT", + "dependencies": { + "@babel/helper-string-parser": "^7.25.9", + "@babel/helper-validator-identifier": "^7.25.9" + }, + "engines": { + "node": ">=6.9.0" + } + }, "node_modules/@esbuild/aix-ppc64": { "version": "0.21.5", "resolved": "https://registry.npmjs.org/@esbuild/aix-ppc64/-/aix-ppc64-0.21.5.tgz", @@ -90,7 +116,6 @@ "cpu": [ "ppc64" ], - "dev": true, "optional": true, "os": [ "aix" @@ -106,7 +131,6 @@ "cpu": [ "arm" ], - "dev": true, "optional": true, "os": [ "android" @@ -122,7 +146,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "android" @@ -138,7 +161,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "android" @@ -154,7 +176,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "darwin" @@ -170,7 +191,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "darwin" @@ -186,7 +206,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "freebsd" @@ -202,7 +221,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "freebsd" @@ -218,7 +236,6 @@ "cpu": [ "arm" ], - "dev": true, "optional": true, "os": [ "linux" @@ -234,7 +251,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -250,7 +266,6 @@ "cpu": [ "ia32" ], - "dev": true, "optional": true, "os": [ "linux" @@ -266,7 +281,6 @@ "cpu": [ "loong64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -282,7 +296,6 @@ "cpu": [ "mips64el" ], - "dev": true, "optional": true, "os": [ "linux" @@ -298,7 +311,6 @@ "cpu": [ "ppc64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -314,7 +326,6 @@ "cpu": [ "riscv64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -330,7 +341,6 @@ "cpu": [ "s390x" ], - "dev": true, "optional": true, "os": [ "linux" @@ -346,7 +356,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -362,7 +371,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "netbsd" @@ -378,7 +386,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "openbsd" @@ -394,7 +401,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "sunos" @@ -410,7 +416,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "win32" @@ -426,7 +431,6 @@ "cpu": [ "ia32" ], - "dev": true, "optional": true, "os": [ "win32" @@ -442,7 +446,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "win32" @@ -549,7 +552,7 @@ "version": "0.3.3", "resolved": "https://registry.npmjs.org/@jridgewell/gen-mapping/-/gen-mapping-0.3.3.tgz", "integrity": "sha512-HLhSWOLRi875zjjMG/r+Nv0oCW8umGb0BgEhyX3dDX3egwZtB8PqLnjz3yedt8R5StBrzcg4aBpnh8UA9D1BoQ==", - "dev": true, + "devOptional": true, "dependencies": { "@jridgewell/set-array": "^1.0.1", "@jridgewell/sourcemap-codec": "^1.4.10", @@ -563,7 +566,7 @@ "version": "3.1.1", "resolved": "https://registry.npmjs.org/@jridgewell/resolve-uri/-/resolve-uri-3.1.1.tgz", "integrity": "sha512-dSYZh7HhCDtCKm4QakX0xFpsRDqjjtZf/kjI/v3T3Nwt5r8/qz/M19F9ySyOqU94SXBmeG9ttTul+YnR4LOxFA==", - "dev": true, + "devOptional": true, "engines": { "node": ">=6.0.0" } @@ -572,7 +575,7 @@ "version": "1.1.2", "resolved": "https://registry.npmjs.org/@jridgewell/set-array/-/set-array-1.1.2.tgz", "integrity": "sha512-xnkseuNADM0gt2bs+BvhO0p78Mk762YnZdsuzFV018NoG1Sj1SCQvpSqa7XUaTam5vAGasABV9qXASMKnFMwMw==", - "dev": true, + "devOptional": true, "engines": { "node": ">=6.0.0" } @@ -581,23 +584,23 @@ "version": "0.3.5", "resolved": "https://registry.npmjs.org/@jridgewell/source-map/-/source-map-0.3.5.tgz", "integrity": "sha512-UTYAUj/wviwdsMfzoSJspJxbkH5o1snzwX0//0ENX1u/55kkZZkcTZP6u9bwKGkv+dkk9at4m1Cpt0uY80kcpQ==", - "dev": true, + "devOptional": true, "dependencies": { "@jridgewell/gen-mapping": "^0.3.0", "@jridgewell/trace-mapping": "^0.3.9" } }, "node_modules/@jridgewell/sourcemap-codec": { - "version": "1.4.15", - "resolved": "https://registry.npmjs.org/@jridgewell/sourcemap-codec/-/sourcemap-codec-1.4.15.tgz", - "integrity": "sha512-eF2rxCRulEKXHTRiDrDy6erMYWqNw4LPdQ8UQA4huuxaQsVeRPFl2oM8oDGxMFhJUWZf9McpLtJasDDZb/Bpeg==", - "dev": true + "version": "1.5.0", + "resolved": "https://registry.npmjs.org/@jridgewell/sourcemap-codec/-/sourcemap-codec-1.5.0.tgz", + "integrity": "sha512-gv3ZRaISU3fjPAgNsriBRqGWQL6quFx04YMPW/zD8XMLsU32mhCCbfbO6KZFLjvYpCZ8zyDEgqsgf+PwPaM7GQ==", + "license": "MIT" }, "node_modules/@jridgewell/trace-mapping": { "version": "0.3.20", "resolved": "https://registry.npmjs.org/@jridgewell/trace-mapping/-/trace-mapping-0.3.20.tgz", "integrity": "sha512-R8LcPeWZol2zR8mmH3JeKQ6QRCFb7XgUhV9ZlGhHLGyg4wpPiPZNQOOWhFZhxKw8u//yTbNGI42Bx/3paXEQ+Q==", - "dev": true, + "devOptional": true, "dependencies": { "@jridgewell/resolve-uri": "^3.1.0", "@jridgewell/sourcemap-codec": "^1.4.14" @@ -651,6 +654,302 @@ "node": ">= 8" } }, + "node_modules/@parcel/watcher": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher/-/watcher-2.5.1.tgz", + "integrity": "sha512-dfUnCxiN9H4ap84DvD2ubjw+3vUNpstxa0TneY/Paat8a3R4uQZDLSvWjmznAY/DoahqTHl9V46HF/Zs3F29pg==", + "hasInstallScript": true, + "license": "MIT", + "optional": true, + "dependencies": { + "detect-libc": "^1.0.3", + "is-glob": "^4.0.3", + "micromatch": "^4.0.5", + "node-addon-api": "^7.0.0" + }, + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + }, + "optionalDependencies": { + "@parcel/watcher-android-arm64": "2.5.1", + "@parcel/watcher-darwin-arm64": "2.5.1", + "@parcel/watcher-darwin-x64": "2.5.1", + "@parcel/watcher-freebsd-x64": "2.5.1", + "@parcel/watcher-linux-arm-glibc": "2.5.1", + "@parcel/watcher-linux-arm-musl": "2.5.1", + "@parcel/watcher-linux-arm64-glibc": "2.5.1", + "@parcel/watcher-linux-arm64-musl": "2.5.1", + "@parcel/watcher-linux-x64-glibc": "2.5.1", + "@parcel/watcher-linux-x64-musl": "2.5.1", + "@parcel/watcher-win32-arm64": "2.5.1", + "@parcel/watcher-win32-ia32": "2.5.1", + "@parcel/watcher-win32-x64": "2.5.1" + } + }, + "node_modules/@parcel/watcher-android-arm64": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-android-arm64/-/watcher-android-arm64-2.5.1.tgz", + "integrity": "sha512-KF8+j9nNbUN8vzOFDpRMsaKBHZ/mcjEjMToVMJOhTozkDonQFFrRcfdLWn6yWKCmJKmdVxSgHiYvTCef4/qcBA==", + "cpu": [ + "arm64" + ], + "license": "MIT", + "optional": true, + "os": [ + "android" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-darwin-arm64": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-darwin-arm64/-/watcher-darwin-arm64-2.5.1.tgz", + "integrity": "sha512-eAzPv5osDmZyBhou8PoF4i6RQXAfeKL9tjb3QzYuccXFMQU0ruIc/POh30ePnaOyD1UXdlKguHBmsTs53tVoPw==", + "cpu": [ + "arm64" + ], + "license": "MIT", + "optional": true, + "os": [ + "darwin" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-darwin-x64": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-darwin-x64/-/watcher-darwin-x64-2.5.1.tgz", + "integrity": "sha512-1ZXDthrnNmwv10A0/3AJNZ9JGlzrF82i3gNQcWOzd7nJ8aj+ILyW1MTxVk35Db0u91oD5Nlk9MBiujMlwmeXZg==", + "cpu": [ + "x64" + ], + "license": "MIT", + "optional": true, + "os": [ + "darwin" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-freebsd-x64": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-freebsd-x64/-/watcher-freebsd-x64-2.5.1.tgz", + "integrity": "sha512-SI4eljM7Flp9yPuKi8W0ird8TI/JK6CSxju3NojVI6BjHsTyK7zxA9urjVjEKJ5MBYC+bLmMcbAWlZ+rFkLpJQ==", + "cpu": [ + "x64" + ], + "license": "MIT", + "optional": true, + "os": [ + "freebsd" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-linux-arm-glibc": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-linux-arm-glibc/-/watcher-linux-arm-glibc-2.5.1.tgz", + "integrity": "sha512-RCdZlEyTs8geyBkkcnPWvtXLY44BCeZKmGYRtSgtwwnHR4dxfHRG3gR99XdMEdQ7KeiDdasJwwvNSF5jKtDwdA==", + "cpu": [ + "arm" + ], + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-linux-arm-musl": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-linux-arm-musl/-/watcher-linux-arm-musl-2.5.1.tgz", + "integrity": "sha512-6E+m/Mm1t1yhB8X412stiKFG3XykmgdIOqhjWj+VL8oHkKABfu/gjFj8DvLrYVHSBNC+/u5PeNrujiSQ1zwd1Q==", + "cpu": [ + "arm" + ], + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-linux-arm64-glibc": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-linux-arm64-glibc/-/watcher-linux-arm64-glibc-2.5.1.tgz", + "integrity": "sha512-LrGp+f02yU3BN9A+DGuY3v3bmnFUggAITBGriZHUREfNEzZh/GO06FF5u2kx8x+GBEUYfyTGamol4j3m9ANe8w==", + "cpu": [ + "arm64" + ], + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-linux-arm64-musl": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-linux-arm64-musl/-/watcher-linux-arm64-musl-2.5.1.tgz", + "integrity": "sha512-cFOjABi92pMYRXS7AcQv9/M1YuKRw8SZniCDw0ssQb/noPkRzA+HBDkwmyOJYp5wXcsTrhxO0zq1U11cK9jsFg==", + "cpu": [ + "arm64" + ], + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-linux-x64-glibc": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-linux-x64-glibc/-/watcher-linux-x64-glibc-2.5.1.tgz", + "integrity": "sha512-GcESn8NZySmfwlTsIur+49yDqSny2IhPeZfXunQi48DMugKeZ7uy1FX83pO0X22sHntJ4Ub+9k34XQCX+oHt2A==", + "cpu": [ + "x64" + ], + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-linux-x64-musl": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-linux-x64-musl/-/watcher-linux-x64-musl-2.5.1.tgz", + "integrity": "sha512-n0E2EQbatQ3bXhcH2D1XIAANAcTZkQICBPVaxMeaCVBtOpBZpWJuf7LwyWPSBDITb7In8mqQgJ7gH8CILCURXg==", + "cpu": [ + "x64" + ], + "license": "MIT", + "optional": true, + "os": [ + "linux" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-win32-arm64": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-win32-arm64/-/watcher-win32-arm64-2.5.1.tgz", + "integrity": "sha512-RFzklRvmc3PkjKjry3hLF9wD7ppR4AKcWNzH7kXR7GUe0Igb3Nz8fyPwtZCSquGrhU5HhUNDr/mKBqj7tqA2Vw==", + "cpu": [ + "arm64" + ], + "license": "MIT", + "optional": true, + "os": [ + "win32" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-win32-ia32": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-win32-ia32/-/watcher-win32-ia32-2.5.1.tgz", + "integrity": "sha512-c2KkcVN+NJmuA7CGlaGD1qJh1cLfDnQsHjE89E60vUEMlqduHGCdCLJCID5geFVM0dOtA3ZiIO8BoEQmzQVfpQ==", + "cpu": [ + "ia32" + ], + "license": "MIT", + "optional": true, + "os": [ + "win32" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, + "node_modules/@parcel/watcher-win32-x64": { + "version": "2.5.1", + "resolved": "https://registry.npmjs.org/@parcel/watcher-win32-x64/-/watcher-win32-x64-2.5.1.tgz", + "integrity": "sha512-9lHBdJITeNR++EvSQVUcaZoWupyHfXe1jZvGZ06O/5MflPcuPLtEphScIBL+AiCWBO46tDSHzWyD0uDmmZqsgA==", + "cpu": [ + "x64" + ], + "license": "MIT", + "optional": true, + "os": [ + "win32" + ], + "engines": { + "node": ">= 10.0.0" + }, + "funding": { + "type": "opencollective", + "url": "https://opencollective.com/parcel" + } + }, "node_modules/@pkgr/core": { "version": "0.1.0", "resolved": "https://registry.npmjs.org/@pkgr/core/-/core-0.1.0.tgz", @@ -663,28 +962,6 @@ "url": "https://opencollective.com/unts" } }, - "node_modules/@rollup/pluginutils": { - "version": "5.1.0", - "resolved": "https://registry.npmjs.org/@rollup/pluginutils/-/pluginutils-5.1.0.tgz", - "integrity": "sha512-XTIWOPPcpvyKI6L1NHo0lFlCyznUEyPmPY1mc3KpPVDYulHSTvyeLNVW00QTLIAFNhR3kYnJTQHeGqU4M3n09g==", - "dev": true, - "dependencies": { - "@types/estree": "^1.0.0", - "estree-walker": "^2.0.2", - "picomatch": "^2.3.1" - }, - "engines": { - "node": ">=14.0.0" - }, - "peerDependencies": { - "rollup": "^1.20.0||^2.0.0||^3.0.0||^4.0.0" - }, - "peerDependenciesMeta": { - "rollup": { - "optional": true - } - } - }, "node_modules/@rollup/rollup-android-arm-eabi": { "version": "4.21.0", "resolved": "https://registry.npmjs.org/@rollup/rollup-android-arm-eabi/-/rollup-android-arm-eabi-4.21.0.tgz", @@ -692,7 +969,6 @@ "cpu": [ "arm" ], - "dev": true, "optional": true, "os": [ "android" @@ -705,7 +981,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "android" @@ -718,7 +993,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "darwin" @@ -731,7 +1005,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "darwin" @@ -744,7 +1017,6 @@ "cpu": [ "arm" ], - "dev": true, "optional": true, "os": [ "linux" @@ -757,7 +1029,6 @@ "cpu": [ "arm" ], - "dev": true, "optional": true, "os": [ "linux" @@ -770,7 +1041,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -783,7 +1053,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -796,7 +1065,6 @@ "cpu": [ "ppc64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -809,7 +1077,6 @@ "cpu": [ "riscv64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -822,7 +1089,6 @@ "cpu": [ "s390x" ], - "dev": true, "optional": true, "os": [ "linux" @@ -835,7 +1101,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -848,7 +1113,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "linux" @@ -861,7 +1125,6 @@ "cpu": [ "arm64" ], - "dev": true, "optional": true, "os": [ "win32" @@ -874,7 +1137,6 @@ "cpu": [ "ia32" ], - "dev": true, "optional": true, "os": [ "win32" @@ -887,7 +1149,6 @@ "cpu": [ "x64" ], - "dev": true, "optional": true, "os": [ "win32" @@ -904,28 +1165,17 @@ "resolved": "https://registry.npmjs.org/@types/eslint/-/eslint-8.56.0.tgz", "integrity": "sha512-FlsN0p4FhuYRjIxpbdXovvHQhtlG05O1GG/RNWvdAxTboR438IOTwmrY/vLA+Xfgg06BTkP045M3vpFwTMv1dg==", "dev": true, + "optional": true, "peer": true, "dependencies": { "@types/estree": "*", "@types/json-schema": "*" } }, - "node_modules/@types/eslint-scope": { - "version": "3.7.7", - "resolved": "https://registry.npmjs.org/@types/eslint-scope/-/eslint-scope-3.7.7.tgz", - "integrity": "sha512-MzMFlSLBqNF2gcHWO0G1vP/YQyfvrxZ0bF+u7mzUdZ1/xK4A4sru+nraZz5i3iEIk1l1uyicaDVTB4QbbEkAYg==", - "dev": true, - "peer": true, - "dependencies": { - "@types/eslint": "*", - "@types/estree": "*" - } - }, "node_modules/@types/estree": { "version": "1.0.5", "resolved": "https://registry.npmjs.org/@types/estree/-/estree-1.0.5.tgz", - "integrity": "sha512-/kYRxGDLWzHOB7q+wtSUQlFrtcdUccpfy+X+9iMBpHK8QLLhx2wIPYuS5DYtR9Wa/YlZAbIovy7qVdB1Aq6Lyw==", - "dev": true + "integrity": "sha512-/kYRxGDLWzHOB7q+wtSUQlFrtcdUccpfy+X+9iMBpHK8QLLhx2wIPYuS5DYtR9Wa/YlZAbIovy7qVdB1Aq6Lyw==" }, "node_modules/@types/json-schema": { "version": "7.0.15", @@ -937,7 +1187,7 @@ "version": "18.19.45", "resolved": "https://registry.npmjs.org/@types/node/-/node-18.19.45.tgz", "integrity": "sha512-VZxPKNNhjKmaC1SUYowuXSRSMGyQGmQjvvA1xE4QZ0xce2kLtEhPDS+kqpCPBZYgqblCLQ2DAjSzmgCM5auvhA==", - "dev": true, + "devOptional": true, "dependencies": { "undici-types": "~5.26.4" } @@ -1198,51 +1448,101 @@ "integrity": "sha512-zuVdFrMJiuCDQUMCzQaD6KL28MjnqqN8XnAqiEq9PNm/hCPTSGfrXCOfwj1ow4LFb/tNymJPwsNbVePc1xFqrQ==", "dev": true }, - "node_modules/@vitejs/plugin-vue2": { - "version": "2.3.1", - "resolved": "https://registry.npmjs.org/@vitejs/plugin-vue2/-/plugin-vue2-2.3.1.tgz", - "integrity": "sha512-/ksaaz2SRLN11JQhLdEUhDzOn909WEk99q9t9w+N12GjQCljzv7GyvAbD/p20aBUjHkvpGOoQ+FCOkG+mjDF4A==", - "dev": true, + "node_modules/@vitejs/plugin-vue": { + "version": "5.2.3", + "resolved": "https://registry.npmjs.org/@vitejs/plugin-vue/-/plugin-vue-5.2.3.tgz", + "integrity": "sha512-IYSLEQj4LgZZuoVpdSUCw3dIynTWQgPlaRP6iAvMle4My0HdYwr5g5wQAfwOeHQBmYwEkqF70nRpSilr6PoUDg==", + "license": "MIT", "engines": { - "node": "^14.18.0 || >= 16.0.0" + "node": "^18.0.0 || >=20.0.0" }, "peerDependencies": { - "vite": "^3.0.0 || ^4.0.0 || ^5.0.0", - "vue": "^2.7.0-0" + "vite": "^5.0.0 || ^6.0.0", + "vue": "^3.2.25" + } + }, + "node_modules/@vue/compiler-core": { + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/@vue/compiler-core/-/compiler-core-3.5.13.tgz", + "integrity": "sha512-oOdAkwqUfW1WqpwSYJce06wvt6HljgY3fGeM9NcVA1HaYOij3mZG9Rkysn0OHuyUAGMbEbARIpsG+LPVlBJ5/Q==", + "license": "MIT", + "dependencies": { + "@babel/parser": "^7.25.3", + "@vue/shared": "3.5.13", + "entities": "^4.5.0", + "estree-walker": "^2.0.2", + "source-map-js": "^1.2.0" + } + }, + "node_modules/@vue/compiler-dom": { + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/@vue/compiler-dom/-/compiler-dom-3.5.13.tgz", + "integrity": "sha512-ZOJ46sMOKUjO3e94wPdCzQ6P1Lx/vhp2RSvfaab88Ajexs0AHeV0uasYhi99WPaogmBlRHNRuly8xV75cNTMDA==", + "license": "MIT", + "dependencies": { + "@vue/compiler-core": "3.5.13", + "@vue/shared": "3.5.13" } }, "node_modules/@vue/compiler-sfc": { - "version": "2.7.16", - "resolved": "https://registry.npmjs.org/@vue/compiler-sfc/-/compiler-sfc-2.7.16.tgz", - "integrity": "sha512-KWhJ9k5nXuNtygPU7+t1rX6baZeqOYLEforUPjgNDBnLicfHCoi48H87Q8XyLZOrNNsmhuwKqtpDQWjEFe6Ekg==", + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/@vue/compiler-sfc/-/compiler-sfc-3.5.13.tgz", + "integrity": "sha512-6VdaljMpD82w6c2749Zhf5T9u5uLBWKnVue6XWxprDobftnletJ8+oel7sexFfM3qIxNmVE7LSFGTpv6obNyaQ==", + "license": "MIT", "dependencies": { - "@babel/parser": "^7.23.5", - "postcss": "^8.4.14", - "source-map": "^0.6.1" - }, - "optionalDependencies": { - "prettier": "^1.18.2 || ^2.0.0" + "@babel/parser": "^7.25.3", + "@vue/compiler-core": "3.5.13", + "@vue/compiler-dom": "3.5.13", + "@vue/compiler-ssr": "3.5.13", + "@vue/shared": "3.5.13", + "estree-walker": "^2.0.2", + "magic-string": "^0.30.11", + "postcss": "^8.4.48", + "source-map-js": "^1.2.0" } }, - "node_modules/@vue/compiler-sfc/node_modules/prettier": { - "version": "2.8.8", - "resolved": "https://registry.npmjs.org/prettier/-/prettier-2.8.8.tgz", - "integrity": "sha512-tdN8qQGvNjw4CHbY+XXk0JgCXn9QiF21a55rBe5LJAU+kDyC4WQn4+awm2Xfk2lQMk5fKup9XgzTZtGkjBdP9Q==", - "optional": true, - "bin": { - "prettier": "bin-prettier.js" - }, - "engines": { - "node": ">=10.13.0" - }, - "funding": { - "url": "https://github.com/prettier/prettier?sponsor=1" + "node_modules/@vue/compiler-ssr": { + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/@vue/compiler-ssr/-/compiler-ssr-3.5.13.tgz", + "integrity": "sha512-wMH6vrYHxQl/IybKJagqbquvxpWCuVYpoUJfCqFZwa/JY1GdATAQ+TgVtgrwwMZ0D07QhA99rs/EAAWfvG6KpA==", + "license": "MIT", + "dependencies": { + "@vue/compiler-dom": "3.5.13", + "@vue/shared": "3.5.13" } }, "node_modules/@vue/devtools-api": { - "version": "6.5.1", - "resolved": "https://registry.npmjs.org/@vue/devtools-api/-/devtools-api-6.5.1.tgz", - "integrity": "sha512-+KpckaAQyfbvshdDW5xQylLni1asvNSGme1JFs8I1+/H5pHEhqUKMEQD/qn3Nx5+/nycBq11qAEi8lk+LXI2dA==" + "version": "7.7.2", + "resolved": "https://registry.npmjs.org/@vue/devtools-api/-/devtools-api-7.7.2.tgz", + "integrity": "sha512-1syn558KhyN+chO5SjlZIwJ8bV/bQ1nOVTG66t2RbG66ZGekyiYNmRO7X9BJCXQqPsFHlnksqvPhce2qpzxFnA==", + "license": "MIT", + "dependencies": { + "@vue/devtools-kit": "^7.7.2" + } + }, + "node_modules/@vue/devtools-kit": { + "version": "7.7.2", + "resolved": "https://registry.npmjs.org/@vue/devtools-kit/-/devtools-kit-7.7.2.tgz", + "integrity": "sha512-CY0I1JH3Z8PECbn6k3TqM1Bk9ASWxeMtTCvZr7vb+CHi+X/QwQm5F1/fPagraamKMAHVfuuCbdcnNg1A4CYVWQ==", + "license": "MIT", + "dependencies": { + "@vue/devtools-shared": "^7.7.2", + "birpc": "^0.2.19", + "hookable": "^5.5.3", + "mitt": "^3.0.1", + "perfect-debounce": "^1.0.0", + "speakingurl": "^14.0.1", + "superjson": "^2.2.1" + } + }, + "node_modules/@vue/devtools-shared": { + "version": "7.7.2", + "resolved": "https://registry.npmjs.org/@vue/devtools-shared/-/devtools-shared-7.7.2.tgz", + "integrity": "sha512-uBFxnp8gwW2vD6FrJB8JZLUzVb6PNRG0B0jBnHsOH8uKyva2qINY8PTF5Te4QlTbMDqU5K6qtJDr6cNsKWhbOA==", + "license": "MIT", + "dependencies": { + "rfdc": "^1.4.1" + } }, "node_modules/@vue/eslint-config-prettier": { "version": "9.0.0", @@ -1282,192 +1582,80 @@ } } }, + "node_modules/@vue/reactivity": { + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/@vue/reactivity/-/reactivity-3.5.13.tgz", + "integrity": "sha512-NaCwtw8o48B9I6L1zl2p41OHo/2Z4wqYGGIK1Khu5T7yxrn+ATOixn/Udn2m+6kZKB/J7cuT9DbWWhRxqixACg==", + "license": "MIT", + "dependencies": { + "@vue/shared": "3.5.13" + } + }, + "node_modules/@vue/runtime-core": { + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/@vue/runtime-core/-/runtime-core-3.5.13.tgz", + "integrity": "sha512-Fj4YRQ3Az0WTZw1sFe+QDb0aXCerigEpw418pw1HBUKFtnQHWzwojaukAs2X/c9DQz4MQ4bsXTGlcpGxU/RCIw==", + "license": "MIT", + "dependencies": { + "@vue/reactivity": "3.5.13", + "@vue/shared": "3.5.13" + } + }, + "node_modules/@vue/runtime-dom": { + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/@vue/runtime-dom/-/runtime-dom-3.5.13.tgz", + "integrity": "sha512-dLaj94s93NYLqjLiyFzVs9X6dWhTdAlEAciC3Moq7gzAc13VJUdCnjjRurNM6uTLFATRHexHCTu/Xp3eW6yoog==", + "license": "MIT", + "dependencies": { + "@vue/reactivity": "3.5.13", + "@vue/runtime-core": "3.5.13", + "@vue/shared": "3.5.13", + "csstype": "^3.1.3" + } + }, + "node_modules/@vue/server-renderer": { + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/@vue/server-renderer/-/server-renderer-3.5.13.tgz", + "integrity": "sha512-wAi4IRJV/2SAW3htkTlB+dHeRmpTiVIK1OGLWV1yeStVSebSQQOwGwIq0D3ZIoBj2C2qpgz5+vX9iEBkTdk5YA==", + "license": "MIT", + "dependencies": { + "@vue/compiler-ssr": "3.5.13", + "@vue/shared": "3.5.13" + }, + "peerDependencies": { + "vue": "3.5.13" + } + }, + "node_modules/@vue/shared": { + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/@vue/shared/-/shared-3.5.13.tgz", + "integrity": "sha512-/hnE/qP5ZoGpol0a5mDi45bOd7t3tjYJBjsgCsivow7D48cJeV5l05RD82lPqi7gRiphZM37rnhW1l6ZoCNNnQ==", + "license": "MIT" + }, "node_modules/@vue/tsconfig": { "version": "0.5.1", "resolved": "https://registry.npmjs.org/@vue/tsconfig/-/tsconfig-0.5.1.tgz", "integrity": "sha512-VcZK7MvpjuTPx2w6blwnwZAu5/LgBUtejFOi3pPGQFXQN5Ela03FUtd2Qtg4yWGGissVL0dr6Ro1LfOFh+PCuQ==", "dev": true }, - "node_modules/@webassemblyjs/ast": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/ast/-/ast-1.11.6.tgz", - "integrity": "sha512-IN1xI7PwOvLPgjcf180gC1bqn3q/QaOCwYUahIOhbYUu8KA/3tw2RT/T0Gidi1l7Hhj5D/INhJxiICObqpMu4Q==", - "dev": true, - "peer": true, + "node_modules/@vuetify/loader-shared": { + "version": "2.1.0", + "resolved": "https://registry.npmjs.org/@vuetify/loader-shared/-/loader-shared-2.1.0.tgz", + "integrity": "sha512-dNE6Ceym9ijFsmJKB7YGW0cxs7xbYV8+1LjU6jd4P14xOt/ji4Igtgzt0rJFbxu+ZhAzqz853lhB0z8V9Dy9cQ==", "dependencies": { - "@webassemblyjs/helper-numbers": "1.11.6", - "@webassemblyjs/helper-wasm-bytecode": "1.11.6" + "upath": "^2.0.1" + }, + "peerDependencies": { + "vue": "^3.0.0", + "vuetify": "^3.0.0" } }, - "node_modules/@webassemblyjs/floating-point-hex-parser": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/floating-point-hex-parser/-/floating-point-hex-parser-1.11.6.tgz", - "integrity": "sha512-ejAj9hfRJ2XMsNHk/v6Fu2dGS+i4UaXBXGemOfQ/JfQ6mdQg/WXtwleQRLLS4OvfDhv8rYnVwH27YJLMyYsxhw==", - "dev": true, - "peer": true - }, - "node_modules/@webassemblyjs/helper-api-error": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/helper-api-error/-/helper-api-error-1.11.6.tgz", - "integrity": "sha512-o0YkoP4pVu4rN8aTJgAyj9hC2Sv5UlkzCHhxqWj8butaLvnpdc2jOwh4ewE6CX0txSfLn/UYaV/pheS2Txg//Q==", - "dev": true, - "peer": true - }, - "node_modules/@webassemblyjs/helper-buffer": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/helper-buffer/-/helper-buffer-1.11.6.tgz", - "integrity": "sha512-z3nFzdcp1mb8nEOFFk8DrYLpHvhKC3grJD2ardfKOzmbmJvEf/tPIqCY+sNcwZIY8ZD7IkB2l7/pqhUhqm7hLA==", - "dev": true, - "peer": true - }, - "node_modules/@webassemblyjs/helper-numbers": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/helper-numbers/-/helper-numbers-1.11.6.tgz", - "integrity": "sha512-vUIhZ8LZoIWHBohiEObxVm6hwP034jwmc9kuq5GdHZH0wiLVLIPcMCdpJzG4C11cHoQ25TFIQj9kaVADVX7N3g==", - "dev": true, - "peer": true, - "dependencies": { - "@webassemblyjs/floating-point-hex-parser": "1.11.6", - "@webassemblyjs/helper-api-error": "1.11.6", - "@xtuc/long": "4.2.2" - } - }, - "node_modules/@webassemblyjs/helper-wasm-bytecode": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/helper-wasm-bytecode/-/helper-wasm-bytecode-1.11.6.tgz", - "integrity": "sha512-sFFHKwcmBprO9e7Icf0+gddyWYDViL8bpPjJJl0WHxCdETktXdmtWLGVzoHbqUcY4Be1LkNfwTmXOJUFZYSJdA==", - "dev": true, - "peer": true - }, - "node_modules/@webassemblyjs/helper-wasm-section": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/helper-wasm-section/-/helper-wasm-section-1.11.6.tgz", - "integrity": "sha512-LPpZbSOwTpEC2cgn4hTydySy1Ke+XEu+ETXuoyvuyezHO3Kjdu90KK95Sh9xTbmjrCsUwvWwCOQQNta37VrS9g==", - "dev": true, - "peer": true, - "dependencies": { - "@webassemblyjs/ast": "1.11.6", - "@webassemblyjs/helper-buffer": "1.11.6", - "@webassemblyjs/helper-wasm-bytecode": "1.11.6", - "@webassemblyjs/wasm-gen": "1.11.6" - } - }, - "node_modules/@webassemblyjs/ieee754": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/ieee754/-/ieee754-1.11.6.tgz", - "integrity": "sha512-LM4p2csPNvbij6U1f19v6WR56QZ8JcHg3QIJTlSwzFcmx6WSORicYj6I63f9yU1kEUtrpG+kjkiIAkevHpDXrg==", - "dev": true, - "peer": true, - "dependencies": { - "@xtuc/ieee754": "^1.2.0" - } - }, - "node_modules/@webassemblyjs/leb128": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/leb128/-/leb128-1.11.6.tgz", - "integrity": "sha512-m7a0FhE67DQXgouf1tbN5XQcdWoNgaAuoULHIfGFIEVKA6tu/edls6XnIlkmS6FrXAquJRPni3ZZKjw6FSPjPQ==", - "dev": true, - "peer": true, - "dependencies": { - "@xtuc/long": "4.2.2" - } - }, - "node_modules/@webassemblyjs/utf8": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/utf8/-/utf8-1.11.6.tgz", - "integrity": "sha512-vtXf2wTQ3+up9Zsg8sa2yWiQpzSsMyXj0qViVP6xKGCUT8p8YJ6HqI7l5eCnWx1T/FYdsv07HQs2wTFbbof/RA==", - "dev": true, - "peer": true - }, - "node_modules/@webassemblyjs/wasm-edit": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/wasm-edit/-/wasm-edit-1.11.6.tgz", - "integrity": "sha512-Ybn2I6fnfIGuCR+Faaz7YcvtBKxvoLV3Lebn1tM4o/IAJzmi9AWYIPWpyBfU8cC+JxAO57bk4+zdsTjJR+VTOw==", - "dev": true, - "peer": true, - "dependencies": { - "@webassemblyjs/ast": "1.11.6", - "@webassemblyjs/helper-buffer": "1.11.6", - "@webassemblyjs/helper-wasm-bytecode": "1.11.6", - "@webassemblyjs/helper-wasm-section": "1.11.6", - "@webassemblyjs/wasm-gen": "1.11.6", - "@webassemblyjs/wasm-opt": "1.11.6", - "@webassemblyjs/wasm-parser": "1.11.6", - "@webassemblyjs/wast-printer": "1.11.6" - } - }, - "node_modules/@webassemblyjs/wasm-gen": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/wasm-gen/-/wasm-gen-1.11.6.tgz", - "integrity": "sha512-3XOqkZP/y6B4F0PBAXvI1/bky7GryoogUtfwExeP/v7Nzwo1QLcq5oQmpKlftZLbT+ERUOAZVQjuNVak6UXjPA==", - "dev": true, - "peer": true, - "dependencies": { - "@webassemblyjs/ast": "1.11.6", - "@webassemblyjs/helper-wasm-bytecode": "1.11.6", - "@webassemblyjs/ieee754": "1.11.6", - "@webassemblyjs/leb128": "1.11.6", - "@webassemblyjs/utf8": "1.11.6" - } - }, - "node_modules/@webassemblyjs/wasm-opt": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/wasm-opt/-/wasm-opt-1.11.6.tgz", - "integrity": "sha512-cOrKuLRE7PCe6AsOVl7WasYf3wbSo4CeOk6PkrjS7g57MFfVUF9u6ysQBBODX0LdgSvQqRiGz3CXvIDKcPNy4g==", - "dev": true, - "peer": true, - "dependencies": { - "@webassemblyjs/ast": "1.11.6", - "@webassemblyjs/helper-buffer": "1.11.6", - "@webassemblyjs/wasm-gen": "1.11.6", - "@webassemblyjs/wasm-parser": "1.11.6" - } - }, - "node_modules/@webassemblyjs/wasm-parser": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/wasm-parser/-/wasm-parser-1.11.6.tgz", - "integrity": "sha512-6ZwPeGzMJM3Dqp3hCsLgESxBGtT/OeCvCZ4TA1JUPYgmhAx38tTPR9JaKy0S5H3evQpO/h2uWs2j6Yc/fjkpTQ==", - "dev": true, - "peer": true, - "dependencies": { - "@webassemblyjs/ast": "1.11.6", - "@webassemblyjs/helper-api-error": "1.11.6", - "@webassemblyjs/helper-wasm-bytecode": "1.11.6", - "@webassemblyjs/ieee754": "1.11.6", - "@webassemblyjs/leb128": "1.11.6", - "@webassemblyjs/utf8": "1.11.6" - } - }, - "node_modules/@webassemblyjs/wast-printer": { - "version": "1.11.6", - "resolved": "https://registry.npmjs.org/@webassemblyjs/wast-printer/-/wast-printer-1.11.6.tgz", - "integrity": "sha512-JM7AhRcE+yW2GWYaKeHL5vt4xqee5N2WcezptmgyhNS+ScggqcT1OtXykhAb13Sn5Yas0j2uv9tHgrjwvzAP4A==", - "dev": true, - "peer": true, - "dependencies": { - "@webassemblyjs/ast": "1.11.6", - "@xtuc/long": "4.2.2" - } - }, - "node_modules/@xtuc/ieee754": { - "version": "1.2.0", - "resolved": "https://registry.npmjs.org/@xtuc/ieee754/-/ieee754-1.2.0.tgz", - "integrity": "sha512-DX8nKgqcGwsc0eJSqYt5lwP4DH5FlHnmuWWBRy7X0NcaGR0ZtuyeESgMwTYVEtxmsNGY+qit4QYT/MIYTOTPeA==", - "dev": true, - "peer": true - }, - "node_modules/@xtuc/long": { - "version": "4.2.2", - "resolved": "https://registry.npmjs.org/@xtuc/long/-/long-4.2.2.tgz", - "integrity": "sha512-NuHqBY1PB/D8xU6s/thBgOAiAP7HOYDQ32+BFZILJ8ivkUkAHQnWfn6WhL79Owj1qmUnoN/YPhktdIoucipkAQ==", - "dev": true, - "peer": true - }, "node_modules/acorn": { - "version": "8.11.3", - "resolved": "https://registry.npmjs.org/acorn/-/acorn-8.11.3.tgz", - "integrity": "sha512-Y9rRfJG5jcKOE0CLisYbojUjIrIEE7AGMzA/Sm4BslANhbS+cDMpgBdcPT91oJ7OuJ9hYJBx59RjbhxVnrF8Xg==", - "dev": true, + "version": "8.14.1", + "resolved": "https://registry.npmjs.org/acorn/-/acorn-8.14.1.tgz", + "integrity": "sha512-OvQ/2pUDKmgfCg++xsTX1wGxfTaszcHVcTctW4UJB4hibJx2HXxxO5UmVgyjMa+ZDsiaf5wWLXYpRWMmBI0QHg==", + "devOptional": true, + "license": "MIT", "bin": { "acorn": "bin/acorn" }, @@ -1475,16 +1663,6 @@ "node": ">=0.4.0" } }, - "node_modules/acorn-import-assertions": { - "version": "1.9.0", - "resolved": "https://registry.npmjs.org/acorn-import-assertions/-/acorn-import-assertions-1.9.0.tgz", - "integrity": "sha512-cmMwop9x+8KFhxvKrKfPYmN6/pKTYYHBqLa0DfvVZcKMJWNyWLnaqND7dx/qn66R7ewM1UX5XMaDVP5wlVTaVA==", - "dev": true, - "peer": true, - "peerDependencies": { - "acorn": "^8" - } - }, "node_modules/acorn-jsx": { "version": "5.3.2", "resolved": "https://registry.npmjs.org/acorn-jsx/-/acorn-jsx-5.3.2.tgz", @@ -1510,16 +1688,6 @@ "url": "https://github.com/sponsors/epoberezkin" } }, - "node_modules/ajv-keywords": { - "version": "3.5.2", - "resolved": "https://registry.npmjs.org/ajv-keywords/-/ajv-keywords-3.5.2.tgz", - "integrity": "sha512-5p6WTN0DdTGVQk6VjcEju19IgaHudalcfabD7yhDGeA6bcQnmL+CpveLJq/3hvfwd1aof6L386Ougkx6RfyMIQ==", - "dev": true, - "peer": true, - "peerDependencies": { - "ajv": "^6.9.1" - } - }, "node_modules/ansi-regex": { "version": "5.0.1", "resolved": "https://registry.npmjs.org/ansi-regex/-/ansi-regex-5.0.1.tgz", @@ -1544,19 +1712,6 @@ "url": "https://github.com/chalk/ansi-styles?sponsor=1" } }, - "node_modules/anymatch": { - "version": "3.1.3", - "resolved": "https://registry.npmjs.org/anymatch/-/anymatch-3.1.3.tgz", - "integrity": "sha512-KMReFUr0B4t+D+OBkjR3KYqvocp2XaSzO55UcB6mgQMd3KbcE+mWTyvVV7D/zsdEbNnV6acZUutkiHQXvTr1Rw==", - "dev": true, - "dependencies": { - "normalize-path": "^3.0.0", - "picomatch": "^2.0.4" - }, - "engines": { - "node": ">= 8" - } - }, "node_modules/argparse": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/argparse/-/argparse-2.0.1.tgz", @@ -1659,13 +1814,13 @@ "node": ">= 0.6.0" } }, - "node_modules/binary-extensions": { - "version": "2.2.0", - "resolved": "https://registry.npmjs.org/binary-extensions/-/binary-extensions-2.2.0.tgz", - "integrity": "sha512-jDctJ/IVQbZoJykoeHbhXpOlNBqGNcwXJKJog42E5HDPUwQTSdjCHdihjj0DlnheQ7blbT6dHOafNAiS8ooQKA==", - "dev": true, - "engines": { - "node": ">=8" + "node_modules/birpc": { + "version": "0.2.19", + "resolved": "https://registry.npmjs.org/birpc/-/birpc-0.2.19.tgz", + "integrity": "sha512-5WeXXAvTmitV1RqJFppT5QtUiz2p1mRSYU000Jkft5ZUCLJIk4uQriYNO50HknxKwM6jd8utNc66K1qGIwwWBQ==", + "license": "MIT", + "funding": { + "url": "https://github.com/sponsors/antfu" } }, "node_modules/boolbase": { @@ -1688,7 +1843,7 @@ "version": "3.0.2", "resolved": "https://registry.npmjs.org/braces/-/braces-3.0.2.tgz", "integrity": "sha512-b8um+L1RzM3WDSzvhm6gIz1yfTbBt6YTlcEKAvsmqCZZFw46z626lVj9j1yEPW33H5H+lBQpZMP1k8l+78Ha0A==", - "dev": true, + "devOptional": true, "dependencies": { "fill-range": "^7.0.1" }, @@ -1696,39 +1851,6 @@ "node": ">=8" } }, - "node_modules/browserslist": { - "version": "4.22.2", - "resolved": "https://registry.npmjs.org/browserslist/-/browserslist-4.22.2.tgz", - "integrity": "sha512-0UgcrvQmBDvZHFGdYUehrCNIazki7/lUP3kkoi/r3YB2amZbFM9J43ZRkJTXBUZK4gmx56+Sqk9+Vs9mwZx9+A==", - "dev": true, - "funding": [ - { - "type": "opencollective", - "url": "https://opencollective.com/browserslist" - }, - { - "type": "tidelift", - "url": "https://tidelift.com/funding/github/npm/browserslist" - }, - { - "type": "github", - "url": "https://github.com/sponsors/ai" - } - ], - "peer": true, - "dependencies": { - "caniuse-lite": "^1.0.30001565", - "electron-to-chromium": "^1.4.601", - "node-releases": "^2.0.14", - "update-browserslist-db": "^1.0.13" - }, - "bin": { - "browserslist": "cli.js" - }, - "engines": { - "node": "^6 || ^7 || ^8 || ^9 || ^10 || ^11 || ^12 || >=13.7" - } - }, "node_modules/btoa": { "version": "1.2.1", "resolved": "https://registry.npmjs.org/btoa/-/btoa-1.2.1.tgz", @@ -1744,7 +1866,7 @@ "version": "1.1.2", "resolved": "https://registry.npmjs.org/buffer-from/-/buffer-from-1.1.2.tgz", "integrity": "sha512-E+XQCRwSbaaiChtv6k6Dwgc+bx+Bs6vuKJHHl5kox/BaKbhiXzqQOwK4cO22yElGp2OCmjwVhT3HmxgyPGnJfQ==", - "dev": true + "devOptional": true }, "node_modules/call-bind": { "version": "1.0.5", @@ -1769,27 +1891,6 @@ "node": ">=6" } }, - "node_modules/caniuse-lite": { - "version": "1.0.30001572", - "resolved": "https://registry.npmjs.org/caniuse-lite/-/caniuse-lite-1.0.30001572.tgz", - "integrity": "sha512-1Pbh5FLmn5y4+QhNyJE9j3/7dK44dGB83/ZMjv/qJk86TvDbjk0LosiZo0i0WB0Vx607qMX9jYrn1VLHCkN4rw==", - "dev": true, - "funding": [ - { - "type": "opencollective", - "url": "https://opencollective.com/browserslist" - }, - { - "type": "tidelift", - "url": "https://tidelift.com/funding/github/npm/caniuse-lite" - }, - { - "type": "github", - "url": "https://github.com/sponsors/ai" - } - ], - "peer": true - }, "node_modules/canvg": { "version": "3.0.10", "resolved": "https://registry.npmjs.org/canvg/-/canvg-3.0.10.tgz", @@ -1831,55 +1932,6 @@ "url": "https://github.com/chalk/chalk?sponsor=1" } }, - "node_modules/chokidar": { - "version": "3.5.3", - "resolved": "https://registry.npmjs.org/chokidar/-/chokidar-3.5.3.tgz", - "integrity": "sha512-Dr3sfKRP6oTcjf2JmUmFJfeVMvXBdegxB0iVQ5eb2V10uFJUCAS8OByZdVAyVb8xXNz3GjjTgj9kLWsZTqE6kw==", - "dev": true, - "funding": [ - { - "type": "individual", - "url": "https://paulmillr.com/funding/" - } - ], - "dependencies": { - "anymatch": "~3.1.2", - "braces": "~3.0.2", - "glob-parent": "~5.1.2", - "is-binary-path": "~2.1.0", - "is-glob": "~4.0.1", - "normalize-path": "~3.0.0", - "readdirp": "~3.6.0" - }, - "engines": { - "node": ">= 8.10.0" - }, - "optionalDependencies": { - "fsevents": "~2.3.2" - } - }, - "node_modules/chokidar/node_modules/glob-parent": { - "version": "5.1.2", - "resolved": "https://registry.npmjs.org/glob-parent/-/glob-parent-5.1.2.tgz", - "integrity": "sha512-AOIgSQCepiJYwP3ARnGx+5VnTu2HBYdzbGP45eLw1vr3zB3vZLeyed1sC9hnbcOc9/SrMyM5RPQrkGz4aS9Zow==", - "dev": true, - "dependencies": { - "is-glob": "^4.0.1" - }, - "engines": { - "node": ">= 6" - } - }, - "node_modules/chrome-trace-event": { - "version": "1.0.3", - "resolved": "https://registry.npmjs.org/chrome-trace-event/-/chrome-trace-event-1.0.3.tgz", - "integrity": "sha512-p3KULyQg4S7NIHixdwbGX+nFHkoBiA4YQmyWtjb8XngSKV124nJmRysgAeujbUVb15vh+RvFUfCPqU7rXk+hZg==", - "dev": true, - "peer": true, - "engines": { - "node": ">=6.0" - } - }, "node_modules/color-convert": { "version": "2.0.1", "resolved": "https://registry.npmjs.org/color-convert/-/color-convert-2.0.1.tgz", @@ -1913,7 +1965,7 @@ "version": "2.20.3", "resolved": "https://registry.npmjs.org/commander/-/commander-2.20.3.tgz", "integrity": "sha512-GpVkmM8vF2vQUkj2LvZmD35JxeJOLCwJ9cUkugyk2nuhbv3+mJvpLYYt+0+USMxE+oj+ey/lJEnhZw75x/OMcQ==", - "dev": true + "devOptional": true }, "node_modules/concat-map": { "version": "0.0.1", @@ -1921,6 +1973,21 @@ "integrity": "sha512-/Srv4dswyQNBfohGpz9o6Yb3Gz3SrUDqBH5rTuhGR7ahtlbYKnVxw2bCFMRljaA7EXHaXZ8wsHdodFvbkhKmqg==", "dev": true }, + "node_modules/copy-anything": { + "version": "3.0.5", + "resolved": "https://registry.npmjs.org/copy-anything/-/copy-anything-3.0.5.tgz", + "integrity": "sha512-yCEafptTtb4bk7GLEQoM8KVJpxAfdBJYaXyzQEgQQQgYrZiDp8SJmGKlYza6CYjEDNstAdNdKA3UuoULlEbS6w==", + "license": "MIT", + "dependencies": { + "is-what": "^4.1.8" + }, + "engines": { + "node": ">=12.13" + }, + "funding": { + "url": "https://github.com/sponsors/mesqueeb" + } + }, "node_modules/core-js": { "version": "3.35.0", "resolved": "https://registry.npmjs.org/core-js/-/core-js-3.35.0.tgz", @@ -1970,15 +2037,16 @@ "node_modules/csstype": { "version": "3.1.3", "resolved": "https://registry.npmjs.org/csstype/-/csstype-3.1.3.tgz", - "integrity": "sha512-M1uQkMl8rQK/szD0LNhtqxIPLpimGm8sOBwU7lLnCpSbTyY3yeU1Vc7l4KT5zT4s/yOxHH5O7tIuuLOCnLADRw==" + "integrity": "sha512-M1uQkMl8rQK/szD0LNhtqxIPLpimGm8sOBwU7lLnCpSbTyY3yeU1Vc7l4KT5zT4s/yOxHH5O7tIuuLOCnLADRw==", + "license": "MIT" }, "node_modules/debug": { - "version": "4.3.4", - "resolved": "https://registry.npmjs.org/debug/-/debug-4.3.4.tgz", - "integrity": "sha512-PRWFHuSU3eDtQJPvnNY7Jcket1j0t5OuOsFzPPzsekD52Zl8qUfFIPEiswXqIvHWGVHOgX+7G/vCNNhehwxfkQ==", - "dev": true, + "version": "4.4.0", + "resolved": "https://registry.npmjs.org/debug/-/debug-4.4.0.tgz", + "integrity": "sha512-6WTZ/IxCY/T6BALoZHaE4ctp9xm+Z5kY/pzYaCHRFeyVhojxlrm+46y68HA6hr0TcwEssoxNiDEUJQjfPZ/RYA==", + "license": "MIT", "dependencies": { - "ms": "2.1.2" + "ms": "^2.1.3" }, "engines": { "node": ">=6.0" @@ -2043,6 +2111,19 @@ "node": ">=0.4.0" } }, + "node_modules/detect-libc": { + "version": "1.0.3", + "resolved": "https://registry.npmjs.org/detect-libc/-/detect-libc-1.0.3.tgz", + "integrity": "sha512-pGjwhsmsp4kL2RTz08wcOlGN83otlqHeD/Z5T8GXZB+/YcpQ/dgo+lbU8ZsGxV0HIvqqxo9l7mqYwyYMD9bKDg==", + "license": "Apache-2.0", + "optional": true, + "bin": { + "detect-libc": "bin/detect-libc.js" + }, + "engines": { + "node": ">=0.10" + } + }, "node_modules/dir-glob": { "version": "3.0.1", "resolved": "https://registry.npmjs.org/dir-glob/-/dir-glob-3.0.1.tgz", @@ -2073,25 +2154,16 @@ "integrity": "sha512-kxxKlPEDa6Nc5WJi+qRgPbOAbgTpSULL+vI3NUXsZMlkJxTqYI9wg5ZTay2sFrdZRWHPWNi+EdAhcJf81WtoMQ==", "optional": true }, - "node_modules/electron-to-chromium": { - "version": "1.4.616", - "resolved": "https://registry.npmjs.org/electron-to-chromium/-/electron-to-chromium-1.4.616.tgz", - "integrity": "sha512-1n7zWYh8eS0L9Uy+GskE0lkBUNK83cXTVJI0pU3mGprFsbfSdAc15VTFbo+A+Bq4pwstmL30AVcEU3Fo463lNg==", - "dev": true, - "peer": true - }, - "node_modules/enhanced-resolve": { - "version": "5.15.0", - "resolved": "https://registry.npmjs.org/enhanced-resolve/-/enhanced-resolve-5.15.0.tgz", - "integrity": "sha512-LXYT42KJ7lpIKECr2mAXIaMldcNCh/7E0KBKOu4KSfkHmP+mZmSs+8V5gBAqisWBy0OO4W5Oyys0GO1Y8KtdKg==", - "dev": true, - "peer": true, - "dependencies": { - "graceful-fs": "^4.2.4", - "tapable": "^2.2.0" - }, + "node_modules/entities": { + "version": "4.5.0", + "resolved": "https://registry.npmjs.org/entities/-/entities-4.5.0.tgz", + "integrity": "sha512-V0hjH4dGPh9Ao5p0MoRY6BVqtwCjhz6vI5LT8AJ55H+4g9/4vbHx1I54fS0XuclLhDHArPQCiMjDxjaL8fPxhw==", + "license": "BSD-2-Clause", "engines": { - "node": ">=10.13.0" + "node": ">=0.12" + }, + "funding": { + "url": "https://github.com/fb55/entities?sponsor=1" } }, "node_modules/error-ex": { @@ -2156,13 +2228,6 @@ "url": "https://github.com/sponsors/ljharb" } }, - "node_modules/es-module-lexer": { - "version": "1.4.1", - "resolved": "https://registry.npmjs.org/es-module-lexer/-/es-module-lexer-1.4.1.tgz", - "integrity": "sha512-cXLGjP0c4T3flZJKQSuziYoq7MlT+rnvfZjfp7h+I7K9BNX54kP9nyWvdbwjQ4u1iWbOL4u96fgeZLToQlZC7w==", - "dev": true, - "peer": true - }, "node_modules/es-set-tostringtag": { "version": "2.0.2", "resolved": "https://registry.npmjs.org/es-set-tostringtag/-/es-set-tostringtag-2.0.2.tgz", @@ -2198,7 +2263,6 @@ "version": "0.21.5", "resolved": "https://registry.npmjs.org/esbuild/-/esbuild-0.21.5.tgz", "integrity": "sha512-mg3OPMV4hXywwpoDxu3Qda5xCKQi+vCTZq8S9J/EpkhB2HzKXq4SNFZE3+NK93JYxc8VMSep+lOUSC/RVKaBqw==", - "dev": true, "hasInstallScript": true, "bin": { "esbuild": "bin/esbuild" @@ -2232,16 +2296,6 @@ "@esbuild/win32-x64": "0.21.5" } }, - "node_modules/escalade": { - "version": "3.1.1", - "resolved": "https://registry.npmjs.org/escalade/-/escalade-3.1.1.tgz", - "integrity": "sha512-k0er2gUkLf8O0zKJiAhmkTnJlTvINGv7ygDNPbeIsX/TJjGJZHuh9B2UxbsaEkmlEo9MfhrSzmhIlhRlI2GXnw==", - "dev": true, - "peer": true, - "engines": { - "node": ">=6" - } - }, "node_modules/escape-string-regexp": { "version": "4.0.0", "resolved": "https://registry.npmjs.org/escape-string-regexp/-/escape-string-regexp-4.0.0.tgz", @@ -2372,18 +2426,19 @@ "eslint": "^6.2.0 || ^7.0.0 || ^8.0.0" } }, - "node_modules/eslint-scope": { - "version": "5.1.1", - "resolved": "https://registry.npmjs.org/eslint-scope/-/eslint-scope-5.1.1.tgz", - "integrity": "sha512-2NxwbF/hZ0KpepYN0cNbo+FN6XoK7GaHlQhgx/hIZl6Va0bF45RQOOwhLIy8lQDbuCiadSLCBnH2CFYquit5bw==", + "node_modules/eslint-plugin-vuetify": { + "version": "2.5.2", + "resolved": "https://registry.npmjs.org/eslint-plugin-vuetify/-/eslint-plugin-vuetify-2.5.2.tgz", + "integrity": "sha512-Gm3W2R+tmEcATI5Qk8W13uZKmsdajlykG/AdL44E6Lwt1ttAbMi50DNMfkgZrCg7WAq3qd2IRiYx0QKtkpdf/A==", "dev": true, - "peer": true, + "license": "MIT", "dependencies": { - "esrecurse": "^4.3.0", - "estraverse": "^4.1.1" + "eslint-plugin-vue": ">=9.6.0", + "requireindex": "^1.2.0" }, - "engines": { - "node": ">=8.0.0" + "peerDependencies": { + "eslint": "^8.0.0 || ^9.0.0", + "vuetify": "^3.0.0" } }, "node_modules/eslint-visitor-keys": { @@ -2482,21 +2537,10 @@ "node": ">=4.0" } }, - "node_modules/estraverse": { - "version": "4.3.0", - "resolved": "https://registry.npmjs.org/estraverse/-/estraverse-4.3.0.tgz", - "integrity": "sha512-39nnKffWz8xN1BU/2c79n9nB9HDzo0niYUqx6xyqUnyoAnQyyWpOTdZEeiCch8BBu515t4wp9ZmgVfVhn9EBpw==", - "dev": true, - "peer": true, - "engines": { - "node": ">=4.0" - } - }, "node_modules/estree-walker": { "version": "2.0.2", "resolved": "https://registry.npmjs.org/estree-walker/-/estree-walker-2.0.2.tgz", - "integrity": "sha512-Rfkk/Mp/DL7JVje3u18FxFujQlTNR2q6QfMSMB7AvCBx91NGj/ba3kCfza0f6dVDbw7YlRf/nDrn7pQrCCyQ/w==", - "dev": true + "integrity": "sha512-Rfkk/Mp/DL7JVje3u18FxFujQlTNR2q6QfMSMB7AvCBx91NGj/ba3kCfza0f6dVDbw7YlRf/nDrn7pQrCCyQ/w==" }, "node_modules/esutils": { "version": "2.0.3", @@ -2507,16 +2551,6 @@ "node": ">=0.10.0" } }, - "node_modules/events": { - "version": "3.3.0", - "resolved": "https://registry.npmjs.org/events/-/events-3.3.0.tgz", - "integrity": "sha512-mQw+2fkQbALzQ7V0MY0IqdnXNOeTtP4r0lN9z7AAawCXgqea7bDii20AYrIBrFd/Hx0M2Ocz6S111CaFkUcb0Q==", - "dev": true, - "peer": true, - "engines": { - "node": ">=0.8.x" - } - }, "node_modules/fast-deep-equal": { "version": "3.1.3", "resolved": "https://registry.npmjs.org/fast-deep-equal/-/fast-deep-equal-3.1.3.tgz", @@ -2600,7 +2634,7 @@ "version": "7.0.1", "resolved": "https://registry.npmjs.org/fill-range/-/fill-range-7.0.1.tgz", "integrity": "sha512-qOo9F+dMUmC2Lcb4BbVvnKJxTPjCm+RRpe4gDuGrzkL7mEVl/djYSu2OdQ2Pa302N4oqkSg9ir6jaLWJ2USVpQ==", - "dev": true, + "devOptional": true, "dependencies": { "to-regex-range": "^5.0.1" }, @@ -2695,7 +2729,6 @@ "version": "2.3.3", "resolved": "https://registry.npmjs.org/fsevents/-/fsevents-2.3.3.tgz", "integrity": "sha512-5xoDfX+fL7faATnagmWPpbFtwh/R77WmMMqqHGS65C3vvB0YHrgF+B1YmZ3441tMj5n63k0212XNoJwzlhffQw==", - "dev": true, "hasInstallScript": true, "optional": true, "os": [ @@ -2804,13 +2837,6 @@ "node": ">=10.13.0" } }, - "node_modules/glob-to-regexp": { - "version": "0.4.1", - "resolved": "https://registry.npmjs.org/glob-to-regexp/-/glob-to-regexp-0.4.1.tgz", - "integrity": "sha512-lkX1HJXwyMcprw/5YUZc2s7DrpAiHB21/V+E1rHUrVNokkvB6bqMzT0VfV6/86ZNabt1k14YOIaT7nDvOX3Iiw==", - "dev": true, - "peer": true - }, "node_modules/globals": { "version": "13.24.0", "resolved": "https://registry.npmjs.org/globals/-/globals-13.24.0.tgz", @@ -2966,6 +2992,12 @@ "node": ">= 0.4" } }, + "node_modules/hookable": { + "version": "5.5.3", + "resolved": "https://registry.npmjs.org/hookable/-/hookable-5.5.3.tgz", + "integrity": "sha512-Yc+BQe8SvoXH1643Qez1zqLRmbA5rCL+sSmk6TVos0LWVfNIB7PGncdlId77WzLGSIB5KaWgTaNTs2lNVEI6VQ==", + "license": "MIT" + }, "node_modules/hosted-git-info": { "version": "2.8.9", "resolved": "https://registry.npmjs.org/hosted-git-info/-/hosted-git-info-2.8.9.tgz", @@ -2994,6 +3026,13 @@ "node": ">= 4" } }, + "node_modules/immutable": { + "version": "5.1.1", + "resolved": "https://registry.npmjs.org/immutable/-/immutable-5.1.1.tgz", + "integrity": "sha512-3jatXi9ObIsPGr3N5hGw/vWWcTkq6hUYhpQz4k0wLC+owqWi/LiugIw9x0EdNZ2yGedKN/HzePiBvaJRXa0Ujg==", + "devOptional": true, + "license": "MIT" + }, "node_modules/import-fresh": { "version": "3.3.0", "resolved": "https://registry.npmjs.org/import-fresh/-/import-fresh-3.3.0.tgz", @@ -3081,18 +3120,6 @@ "url": "https://github.com/sponsors/ljharb" } }, - "node_modules/is-binary-path": { - "version": "2.1.0", - "resolved": "https://registry.npmjs.org/is-binary-path/-/is-binary-path-2.1.0.tgz", - "integrity": "sha512-ZMERYes6pDydyuGidse7OsHxtbI7WVeUEozgR/g7rd0xUimYNlvZRE/K2MgZTjWy725IfelLeVcEM97mmtRGXw==", - "dev": true, - "dependencies": { - "binary-extensions": "^2.0.0" - }, - "engines": { - "node": ">=8" - } - }, "node_modules/is-boolean-object": { "version": "1.1.2", "resolved": "https://registry.npmjs.org/is-boolean-object/-/is-boolean-object-1.1.2.tgz", @@ -3152,7 +3179,7 @@ "version": "2.1.1", "resolved": "https://registry.npmjs.org/is-extglob/-/is-extglob-2.1.1.tgz", "integrity": "sha512-SbKbANkN603Vi4jEZv49LeVJMn4yGwsbzZworEoyEiutsN3nJYdbO36zfhGJ6QEDpOZIFkDtnq5JRxmvl3jsoQ==", - "dev": true, + "devOptional": true, "engines": { "node": ">=0.10.0" } @@ -3161,7 +3188,7 @@ "version": "4.0.3", "resolved": "https://registry.npmjs.org/is-glob/-/is-glob-4.0.3.tgz", "integrity": "sha512-xelSayHH36ZgE7ZWhli7pW34hNbNl8Ojv5KVmkJD4hBdD3th8Tfk9vYasLM+mXWOZhFkgZfxhLSnrwRr4elSSg==", - "dev": true, + "devOptional": true, "dependencies": { "is-extglob": "^2.1.1" }, @@ -3185,7 +3212,7 @@ "version": "7.0.0", "resolved": "https://registry.npmjs.org/is-number/-/is-number-7.0.0.tgz", "integrity": "sha512-41Cifkg6e8TylSpdtTpeLVMqvSBEVzTttHvERD741+pnZ8ANv0004MRL43QKPDlK9cGvNp6NZWZUBlbGXYxxng==", - "dev": true, + "devOptional": true, "engines": { "node": ">=0.12.0" } @@ -3299,6 +3326,18 @@ "url": "https://github.com/sponsors/ljharb" } }, + "node_modules/is-what": { + "version": "4.1.16", + "resolved": "https://registry.npmjs.org/is-what/-/is-what-4.1.16.tgz", + "integrity": "sha512-ZhMwEosbFJkA0YhFnNDgTM4ZxDRsS6HqTo7qsZM08fehyRYIYa0yHu5R6mgo1n/8MgaPBXiPimPD77baVFYg+A==", + "license": "MIT", + "engines": { + "node": ">=12.13" + }, + "funding": { + "url": "https://github.com/sponsors/mesqueeb" + } + }, "node_modules/isarray": { "version": "2.0.5", "resolved": "https://registry.npmjs.org/isarray/-/isarray-2.0.5.tgz", @@ -3311,37 +3350,6 @@ "integrity": "sha512-RHxMLp9lnKHGHRng9QFhRCMbYAcVpn69smSGcq3f36xjgVVWThj4qqLbTLlq7Ssj8B+fIQ1EuCEGI2lKsyQeIw==", "dev": true }, - "node_modules/jest-worker": { - "version": "27.5.1", - "resolved": "https://registry.npmjs.org/jest-worker/-/jest-worker-27.5.1.tgz", - "integrity": "sha512-7vuh85V5cdDofPyxn58nrPjBktZo0u9x1g8WtjQol+jZDaE+fhN+cIvTj11GndBnMnyfrUOG1sZQxCdjKh+DKg==", - "dev": true, - "peer": true, - "dependencies": { - "@types/node": "*", - "merge-stream": "^2.0.0", - "supports-color": "^8.0.0" - }, - "engines": { - "node": ">= 10.13.0" - } - }, - "node_modules/jest-worker/node_modules/supports-color": { - "version": "8.1.1", - "resolved": "https://registry.npmjs.org/supports-color/-/supports-color-8.1.1.tgz", - "integrity": "sha512-MpUEN2OodtUzxvKQl72cUF7RQ5EiHsGvSsVG0ia9c5RbWGL2CI4C7EpPS8UTBIplnlzZiNuV56w+FuNxy3ty2Q==", - "dev": true, - "peer": true, - "dependencies": { - "has-flag": "^4.0.0" - }, - "engines": { - "node": ">=10" - }, - "funding": { - "url": "https://github.com/chalk/supports-color?sponsor=1" - } - }, "node_modules/js-yaml": { "version": "4.1.0", "resolved": "https://registry.npmjs.org/js-yaml/-/js-yaml-4.1.0.tgz", @@ -3366,13 +3374,6 @@ "integrity": "sha512-mrqyZKfX5EhL7hvqcV6WG1yYjnjeuYDzDhhcAAUrq8Po85NBQBJP+ZDUT75qZQ98IkUoBqdkExkukOU7Ts2wrw==", "dev": true }, - "node_modules/json-parse-even-better-errors": { - "version": "2.3.1", - "resolved": "https://registry.npmjs.org/json-parse-even-better-errors/-/json-parse-even-better-errors-2.3.1.tgz", - "integrity": "sha512-xyFwyhro/JEof6Ghe2iz2NcXoj2sloNsWr/XsERDK/oiPCfaNhl5ONfp+jQdAZRQQ0IJWNzH9zIZF7li91kh2w==", - "dev": true, - "peer": true - }, "node_modules/json-schema-traverse": { "version": "0.4.1", "resolved": "https://registry.npmjs.org/json-schema-traverse/-/json-schema-traverse-0.4.1.tgz", @@ -3444,28 +3445,6 @@ "node": ">=4" } }, - "node_modules/loader-runner": { - "version": "4.3.0", - "resolved": "https://registry.npmjs.org/loader-runner/-/loader-runner-4.3.0.tgz", - "integrity": "sha512-3R/1M+yS3j5ou80Me59j7F9IMs4PXs3VqRrm0TU3AbKPxlmpoY1TNscJV/oGJXo8qCatFGTfDbY6W6ipGOYXfg==", - "dev": true, - "peer": true, - "engines": { - "node": ">=6.11.5" - } - }, - "node_modules/local-pkg": { - "version": "0.4.3", - "resolved": "https://registry.npmjs.org/local-pkg/-/local-pkg-0.4.3.tgz", - "integrity": "sha512-SFppqq5p42fe2qcZQqqEOiVRXl+WCP1MdT6k7BDEW1j++sp5fIY+/fdRQitvKgB5BrBcmrs5m/L0v2FrU5MY1g==", - "dev": true, - "engines": { - "node": ">=14" - }, - "funding": { - "url": "https://github.com/sponsors/antfu" - } - }, "node_modules/locate-path": { "version": "6.0.0", "resolved": "https://registry.npmjs.org/locate-path/-/locate-path-6.0.0.tgz", @@ -3505,15 +3484,12 @@ } }, "node_modules/magic-string": { - "version": "0.30.5", - "resolved": "https://registry.npmjs.org/magic-string/-/magic-string-0.30.5.tgz", - "integrity": "sha512-7xlpfBaQaP/T6Vh8MO/EqXSW5En6INHEvEXQiuff7Gku0PWjU3uf6w/j9o7O+SpB5fOAkrI5HeoNgwjEO0pFsA==", - "dev": true, + "version": "0.30.17", + "resolved": "https://registry.npmjs.org/magic-string/-/magic-string-0.30.17.tgz", + "integrity": "sha512-sNPKHvyjVf7gyjwS4xGTaW/mCnF8wnjtifKBEhxfZ7E/S8tQ0rssrwGNn6q8JH/ohItJfSQp9mBtQYuTlH5QnA==", + "license": "MIT", "dependencies": { - "@jridgewell/sourcemap-codec": "^1.4.15" - }, - "engines": { - "node": ">=12" + "@jridgewell/sourcemap-codec": "^1.5.0" } }, "node_modules/memorystream": { @@ -3525,13 +3501,6 @@ "node": ">= 0.10.0" } }, - "node_modules/merge-stream": { - "version": "2.0.0", - "resolved": "https://registry.npmjs.org/merge-stream/-/merge-stream-2.0.0.tgz", - "integrity": "sha512-abv/qOcuPfk3URPfDzmZU1LKmuw8kT+0nIHvKrKgFrwifol/doWcdA4ZqsWQ8ENrFKkd67Mfpo/LovbIUsbt3w==", - "dev": true, - "peer": true - }, "node_modules/merge2": { "version": "1.4.1", "resolved": "https://registry.npmjs.org/merge2/-/merge2-1.4.1.tgz", @@ -3551,7 +3520,7 @@ "version": "4.0.5", "resolved": "https://registry.npmjs.org/micromatch/-/micromatch-4.0.5.tgz", "integrity": "sha512-DMy+ERcEW2q8Z2Po+WNXuw3c5YaUSFjAO5GsJqfEl7UjvtIuFKO6ZrKvcItdy98dwFI2N1tg3zNIdKaQT+aNdA==", - "dev": true, + "devOptional": true, "dependencies": { "braces": "^3.0.2", "picomatch": "^2.3.1" @@ -3591,22 +3560,29 @@ "node": "*" } }, + "node_modules/mitt": { + "version": "3.0.1", + "resolved": "https://registry.npmjs.org/mitt/-/mitt-3.0.1.tgz", + "integrity": "sha512-vKivATfr97l2/QBCYAkXYDbrIWPM2IIKEl7YPhjCvKlG3kE2gm+uBo6nEXK3M5/Ffh/FLpKExzOQ3JJoJGFKBw==", + "license": "MIT" + }, "node_modules/ms": { - "version": "2.1.2", - "resolved": "https://registry.npmjs.org/ms/-/ms-2.1.2.tgz", - "integrity": "sha512-sGkPx+VjMtmA6MX27oA4FBFELFCZZ4S4XqeGOXCv68tT+jb3vk/RyaKWP0PTKyWtmLSM0b+adUTEvbs1PEaH2w==", - "dev": true + "version": "2.1.3", + "resolved": "https://registry.npmjs.org/ms/-/ms-2.1.3.tgz", + "integrity": "sha512-6FlzubTLZG3J2a/NVCAleEhjzq5oxgHyaCU9yYXvcLsvoVaHJq/s5xXI6/XXP6tz7R9xAOtHnSO/tXtF3WRTlA==", + "license": "MIT" }, "node_modules/nanoid": { - "version": "3.3.7", - "resolved": "https://registry.npmjs.org/nanoid/-/nanoid-3.3.7.tgz", - "integrity": "sha512-eSRppjcPIatRIMC1U6UngP8XFcz8MQWGQdt1MTBQ7NaAmvXDfvNxbvWV3x2y6CdEUciCSsDHDQZbhYaB8QEo2g==", + "version": "3.3.11", + "resolved": "https://registry.npmjs.org/nanoid/-/nanoid-3.3.11.tgz", + "integrity": "sha512-N8SpfPUnUp1bK+PMYW8qSWdl9U+wwNWI4QKxOYDy9JAro3WMX7p2OeVRF9v+347pnakNevPmiHhNmZ2HbFA76w==", "funding": [ { "type": "github", "url": "https://github.com/sponsors/ai" } ], + "license": "MIT", "bin": { "nanoid": "bin/nanoid.cjs" }, @@ -3620,24 +3596,18 @@ "integrity": "sha512-OWND8ei3VtNC9h7V60qff3SVobHr996CTwgxubgyQYEpg290h9J0buyECNNJexkFm5sOajh5G116RYA1c8ZMSw==", "dev": true }, - "node_modules/neo-async": { - "version": "2.6.2", - "resolved": "https://registry.npmjs.org/neo-async/-/neo-async-2.6.2.tgz", - "integrity": "sha512-Yd3UES5mWCSqR+qNT93S3UoYUkqAZ9lLg8a7g9rimsWmYGK8cVToA4/sF3RrshdyV3sAGMXVUmpMYOw+dLpOuw==", - "dev": true - }, "node_modules/nice-try": { "version": "1.0.5", "resolved": "https://registry.npmjs.org/nice-try/-/nice-try-1.0.5.tgz", "integrity": "sha512-1nh45deeb5olNY7eX82BkPO7SSxR5SSYJiPTrTdFUVYwAl8CKMA5N9PjTYkHiRjisVcxcQ1HXdLhx2qxxJzLNQ==", "dev": true }, - "node_modules/node-releases": { - "version": "2.0.14", - "resolved": "https://registry.npmjs.org/node-releases/-/node-releases-2.0.14.tgz", - "integrity": "sha512-y10wOWt8yZpqXmOgRo77WaHEmhYQYGNA6y421PKsKYWEK8aW+cqAphborZDhqfyKrbZEN92CN1X2KbafY2s7Yw==", - "dev": true, - "peer": true + "node_modules/node-addon-api": { + "version": "7.1.1", + "resolved": "https://registry.npmjs.org/node-addon-api/-/node-addon-api-7.1.1.tgz", + "integrity": "sha512-5m3bsyrjFWE1xf7nz7YXdN4udnVtXK6/Yfgn5qnahL6bCkf2yKt4k3nuTKAtT4r3IG8JNR2ncsIMdZuAzJjHQQ==", + "license": "MIT", + "optional": true }, "node_modules/normalize-package-data": { "version": "2.5.0", @@ -3660,15 +3630,6 @@ "semver": "bin/semver" } }, - "node_modules/normalize-path": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/normalize-path/-/normalize-path-3.0.0.tgz", - "integrity": "sha512-6eZs5Ls3WtCisHWp9S2GUy8dqkpGi4BVSz3GaqiE6ezub0512ESztXUwUB6C6IKbQkY2Pnb/mD4WYojCRwcwLA==", - "dev": true, - "engines": { - "node": ">=0.10.0" - } - }, "node_modules/npm-run-all": { "version": "4.1.5", "resolved": "https://registry.npmjs.org/npm-run-all/-/npm-run-all-4.1.5.tgz", @@ -4003,6 +3964,12 @@ "node": ">=8" } }, + "node_modules/perfect-debounce": { + "version": "1.0.0", + "resolved": "https://registry.npmjs.org/perfect-debounce/-/perfect-debounce-1.0.0.tgz", + "integrity": "sha512-xCy9V055GLEqoFaHoC1SoLIaLmWctgCUaBaWxDZ7/Zx4CTyX7cJQLJOok/orfjZAh9kEYpjJa4d0KcJmCbctZA==", + "license": "MIT" + }, "node_modules/performance-now": { "version": "2.1.0", "resolved": "https://registry.npmjs.org/performance-now/-/performance-now-2.1.0.tgz", @@ -4010,15 +3977,16 @@ "optional": true }, "node_modules/picocolors": { - "version": "1.0.1", - "resolved": "https://registry.npmjs.org/picocolors/-/picocolors-1.0.1.tgz", - "integrity": "sha512-anP1Z8qwhkbmu7MFP5iTt+wQKXgwzf7zTyGlcdzabySa9vd0Xt392U0rVmz9poOaBj0uHJKyyo9/upk0HrEQew==" + "version": "1.1.1", + "resolved": "https://registry.npmjs.org/picocolors/-/picocolors-1.1.1.tgz", + "integrity": "sha512-xceH2snhtb5M9liqDsmEw56le376mTZkEX/jEb/RxNFyegNul7eNslCXP9FDj/Lcu0X8KEyMceP2ntpaHrDEVA==", + "license": "ISC" }, "node_modules/picomatch": { "version": "2.3.1", "resolved": "https://registry.npmjs.org/picomatch/-/picomatch-2.3.1.tgz", "integrity": "sha512-JU3teHTNjmE2VCGFzuY8EXzCDVwEqB2a8fsIvwaStHhAWJEeVd1o1QD80CU6+ZdEXXSLbSsuLwJjkCBWqRQUVA==", - "dev": true, + "devOptional": true, "engines": { "node": ">=8.6" }, @@ -4048,59 +4016,30 @@ } }, "node_modules/pinia": { - "version": "2.1.7", - "resolved": "https://registry.npmjs.org/pinia/-/pinia-2.1.7.tgz", - "integrity": "sha512-+C2AHFtcFqjPih0zpYuvof37SFxMQ7OEG2zV9jRI12i9BOy3YQVAHwdKtyyc8pDcDyIc33WCIsZaCFWU7WWxGQ==", + "version": "3.0.2", + "resolved": "https://registry.npmjs.org/pinia/-/pinia-3.0.2.tgz", + "integrity": "sha512-sH2JK3wNY809JOeiiURUR0wehJ9/gd9qFN2Y828jCbxEzKEmEt0pzCXwqiSTfuRsK9vQsOflSdnbdBOGrhtn+g==", + "license": "MIT", "dependencies": { - "@vue/devtools-api": "^6.5.0", - "vue-demi": ">=0.14.5" + "@vue/devtools-api": "^7.7.2" }, "funding": { "url": "https://github.com/sponsors/posva" }, "peerDependencies": { - "@vue/composition-api": "^1.4.0", "typescript": ">=4.4.4", - "vue": "^2.6.14 || ^3.3.0" + "vue": "^2.7.0 || ^3.5.11" }, "peerDependenciesMeta": { - "@vue/composition-api": { - "optional": true - }, "typescript": { "optional": true } } }, - "node_modules/pinia/node_modules/vue-demi": { - "version": "0.14.6", - "resolved": "https://registry.npmjs.org/vue-demi/-/vue-demi-0.14.6.tgz", - "integrity": "sha512-8QA7wrYSHKaYgUxDA5ZC24w+eHm3sYCbp0EzcDwKqN3p6HqtTCGR/GVsPyZW92unff4UlcSh++lmqDWN3ZIq4w==", - "hasInstallScript": true, - "bin": { - "vue-demi-fix": "bin/vue-demi-fix.js", - "vue-demi-switch": "bin/vue-demi-switch.js" - }, - "engines": { - "node": ">=12" - }, - "funding": { - "url": "https://github.com/sponsors/antfu" - }, - "peerDependencies": { - "@vue/composition-api": "^1.0.0-rc.1", - "vue": "^3.0.0-0 || ^2.6.0" - }, - "peerDependenciesMeta": { - "@vue/composition-api": { - "optional": true - } - } - }, "node_modules/postcss": { - "version": "8.4.41", - "resolved": "https://registry.npmjs.org/postcss/-/postcss-8.4.41.tgz", - "integrity": "sha512-TesUflQ0WKZqAvg52PWL6kHgLKP6xB6heTOdoYM0Wt2UHyxNa4K25EZZMgKns3BH1RLVbZCREPpLY0rhnNoHVQ==", + "version": "8.5.3", + "resolved": "https://registry.npmjs.org/postcss/-/postcss-8.5.3.tgz", + "integrity": "sha512-dle9A3yYxlBSrt8Fu+IpjGT8SY8hN0mlaA6GY8t0P5PjIOZemULz/E2Bnm/2dcUOena75OTNkHI76uZBNUUq3A==", "funding": [ { "type": "opencollective", @@ -4115,10 +4054,11 @@ "url": "https://github.com/sponsors/ai" } ], + "license": "MIT", "dependencies": { - "nanoid": "^3.3.7", - "picocolors": "^1.0.1", - "source-map-js": "^1.2.0" + "nanoid": "^3.3.8", + "picocolors": "^1.1.1", + "source-map-js": "^1.2.1" }, "engines": { "node": "^10 || ^12 || >=14" @@ -4216,16 +4156,6 @@ "performance-now": "^2.1.0" } }, - "node_modules/randombytes": { - "version": "2.1.0", - "resolved": "https://registry.npmjs.org/randombytes/-/randombytes-2.1.0.tgz", - "integrity": "sha512-vYl3iOX+4CKUWuxGi9Ukhie6fsqXqS9FE2Zaic4tNFD2N2QQaXOMFbuKK4QmDHC0JO6B1Zp41J0LpT0oR68amQ==", - "dev": true, - "peer": true, - "dependencies": { - "safe-buffer": "^5.1.0" - } - }, "node_modules/read-pkg": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/read-pkg/-/read-pkg-3.0.0.tgz", @@ -4252,18 +4182,6 @@ "node": ">=4" } }, - "node_modules/readdirp": { - "version": "3.6.0", - "resolved": "https://registry.npmjs.org/readdirp/-/readdirp-3.6.0.tgz", - "integrity": "sha512-hOS089on8RduqdbhvQ5Z37A0ESjsqz6qnRcffsMU3495FuTdqSm+7bhJ29JvIOsBDEEnan5DPu9t3To9VRlMzA==", - "dev": true, - "dependencies": { - "picomatch": "^2.2.1" - }, - "engines": { - "node": ">=8.10.0" - } - }, "node_modules/regenerator-runtime": { "version": "0.14.1", "resolved": "https://registry.npmjs.org/regenerator-runtime/-/regenerator-runtime-0.14.1.tgz", @@ -4286,6 +4204,16 @@ "url": "https://github.com/sponsors/ljharb" } }, + "node_modules/requireindex": { + "version": "1.2.0", + "resolved": "https://registry.npmjs.org/requireindex/-/requireindex-1.2.0.tgz", + "integrity": "sha512-L9jEkOi3ASd9PYit2cwRfyppc9NoABujTP8/5gFcbERmo5jUoAKovIC3fsF17pkTnGsrByysqX+Kxd2OTNI1ww==", + "dev": true, + "license": "MIT", + "engines": { + "node": ">=0.10.5" + } + }, "node_modules/resolve": { "version": "1.22.8", "resolved": "https://registry.npmjs.org/resolve/-/resolve-1.22.8.tgz", @@ -4322,6 +4250,12 @@ "node": ">=0.10.0" } }, + "node_modules/rfdc": { + "version": "1.4.1", + "resolved": "https://registry.npmjs.org/rfdc/-/rfdc-1.4.1.tgz", + "integrity": "sha512-q1b3N5QkRUWUl7iyylaaj3kOpIT0N2i9MqIEQXP73GVsN9cw3fdx8X63cEmWhJGi2PPCF23Ijp7ktmd39rawIA==", + "license": "MIT" + }, "node_modules/rgbcolor": { "version": "1.0.1", "resolved": "https://registry.npmjs.org/rgbcolor/-/rgbcolor-1.0.1.tgz", @@ -4350,7 +4284,6 @@ "version": "4.21.0", "resolved": "https://registry.npmjs.org/rollup/-/rollup-4.21.0.tgz", "integrity": "sha512-vo+S/lfA2lMS7rZ2Qoubi6I5hwZwzXeUIctILZLbHI+laNtvhhOIon2S1JksA5UEDQ7l3vberd0fxK44lTYjbQ==", - "dev": true, "dependencies": { "@types/estree": "1.0.5" }, @@ -4422,27 +4355,6 @@ "url": "https://github.com/sponsors/ljharb" } }, - "node_modules/safe-buffer": { - "version": "5.2.1", - "resolved": "https://registry.npmjs.org/safe-buffer/-/safe-buffer-5.2.1.tgz", - "integrity": "sha512-rp3So07KcdmmKbGvgaNxQSJr7bGVSVk5S9Eq1F+ppbRo70+YeaDxkw5Dd8NPN+GD6bjnYm2VuPuCXmpuYvmCXQ==", - "dev": true, - "funding": [ - { - "type": "github", - "url": "https://github.com/sponsors/feross" - }, - { - "type": "patreon", - "url": "https://www.patreon.com/feross" - }, - { - "type": "consulting", - "url": "https://feross.org/support" - } - ], - "peer": true - }, "node_modules/safe-regex-test": { "version": "1.0.0", "resolved": "https://registry.npmjs.org/safe-regex-test/-/safe-regex-test-1.0.0.tgz", @@ -4458,74 +4370,54 @@ } }, "node_modules/sass": { - "version": "1.32.13", - "resolved": "https://registry.npmjs.org/sass/-/sass-1.32.13.tgz", - "integrity": "sha512-dEgI9nShraqP7cXQH+lEXVf73WOPCse0QlFzSD8k+1TcOxCMwVXfQlr0jtoluZysQOyJGnfr21dLvYKDJq8HkA==", - "dev": true, + "version": "1.86.3", + "resolved": "https://registry.npmjs.org/sass/-/sass-1.86.3.tgz", + "integrity": "sha512-iGtg8kus4GrsGLRDLRBRHY9dNVA78ZaS7xr01cWnS7PEMQyFtTqBiyCrfpTYTZXRWM94akzckYjh8oADfFNTzw==", + "devOptional": true, + "license": "MIT", "dependencies": { - "chokidar": ">=3.0.0 <4.0.0" + "chokidar": "^4.0.0", + "immutable": "^5.0.2", + "source-map-js": ">=0.6.2 <2.0.0" }, "bin": { "sass": "sass.js" }, "engines": { - "node": ">=8.9.0" + "node": ">=14.0.0" + }, + "optionalDependencies": { + "@parcel/watcher": "^2.4.1" } }, - "node_modules/sass-loader": { - "version": "13.3.3", - "resolved": "https://registry.npmjs.org/sass-loader/-/sass-loader-13.3.3.tgz", - "integrity": "sha512-mt5YN2F1MOZr3d/wBRcZxeFgwgkH44wVc2zohO2YF6JiOMkiXe4BYRZpSu2sO1g71mo/j16txzUhsKZlqjVGzA==", - "dev": true, + "node_modules/sass/node_modules/chokidar": { + "version": "4.0.3", + "resolved": "https://registry.npmjs.org/chokidar/-/chokidar-4.0.3.tgz", + "integrity": "sha512-Qgzu8kfBvo+cA4962jnP1KkS6Dop5NS6g7R5LFYJr4b8Ub94PPQXUksCw9PvXoeXPRRddRNC5C1JQUR2SMGtnA==", + "devOptional": true, + "license": "MIT", "dependencies": { - "neo-async": "^2.6.2" + "readdirp": "^4.0.1" }, "engines": { - "node": ">= 14.15.0" + "node": ">= 14.16.0" }, "funding": { - "type": "opencollective", - "url": "https://opencollective.com/webpack" - }, - "peerDependencies": { - "fibers": ">= 3.1.0", - "node-sass": "^4.0.0 || ^5.0.0 || ^6.0.0 || ^7.0.0 || ^8.0.0 || ^9.0.0", - "sass": "^1.3.0", - "sass-embedded": "*", - "webpack": "^5.0.0" - }, - "peerDependenciesMeta": { - "fibers": { - "optional": true - }, - "node-sass": { - "optional": true - }, - "sass": { - "optional": true - }, - "sass-embedded": { - "optional": true - } + "url": "https://paulmillr.com/funding/" } }, - "node_modules/schema-utils": { - "version": "3.3.0", - "resolved": "https://registry.npmjs.org/schema-utils/-/schema-utils-3.3.0.tgz", - "integrity": "sha512-pN/yOAvcC+5rQ5nERGuwrjLlYvLTbCibnZ1I7B1LaiAz9BRBlE9GMgE/eqV30P7aJQUf7Ddimy/RsbYO/GrVGg==", - "dev": true, - "peer": true, - "dependencies": { - "@types/json-schema": "^7.0.8", - "ajv": "^6.12.5", - "ajv-keywords": "^3.5.2" - }, + "node_modules/sass/node_modules/readdirp": { + "version": "4.1.2", + "resolved": "https://registry.npmjs.org/readdirp/-/readdirp-4.1.2.tgz", + "integrity": "sha512-GDhwkLfywWL2s6vEjyhri+eXmfH6j1L7JE27WhqLeYzoh/A3DBaYGEj2H/HFZCn/kMfim73FXxEJTw06WtxQwg==", + "devOptional": true, + "license": "MIT", "engines": { - "node": ">= 10.13.0" + "node": ">= 14.18.0" }, "funding": { - "type": "opencollective", - "url": "https://opencollective.com/webpack" + "type": "individual", + "url": "https://paulmillr.com/funding/" } }, "node_modules/semver": { @@ -4543,16 +4435,6 @@ "node": ">=10" } }, - "node_modules/serialize-javascript": { - "version": "6.0.1", - "resolved": "https://registry.npmjs.org/serialize-javascript/-/serialize-javascript-6.0.1.tgz", - "integrity": "sha512-owoXEFjWRllis8/M1Q+Cw5k8ZH40e3zhp/ovX+Xr/vi1qj6QesbyXXViFbpNvWvPNAD62SutwEXavefrLJWj7w==", - "dev": true, - "peer": true, - "dependencies": { - "randombytes": "^2.1.0" - } - }, "node_modules/set-function-length": { "version": "1.1.1", "resolved": "https://registry.npmjs.org/set-function-length/-/set-function-length-1.1.1.tgz", @@ -4639,14 +4521,16 @@ "version": "0.6.1", "resolved": "https://registry.npmjs.org/source-map/-/source-map-0.6.1.tgz", "integrity": "sha512-UjgapumWlbMhkBgzT7Ykc5YXUT46F0iKu8SGXq0bcwP5dz/h0Plj6enJqjz1Zbq2l5WaqYnrVbwWOWMyF3F47g==", + "devOptional": true, "engines": { "node": ">=0.10.0" } }, "node_modules/source-map-js": { - "version": "1.2.0", - "resolved": "https://registry.npmjs.org/source-map-js/-/source-map-js-1.2.0.tgz", - "integrity": "sha512-itJW8lvSA0TXEphiRoawsCksnlf8SyvmFzIhltqAHluXd88pkCd+cXJVHTDwdCr0IzwptSm035IHQktUu1QUMg==", + "version": "1.2.1", + "resolved": "https://registry.npmjs.org/source-map-js/-/source-map-js-1.2.1.tgz", + "integrity": "sha512-UXWMKhLOwVKb728IUtQPXxfYU+usdybtUrK/8uGE8CQMvrhOpwvzDBwj0QhSL7MQc7vIsISBG8VQ8+IDQxpfQA==", + "license": "BSD-3-Clause", "engines": { "node": ">=0.10.0" } @@ -4655,7 +4539,7 @@ "version": "0.5.21", "resolved": "https://registry.npmjs.org/source-map-support/-/source-map-support-0.5.21.tgz", "integrity": "sha512-uBHU3L3czsIyYXKX88fdrGovxdSCoTGDRZ6SYXtSRxLZUzHg5P/66Ht6uoUlHu9EZod+inXhKo3qQgwXUT/y1w==", - "dev": true, + "devOptional": true, "dependencies": { "buffer-from": "^1.0.0", "source-map": "^0.6.0" @@ -4693,6 +4577,15 @@ "integrity": "sha512-eWN+LnM3GR6gPu35WxNgbGl8rmY1AEmoMDvL/QD6zYmPWgywxWqJWNdLGT+ke8dKNWrcYgYjPpG5gbTfghP8rw==", "dev": true }, + "node_modules/speakingurl": { + "version": "14.0.1", + "resolved": "https://registry.npmjs.org/speakingurl/-/speakingurl-14.0.1.tgz", + "integrity": "sha512-1POYv7uv2gXoyGFpBCmpDVSNV74IfsWlDW216UPjbWufNf+bSU6GdbDsxdcxtfwb4xlI3yxzOTKClUosxARYrQ==", + "license": "BSD-3-Clause", + "engines": { + "node": ">=0.10.0" + } + }, "node_modules/stackblur-canvas": { "version": "2.6.0", "resolved": "https://registry.npmjs.org/stackblur-canvas/-/stackblur-canvas-2.6.0.tgz", @@ -4797,6 +4690,18 @@ "url": "https://github.com/sponsors/sindresorhus" } }, + "node_modules/superjson": { + "version": "2.2.2", + "resolved": "https://registry.npmjs.org/superjson/-/superjson-2.2.2.tgz", + "integrity": "sha512-5JRxVqC8I8NuOUjzBbvVJAKNM8qoVuH0O77h4WInc/qC2q5IreqKxYwgkga3PfA22OayK2ikceb/B26dztPl+Q==", + "license": "MIT", + "dependencies": { + "copy-anything": "^3.0.2" + }, + "engines": { + "node": ">=16" + } + }, "node_modules/supports-color": { "version": "7.2.0", "resolved": "https://registry.npmjs.org/supports-color/-/supports-color-7.2.0.tgz", @@ -4846,21 +4751,11 @@ "url": "https://opencollective.com/unts" } }, - "node_modules/tapable": { - "version": "2.2.1", - "resolved": "https://registry.npmjs.org/tapable/-/tapable-2.2.1.tgz", - "integrity": "sha512-GNzQvQTOIP6RyTfE2Qxb8ZVlNmw0n88vp1szwWRimP02mnTsx3Wtn5qRdqY9w2XduFNUgvOwhNnQsjwCp+kqaQ==", - "dev": true, - "peer": true, - "engines": { - "node": ">=6" - } - }, "node_modules/terser": { "version": "5.26.0", "resolved": "https://registry.npmjs.org/terser/-/terser-5.26.0.tgz", "integrity": "sha512-dytTGoE2oHgbNV9nTzgBEPaqAWvcJNl66VZ0BkJqlvp71IjO8CxdBx/ykCNb47cLnCmCvRZ6ZR0tLkqvZCdVBQ==", - "dev": true, + "devOptional": true, "dependencies": { "@jridgewell/source-map": "^0.3.3", "acorn": "^8.8.2", @@ -4874,41 +4769,6 @@ "node": ">=10" } }, - "node_modules/terser-webpack-plugin": { - "version": "5.3.10", - "resolved": "https://registry.npmjs.org/terser-webpack-plugin/-/terser-webpack-plugin-5.3.10.tgz", - "integrity": "sha512-BKFPWlPDndPs+NGGCr1U59t0XScL5317Y0UReNrHaw9/FwhPENlq6bfgs+4yPfyP51vqC1bQ4rp1EfXW5ZSH9w==", - "dev": true, - "peer": true, - "dependencies": { - "@jridgewell/trace-mapping": "^0.3.20", - "jest-worker": "^27.4.5", - "schema-utils": "^3.1.1", - "serialize-javascript": "^6.0.1", - "terser": "^5.26.0" - }, - "engines": { - "node": ">= 10.13.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/webpack" - }, - "peerDependencies": { - "webpack": "^5.1.0" - }, - "peerDependenciesMeta": { - "@swc/core": { - "optional": true - }, - "esbuild": { - "optional": true - }, - "uglify-js": { - "optional": true - } - } - }, "node_modules/text-segmentation": { "version": "1.0.3", "resolved": "https://registry.npmjs.org/text-segmentation/-/text-segmentation-1.0.3.tgz", @@ -4933,7 +4793,7 @@ "version": "5.0.1", "resolved": "https://registry.npmjs.org/to-regex-range/-/to-regex-range-5.0.1.tgz", "integrity": "sha512-65P7iz6X5yEr1cwcgvQxbbIw7Uk3gOy5dIdtZ4rDveLqhrdJP+Li/Hx6tyK0NEb+2GCyneCMJiGqrADCSNk8sQ==", - "dev": true, + "devOptional": true, "dependencies": { "is-number": "^7.0.0" }, @@ -5080,110 +4940,15 @@ "version": "5.26.5", "resolved": "https://registry.npmjs.org/undici-types/-/undici-types-5.26.5.tgz", "integrity": "sha512-JlCMO+ehdEIKqlFxk6IfVoAUVmgz7cU7zD/h9XZ0qzeosSHmUJVOzSQvvYSYWXkFXC+IfLKSIffhv0sVZup6pA==", - "dev": true + "devOptional": true }, - "node_modules/unplugin": { - "version": "1.6.0", - "resolved": "https://registry.npmjs.org/unplugin/-/unplugin-1.6.0.tgz", - "integrity": "sha512-BfJEpWBu3aE/AyHx8VaNE/WgouoQxgH9baAiH82JjX8cqVyi3uJQstqwD5J+SZxIK326SZIhsSZlALXVBCknTQ==", - "dev": true, - "dependencies": { - "acorn": "^8.11.2", - "chokidar": "^3.5.3", - "webpack-sources": "^3.2.3", - "webpack-virtual-modules": "^0.6.1" - } - }, - "node_modules/unplugin-vue-components": { - "version": "0.26.0", - "resolved": "https://registry.npmjs.org/unplugin-vue-components/-/unplugin-vue-components-0.26.0.tgz", - "integrity": "sha512-s7IdPDlnOvPamjunVxw8kNgKNK8A5KM1YpK5j/p97jEKTjlPNrA0nZBiSfAKKlK1gWZuyWXlKL5dk3EDw874LQ==", - "dev": true, - "dependencies": { - "@antfu/utils": "^0.7.6", - "@rollup/pluginutils": "^5.0.4", - "chokidar": "^3.5.3", - "debug": "^4.3.4", - "fast-glob": "^3.3.1", - "local-pkg": "^0.4.3", - "magic-string": "^0.30.3", - "minimatch": "^9.0.3", - "resolve": "^1.22.4", - "unplugin": "^1.4.0" - }, - "engines": { - "node": ">=14" - }, - "funding": { - "url": "https://github.com/sponsors/antfu" - }, - "peerDependencies": { - "@babel/parser": "^7.15.8", - "@nuxt/kit": "^3.2.2", - "vue": "2 || 3" - }, - "peerDependenciesMeta": { - "@babel/parser": { - "optional": true - }, - "@nuxt/kit": { - "optional": true - } - } - }, - "node_modules/unplugin-vue-components/node_modules/brace-expansion": { + "node_modules/upath": { "version": "2.0.1", - "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-2.0.1.tgz", - "integrity": "sha512-XnAIvQ8eM+kC6aULx6wuQiwVsnzsi9d3WxzV3FpWTGA19F621kwdbsAcFKXgKUHZWsy+mY6iL1sHTxWEFCytDA==", - "dev": true, - "dependencies": { - "balanced-match": "^1.0.0" - } - }, - "node_modules/unplugin-vue-components/node_modules/minimatch": { - "version": "9.0.3", - "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-9.0.3.tgz", - "integrity": "sha512-RHiac9mvaRw0x3AYRgDC1CxAP7HTcNrrECeA8YYJeWnpo+2Q5CegtZjaotWTWxDG3UeGA1coE05iH1mPjT/2mg==", - "dev": true, - "dependencies": { - "brace-expansion": "^2.0.1" - }, + "resolved": "https://registry.npmjs.org/upath/-/upath-2.0.1.tgz", + "integrity": "sha512-1uEe95xksV1O0CYKXo8vQvN1JEbtJp7lb7C5U9HMsIp6IVwntkH/oNUzyVNQSd4S1sYk2FpSSW44FqMc8qee5w==", "engines": { - "node": ">=16 || 14 >=14.17" - }, - "funding": { - "url": "https://github.com/sponsors/isaacs" - } - }, - "node_modules/update-browserslist-db": { - "version": "1.0.13", - "resolved": "https://registry.npmjs.org/update-browserslist-db/-/update-browserslist-db-1.0.13.tgz", - "integrity": "sha512-xebP81SNcPuNpPP3uzeW1NYXxI3rxyJzF3pD6sH4jE7o/IX+WtSpwnVU+qIsDPyk0d3hmFQ7mjqc6AtV604hbg==", - "dev": true, - "funding": [ - { - "type": "opencollective", - "url": "https://opencollective.com/browserslist" - }, - { - "type": "tidelift", - "url": "https://tidelift.com/funding/github/npm/browserslist" - }, - { - "type": "github", - "url": "https://github.com/sponsors/ai" - } - ], - "peer": true, - "dependencies": { - "escalade": "^3.1.1", - "picocolors": "^1.0.0" - }, - "bin": { - "update-browserslist-db": "cli.js" - }, - "peerDependencies": { - "browserslist": ">= 4.21.0" + "node": ">=4", + "yarn": "*" } }, "node_modules/uri-js": { @@ -5224,7 +4989,6 @@ "version": "5.4.2", "resolved": "https://registry.npmjs.org/vite/-/vite-5.4.2.tgz", "integrity": "sha512-dDrQTRHp5C1fTFzcSaMxjk6vdpKvT+2/mIdE07Gw2ykehT49O0z/VHS3zZ8iV/Gh8BJJKHWOe5RjaNrW5xf/GA==", - "dev": true, "dependencies": { "esbuild": "^0.21.3", "postcss": "^8.4.41", @@ -5279,14 +5043,43 @@ } } }, - "node_modules/vue": { - "version": "2.7.16", - "resolved": "https://registry.npmjs.org/vue/-/vue-2.7.16.tgz", - "integrity": "sha512-4gCtFXaAA3zYZdTp5s4Hl2sozuySsgz4jy1EnpBHNfpMa9dK1ZCG7viqBPCwXtmgc8nHqUsAu3G4gtmXkkY3Sw==", - "deprecated": "Vue 2 has reached EOL and is no longer actively maintained. See https://v2.vuejs.org/eol/ for more details.", + "node_modules/vite-plugin-vuetify": { + "version": "2.1.1", + "resolved": "https://registry.npmjs.org/vite-plugin-vuetify/-/vite-plugin-vuetify-2.1.1.tgz", + "integrity": "sha512-Pb7bKhQH8qPMzURmEGq2aIqCJkruFNsyf1NcrrtnjsOIkqJPMcBbiP0oJoO8/uAmyB5W/1JTbbUEsyXdMM0QHQ==", "dependencies": { - "@vue/compiler-sfc": "2.7.16", - "csstype": "^3.1.0" + "@vuetify/loader-shared": "^2.1.0", + "debug": "^4.3.3", + "upath": "^2.0.1" + }, + "engines": { + "node": "^18.0.0 || >=20.0.0" + }, + "peerDependencies": { + "vite": ">=5", + "vue": "^3.0.0", + "vuetify": "^3.0.0" + } + }, + "node_modules/vue": { + "version": "3.5.13", + "resolved": "https://registry.npmjs.org/vue/-/vue-3.5.13.tgz", + "integrity": "sha512-wmeiSMxkZCSc+PM2w2VRsOYAZC8GdipNFRTsLSfodVqI9mbejKeXEGr8SckuLnrQPGe3oJN5c3K0vpoU9q/wCQ==", + "license": "MIT", + "dependencies": { + "@vue/compiler-dom": "3.5.13", + "@vue/compiler-sfc": "3.5.13", + "@vue/runtime-dom": "3.5.13", + "@vue/server-renderer": "3.5.13", + "@vue/shared": "3.5.13" + }, + "peerDependencies": { + "typescript": "*" + }, + "peerDependenciesMeta": { + "typescript": { + "optional": true + } } }, "node_modules/vue-eslint-parser": { @@ -5339,123 +5132,70 @@ } }, "node_modules/vue-router": { - "version": "3.6.5", - "resolved": "https://registry.npmjs.org/vue-router/-/vue-router-3.6.5.tgz", - "integrity": "sha512-VYXZQLtjuvKxxcshuRAwjHnciqZVoXAjTjcqBTz4rKc8qih9g9pI3hbDjmqXaHdgL3v8pV6P8Z335XvHzESxLQ==" + "version": "4.5.0", + "resolved": "https://registry.npmjs.org/vue-router/-/vue-router-4.5.0.tgz", + "integrity": "sha512-HDuk+PuH5monfNuY+ct49mNmkCRK4xJAV9Ts4z9UFc4rzdDnxQLyCMGGc8pKhZhHTVzfanpNwB/lwqevcBwI4w==", + "license": "MIT", + "dependencies": { + "@vue/devtools-api": "^6.6.4" + }, + "funding": { + "url": "https://github.com/sponsors/posva" + }, + "peerDependencies": { + "vue": "^3.2.0" + } + }, + "node_modules/vue-router/node_modules/@vue/devtools-api": { + "version": "6.6.4", + "resolved": "https://registry.npmjs.org/@vue/devtools-api/-/devtools-api-6.6.4.tgz", + "integrity": "sha512-sGhTPMuXqZ1rVOk32RylztWkfXTRhuS7vgAKv0zjqk8gbsHkJ7xfFf+jbySxt7tWObEJwyKaHMikV/WGDiQm8g==", + "license": "MIT" }, "node_modules/vue-virtual-scroll-list": { "version": "2.3.5", "resolved": "https://registry.npmjs.org/vue-virtual-scroll-list/-/vue-virtual-scroll-list-2.3.5.tgz", "integrity": "sha512-YFK6u5yltqtAOfTBcij/KGAS2SoZvzbNIAf9qTULauPObEp53xj22tDuohrrM2vNkgoD5kejXICIUBt2Q4ZDqQ==" }, - "node_modules/vue2-helpers": { - "version": "2.1.1", - "resolved": "https://registry.npmjs.org/vue2-helpers/-/vue2-helpers-2.1.1.tgz", - "integrity": "sha512-ujYiQ5xfO8qKP3ly8hMqtNA/QGoJCTmKdYErsL3Oxr3nURJ5axah3IV4ztC/Y3zR6qsST0yVwuG1nEneQ9jXQQ==", - "license": "Apache-2.0", + "node_modules/vue3-virtual-scroll-list": { + "version": "0.2.1", + "resolved": "https://registry.npmjs.org/vue3-virtual-scroll-list/-/vue3-virtual-scroll-list-0.2.1.tgz", + "integrity": "sha512-G4KxITUOy9D4ro15zOp40D6ogmMefzjIyMsBKqN3xGbV1P6dlKYMx+BBXCKm3Nr/6iipcUKM272Sh2AJRyWMyQ==", + "license": "MIT", "peerDependencies": { - "vue": "~2.7.0", - "vue-router": "^3", - "vuex": "^3" - }, - "peerDependenciesMeta": { - "vue-router": { - "optional": true - }, - "vuex": { - "optional": true - } + "vue": ">=3.0.0" } }, "node_modules/vuetify": { - "version": "2.7.1", - "resolved": "https://registry.npmjs.org/vuetify/-/vuetify-2.7.1.tgz", - "integrity": "sha512-DVFmRsDtYrITw9yuGLwpFWngFYzEgk0KwloDCIV3+vhZw+NBFJOSzdbttbYmOwtqvQlhDxUyIRQolrRbSFAKlg==", + "version": "3.8.1", + "resolved": "https://registry.npmjs.org/vuetify/-/vuetify-3.8.1.tgz", + "integrity": "sha512-3qReKBBWIIdJJmwnFU1blVIKHDtnLfIP7kk0MwUrrfjYkWmsDpsymtDnsukkTCnlJ1WvhLr64eQFosr0RVbj9w==", + "license": "MIT", + "engines": { + "node": "^12.20 || >=14.13" + }, "funding": { "type": "github", "url": "https://github.com/sponsors/johnleider" }, "peerDependencies": { - "vue": "^2.6.4" - } - }, - "node_modules/watchpack": { - "version": "2.4.0", - "resolved": "https://registry.npmjs.org/watchpack/-/watchpack-2.4.0.tgz", - "integrity": "sha512-Lcvm7MGST/4fup+ifyKi2hjyIAwcdI4HRgtvTpIUxBRhB+RFtUh8XtDOxUfctVCnhVi+QQj49i91OyvzkJl6cg==", - "dev": true, - "peer": true, - "dependencies": { - "glob-to-regexp": "^0.4.1", - "graceful-fs": "^4.1.2" - }, - "engines": { - "node": ">=10.13.0" - } - }, - "node_modules/webpack": { - "version": "5.89.0", - "resolved": "https://registry.npmjs.org/webpack/-/webpack-5.89.0.tgz", - "integrity": "sha512-qyfIC10pOr70V+jkmud8tMfajraGCZMBWJtrmuBymQKCrLTRejBI8STDp1MCyZu/QTdZSeacCQYpYNQVOzX5kw==", - "dev": true, - "peer": true, - "dependencies": { - "@types/eslint-scope": "^3.7.3", - "@types/estree": "^1.0.0", - "@webassemblyjs/ast": "^1.11.5", - "@webassemblyjs/wasm-edit": "^1.11.5", - "@webassemblyjs/wasm-parser": "^1.11.5", - "acorn": "^8.7.1", - "acorn-import-assertions": "^1.9.0", - "browserslist": "^4.14.5", - "chrome-trace-event": "^1.0.2", - "enhanced-resolve": "^5.15.0", - "es-module-lexer": "^1.2.1", - "eslint-scope": "5.1.1", - "events": "^3.2.0", - "glob-to-regexp": "^0.4.1", - "graceful-fs": "^4.2.9", - "json-parse-even-better-errors": "^2.3.1", - "loader-runner": "^4.2.0", - "mime-types": "^2.1.27", - "neo-async": "^2.6.2", - "schema-utils": "^3.2.0", - "tapable": "^2.1.1", - "terser-webpack-plugin": "^5.3.7", - "watchpack": "^2.4.0", - "webpack-sources": "^3.2.3" - }, - "bin": { - "webpack": "bin/webpack.js" - }, - "engines": { - "node": ">=10.13.0" - }, - "funding": { - "type": "opencollective", - "url": "https://opencollective.com/webpack" + "typescript": ">=4.7", + "vite-plugin-vuetify": ">=2.1.0", + "vue": "^3.5.0", + "webpack-plugin-vuetify": ">=3.1.0" }, "peerDependenciesMeta": { - "webpack-cli": { + "typescript": { + "optional": true + }, + "vite-plugin-vuetify": { + "optional": true + }, + "webpack-plugin-vuetify": { "optional": true } } }, - "node_modules/webpack-sources": { - "version": "3.2.3", - "resolved": "https://registry.npmjs.org/webpack-sources/-/webpack-sources-3.2.3.tgz", - "integrity": "sha512-/DyMEOrDgLKKIG0fmvtz+4dUX/3Ghozwgm6iPp8KRhvn+eQf9+Q7GWxVNMk3+uCPWfdXYC4ExGBckIXdFEfH1w==", - "dev": true, - "engines": { - "node": ">=10.13.0" - } - }, - "node_modules/webpack-virtual-modules": { - "version": "0.6.1", - "resolved": "https://registry.npmjs.org/webpack-virtual-modules/-/webpack-virtual-modules-0.6.1.tgz", - "integrity": "sha512-poXpCylU7ExuvZK8z+On3kX+S8o/2dQ/SVYueKA0D4WEMXROXgY8Ez50/bQEUmvoSMMrWcrJqCHuhAbsiwg7Dg==", - "dev": true - }, "node_modules/which": { "version": "2.0.2", "resolved": "https://registry.npmjs.org/which/-/which-2.0.2.tgz", diff --git a/photon-client/package.json b/photon-client/package.json index 1c4f23861..23edaa566 100644 --- a/photon-client/package.json +++ b/photon-client/package.json @@ -18,35 +18,35 @@ "@fontsource/prompt": "^5.0.9", "@mdi/font": "^7.4.47", "@msgpack/msgpack": "^3.0.0-beta2", + "@vitejs/plugin-vue": "^5.2.3", "axios": "^1.6.3", "jspdf": "^2.5.1", "lodash": "^4.17.21", - "pinia": "^2.1.4", + "pinia": "^3.0.2", "three": "^0.160.0", - "vue": "^2.7.14", - "vue-router": "^3.6.5", + "vite-plugin-vuetify": "^2.1.1", + "vue": "^3.5.13", + "vue-router": "^4.5.0", "vue-virtual-scroll-list": "^2.3.5", - "vue2-helpers": "^2.1.1", - "vuetify": "^2.7.1" + "vue3-virtual-scroll-list": "^0.2.1", + "vuetify": "^3.8.1" }, "devDependencies": { "@rushstack/eslint-patch": "^1.3.2", "@types/node": "^18.19.45", "@types/three": "^0.160.0", - "@vitejs/plugin-vue2": "^2.3.1", "@vue/eslint-config-prettier": "^9.0.0", "@vue/eslint-config-typescript": "^12.0.0", "@vue/tsconfig": "^0.5.1", "deepmerge": "^4.3.1", "eslint": "^8.56.0", "eslint-plugin-vue": "^9.19.2", + "eslint-plugin-vuetify": "^2.5.2", "npm-run-all": "^4.1.5", "prettier": "3.2.2", - "sass": "~1.32", - "sass-loader": "^13.3.2", + "sass": "^1.86.3", "terser": "^5.14.2", "typescript": "^5.3.3", - "unplugin-vue-components": "^0.26.0", "vite": "^5.4.2" } } diff --git a/photon-client/src/App.vue b/photon-client/src/App.vue index 0d24fbed5..a6d9cdc4e 100644 --- a/photon-client/src/App.vue +++ b/photon-client/src/App.vue @@ -58,9 +58,9 @@ if (!is_demo) { - + - + @@ -71,9 +71,10 @@ if (!is_demo) { diff --git a/photon-client/src/assets/styles/settings.scss b/photon-client/src/assets/styles/settings.scss new file mode 100644 index 000000000..b82cf4ad8 --- /dev/null +++ b/photon-client/src/assets/styles/settings.scss @@ -0,0 +1,4 @@ +@forward "vuetify/settings" with ( + $button-colored-disabled: false, + $button-disabled-opacity: 0.4 +); diff --git a/photon-client/src/assets/styles/variables.scss b/photon-client/src/assets/styles/variables.scss index c43ac0d10..0f00f5f54 100644 --- a/photon-client/src/assets/styles/variables.scss +++ b/photon-client/src/assets/styles/variables.scss @@ -9,15 +9,15 @@ body { background: $body-background; } -.v-application { +html { font-family: $default-font !important; } .v-row-group__header { background: #005281 !important; } -.theme--dark.v-data-table - > .v-data-table__wrapper +.v-table + > .v-table__wrapper > table > tbody > tr:hover:not(.v-data-table__expanded__content):not(.v-data-table__empty-wrapper) { @@ -27,3 +27,7 @@ body { .v-card__title { word-break: break-word !important; } + +.v-field__input { + padding: 0px !important; +} diff --git a/photon-client/src/components/app/photon-camera-stream.vue b/photon-client/src/components/app/photon-camera-stream.vue index 97f8aaff8..addd6a265 100644 --- a/photon-client/src/components/app/photon-camera-stream.vue +++ b/photon-client/src/components/app/photon-camera-stream.vue @@ -3,7 +3,7 @@ import { computed, inject, ref, onBeforeUnmount } from "vue"; import { useStateStore } from "@/stores/StateStore"; import { useCameraSettingsStore } from "@/stores/settings/CameraSettingsStore"; import loadingImage from "@/assets/images/loading-transparent.svg"; -import type { StyleValue } from "vue/types/jsx"; +import type { StyleValue } from "vue"; import PvIcon from "@/components/common/pv-icon.vue"; import type { UiCameraConfiguration } from "@/types/SettingTypes"; diff --git a/photon-client/src/components/app/photon-error-snackbar.vue b/photon-client/src/components/app/photon-error-snackbar.vue index 950f49b22..914d8b281 100644 --- a/photon-client/src/components/app/photon-error-snackbar.vue +++ b/photon-client/src/components/app/photon-error-snackbar.vue @@ -5,7 +5,7 @@ import { useStateStore } from "@/stores/StateStore";