From ded6790bcd20e362cda7b22a9d1237f96b604b58 Mon Sep 17 00:00:00 2001 From: Ryan Blue Date: Sat, 29 Nov 2025 23:44:02 -0500 Subject: [PATCH 01/27] [cmake] Only add wpilibj to generated config if Java is enabled (#8434) Fixes #8422 --- CMakeLists.txt | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index e7592ac89c..fcf78ed430 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -351,7 +351,9 @@ endif() if(WITH_WPILIB) set(APRILTAG_DEP_REPLACE "find_dependency(apriltag)") set(WPILIBC_DEP_REPLACE "find_dependency(wpilibc)") - set(WPILIBJ_DEP_REPLACE "find_dependency(wpilibj)") + if(WITH_JAVA) + set(WPILIBJ_DEP_REPLACE "find_dependency(wpilibj)") + endif() set(WPILIBNEWCOMMANDS_DEP_REPLACE "find_dependency(wpilibNewCommands)") add_subdirectory(apriltag) add_subdirectory(wpilibj) From 6f86f533e5e7bd9a4bc576716f43efc5b0b7cf60 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Fri, 5 Dec 2025 11:55:28 -0700 Subject: [PATCH 02/27] [wpiutil] MemoryBuffer: Fix zero extending size_t warning on Win32 (#8450) --- .../src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp b/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp index 158a256855..aa8d7b68ca 100644 --- a/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp +++ b/wpiutil/src/main/native/thirdparty/llvm/cpp/llvm/MemoryBuffer.cpp @@ -189,7 +189,7 @@ class MemoryBufferMMapFile : public MB { MappedFileRegion m_mfr; static uint64_t getLegalMapOffset(uint64_t offset) { - return offset & ~(MappedFileRegion::GetAlignment() - 1); + return offset & ~(static_cast(MappedFileRegion::GetAlignment()) - 1); } static uint64_t getLegalMapSize(uint64_t len, uint64_t offset) { From 57c40a3dfcde4edd1af4f7d907dd5c9885083207 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Fri, 5 Dec 2025 16:20:49 -0700 Subject: [PATCH 03/27] [hal] Add more usage reporting constants (#8451) Fixes #7234 Fixes #6919 Supports #2925 Supersedes #8212 Supersedes #7708 --- hal/src/generate/Instances.txt | 1 + hal/src/generate/ResourceType.txt | 9 +++++++++ .../java/edu/wpi/first/hal/FRCNetComm.java | 20 +++++++++++++++++++ .../native/include/hal/FRCUsageReporting.h | 10 ++++++++++ .../main/native/include/hal/UsageReporting.h | 10 ++++++++++ 5 files changed, 50 insertions(+) diff --git a/hal/src/generate/Instances.txt b/hal/src/generate/Instances.txt index c8b566d6d9..bbb9dadb43 100644 --- a/hal/src/generate/Instances.txt +++ b/hal/src/generate/Instances.txt @@ -17,6 +17,7 @@ kFramework_AdvantageKit = 7 kFramework_MagicBot = 8 kFramework_KitBotTraditional = 9 kFramework_KitBotInline = 10 +kFramework_Everybot = 11 kRobotDrive_ArcadeStandard = 1 kRobotDrive_ArcadeButtonSpin = 2 kRobotDrive_ArcadeRatioCurve = 3 diff --git a/hal/src/generate/ResourceType.txt b/hal/src/generate/ResourceType.txt index a275ff7aff..2f908073dd 100644 --- a/hal/src/generate/ResourceType.txt +++ b/hal/src/generate/ResourceType.txt @@ -125,3 +125,12 @@ kResourceType_ThriftyNova = 123 kResourceType_RevServoHub = 124 kResourceType_PWFSEN36005 = 125 kResourceType_LaserShark = 126 +kResourceType_YAMS = 127 +kResourceType_LEDPattern = 128 +kResourceType_LinearQuadraticRegulator = 129 +kResourceType_KalmanFilter = 130 +kResourceType_PoseEstimator = 131 +kResourceType_PoseEstimator3d = 132 +kResourceType_LinearSystemLoop = 133 +kResourceType_LumenLabs_ConnectorX = 134 +kResourceType_LumenLabs_ConnectorXLED = 135 diff --git a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java b/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java index acb569d2de..23a1a4b84a 100644 --- a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java +++ b/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java @@ -273,6 +273,24 @@ public final class FRCNetComm { public static final int kResourceType_PWFSEN36005 = 125; /** kResourceType_LaserShark = 126. */ public static final int kResourceType_LaserShark = 126; + /** kResourceType_YAMS = 127. */ + public static final int kResourceType_YAMS = 127; + /** kResourceType_LEDPattern = 128. */ + public static final int kResourceType_LEDPattern = 128; + /** kResourceType_LinearQuadraticRegulator = 129. */ + public static final int kResourceType_LinearQuadraticRegulator = 129; + /** kResourceType_KalmanFilter = 130. */ + public static final int kResourceType_KalmanFilter = 130; + /** kResourceType_PoseEstimator = 131. */ + public static final int kResourceType_PoseEstimator = 131; + /** kResourceType_PoseEstimator3d = 132. */ + public static final int kResourceType_PoseEstimator3d = 132; + /** kResourceType_LinearSystemLoop = 133. */ + public static final int kResourceType_LinearSystemLoop = 133; + /** kResourceType_LumenLabs_ConnectorX = 134. */ + public static final int kResourceType_LumenLabs_ConnectorX = 134; + /** kResourceType_LumenLabs_ConnectorXLED = 135. */ + public static final int kResourceType_LumenLabs_ConnectorXLED = 135; } /** @@ -321,6 +339,8 @@ public final class FRCNetComm { public static final int kFramework_KitBotTraditional = 9; /** kFramework_KitBotInline = 10. */ public static final int kFramework_KitBotInline = 10; + /** kFramework_Everybot = 11. */ + public static final int kFramework_Everybot = 11; /** kRobotDrive_ArcadeStandard = 1. */ public static final int kRobotDrive_ArcadeStandard = 1; /** kRobotDrive_ArcadeButtonSpin = 2. */ diff --git a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h b/hal/src/generated/main/native/include/hal/FRCUsageReporting.h index 76bc53cf98..10ae1fcb3d 100644 --- a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h +++ b/hal/src/generated/main/native/include/hal/FRCUsageReporting.h @@ -178,6 +178,15 @@ namespace HALUsageReporting { kResourceType_RevServoHub = 124, kResourceType_PWFSEN36005 = 125, kResourceType_LaserShark = 126, + kResourceType_YAMS = 127, + kResourceType_LEDPattern = 128, + kResourceType_LinearQuadraticRegulator = 129, + kResourceType_KalmanFilter = 130, + kResourceType_PoseEstimator = 131, + kResourceType_PoseEstimator3d = 132, + kResourceType_LinearSystemLoop = 133, + kResourceType_LumenLabs_ConnectorX = 134, + kResourceType_LumenLabs_ConnectorXLED = 135, }; enum tInstances : int32_t { kLanguage_LabVIEW = 1, @@ -199,6 +208,7 @@ namespace HALUsageReporting { kFramework_MagicBot = 8, kFramework_KitBotTraditional = 9, kFramework_KitBotInline = 10, + kFramework_Everybot = 11, kRobotDrive_ArcadeStandard = 1, kRobotDrive_ArcadeButtonSpin = 2, kRobotDrive_ArcadeRatioCurve = 3, diff --git a/hal/src/generated/main/native/include/hal/UsageReporting.h b/hal/src/generated/main/native/include/hal/UsageReporting.h index ca88ab4630..ffa42f8fd5 100644 --- a/hal/src/generated/main/native/include/hal/UsageReporting.h +++ b/hal/src/generated/main/native/include/hal/UsageReporting.h @@ -147,6 +147,15 @@ typedef enum kResourceType_RevServoHub = 124, kResourceType_PWFSEN36005 = 125, kResourceType_LaserShark = 126, + kResourceType_YAMS = 127, + kResourceType_LEDPattern = 128, + kResourceType_LinearQuadraticRegulator = 129, + kResourceType_KalmanFilter = 130, + kResourceType_PoseEstimator = 131, + kResourceType_PoseEstimator3d = 132, + kResourceType_LinearSystemLoop = 133, + kResourceType_LumenLabs_ConnectorX = 134, + kResourceType_LumenLabs_ConnectorXLED = 135, // kResourceType_MaximumID = 255, } tResourceType; @@ -172,6 +181,7 @@ typedef enum kFramework_MagicBot = 8, kFramework_KitBotTraditional = 9, kFramework_KitBotInline = 10, + kFramework_Everybot = 11, kRobotDrive_ArcadeStandard = 1, kRobotDrive_ArcadeButtonSpin = 2, kRobotDrive_ArcadeRatioCurve = 3, From a61866912be7f20266ce807e997ba2aa50e956b4 Mon Sep 17 00:00:00 2001 From: Levi <32989720+nobody5050@users.noreply.github.com> Date: Fri, 5 Dec 2025 21:13:39 -0600 Subject: [PATCH 04/27] [hal] Rename Lumen to Lumyn in usage reporting (#8455) --- hal/src/generate/ResourceType.txt | 4 ++-- .../generated/main/java/edu/wpi/first/hal/FRCNetComm.java | 8 ++++---- .../generated/main/native/include/hal/FRCUsageReporting.h | 4 ++-- .../generated/main/native/include/hal/UsageReporting.h | 4 ++-- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/hal/src/generate/ResourceType.txt b/hal/src/generate/ResourceType.txt index 2f908073dd..f572a44eb8 100644 --- a/hal/src/generate/ResourceType.txt +++ b/hal/src/generate/ResourceType.txt @@ -132,5 +132,5 @@ kResourceType_KalmanFilter = 130 kResourceType_PoseEstimator = 131 kResourceType_PoseEstimator3d = 132 kResourceType_LinearSystemLoop = 133 -kResourceType_LumenLabs_ConnectorX = 134 -kResourceType_LumenLabs_ConnectorXLED = 135 +kResourceType_LumynLabs_ConnectorX = 134 +kResourceType_LumynLabs_ConnectorXAnimate = 135 diff --git a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java b/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java index 23a1a4b84a..fdb51a83d2 100644 --- a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java +++ b/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java @@ -287,10 +287,10 @@ public final class FRCNetComm { public static final int kResourceType_PoseEstimator3d = 132; /** kResourceType_LinearSystemLoop = 133. */ public static final int kResourceType_LinearSystemLoop = 133; - /** kResourceType_LumenLabs_ConnectorX = 134. */ - public static final int kResourceType_LumenLabs_ConnectorX = 134; - /** kResourceType_LumenLabs_ConnectorXLED = 135. */ - public static final int kResourceType_LumenLabs_ConnectorXLED = 135; + /** kResourceType_LumynLabs_ConnectorX = 134. */ + public static final int kResourceType_LumynLabs_ConnectorX = 134; + /** kResourceType_LumynLabs_ConnectorXAnimate = 135. */ + public static final int kResourceType_LumynLabs_ConnectorXAnimate = 135; } /** diff --git a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h b/hal/src/generated/main/native/include/hal/FRCUsageReporting.h index 10ae1fcb3d..309dbc49d3 100644 --- a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h +++ b/hal/src/generated/main/native/include/hal/FRCUsageReporting.h @@ -185,8 +185,8 @@ namespace HALUsageReporting { kResourceType_PoseEstimator = 131, kResourceType_PoseEstimator3d = 132, kResourceType_LinearSystemLoop = 133, - kResourceType_LumenLabs_ConnectorX = 134, - kResourceType_LumenLabs_ConnectorXLED = 135, + kResourceType_LumynLabs_ConnectorX = 134, + kResourceType_LumynLabs_ConnectorXAnimate = 135, }; enum tInstances : int32_t { kLanguage_LabVIEW = 1, diff --git a/hal/src/generated/main/native/include/hal/UsageReporting.h b/hal/src/generated/main/native/include/hal/UsageReporting.h index ffa42f8fd5..b0d5295577 100644 --- a/hal/src/generated/main/native/include/hal/UsageReporting.h +++ b/hal/src/generated/main/native/include/hal/UsageReporting.h @@ -154,8 +154,8 @@ typedef enum kResourceType_PoseEstimator = 131, kResourceType_PoseEstimator3d = 132, kResourceType_LinearSystemLoop = 133, - kResourceType_LumenLabs_ConnectorX = 134, - kResourceType_LumenLabs_ConnectorXLED = 135, + kResourceType_LumynLabs_ConnectorX = 134, + kResourceType_LumynLabs_ConnectorXAnimate = 135, // kResourceType_MaximumID = 255, } tResourceType; From 0d1dd84e864122dab9809a187dcb02773b2c4d11 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Sat, 6 Dec 2025 09:16:45 -0800 Subject: [PATCH 05/27] [wpilib] LEDPattern: Add usage reporting (#8452) --- wpilibc/src/main/native/cpp/LEDPattern.cpp | 5 ++++- .../java/edu/wpi/first/wpilibj/LEDPattern.java | 15 +++++++++++++++ 2 files changed, 19 insertions(+), 1 deletion(-) diff --git a/wpilibc/src/main/native/cpp/LEDPattern.cpp b/wpilibc/src/main/native/cpp/LEDPattern.cpp index 363bd545fe..7f1dd6c6b1 100644 --- a/wpilibc/src/main/native/cpp/LEDPattern.cpp +++ b/wpilibc/src/main/native/cpp/LEDPattern.cpp @@ -11,6 +11,7 @@ #include #include +#include #include #include @@ -21,7 +22,9 @@ using namespace frc; LEDPattern::LEDPattern(std::function)> impl) - : m_impl(std::move(impl)) {} + : m_impl(std::move(impl)) { + HAL_Report(HALUsageReporting::kResourceType_LEDPattern, 1); +} void LEDPattern::ApplyTo(LEDPattern::LEDReader reader, std::function writer) const { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/LEDPattern.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/LEDPattern.java index 902a54c031..67f135319e 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/LEDPattern.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/LEDPattern.java @@ -9,6 +9,8 @@ import static edu.wpi.first.units.Units.Microsecond; import static edu.wpi.first.units.Units.Microseconds; import static edu.wpi.first.units.Units.Value; +import edu.wpi.first.hal.FRCNetComm.tResourceType; +import edu.wpi.first.hal.HAL; import edu.wpi.first.math.MathUtil; import edu.wpi.first.units.collections.LongToObjectHashMap; import edu.wpi.first.units.measure.Dimensionless; @@ -149,6 +151,7 @@ public interface LEDPattern { * @return the mapped pattern */ default LEDPattern mapIndex(IndexMapper indexMapper) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { int bufLen = reader.getLength(); applyTo( @@ -294,6 +297,7 @@ public interface LEDPattern { final long totalTimeMicros = (long) (onTime.in(Microseconds) + offTime.in(Microseconds)); final long onTimeMicros = (long) onTime.in(Microseconds); + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { if (RobotController.getTime() % totalTimeMicros < onTimeMicros) { applyTo(reader, writer); @@ -323,6 +327,7 @@ public interface LEDPattern { * @return the blinking pattern */ default LEDPattern synchronizedBlink(BooleanSupplier signal) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { if (signal.getAsBoolean()) { applyTo(reader, writer); @@ -342,6 +347,7 @@ public interface LEDPattern { default LEDPattern breathe(Time period) { final long periodMicros = (long) period.in(Microseconds); + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { applyTo( reader, @@ -373,6 +379,7 @@ public interface LEDPattern { * @return the combined overlay pattern */ default LEDPattern overlayOn(LEDPattern base) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { // write the base pattern down first... base.applyTo(reader, writer); @@ -400,6 +407,7 @@ public interface LEDPattern { * @return the blended pattern */ default LEDPattern blend(LEDPattern other) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { applyTo(reader, writer); @@ -431,6 +439,7 @@ public interface LEDPattern { * @return the masked pattern */ default LEDPattern mask(LEDPattern mask) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { // Apply the current pattern down as normal... applyTo(reader, writer); @@ -470,6 +479,7 @@ public interface LEDPattern { default LEDPattern atBrightness(Dimensionless relativeBrightness) { double multiplier = relativeBrightness.in(Value); + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { applyTo( reader, @@ -496,6 +506,7 @@ public interface LEDPattern { * @return the pattern */ static LEDPattern solid(Color color) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { int bufLen = reader.getLength(); for (int led = 0; led < bufLen; led++) { @@ -525,6 +536,7 @@ public interface LEDPattern { * @return the mask pattern */ static LEDPattern progressMaskLayer(DoubleSupplier progressSupplier) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { double progress = MathUtil.clamp(progressSupplier.getAsDouble(), 0, 1); @@ -561,6 +573,7 @@ public interface LEDPattern { * @return a motionless step pattern */ static LEDPattern steps(Map steps) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); if (steps.isEmpty()) { // no colors specified DriverStation.reportWarning("Creating LED steps with no colors!", false); @@ -622,6 +635,7 @@ public interface LEDPattern { * @return a motionless gradient pattern */ static LEDPattern gradient(GradientType type, Color... colors) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); if (colors.length == 0) { // Nothing to display DriverStation.reportWarning("Creating a gradient with no colors!", false); @@ -679,6 +693,7 @@ public interface LEDPattern { * @return the rainbow pattern */ static LEDPattern rainbow(int saturation, int value) { + HAL.report(tResourceType.kResourceType_LEDPattern, 1); return (reader, writer) -> { int bufLen = reader.getLength(); for (int i = 0; i < bufLen; i++) { From baa6379267085a53e8aa9aabf3bb2d176900f2ab Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Sat, 6 Dec 2025 09:17:02 -0800 Subject: [PATCH 06/27] [wpimath] Add usage reporting for state-space classes (#8453) - LinearQuadraticRegulator - Kalman filters - Pose estimators - LinearSystemLoop Fixes #2925. --- wpilibc/src/main/native/cppcs/RobotBase.cpp | 16 ++++++++++++++++ .../java/edu/wpi/first/wpilibj/RobotBase.java | 10 ++++++++++ .../java/edu/wpi/first/math/MathUsageId.java | 15 +++++++++++++++ .../controller/LinearQuadraticRegulator.java | 6 ++++++ .../math/estimator/ExtendedKalmanFilter.java | 4 ++++ .../wpi/first/math/estimator/KalmanFilter.java | 4 ++++ .../wpi/first/math/estimator/PoseEstimator.java | 2 ++ .../first/math/estimator/PoseEstimator3d.java | 2 ++ .../math/estimator/SteadyStateKalmanFilter.java | 3 +++ .../math/estimator/UnscentedKalmanFilter.java | 3 +++ .../wpi/first/math/system/LinearSystemLoop.java | 3 +++ .../frc/controller/LinearQuadraticRegulator.h | 4 ++++ .../include/frc/estimator/ExtendedKalmanFilter.h | 4 ++++ .../native/include/frc/estimator/KalmanFilter.h | 2 ++ .../native/include/frc/estimator/PoseEstimator.h | 2 ++ .../include/frc/estimator/PoseEstimator3d.h | 2 ++ .../frc/estimator/SteadyStateKalmanFilter.h | 2 ++ .../frc/estimator/UnscentedKalmanFilter.h | 4 ++++ .../native/include/frc/system/LinearSystemLoop.h | 2 ++ .../src/main/native/include/wpimath/MathShared.h | 5 +++++ 20 files changed, 95 insertions(+) diff --git a/wpilibc/src/main/native/cppcs/RobotBase.cpp b/wpilibc/src/main/native/cppcs/RobotBase.cpp index 58f1ec81b5..69dc19e9b4 100644 --- a/wpilibc/src/main/native/cppcs/RobotBase.cpp +++ b/wpilibc/src/main/native/cppcs/RobotBase.cpp @@ -146,6 +146,22 @@ class WPILibMathShared : public wpi::math::MathShared { HAL_Report(HALUsageReporting::kResourceType_PathWeaverTrajectory, count); break; + case wpi::math::MathUsageId::kController_LinearQuadraticRegulator: + HAL_Report(HALUsageReporting::kResourceType_LinearQuadraticRegulator, + count); + break; + case wpi::math::MathUsageId::kEstimator_KalmanFilter: + HAL_Report(HALUsageReporting::kResourceType_KalmanFilter, count); + break; + case wpi::math::MathUsageId::kEstimator_PoseEstimator: + HAL_Report(HALUsageReporting::kResourceType_PoseEstimator, count); + break; + case wpi::math::MathUsageId::kEstimator_PoseEstimator3d: + HAL_Report(HALUsageReporting::kResourceType_PoseEstimator3d, count); + break; + case wpi::math::MathUsageId::kSystem_LinearSystemLoop: + HAL_Report(HALUsageReporting::kResourceType_LinearSystemLoop, count); + break; } } diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java index 0cf6403196..02b9c84137 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java @@ -126,6 +126,16 @@ public abstract class RobotBase implements AutoCloseable { HAL.report(tResourceType.kResourceType_BangBangController, count); case kTrajectory_PathWeaver -> HAL.report(tResourceType.kResourceType_PathWeaverTrajectory, count); + case kController_LinearQuadraticRegulator -> + HAL.report(tResourceType.kResourceType_LinearQuadraticRegulator, count); + case kEstimator_KalmanFilter -> + HAL.report(tResourceType.kResourceType_KalmanFilter, count); + case kEstimator_PoseEstimator -> + HAL.report(tResourceType.kResourceType_PoseEstimator, count); + case kEstimator_PoseEstimator3d -> + HAL.report(tResourceType.kResourceType_PoseEstimator3d, count); + case kSystem_LinearSystemLoop -> + HAL.report(tResourceType.kResourceType_LinearSystemLoop, count); default -> { // NOP } diff --git a/wpimath/src/main/java/edu/wpi/first/math/MathUsageId.java b/wpimath/src/main/java/edu/wpi/first/math/MathUsageId.java index 94c0056743..40c11b10b4 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/MathUsageId.java +++ b/wpimath/src/main/java/edu/wpi/first/math/MathUsageId.java @@ -41,4 +41,19 @@ public enum MathUsageId { /** PathWeaver Trajectory. */ kTrajectory_PathWeaver, + + /** Linear Quadratic Regulator. */ + kController_LinearQuadraticRegulator, + + /** Kalman Filter. */ + kEstimator_KalmanFilter, + + /** Pose Estimator. */ + kEstimator_PoseEstimator, + + /** 3D Pose Estimator. */ + kEstimator_PoseEstimator3d, + + /** Linear System Loop. */ + kSystem_LinearSystemLoop, } diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java index 7b06a50340..7d771e1b88 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/LinearQuadraticRegulator.java @@ -5,6 +5,8 @@ package edu.wpi.first.math.controller; import edu.wpi.first.math.DARE; +import edu.wpi.first.math.MathSharedStore; +import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Num; import edu.wpi.first.math.StateSpaceUtil; @@ -124,6 +126,8 @@ public class LinearQuadraticRegulator(new SimpleMatrix(B.getNumCols(), 1)); reset(); + MathSharedStore.getMathShared() + .reportUsage(MathUsageId.kController_LinearQuadraticRegulator, 1); } /** @@ -163,6 +167,8 @@ public class LinearQuadraticRegulator(new SimpleMatrix(B.getNumCols(), 1)); reset(); + MathSharedStore.getMathShared() + .reportUsage(MathUsageId.kController_LinearQuadraticRegulator, 1); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java index fa8f9245e9..0182aea58c 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/ExtendedKalmanFilter.java @@ -5,6 +5,8 @@ package edu.wpi.first.math.estimator; import edu.wpi.first.math.DARE; +import edu.wpi.first.math.MathSharedStore; +import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Nat; import edu.wpi.first.math.Num; @@ -163,6 +165,8 @@ public class ExtendedKalmanFilter(DARE.dare(discA.transpose(), C.transpose(), discQ, discR)); reset(); + + MathSharedStore.getMathShared().reportUsage(MathUsageId.kEstimator_KalmanFilter, 1); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java index 4e9bf4b3e8..f257eff66c 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java @@ -5,6 +5,7 @@ package edu.wpi.first.math.estimator; import edu.wpi.first.math.MathSharedStore; +import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Nat; @@ -79,6 +80,7 @@ public class PoseEstimator { m_q.set(i, 0, stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0)); } setVisionMeasurementStdDevs(visionMeasurementStdDevs); + MathSharedStore.getMathShared().reportUsage(MathUsageId.kEstimator_PoseEstimator, 1); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java index 463cb9481c..a48dd5030d 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java @@ -5,6 +5,7 @@ package edu.wpi.first.math.estimator; import edu.wpi.first.math.MathSharedStore; +import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Nat; @@ -87,6 +88,7 @@ public class PoseEstimator3d { m_q.set(i, 0, stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0)); } setVisionMeasurementStdDevs(visionMeasurementStdDevs); + MathSharedStore.getMathShared().reportUsage(MathUsageId.kEstimator_PoseEstimator3d, 1); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java index 4b5ca7bc65..454582f526 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/SteadyStateKalmanFilter.java @@ -5,6 +5,8 @@ package edu.wpi.first.math.estimator; import edu.wpi.first.math.DARE; +import edu.wpi.first.math.MathSharedStore; +import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Nat; import edu.wpi.first.math.Num; @@ -107,6 +109,7 @@ public class SteadyStateKalmanFilter(S.getStorage().solve(C.times(P).getStorage()).transpose()); reset(); + MathSharedStore.getMathShared().reportUsage(MathUsageId.kEstimator_KalmanFilter, 4); } /** Resets the observer. */ diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java index 1bc474b4c1..12671f9e74 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/UnscentedKalmanFilter.java @@ -4,6 +4,8 @@ package edu.wpi.first.math.estimator; +import edu.wpi.first.math.MathSharedStore; +import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Nat; import edu.wpi.first.math.Num; @@ -163,6 +165,7 @@ public class UnscentedKalmanFilter(states); reset(); + MathSharedStore.getMathShared().reportUsage(MathUsageId.kEstimator_KalmanFilter, 3); } static diff --git a/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java b/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java index 78cace9a21..126ae38475 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java +++ b/wpimath/src/main/java/edu/wpi/first/math/system/LinearSystemLoop.java @@ -4,6 +4,8 @@ package edu.wpi.first.math.system; +import edu.wpi.first.math.MathSharedStore; +import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.Matrix; import edu.wpi.first.math.Num; import edu.wpi.first.math.StateSpaceUtil; @@ -132,6 +134,7 @@ public class LinearSystemLoop(new SimpleMatrix(controller.getK().getNumCols(), 1)); reset(m_nextR); + MathSharedStore.getMathShared().reportUsage(MathUsageId.kSystem_LinearSystemLoop, 1); } /** diff --git a/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h b/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h index 10a2862683..c1aa71caa4 100644 --- a/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h +++ b/wpimath/src/main/native/include/frc/controller/LinearQuadraticRegulator.h @@ -135,6 +135,8 @@ class LinearQuadraticRegulator { } Reset(); + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kController_LinearQuadraticRegulator, 1); } /** @@ -194,6 +196,8 @@ class LinearQuadraticRegulator { } Reset(); + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kController_LinearQuadraticRegulator, 1); } LinearQuadraticRegulator(LinearQuadraticRegulator&&) = default; diff --git a/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.h b/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.h index 22eddbc281..e9b44dceca 100644 --- a/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.h +++ b/wpimath/src/main/native/include/frc/estimator/ExtendedKalmanFilter.h @@ -137,6 +137,8 @@ class ExtendedKalmanFilter { m_initP = StateMatrix::Zero(); } m_P = m_initP; + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kEstimator_KalmanFilter, 2); } /** @@ -221,6 +223,8 @@ class ExtendedKalmanFilter { m_initP = StateMatrix::Zero(); } m_P = m_initP; + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kEstimator_KalmanFilter, 2); } /** diff --git a/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h b/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h index aa169368bb..71684b52c7 100644 --- a/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h +++ b/wpimath/src/main/native/include/frc/estimator/KalmanFilter.h @@ -118,6 +118,8 @@ class KalmanFilter { } Reset(); + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kEstimator_KalmanFilter, 1); } /** diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h index 1aaf4a39d8..de091d4acb 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h @@ -70,6 +70,8 @@ class WPILIB_DLLEXPORT PoseEstimator { } SetVisionMeasurementStdDevs(visionMeasurementStdDevs); + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kEstimator_PoseEstimator, 1); } /** diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h b/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h index ecf9ccbf88..e33e71b356 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h @@ -76,6 +76,8 @@ class WPILIB_DLLEXPORT PoseEstimator3d { } SetVisionMeasurementStdDevs(visionMeasurementStdDevs); + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kEstimator_PoseEstimator3d, 1); } /** diff --git a/wpimath/src/main/native/include/frc/estimator/SteadyStateKalmanFilter.h b/wpimath/src/main/native/include/frc/estimator/SteadyStateKalmanFilter.h index 734c70c7e0..fd36f9fd75 100644 --- a/wpimath/src/main/native/include/frc/estimator/SteadyStateKalmanFilter.h +++ b/wpimath/src/main/native/include/frc/estimator/SteadyStateKalmanFilter.h @@ -149,6 +149,8 @@ class SteadyStateKalmanFilter { } Reset(); + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kEstimator_KalmanFilter, 4); } SteadyStateKalmanFilter(SteadyStateKalmanFilter&&) = default; diff --git a/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.h b/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.h index 21838870a8..b4e37d7859 100644 --- a/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.h +++ b/wpimath/src/main/native/include/frc/estimator/UnscentedKalmanFilter.h @@ -107,6 +107,8 @@ class UnscentedKalmanFilter { m_dt = dt; Reset(); + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kEstimator_KalmanFilter, 3); } /** @@ -166,6 +168,8 @@ class UnscentedKalmanFilter { m_dt = dt; Reset(); + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kEstimator_KalmanFilter, 3); } /** diff --git a/wpimath/src/main/native/include/frc/system/LinearSystemLoop.h b/wpimath/src/main/native/include/frc/system/LinearSystemLoop.h index c61531ae08..f4b6e39326 100644 --- a/wpimath/src/main/native/include/frc/system/LinearSystemLoop.h +++ b/wpimath/src/main/native/include/frc/system/LinearSystemLoop.h @@ -129,6 +129,8 @@ class LinearSystemLoop { m_clampFunc(clampFunction) { m_nextR.setZero(); Reset(m_nextR); + wpi::math::MathSharedStore::ReportUsage( + wpi::math::MathUsageId::kSystem_LinearSystemLoop, 1); } LinearSystemLoop(LinearSystemLoop&&) = default; diff --git a/wpimath/src/main/native/include/wpimath/MathShared.h b/wpimath/src/main/native/include/wpimath/MathShared.h index 4394b707a7..792b0d20b6 100644 --- a/wpimath/src/main/native/include/wpimath/MathShared.h +++ b/wpimath/src/main/native/include/wpimath/MathShared.h @@ -26,6 +26,11 @@ enum class MathUsageId { kController_ProfiledPIDController, kController_BangBangController, kTrajectory_PathWeaver, + kController_LinearQuadraticRegulator, + kEstimator_KalmanFilter, + kEstimator_PoseEstimator, + kEstimator_PoseEstimator3d, + kSystem_LinearSystemLoop, }; class WPILIB_DLLEXPORT MathShared { From 3dc334c1ee116a8bc72131709aac3ac8b29daeb7 Mon Sep 17 00:00:00 2001 From: Benjamin Hall Date: Sat, 13 Dec 2025 18:53:53 -0500 Subject: [PATCH 07/27] [wpimath] Fix `ResetTranslation` and `ResetRotation` in `PoseEstimator` and `PoseEstimator3d` causing the robot to teleport (#8285) Fixes https://github.com/wpilibsuite/allwpilib/issues/8284. If we have vision updates at the time of the `Reset*` call, we can correct the translation/rotation of the new odometry pose by adding a new vision update where: - `ResetTranslation`: the translation is hard-coded to the new translation, and the rotation components are set to those of the latest vision update (prior to clearing the map). - `ResetRotation`: the rotation is hard-coded to the new rotation, and the translation components are set to those of the latest vision update (prior to clearing the map). --- .../first/math/estimator/PoseEstimator.java | 34 ++++++++++-- .../first/math/estimator/PoseEstimator3d.java | 34 ++++++++++-- .../include/frc/estimator/PoseEstimator.h | 54 +++++++++++++++++-- .../include/frc/estimator/PoseEstimator3d.h | 54 +++++++++++++++++-- .../SwerveDrivePoseEstimator3dTest.java | 37 +++++++++++-- .../SwerveDrivePoseEstimatorTest.java | 30 +++++++++-- .../SwerveDrivePoseEstimator3dTest.cpp | 30 +++++++++-- .../SwerveDrivePoseEstimatorTest.cpp | 26 +++++++-- 8 files changed, 275 insertions(+), 24 deletions(-) diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java index f257eff66c..4c31748329 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java @@ -49,7 +49,9 @@ public class PoseEstimator { TimeInterpolatableBuffer.createBuffer(kBufferDuration); // Maps timestamps to vision updates // Always contains one entry before the oldest entry in m_odometryPoseBuffer, unless there have - // been no vision measurements after the last reset + // been no vision measurements after the last reset. May contain one entry while + // m_odometryPoseBuffer is empty to correct for translation/rotation after a call to + // ResetRotation/ResetTranslation. private final NavigableMap m_visionUpdates = new TreeMap<>(); private Pose2d m_poseEstimate; @@ -147,9 +149,22 @@ public class PoseEstimator { */ public void resetTranslation(Translation2d translation) { m_odometry.resetTranslation(translation); + + final var latestVisionUpdate = m_visionUpdates.lastEntry(); m_odometryPoseBuffer.clear(); m_visionUpdates.clear(); - m_poseEstimate = m_odometry.getPoseMeters(); + + if (latestVisionUpdate != null) { + // apply vision compensation to the pose rotation + final var visionUpdate = + new VisionUpdate( + new Pose2d(translation, latestVisionUpdate.getValue().visionPose.getRotation()), + new Pose2d(translation, latestVisionUpdate.getValue().odometryPose.getRotation())); + m_visionUpdates.put(latestVisionUpdate.getKey(), visionUpdate); + m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters()); + } else { + m_poseEstimate = m_odometry.getPoseMeters(); + } } /** @@ -159,9 +174,22 @@ public class PoseEstimator { */ public void resetRotation(Rotation2d rotation) { m_odometry.resetRotation(rotation); + + final var latestVisionUpdate = m_visionUpdates.lastEntry(); m_odometryPoseBuffer.clear(); m_visionUpdates.clear(); - m_poseEstimate = m_odometry.getPoseMeters(); + + if (latestVisionUpdate != null) { + // apply vision compensation to the pose translation + final var visionUpdate = + new VisionUpdate( + new Pose2d(latestVisionUpdate.getValue().visionPose.getTranslation(), rotation), + new Pose2d(latestVisionUpdate.getValue().odometryPose.getTranslation(), rotation)); + m_visionUpdates.put(latestVisionUpdate.getKey(), visionUpdate); + m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters()); + } else { + m_poseEstimate = m_odometry.getPoseMeters(); + } } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java index a48dd5030d..ad0d1404b8 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java @@ -57,7 +57,9 @@ public class PoseEstimator3d { TimeInterpolatableBuffer.createBuffer(kBufferDuration); // Maps timestamps to vision updates // Always contains one entry before the oldest entry in m_odometryPoseBuffer, unless there have - // been no vision measurements after the last reset + // been no vision measurements after the last reset. May contain one entry while + // m_odometryPoseBuffer is empty to correct for translation/rotation after a call to + // ResetRotation/ResetTranslation. private final NavigableMap m_visionUpdates = new TreeMap<>(); private Pose3d m_poseEstimate; @@ -159,9 +161,22 @@ public class PoseEstimator3d { */ public void resetTranslation(Translation3d translation) { m_odometry.resetTranslation(translation); + + final var latestVisionUpdate = m_visionUpdates.lastEntry(); m_odometryPoseBuffer.clear(); m_visionUpdates.clear(); - m_poseEstimate = m_odometry.getPoseMeters(); + + if (latestVisionUpdate != null) { + // apply vision compensation to the pose rotation + final var visionUpdate = + new VisionUpdate( + new Pose3d(translation, latestVisionUpdate.getValue().visionPose.getRotation()), + new Pose3d(translation, latestVisionUpdate.getValue().odometryPose.getRotation())); + m_visionUpdates.put(latestVisionUpdate.getKey(), visionUpdate); + m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters()); + } else { + m_poseEstimate = m_odometry.getPoseMeters(); + } } /** @@ -171,9 +186,22 @@ public class PoseEstimator3d { */ public void resetRotation(Rotation3d rotation) { m_odometry.resetRotation(rotation); + + final var latestVisionUpdate = m_visionUpdates.lastEntry(); m_odometryPoseBuffer.clear(); m_visionUpdates.clear(); - m_poseEstimate = m_odometry.getPoseMeters(); + + if (latestVisionUpdate != null) { + // apply vision compensation to the pose translation + final var visionUpdate = + new VisionUpdate( + new Pose3d(latestVisionUpdate.getValue().visionPose.getTranslation(), rotation), + new Pose3d(latestVisionUpdate.getValue().odometryPose.getTranslation(), rotation)); + m_visionUpdates.put(latestVisionUpdate.getKey(), visionUpdate); + m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters()); + } else { + m_poseEstimate = m_odometry.getPoseMeters(); + } } /** diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h index de091d4acb..9187889ff6 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h @@ -139,24 +139,70 @@ class WPILIB_DLLEXPORT PoseEstimator { * * @param translation The pose to translation to. */ +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wmaybe-uninitialized" +#endif // defined(__GNUC__) && !defined(__clang__) void ResetTranslation(const Translation2d& translation) { m_odometry.ResetTranslation(translation); + + const std::optional> + latestVisionUpdate = + m_visionUpdates.empty() ? std::nullopt + : std::optional{*m_visionUpdates.crbegin()}; m_odometryPoseBuffer.Clear(); m_visionUpdates.clear(); - m_poseEstimate = m_odometry.GetPose(); + + if (latestVisionUpdate) { + // apply vision compensation to the pose rotation + const VisionUpdate visionUpdate{ + Pose2d{translation, latestVisionUpdate->second.visionPose.Rotation()}, + Pose2d{translation, + latestVisionUpdate->second.odometryPose.Rotation()}}; + m_visionUpdates[latestVisionUpdate->first] = visionUpdate; + m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose()); + } else { + m_poseEstimate = m_odometry.GetPose(); + } } +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic pop +#endif // defined(__GNUC__) && !defined(__clang__) /** * Resets the robot's rotation. * * @param rotation The rotation to reset to. */ +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wmaybe-uninitialized" +#endif // defined(__GNUC__) && !defined(__clang__) void ResetRotation(const Rotation2d& rotation) { m_odometry.ResetRotation(rotation); + + const std::optional> + latestVisionUpdate = + m_visionUpdates.empty() ? std::nullopt + : std::optional{*m_visionUpdates.crbegin()}; m_odometryPoseBuffer.Clear(); m_visionUpdates.clear(); - m_poseEstimate = m_odometry.GetPose(); + + if (latestVisionUpdate) { + // apply vision compensation to the pose translation + const VisionUpdate visionUpdate{ + Pose2d{latestVisionUpdate->second.visionPose.Translation(), rotation}, + Pose2d{latestVisionUpdate->second.odometryPose.Translation(), + rotation}}; + m_visionUpdates[latestVisionUpdate->first] = visionUpdate; + m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose()); + } else { + m_poseEstimate = m_odometry.GetPose(); + } } +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic pop +#endif // defined(__GNUC__) && !defined(__clang__) /** * Gets the estimated robot pose. @@ -436,7 +482,9 @@ class WPILIB_DLLEXPORT PoseEstimator { TimeInterpolatableBuffer m_odometryPoseBuffer{kBufferDuration}; // Maps timestamps to vision updates // Always contains one entry before the oldest entry in m_odometryPoseBuffer, - // unless there have been no vision measurements after the last reset + // unless there have been no vision measurements after the last reset. May + // contain one entry while m_odometryPoseBuffer is empty to correct for + // translation/rotation after a call to ResetRotation/ResetTranslation. std::map m_visionUpdates; Pose2d m_poseEstimate; diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h b/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h index e33e71b356..490a6cbcb2 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h @@ -148,24 +148,70 @@ class WPILIB_DLLEXPORT PoseEstimator3d { * * @param translation The pose to translation to. */ +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wmaybe-uninitialized" +#endif // defined(__GNUC__) && !defined(__clang__) void ResetTranslation(const Translation3d& translation) { m_odometry.ResetTranslation(translation); + + const std::optional> + latestVisionUpdate = + m_visionUpdates.empty() ? std::nullopt + : std::optional{*m_visionUpdates.crbegin()}; m_odometryPoseBuffer.Clear(); m_visionUpdates.clear(); - m_poseEstimate = m_odometry.GetPose(); + + if (latestVisionUpdate) { + // apply vision compensation to the pose rotation + const VisionUpdate visionUpdate{ + Pose3d{translation, latestVisionUpdate->second.visionPose.Rotation()}, + Pose3d{translation, + latestVisionUpdate->second.odometryPose.Rotation()}}; + m_visionUpdates[latestVisionUpdate->first] = visionUpdate; + m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose()); + } else { + m_poseEstimate = m_odometry.GetPose(); + } } +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic pop +#endif // defined(__GNUC__) && !defined(__clang__) /** * Resets the robot's rotation. * * @param rotation The rotation to reset to. */ +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic push +#pragma GCC diagnostic ignored "-Wmaybe-uninitialized" +#endif // defined(__GNUC__) && !defined(__clang__) void ResetRotation(const Rotation3d& rotation) { m_odometry.ResetRotation(rotation); + + const std::optional> + latestVisionUpdate = + m_visionUpdates.empty() ? std::nullopt + : std::optional{*m_visionUpdates.crbegin()}; m_odometryPoseBuffer.Clear(); m_visionUpdates.clear(); - m_poseEstimate = m_odometry.GetPose(); + + if (latestVisionUpdate) { + // apply vision compensation to the pose translation + const VisionUpdate visionUpdate{ + Pose3d{latestVisionUpdate->second.visionPose.Translation(), rotation}, + Pose3d{latestVisionUpdate->second.odometryPose.Translation(), + rotation}}; + m_visionUpdates[latestVisionUpdate->first] = visionUpdate; + m_poseEstimate = visionUpdate.Compensate(m_odometry.GetPose()); + } else { + m_poseEstimate = m_odometry.GetPose(); + } } +#if defined(__GNUC__) && !defined(__clang__) +#pragma GCC diagnostic pop +#endif // defined(__GNUC__) && !defined(__clang__) /** * Gets the estimated robot pose. @@ -451,7 +497,9 @@ class WPILIB_DLLEXPORT PoseEstimator3d { TimeInterpolatableBuffer m_odometryPoseBuffer{kBufferDuration}; // Maps timestamps to vision updates // Always contains one entry before the oldest entry in m_odometryPoseBuffer, - // unless there have been no vision measurements after the last reset + // unless there have been no vision measurements after the last reset. May + // contain one entry while m_odometryPoseBuffer is empty to correct for + // translation/rotation after a call to ResetRotation/ResetTranslation. std::map m_visionUpdates; Pose3d m_poseEstimate; diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator3dTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator3dTest.java index e3cd11a281..06cc16e52b 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator3dTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimator3dTest.java @@ -8,6 +8,7 @@ import static org.junit.jupiter.api.Assertions.assertAll; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertTrue; +import edu.wpi.first.math.MathSharedStore; import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose3d; @@ -509,11 +510,23 @@ class SwerveDrivePoseEstimator3dTest { () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getY(), kEpsilon), () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getZ(), kEpsilon)); + // Add a vision measurement with a different translation + estimator.addVisionMeasurement( + new Pose3d(3, 0, 0, Rotation3d.kZero), MathSharedStore.getTimestamp()); + + assertAll( + () -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon), + () -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon), + () -> assertEquals(0, estimator.getEstimatedPosition().getZ(), kEpsilon), + () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getX(), kEpsilon), + () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getY(), kEpsilon), + () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getZ(), kEpsilon)); + // Test reset rotation estimator.resetRotation(new Rotation3d(Rotation2d.kCCW_Pi_2)); assertAll( - () -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon), + () -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon), () -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon), () -> assertEquals(0, estimator.getEstimatedPosition().getZ(), kEpsilon), () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getX(), kEpsilon), @@ -533,7 +546,7 @@ class SwerveDrivePoseEstimator3dTest { } assertAll( - () -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon), + () -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon), () -> assertEquals(1, estimator.getEstimatedPosition().getY(), kEpsilon), () -> assertEquals(0, estimator.getEstimatedPosition().getZ(), kEpsilon), () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getX(), kEpsilon), @@ -542,6 +555,22 @@ class SwerveDrivePoseEstimator3dTest { assertEquals( Math.PI / 2, estimator.getEstimatedPosition().getRotation().getZ(), kEpsilon)); + // Add a vision measurement with a different rotation + estimator.addVisionMeasurement( + new Pose3d(2.5, 1, 0, new Rotation3d(Rotation2d.kPi)), MathSharedStore.getTimestamp()); + + assertAll( + () -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon), + () -> assertEquals(1, estimator.getEstimatedPosition().getY(), kEpsilon), + () -> assertEquals(0, estimator.getEstimatedPosition().getZ(), kEpsilon), + () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getX(), kEpsilon), + () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getY(), kEpsilon), + () -> + assertEquals( + Math.PI * 3.0 / 4, + estimator.getEstimatedPosition().getRotation().getZ(), + kEpsilon)); + // Test reset translation estimator.resetTranslation(new Translation3d(-1, -1, -1)); @@ -553,7 +582,9 @@ class SwerveDrivePoseEstimator3dTest { () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getY(), kEpsilon), () -> assertEquals( - Math.PI / 2, estimator.getEstimatedPosition().getRotation().getZ(), kEpsilon)); + Math.PI * 3.0 / 4, + estimator.getEstimatedPosition().getRotation().getZ(), + kEpsilon)); // Test reset pose estimator.resetPose(Pose3d.kZero); diff --git a/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java b/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java index 2b259a6a89..c2b6c65743 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/estimator/SwerveDrivePoseEstimatorTest.java @@ -8,6 +8,7 @@ import static org.junit.jupiter.api.Assertions.assertAll; import static org.junit.jupiter.api.Assertions.assertEquals; import static org.junit.jupiter.api.Assertions.assertTrue; +import edu.wpi.first.math.MathSharedStore; import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; @@ -481,11 +482,21 @@ class SwerveDrivePoseEstimatorTest { () -> assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon)); + // Add a vision measurement with a different translation + estimator.addVisionMeasurement( + new Pose2d(3, 0, Rotation2d.kZero), MathSharedStore.getTimestamp()); + + assertAll( + () -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon), + () -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon), + () -> + assertEquals(0, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon)); + // Test reset rotation estimator.resetRotation(Rotation2d.kCCW_Pi_2); assertAll( - () -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon), + () -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon), () -> assertEquals(0, estimator.getEstimatedPosition().getY(), kEpsilon), () -> assertEquals( @@ -504,7 +515,7 @@ class SwerveDrivePoseEstimatorTest { } assertAll( - () -> assertEquals(2, estimator.getEstimatedPosition().getX(), kEpsilon), + () -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon), () -> assertEquals(1, estimator.getEstimatedPosition().getY(), kEpsilon), () -> assertEquals( @@ -512,6 +523,19 @@ class SwerveDrivePoseEstimatorTest { estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon)); + // Add a vision measurement with a different rotation + estimator.addVisionMeasurement( + new Pose2d(2.5, 1, Rotation2d.kPi), MathSharedStore.getTimestamp()); + + assertAll( + () -> assertEquals(2.5, estimator.getEstimatedPosition().getX(), kEpsilon), + () -> assertEquals(1, estimator.getEstimatedPosition().getY(), kEpsilon), + () -> + assertEquals( + Math.PI * 3.0 / 4, + estimator.getEstimatedPosition().getRotation().getRadians(), + kEpsilon)); + // Test reset translation estimator.resetTranslation(new Translation2d(-1, -1)); @@ -520,7 +544,7 @@ class SwerveDrivePoseEstimatorTest { () -> assertEquals(-1, estimator.getEstimatedPosition().getY(), kEpsilon), () -> assertEquals( - Math.PI / 2, + Math.PI * 3.0 / 4, estimator.getEstimatedPosition().getRotation().getRadians(), kEpsilon)); diff --git a/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimator3dTest.cpp b/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimator3dTest.cpp index 612862f4f1..fa405ae0b6 100644 --- a/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimator3dTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimator3dTest.cpp @@ -453,10 +453,21 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Y().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Z().value()); + // Add a vision measurement with a different translation + estimator.AddVisionMeasurement(frc::Pose3d(3_m, 0_m, 0_m, frc::Rotation3d{}), + wpi::math::MathSharedStore::GetTimestamp()); + + EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value()); + EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); + EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Z().value()); + EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().X().value()); + EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Y().value()); + EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Z().value()); + // Test reset rotation estimator.ResetRotation(frc::Rotation3d{0_deg, 0_deg, 90_deg}); - EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); + EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Z().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().X().value()); @@ -471,7 +482,7 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { modulePosition, modulePosition}); } - EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); + EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Y().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Z().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().X().value()); @@ -479,6 +490,19 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(std::numbers::pi / 2, estimator.GetEstimatedPosition().Rotation().Z().value()); + // Add a vision measurement with a different rotation + estimator.AddVisionMeasurement( + frc::Pose3d(2.5_m, 1_m, 0_m, frc::Rotation3d{frc::Rotation2d{180_deg}}), + wpi::math::MathSharedStore::GetTimestamp()); + + EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value()); + EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Y().value()); + EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Z().value()); + EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().X().value()); + EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Y().value()); + EXPECT_DOUBLE_EQ(std::numbers::pi * 3.0 / 4, + estimator.GetEstimatedPosition().Rotation().Z().value()); + // Test reset translation estimator.ResetTranslation(frc::Translation3d{-1_m, -1_m, -1_m}); @@ -487,7 +511,7 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().Z().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Y().value()); - EXPECT_DOUBLE_EQ(std::numbers::pi / 2, + EXPECT_DOUBLE_EQ(std::numbers::pi * 3.0 / 4, estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset pose diff --git a/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp b/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp index 1655074209..5bc75b39bd 100644 --- a/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp @@ -430,10 +430,19 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) { EXPECT_DOUBLE_EQ( 0, estimator.GetEstimatedPosition().Rotation().Radians().value()); + // Add a vision measurement with a different translation + estimator.AddVisionMeasurement(frc::Pose2d{3_m, 0_m, frc::Rotation2d{}}, + wpi::math::MathSharedStore::GetTimestamp()); + + EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value()); + EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); + EXPECT_DOUBLE_EQ( + 0, estimator.GetEstimatedPosition().Rotation().Radians().value()); + // Test reset rotation estimator.ResetRotation(frc::Rotation2d{90_deg}); - EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); + EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); EXPECT_DOUBLE_EQ( std::numbers::pi / 2, @@ -446,19 +455,30 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) { modulePosition, modulePosition}); } - EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); + EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Y().value()); EXPECT_DOUBLE_EQ( std::numbers::pi / 2, estimator.GetEstimatedPosition().Rotation().Radians().value()); + // Add a vision measurement with a different rotation + estimator.AddVisionMeasurement( + frc::Pose2d{2.5_m, 1_m, frc::Rotation2d{180_deg}}, + wpi::math::MathSharedStore::GetTimestamp()); + + EXPECT_DOUBLE_EQ(2.5, estimator.GetEstimatedPosition().X().value()); + EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Y().value()); + EXPECT_DOUBLE_EQ( + std::numbers::pi * 3.0 / 4, + estimator.GetEstimatedPosition().Rotation().Radians().value()); + // Test reset translation estimator.ResetTranslation(frc::Translation2d{-1_m, -1_m}); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().Y().value()); EXPECT_DOUBLE_EQ( - std::numbers::pi / 2, + std::numbers::pi * 3.0 / 4, estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset pose From 1b2f051b4b6d8035ad7a4cf0b85e9aacf26a5441 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sun, 14 Dec 2025 08:06:02 -0800 Subject: [PATCH 08/27] [docs] Replace instance of PWMSpeedController (#8478) --- wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h index 2baa49effa..b357276c63 100644 --- a/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h +++ b/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h @@ -77,7 +77,7 @@ class DifferentialDrive : public RobotDriveBase, * Construct a DifferentialDrive. * * To pass multiple motors per side, use CAN motor controller followers or - * PWMSpeedController::AddFollower(). If a motor needs to be inverted, do so + * PWMMotorController::AddFollower(). If a motor needs to be inverted, do so * before passing it in. * * @param leftMotor Left motor. @@ -91,7 +91,7 @@ class DifferentialDrive : public RobotDriveBase, * Construct a DifferentialDrive. * * To pass multiple motors per side, use CAN motor controller followers or - * PWMSpeedController::AddFollower(). If a motor needs to be inverted, do so + * PWMMotorController::AddFollower(). If a motor needs to be inverted, do so * before passing it in. * * @param leftMotor Left motor setter. From ab3af00d0782ffbed7470f817b9875fd6db0d314 Mon Sep 17 00:00:00 2001 From: Bryce Roethel Date: Sun, 21 Dec 2025 11:08:32 -0500 Subject: [PATCH 09/27] [wpimath] TrapezoidProfile.State implement StructSerializable (#8499) Seems like this was missed in #8163 --- .../java/edu/wpi/first/math/trajectory/TrapezoidProfile.java | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java index f3de310944..13c182141d 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java +++ b/wpimath/src/main/java/edu/wpi/first/math/trajectory/TrapezoidProfile.java @@ -7,6 +7,7 @@ package edu.wpi.first.math.trajectory; import edu.wpi.first.math.MathSharedStore; import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.trajectory.struct.TrapezoidProfileStateStruct; +import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; /** @@ -76,7 +77,7 @@ public class TrapezoidProfile { } /** Profile state. */ - public static class State { + public static class State implements StructSerializable { /** The struct used to serialize this class. */ public static final TrapezoidProfileStateStruct struct = new TrapezoidProfileStateStruct(); From f395954d3c2c016d237a346b116d890114ac6bd3 Mon Sep 17 00:00:00 2001 From: Charlotte Wilson Date: Wed, 31 Dec 2025 12:08:33 -0500 Subject: [PATCH 10/27] [ci] Update Android NDK version to R27D in CMake workflow (#8525) https://github.com/android/ndk/wiki#release-schedule --- .github/workflows/cmake-android.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/cmake-android.yml b/.github/workflows/cmake-android.yml index da7a67f362..32425d5c3c 100644 --- a/.github/workflows/cmake-android.yml +++ b/.github/workflows/cmake-android.yml @@ -30,7 +30,7 @@ jobs: - uses: nttld/setup-ndk@v1 id: setup-ndk with: - ndk-version: r27c + ndk-version: r27d add-to-path: false - uses: actions/setup-java@v4 From 71a788e20bfdeb162fe9c81d9e57e00b98fc359c Mon Sep 17 00:00:00 2001 From: sciencewhiz Date: Fri, 2 Jan 2026 09:46:22 -0700 Subject: [PATCH 11/27] [docs] Update references to 2026 (#8534) --- DevelopmentBuilds.md | 18 +++++++++--------- LICENSE.md | 2 +- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/DevelopmentBuilds.md b/DevelopmentBuilds.md index 47cae2781e..eb314aeb0e 100644 --- a/DevelopmentBuilds.md +++ b/DevelopmentBuilds.md @@ -13,7 +13,7 @@ This article contains instructions on building projects using a development buil Development builds are the per-commit build hosted every time a commit is pushed to the [allwpilib](https://github.com/wpilibsuite/allwpilib/) repository. These builds are then hosted on [artifactory](https://frcmaven.wpi.edu/artifactory/webapp/#/home). -To build a project using a development build, find the build.gradle file and open it. Then, add the following code below the plugin section and replace YEAR with the year of the development version. It is also necessary to use a 2025 GradleRIO version, ie `2025.1.1-beta-1` +To build a project using a development build, find the build.gradle file and open it. Then, add the following code below the plugin section and replace YEAR with the year of the development version. It is also necessary to use a 2026 GradleRIO version, ie `2026.1.1` ```groovy wpi.maven.useLocal = false @@ -28,13 +28,13 @@ Java ```groovy plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1" + id "edu.wpi.first.GradleRIO" version "2026.1.1" } wpi.maven.useLocal = false wpi.maven.useDevelopment = true -wpi.versions.wpilibVersion = '2025.+' -wpi.versions.wpimathVersion = '2025.+' +wpi.versions.wpilibVersion = '2026.+' +wpi.versions.wpimathVersion = '2026.+' ``` C++ @@ -42,13 +42,13 @@ C++ plugins { id "cpp" id "google-test-test-suite" - id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1" + id "edu.wpi.first.GradleRIO" version "2026.1.1" } wpi.maven.useLocal = false wpi.maven.useDevelopment = true -wpi.versions.wpilibVersion = '2025.+' -wpi.versions.wpimathVersion = '2025.+' +wpi.versions.wpilibVersion = '2026.+' +wpi.versions.wpimathVersion = '2026.+' ``` ### Development Build Documentation @@ -64,7 +64,7 @@ Java ```groovy plugins { id "java" - id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1" + id "edu.wpi.first.GradleRIO" version "2026.1.1" } wpi.maven.useLocal = false @@ -78,7 +78,7 @@ C++ plugins { id "cpp" id "google-test-test-suite" - id "edu.wpi.first.GradleRIO" version "2025.1.1-beta-1" + id "edu.wpi.first.GradleRIO" version "2026.1.1" } wpi.maven.useLocal = false diff --git a/LICENSE.md b/LICENSE.md index d744196fe9..eb3061b0d8 100644 --- a/LICENSE.md +++ b/LICENSE.md @@ -1,4 +1,4 @@ -Copyright (c) 2009-2025 FIRST and other WPILib contributors +Copyright (c) 2009-2026 FIRST and other WPILib contributors All rights reserved. Redistribution and use in source and binary forms, with or without From ccb326675337071a329968b55723d4ab716ce1ec Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 3 Jan 2026 16:31:26 -0500 Subject: [PATCH 12/27] [upstream_utils] Remove patch that results in building with NDEBUG causing ODR issues (#8540) --- ...move-StringRef-ArrayRef-and-Optional.patch | 2 +- ...-calls-in-parens-for-Windows-warning.patch | 2 +- ...-Change-unique_function-storage-size.patch | 2 +- .../llvm_patches/0004-Threading-updates.patch | 2 +- .../0005-ifdef-guard-safety.patch | 2 +- .../0006-Explicitly-use-std.patch | 2 +- .../0007-Remove-format_provider.patch | 2 +- .../0008-Add-compiler-warning-pragmas.patch | 2 +- .../0009-Remove-unused-functions.patch | 2 +- .../0010-Detemplatize-SmallVectorBase.patch | 2 +- .../0011-Add-vectors-to-raw_ostream.patch | 2 +- .../0012-Extra-collections-features.patch | 2 +- ...0013-Delete-numbers-from-MathExtras.patch} | 2 +- .../0013-EpochTracker-ABI-macro.patch | 22 ------------------- ...-sgn.patch => 0014-Add-lerp-and-sgn.patch} | 2 +- ...cludes.patch => 0015-Fixup-includes.patch} | 2 +- ...std-is_trivially_copy_constructible.patch} | 2 +- ...pport.patch => 0017-Windows-support.patch} | 2 +- ...8-Remove-call-to-RtlGetLastNtStatus.patch} | 2 +- ...-fmtlib.patch => 0019-Prefer-fmtlib.patch} | 2 +- ...s.h.patch => 0020-Prefer-wpi-s-fs.h.patch} | 2 +- ...tch => 0021-Remove-unused-functions.patch} | 2 +- ...s.patch => 0022-OS-specific-changes.patch} | 2 +- ...-Use-SmallVector-for-UTF-conversion.patch} | 2 +- ...-use-static-pointers-in-raw_ostream.patch} | 2 +- ... => 0025-constexpr-endian-byte-swap.patch} | 2 +- ...from-STLExtras.h-into-PointerUnion..patch} | 2 +- ...027-Unused-variable-in-release-mode.patch} | 2 +- ...r.patch => 0028-Use-C-20-bit-header.patch} | 2 +- ...-Remove-DenseMap-GTest-printer-test.patch} | 2 +- ...raw_ostream-Add-SetNumBytesInBuffer.patch} | 2 +- ...aw_ostream-Replace-errnoAsErrorCode.patch} | 2 +- ...0032-type_traits.h-Add-is_constexpr.patch} | 2 +- ...ve-auto-conversion-from-raw_ostream.patch} | 2 +- ...ch => 0034-Add-SmallVector-erase_if.patch} | 2 +- ...-Fix-AlignedCharArrayUnion-for-C-23.patch} | 2 +- ...-Fix-minIntN-and-maxIntN-assertions.patch} | 2 +- .../llvm/include/wpi/EpochTracker.h | 2 +- 38 files changed, 37 insertions(+), 59 deletions(-) rename upstream_utils/llvm_patches/{0014-Delete-numbers-from-MathExtras.patch => 0013-Delete-numbers-from-MathExtras.patch} (98%) delete mode 100644 upstream_utils/llvm_patches/0013-EpochTracker-ABI-macro.patch rename upstream_utils/llvm_patches/{0015-Add-lerp-and-sgn.patch => 0014-Add-lerp-and-sgn.patch} (96%) rename upstream_utils/llvm_patches/{0016-Fixup-includes.patch => 0015-Fixup-includes.patch} (99%) rename upstream_utils/llvm_patches/{0017-Use-std-is_trivially_copy_constructible.patch => 0016-Use-std-is_trivially_copy_constructible.patch} (95%) rename upstream_utils/llvm_patches/{0018-Windows-support.patch => 0017-Windows-support.patch} (99%) rename upstream_utils/llvm_patches/{0019-Remove-call-to-RtlGetLastNtStatus.patch => 0018-Remove-call-to-RtlGetLastNtStatus.patch} (97%) rename upstream_utils/llvm_patches/{0020-Prefer-fmtlib.patch => 0019-Prefer-fmtlib.patch} (98%) rename upstream_utils/llvm_patches/{0021-Prefer-wpi-s-fs.h.patch => 0020-Prefer-wpi-s-fs.h.patch} (96%) rename upstream_utils/llvm_patches/{0022-Remove-unused-functions.patch => 0021-Remove-unused-functions.patch} (99%) rename upstream_utils/llvm_patches/{0023-OS-specific-changes.patch => 0022-OS-specific-changes.patch} (97%) rename upstream_utils/llvm_patches/{0024-Use-SmallVector-for-UTF-conversion.patch => 0023-Use-SmallVector-for-UTF-conversion.patch} (99%) rename upstream_utils/llvm_patches/{0025-Prefer-to-use-static-pointers-in-raw_ostream.patch => 0024-Prefer-to-use-static-pointers-in-raw_ostream.patch} (95%) rename upstream_utils/llvm_patches/{0026-constexpr-endian-byte-swap.patch => 0025-constexpr-endian-byte-swap.patch} (94%) rename upstream_utils/llvm_patches/{0027-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch => 0026-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch} (97%) rename upstream_utils/llvm_patches/{0028-Unused-variable-in-release-mode.patch => 0027-Unused-variable-in-release-mode.patch} (94%) rename upstream_utils/llvm_patches/{0029-Use-C-20-bit-header.patch => 0028-Use-C-20-bit-header.patch} (99%) rename upstream_utils/llvm_patches/{0030-Remove-DenseMap-GTest-printer-test.patch => 0029-Remove-DenseMap-GTest-printer-test.patch} (94%) rename upstream_utils/llvm_patches/{0031-raw_ostream-Add-SetNumBytesInBuffer.patch => 0030-raw_ostream-Add-SetNumBytesInBuffer.patch} (93%) rename upstream_utils/llvm_patches/{0032-raw_ostream-Replace-errnoAsErrorCode.patch => 0031-raw_ostream-Replace-errnoAsErrorCode.patch} (94%) rename upstream_utils/llvm_patches/{0033-type_traits.h-Add-is_constexpr.patch => 0032-type_traits.h-Add-is_constexpr.patch} (94%) rename upstream_utils/llvm_patches/{0034-Remove-auto-conversion-from-raw_ostream.patch => 0033-Remove-auto-conversion-from-raw_ostream.patch} (95%) rename upstream_utils/llvm_patches/{0035-Add-SmallVector-erase_if.patch => 0034-Add-SmallVector-erase_if.patch} (95%) rename upstream_utils/llvm_patches/{0036-Fix-AlignedCharArrayUnion-for-C-23.patch => 0035-Fix-AlignedCharArrayUnion-for-C-23.patch} (96%) rename upstream_utils/llvm_patches/{0037-Fix-minIntN-and-maxIntN-assertions.patch => 0036-Fix-minIntN-and-maxIntN-assertions.patch} (95%) diff --git a/upstream_utils/llvm_patches/0001-Remove-StringRef-ArrayRef-and-Optional.patch b/upstream_utils/llvm_patches/0001-Remove-StringRef-ArrayRef-and-Optional.patch index 5ed1d49ac6..ae1f814f47 100644 --- a/upstream_utils/llvm_patches/0001-Remove-StringRef-ArrayRef-and-Optional.patch +++ b/upstream_utils/llvm_patches/0001-Remove-StringRef-ArrayRef-and-Optional.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:09:18 -0400 -Subject: [PATCH 01/37] Remove StringRef, ArrayRef, and Optional +Subject: [PATCH 01/36] Remove StringRef, ArrayRef, and Optional --- llvm/include/llvm/ADT/PointerUnion.h | 1 - diff --git a/upstream_utils/llvm_patches/0002-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch b/upstream_utils/llvm_patches/0002-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch index 2632f58d90..b21e044ef1 100644 --- a/upstream_utils/llvm_patches/0002-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch +++ b/upstream_utils/llvm_patches/0002-Wrap-std-min-max-calls-in-parens-for-Windows-warning.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:12:41 -0400 -Subject: [PATCH 02/37] Wrap std::min/max calls in parens, for Windows warnings +Subject: [PATCH 02/36] Wrap std::min/max calls in parens, for Windows warnings --- llvm/include/llvm/ADT/DenseMap.h | 4 ++-- diff --git a/upstream_utils/llvm_patches/0003-Change-unique_function-storage-size.patch b/upstream_utils/llvm_patches/0003-Change-unique_function-storage-size.patch index 0b7955d834..22a98b4278 100644 --- a/upstream_utils/llvm_patches/0003-Change-unique_function-storage-size.patch +++ b/upstream_utils/llvm_patches/0003-Change-unique_function-storage-size.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:13:55 -0400 -Subject: [PATCH 03/37] Change unique_function storage size +Subject: [PATCH 03/36] Change unique_function storage size --- llvm/include/llvm/ADT/FunctionExtras.h | 4 ++-- diff --git a/upstream_utils/llvm_patches/0004-Threading-updates.patch b/upstream_utils/llvm_patches/0004-Threading-updates.patch index f4d05c5f7e..a1e88cebf6 100644 --- a/upstream_utils/llvm_patches/0004-Threading-updates.patch +++ b/upstream_utils/llvm_patches/0004-Threading-updates.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:17:19 -0400 -Subject: [PATCH 04/37] Threading updates +Subject: [PATCH 04/36] Threading updates - Remove guards for threads and exception - Prefer scope gaurd over lock gaurd diff --git a/upstream_utils/llvm_patches/0005-ifdef-guard-safety.patch b/upstream_utils/llvm_patches/0005-ifdef-guard-safety.patch index 4e0f30d925..6dcd4c91cc 100644 --- a/upstream_utils/llvm_patches/0005-ifdef-guard-safety.patch +++ b/upstream_utils/llvm_patches/0005-ifdef-guard-safety.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:28:13 -0400 -Subject: [PATCH 05/37] \#ifdef guard safety +Subject: [PATCH 05/36] \#ifdef guard safety Prevents redefinition if someone is pulling in real LLVM, since the macros are in global namespace --- diff --git a/upstream_utils/llvm_patches/0006-Explicitly-use-std.patch b/upstream_utils/llvm_patches/0006-Explicitly-use-std.patch index d9859e71e5..e2c81eca55 100644 --- a/upstream_utils/llvm_patches/0006-Explicitly-use-std.patch +++ b/upstream_utils/llvm_patches/0006-Explicitly-use-std.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:37:34 -0400 -Subject: [PATCH 06/37] Explicitly use std:: +Subject: [PATCH 06/36] Explicitly use std:: --- llvm/include/llvm/ADT/SmallSet.h | 2 +- diff --git a/upstream_utils/llvm_patches/0007-Remove-format_provider.patch b/upstream_utils/llvm_patches/0007-Remove-format_provider.patch index 8227e9e9f0..1cd071f60b 100644 --- a/upstream_utils/llvm_patches/0007-Remove-format_provider.patch +++ b/upstream_utils/llvm_patches/0007-Remove-format_provider.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sat, 7 May 2022 22:53:50 -0400 -Subject: [PATCH 07/37] Remove format_provider +Subject: [PATCH 07/36] Remove format_provider --- llvm/include/llvm/Support/Chrono.h | 114 ------------------------ diff --git a/upstream_utils/llvm_patches/0008-Add-compiler-warning-pragmas.patch b/upstream_utils/llvm_patches/0008-Add-compiler-warning-pragmas.patch index 6d8bcecd49..01a99ad652 100644 --- a/upstream_utils/llvm_patches/0008-Add-compiler-warning-pragmas.patch +++ b/upstream_utils/llvm_patches/0008-Add-compiler-warning-pragmas.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 13:34:07 -0400 -Subject: [PATCH 08/37] Add compiler warning pragmas +Subject: [PATCH 08/36] Add compiler warning pragmas --- llvm/include/llvm/ADT/FunctionExtras.h | 11 +++++++++++ diff --git a/upstream_utils/llvm_patches/0009-Remove-unused-functions.patch b/upstream_utils/llvm_patches/0009-Remove-unused-functions.patch index f174a5fd7b..20763b3641 100644 --- a/upstream_utils/llvm_patches/0009-Remove-unused-functions.patch +++ b/upstream_utils/llvm_patches/0009-Remove-unused-functions.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 13:43:50 -0400 -Subject: [PATCH 09/37] Remove unused functions +Subject: [PATCH 09/36] Remove unused functions --- llvm/include/llvm/ADT/SmallString.h | 77 ------ diff --git a/upstream_utils/llvm_patches/0010-Detemplatize-SmallVectorBase.patch b/upstream_utils/llvm_patches/0010-Detemplatize-SmallVectorBase.patch index 295e339caa..d784205b01 100644 --- a/upstream_utils/llvm_patches/0010-Detemplatize-SmallVectorBase.patch +++ b/upstream_utils/llvm_patches/0010-Detemplatize-SmallVectorBase.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Thu, 5 May 2022 23:18:34 -0400 -Subject: [PATCH 10/37] Detemplatize SmallVectorBase +Subject: [PATCH 10/36] Detemplatize SmallVectorBase --- llvm/include/llvm/ADT/SmallVector.h | 35 ++++++++++----------------- diff --git a/upstream_utils/llvm_patches/0011-Add-vectors-to-raw_ostream.patch b/upstream_utils/llvm_patches/0011-Add-vectors-to-raw_ostream.patch index 431c847e43..3bab41b93f 100644 --- a/upstream_utils/llvm_patches/0011-Add-vectors-to-raw_ostream.patch +++ b/upstream_utils/llvm_patches/0011-Add-vectors-to-raw_ostream.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 13:48:59 -0400 -Subject: [PATCH 11/37] Add vectors to raw_ostream +Subject: [PATCH 11/36] Add vectors to raw_ostream --- llvm/include/llvm/Support/raw_ostream.h | 115 ++++++++++++++++++++++++ diff --git a/upstream_utils/llvm_patches/0012-Extra-collections-features.patch b/upstream_utils/llvm_patches/0012-Extra-collections-features.patch index 2b34fbc768..557dc158de 100644 --- a/upstream_utils/llvm_patches/0012-Extra-collections-features.patch +++ b/upstream_utils/llvm_patches/0012-Extra-collections-features.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Tue, 3 May 2022 22:16:10 -0400 -Subject: [PATCH 12/37] Extra collections features +Subject: [PATCH 12/36] Extra collections features --- llvm/lib/Support/raw_ostream.cpp | 8 ++++++++ diff --git a/upstream_utils/llvm_patches/0014-Delete-numbers-from-MathExtras.patch b/upstream_utils/llvm_patches/0013-Delete-numbers-from-MathExtras.patch similarity index 98% rename from upstream_utils/llvm_patches/0014-Delete-numbers-from-MathExtras.patch rename to upstream_utils/llvm_patches/0013-Delete-numbers-from-MathExtras.patch index ca2d69fc00..8a8d53f272 100644 --- a/upstream_utils/llvm_patches/0014-Delete-numbers-from-MathExtras.patch +++ b/upstream_utils/llvm_patches/0013-Delete-numbers-from-MathExtras.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Thu, 5 May 2022 18:09:45 -0400 -Subject: [PATCH 14/37] Delete numbers from MathExtras +Subject: [PATCH 13/36] Delete numbers from MathExtras --- llvm/include/llvm/Support/MathExtras.h | 36 -------------------------- diff --git a/upstream_utils/llvm_patches/0013-EpochTracker-ABI-macro.patch b/upstream_utils/llvm_patches/0013-EpochTracker-ABI-macro.patch deleted file mode 100644 index 7f74ecd937..0000000000 --- a/upstream_utils/llvm_patches/0013-EpochTracker-ABI-macro.patch +++ /dev/null @@ -1,22 +0,0 @@ -From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 -From: PJ Reiniger -Date: Wed, 4 May 2022 00:01:00 -0400 -Subject: [PATCH 13/37] EpochTracker ABI macro - ---- - llvm/include/llvm/ADT/EpochTracker.h | 2 +- - 1 file changed, 1 insertion(+), 1 deletion(-) - -diff --git a/llvm/include/llvm/ADT/EpochTracker.h b/llvm/include/llvm/ADT/EpochTracker.h -index fc41d6f2c92d2f9876c741067b5645a74663db04..56d0acda2c1a0e390cfed086fa298b650c4a561f 100644 ---- a/llvm/include/llvm/ADT/EpochTracker.h -+++ b/llvm/include/llvm/ADT/EpochTracker.h -@@ -22,7 +22,7 @@ - - namespace llvm { - --#if LLVM_ENABLE_ABI_BREAKING_CHECKS -+#ifndef NDEBUG //ifndef LLVM_ENABLE_ABI_BREAKING_CHECKS - #define LLVM_DEBUGEPOCHBASE_HANDLEBASE_EMPTYBASE - - /// A base class for data structure classes wishing to make iterators diff --git a/upstream_utils/llvm_patches/0015-Add-lerp-and-sgn.patch b/upstream_utils/llvm_patches/0014-Add-lerp-and-sgn.patch similarity index 96% rename from upstream_utils/llvm_patches/0015-Add-lerp-and-sgn.patch rename to upstream_utils/llvm_patches/0014-Add-lerp-and-sgn.patch index 010525fcaa..95c7149057 100644 --- a/upstream_utils/llvm_patches/0015-Add-lerp-and-sgn.patch +++ b/upstream_utils/llvm_patches/0014-Add-lerp-and-sgn.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Tue, 3 May 2022 22:50:24 -0400 -Subject: [PATCH 15/37] Add lerp and sgn +Subject: [PATCH 14/36] Add lerp and sgn --- llvm/include/llvm/Support/MathExtras.h | 21 +++++++++++++++++++++ diff --git a/upstream_utils/llvm_patches/0016-Fixup-includes.patch b/upstream_utils/llvm_patches/0015-Fixup-includes.patch similarity index 99% rename from upstream_utils/llvm_patches/0016-Fixup-includes.patch rename to upstream_utils/llvm_patches/0015-Fixup-includes.patch index df4c50a7a0..3fd231c33f 100644 --- a/upstream_utils/llvm_patches/0016-Fixup-includes.patch +++ b/upstream_utils/llvm_patches/0015-Fixup-includes.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 16:38:11 -0400 -Subject: [PATCH 16/37] Fixup includes +Subject: [PATCH 15/36] Fixup includes --- llvm/include/llvm/Support/PointerLikeTypeTraits.h | 1 + diff --git a/upstream_utils/llvm_patches/0017-Use-std-is_trivially_copy_constructible.patch b/upstream_utils/llvm_patches/0016-Use-std-is_trivially_copy_constructible.patch similarity index 95% rename from upstream_utils/llvm_patches/0017-Use-std-is_trivially_copy_constructible.patch rename to upstream_utils/llvm_patches/0016-Use-std-is_trivially_copy_constructible.patch index 40adf0eab9..b7552f2b33 100644 --- a/upstream_utils/llvm_patches/0017-Use-std-is_trivially_copy_constructible.patch +++ b/upstream_utils/llvm_patches/0016-Use-std-is_trivially_copy_constructible.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 16:42:09 -0400 -Subject: [PATCH 17/37] Use std::is_trivially_copy_constructible +Subject: [PATCH 16/36] Use std::is_trivially_copy_constructible --- llvm/include/llvm/Support/type_traits.h | 16 ---------------- diff --git a/upstream_utils/llvm_patches/0018-Windows-support.patch b/upstream_utils/llvm_patches/0017-Windows-support.patch similarity index 99% rename from upstream_utils/llvm_patches/0018-Windows-support.patch rename to upstream_utils/llvm_patches/0017-Windows-support.patch index dc981328e1..4d041a5eb4 100644 --- a/upstream_utils/llvm_patches/0018-Windows-support.patch +++ b/upstream_utils/llvm_patches/0017-Windows-support.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Tue, 3 May 2022 20:22:38 -0400 -Subject: [PATCH 18/37] Windows support +Subject: [PATCH 17/36] Windows support --- .../llvm/Support/Windows/WindowsSupport.h | 45 +++++---- diff --git a/upstream_utils/llvm_patches/0019-Remove-call-to-RtlGetLastNtStatus.patch b/upstream_utils/llvm_patches/0018-Remove-call-to-RtlGetLastNtStatus.patch similarity index 97% rename from upstream_utils/llvm_patches/0019-Remove-call-to-RtlGetLastNtStatus.patch rename to upstream_utils/llvm_patches/0018-Remove-call-to-RtlGetLastNtStatus.patch index 2c32a57ed1..1b3b1eb448 100644 --- a/upstream_utils/llvm_patches/0019-Remove-call-to-RtlGetLastNtStatus.patch +++ b/upstream_utils/llvm_patches/0018-Remove-call-to-RtlGetLastNtStatus.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 17 Sep 2024 21:19:52 -0700 -Subject: [PATCH 19/37] Remove call to RtlGetLastNtStatus() +Subject: [PATCH 18/36] Remove call to RtlGetLastNtStatus() --- llvm/lib/Support/ErrorHandling.cpp | 23 ----------------------- diff --git a/upstream_utils/llvm_patches/0020-Prefer-fmtlib.patch b/upstream_utils/llvm_patches/0019-Prefer-fmtlib.patch similarity index 98% rename from upstream_utils/llvm_patches/0020-Prefer-fmtlib.patch rename to upstream_utils/llvm_patches/0019-Prefer-fmtlib.patch index 1d741d0685..a6ec743970 100644 --- a/upstream_utils/llvm_patches/0020-Prefer-fmtlib.patch +++ b/upstream_utils/llvm_patches/0019-Prefer-fmtlib.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 16:46:20 -0400 -Subject: [PATCH 20/37] Prefer fmtlib +Subject: [PATCH 19/36] Prefer fmtlib --- llvm/lib/Support/ErrorHandling.cpp | 20 ++++++-------------- diff --git a/upstream_utils/llvm_patches/0021-Prefer-wpi-s-fs.h.patch b/upstream_utils/llvm_patches/0020-Prefer-wpi-s-fs.h.patch similarity index 96% rename from upstream_utils/llvm_patches/0021-Prefer-wpi-s-fs.h.patch rename to upstream_utils/llvm_patches/0020-Prefer-wpi-s-fs.h.patch index 5967160f63..69576f03a5 100644 --- a/upstream_utils/llvm_patches/0021-Prefer-wpi-s-fs.h.patch +++ b/upstream_utils/llvm_patches/0020-Prefer-wpi-s-fs.h.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 16:49:36 -0400 -Subject: [PATCH 21/37] Prefer wpi's fs.h +Subject: [PATCH 20/36] Prefer wpi's fs.h --- llvm/include/llvm/Support/raw_ostream.h | 7 ++----- diff --git a/upstream_utils/llvm_patches/0022-Remove-unused-functions.patch b/upstream_utils/llvm_patches/0021-Remove-unused-functions.patch similarity index 99% rename from upstream_utils/llvm_patches/0022-Remove-unused-functions.patch rename to upstream_utils/llvm_patches/0021-Remove-unused-functions.patch index 2188642a17..e8b3b3a4c4 100644 --- a/upstream_utils/llvm_patches/0022-Remove-unused-functions.patch +++ b/upstream_utils/llvm_patches/0021-Remove-unused-functions.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 19:16:51 -0400 -Subject: [PATCH 22/37] Remove unused functions +Subject: [PATCH 21/36] Remove unused functions --- llvm/include/llvm/Support/raw_ostream.h | 5 +- diff --git a/upstream_utils/llvm_patches/0023-OS-specific-changes.patch b/upstream_utils/llvm_patches/0022-OS-specific-changes.patch similarity index 97% rename from upstream_utils/llvm_patches/0023-OS-specific-changes.patch rename to upstream_utils/llvm_patches/0022-OS-specific-changes.patch index b17df98e16..b08cf77b4a 100644 --- a/upstream_utils/llvm_patches/0023-OS-specific-changes.patch +++ b/upstream_utils/llvm_patches/0022-OS-specific-changes.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Sun, 8 May 2022 19:30:43 -0400 -Subject: [PATCH 23/37] OS-specific changes +Subject: [PATCH 22/36] OS-specific changes --- llvm/lib/Support/ErrorHandling.cpp | 16 +++++++--------- diff --git a/upstream_utils/llvm_patches/0024-Use-SmallVector-for-UTF-conversion.patch b/upstream_utils/llvm_patches/0023-Use-SmallVector-for-UTF-conversion.patch similarity index 99% rename from upstream_utils/llvm_patches/0024-Use-SmallVector-for-UTF-conversion.patch rename to upstream_utils/llvm_patches/0023-Use-SmallVector-for-UTF-conversion.patch index ea78ec5aa4..bb096a2b05 100644 --- a/upstream_utils/llvm_patches/0024-Use-SmallVector-for-UTF-conversion.patch +++ b/upstream_utils/llvm_patches/0023-Use-SmallVector-for-UTF-conversion.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Mon, 9 May 2022 00:04:30 -0400 -Subject: [PATCH 24/37] Use SmallVector for UTF conversion +Subject: [PATCH 23/36] Use SmallVector for UTF conversion --- llvm/include/llvm/Support/ConvertUTF.h | 6 +++--- diff --git a/upstream_utils/llvm_patches/0025-Prefer-to-use-static-pointers-in-raw_ostream.patch b/upstream_utils/llvm_patches/0024-Prefer-to-use-static-pointers-in-raw_ostream.patch similarity index 95% rename from upstream_utils/llvm_patches/0025-Prefer-to-use-static-pointers-in-raw_ostream.patch rename to upstream_utils/llvm_patches/0024-Prefer-to-use-static-pointers-in-raw_ostream.patch index d81f6a13d8..dd87e46a7b 100644 --- a/upstream_utils/llvm_patches/0025-Prefer-to-use-static-pointers-in-raw_ostream.patch +++ b/upstream_utils/llvm_patches/0024-Prefer-to-use-static-pointers-in-raw_ostream.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Thu, 19 May 2022 00:58:36 -0400 -Subject: [PATCH 25/37] Prefer to use static pointers in raw_ostream +Subject: [PATCH 24/36] Prefer to use static pointers in raw_ostream See #1401 --- diff --git a/upstream_utils/llvm_patches/0026-constexpr-endian-byte-swap.patch b/upstream_utils/llvm_patches/0025-constexpr-endian-byte-swap.patch similarity index 94% rename from upstream_utils/llvm_patches/0026-constexpr-endian-byte-swap.patch rename to upstream_utils/llvm_patches/0025-constexpr-endian-byte-swap.patch index 67ba72a8ca..ed8e269a9f 100644 --- a/upstream_utils/llvm_patches/0026-constexpr-endian-byte-swap.patch +++ b/upstream_utils/llvm_patches/0025-constexpr-endian-byte-swap.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Fri, 1 Mar 2024 11:56:17 -0800 -Subject: [PATCH 26/37] constexpr endian byte swap +Subject: [PATCH 25/36] constexpr endian byte swap --- llvm/include/llvm/Support/Endian.h | 4 +++- diff --git a/upstream_utils/llvm_patches/0027-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch b/upstream_utils/llvm_patches/0026-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch similarity index 97% rename from upstream_utils/llvm_patches/0027-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch rename to upstream_utils/llvm_patches/0026-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch index d64c7d19b8..28831db7bc 100644 --- a/upstream_utils/llvm_patches/0027-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch +++ b/upstream_utils/llvm_patches/0026-Copy-type-traits-from-STLExtras.h-into-PointerUnion..patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Wed, 10 Aug 2022 17:07:52 -0700 -Subject: [PATCH 27/37] Copy type traits from STLExtras.h into PointerUnion.h +Subject: [PATCH 26/36] Copy type traits from STLExtras.h into PointerUnion.h --- llvm/include/llvm/ADT/PointerUnion.h | 46 ++++++++++++++++++++++++++++ diff --git a/upstream_utils/llvm_patches/0028-Unused-variable-in-release-mode.patch b/upstream_utils/llvm_patches/0027-Unused-variable-in-release-mode.patch similarity index 94% rename from upstream_utils/llvm_patches/0028-Unused-variable-in-release-mode.patch rename to upstream_utils/llvm_patches/0027-Unused-variable-in-release-mode.patch index 9da7f8677f..8ad8af32c7 100644 --- a/upstream_utils/llvm_patches/0028-Unused-variable-in-release-mode.patch +++ b/upstream_utils/llvm_patches/0027-Unused-variable-in-release-mode.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Leander Schulten Date: Mon, 10 Jul 2023 00:53:43 +0200 -Subject: [PATCH 28/37] Unused variable in release mode +Subject: [PATCH 27/36] Unused variable in release mode --- llvm/include/llvm/ADT/DenseMap.h | 2 +- diff --git a/upstream_utils/llvm_patches/0029-Use-C-20-bit-header.patch b/upstream_utils/llvm_patches/0028-Use-C-20-bit-header.patch similarity index 99% rename from upstream_utils/llvm_patches/0029-Use-C-20-bit-header.patch rename to upstream_utils/llvm_patches/0028-Use-C-20-bit-header.patch index 87767d948e..770880b1db 100644 --- a/upstream_utils/llvm_patches/0029-Use-C-20-bit-header.patch +++ b/upstream_utils/llvm_patches/0028-Use-C-20-bit-header.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 11 Jul 2023 22:56:09 -0700 -Subject: [PATCH 29/37] Use C++20 header +Subject: [PATCH 28/36] Use C++20 header --- llvm/include/llvm/ADT/DenseMap.h | 3 +- diff --git a/upstream_utils/llvm_patches/0030-Remove-DenseMap-GTest-printer-test.patch b/upstream_utils/llvm_patches/0029-Remove-DenseMap-GTest-printer-test.patch similarity index 94% rename from upstream_utils/llvm_patches/0030-Remove-DenseMap-GTest-printer-test.patch rename to upstream_utils/llvm_patches/0029-Remove-DenseMap-GTest-printer-test.patch index c7d2302696..f66810259d 100644 --- a/upstream_utils/llvm_patches/0030-Remove-DenseMap-GTest-printer-test.patch +++ b/upstream_utils/llvm_patches/0029-Remove-DenseMap-GTest-printer-test.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sun, 30 Jul 2023 14:17:37 -0700 -Subject: [PATCH 30/37] Remove DenseMap GTest printer test +Subject: [PATCH 29/36] Remove DenseMap GTest printer test LLVM modifies internal GTest headers to support it, which we can't do. --- diff --git a/upstream_utils/llvm_patches/0031-raw_ostream-Add-SetNumBytesInBuffer.patch b/upstream_utils/llvm_patches/0030-raw_ostream-Add-SetNumBytesInBuffer.patch similarity index 93% rename from upstream_utils/llvm_patches/0031-raw_ostream-Add-SetNumBytesInBuffer.patch rename to upstream_utils/llvm_patches/0030-raw_ostream-Add-SetNumBytesInBuffer.patch index b2e14af00f..801bb60254 100644 --- a/upstream_utils/llvm_patches/0031-raw_ostream-Add-SetNumBytesInBuffer.patch +++ b/upstream_utils/llvm_patches/0030-raw_ostream-Add-SetNumBytesInBuffer.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Sun, 29 Oct 2023 23:00:08 -0700 -Subject: [PATCH 31/37] raw_ostream: Add SetNumBytesInBuffer +Subject: [PATCH 30/36] raw_ostream: Add SetNumBytesInBuffer --- llvm/include/llvm/Support/raw_ostream.h | 5 +++++ diff --git a/upstream_utils/llvm_patches/0032-raw_ostream-Replace-errnoAsErrorCode.patch b/upstream_utils/llvm_patches/0031-raw_ostream-Replace-errnoAsErrorCode.patch similarity index 94% rename from upstream_utils/llvm_patches/0032-raw_ostream-Replace-errnoAsErrorCode.patch rename to upstream_utils/llvm_patches/0031-raw_ostream-Replace-errnoAsErrorCode.patch index c0a79ca629..bb0ca0261a 100644 --- a/upstream_utils/llvm_patches/0032-raw_ostream-Replace-errnoAsErrorCode.patch +++ b/upstream_utils/llvm_patches/0031-raw_ostream-Replace-errnoAsErrorCode.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 17 Sep 2024 15:30:31 -0700 -Subject: [PATCH 32/37] raw_ostream: Replace errnoAsErrorCode() +Subject: [PATCH 31/36] raw_ostream: Replace errnoAsErrorCode() --- llvm/lib/Support/raw_ostream.cpp | 4 ++-- diff --git a/upstream_utils/llvm_patches/0033-type_traits.h-Add-is_constexpr.patch b/upstream_utils/llvm_patches/0032-type_traits.h-Add-is_constexpr.patch similarity index 94% rename from upstream_utils/llvm_patches/0033-type_traits.h-Add-is_constexpr.patch rename to upstream_utils/llvm_patches/0032-type_traits.h-Add-is_constexpr.patch index 51d178286f..5c5e3208b9 100644 --- a/upstream_utils/llvm_patches/0033-type_traits.h-Add-is_constexpr.patch +++ b/upstream_utils/llvm_patches/0032-type_traits.h-Add-is_constexpr.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Sat, 2 Dec 2023 15:21:32 -0800 -Subject: [PATCH 33/37] type_traits.h: Add is_constexpr() +Subject: [PATCH 32/36] type_traits.h: Add is_constexpr() --- llvm/include/llvm/Support/type_traits.h | 5 +++++ diff --git a/upstream_utils/llvm_patches/0034-Remove-auto-conversion-from-raw_ostream.patch b/upstream_utils/llvm_patches/0033-Remove-auto-conversion-from-raw_ostream.patch similarity index 95% rename from upstream_utils/llvm_patches/0034-Remove-auto-conversion-from-raw_ostream.patch rename to upstream_utils/llvm_patches/0033-Remove-auto-conversion-from-raw_ostream.patch index 571783f649..2a326fbfdc 100644 --- a/upstream_utils/llvm_patches/0034-Remove-auto-conversion-from-raw_ostream.patch +++ b/upstream_utils/llvm_patches/0033-Remove-auto-conversion-from-raw_ostream.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sun, 17 Mar 2024 14:51:11 -0700 -Subject: [PATCH 34/37] Remove auto-conversion from raw_ostream +Subject: [PATCH 33/36] Remove auto-conversion from raw_ostream --- llvm/lib/Support/raw_ostream.cpp | 11 +---------- diff --git a/upstream_utils/llvm_patches/0035-Add-SmallVector-erase_if.patch b/upstream_utils/llvm_patches/0034-Add-SmallVector-erase_if.patch similarity index 95% rename from upstream_utils/llvm_patches/0035-Add-SmallVector-erase_if.patch rename to upstream_utils/llvm_patches/0034-Add-SmallVector-erase_if.patch index 357fadc03e..8e7500976d 100644 --- a/upstream_utils/llvm_patches/0035-Add-SmallVector-erase_if.patch +++ b/upstream_utils/llvm_patches/0034-Add-SmallVector-erase_if.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Tue, 18 Jun 2024 09:07:33 -0700 -Subject: [PATCH 35/37] Add SmallVector erase_if() +Subject: [PATCH 34/36] Add SmallVector erase_if() --- llvm/include/llvm/ADT/SmallVector.h | 8 ++++++++ diff --git a/upstream_utils/llvm_patches/0036-Fix-AlignedCharArrayUnion-for-C-23.patch b/upstream_utils/llvm_patches/0035-Fix-AlignedCharArrayUnion-for-C-23.patch similarity index 96% rename from upstream_utils/llvm_patches/0036-Fix-AlignedCharArrayUnion-for-C-23.patch rename to upstream_utils/llvm_patches/0035-Fix-AlignedCharArrayUnion-for-C-23.patch index b71b47d0e8..7203296dba 100644 --- a/upstream_utils/llvm_patches/0036-Fix-AlignedCharArrayUnion-for-C-23.patch +++ b/upstream_utils/llvm_patches/0035-Fix-AlignedCharArrayUnion-for-C-23.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Sat, 13 Jul 2024 15:24:30 -0700 -Subject: [PATCH 36/37] Fix AlignedCharArrayUnion for C++23 +Subject: [PATCH 35/36] Fix AlignedCharArrayUnion for C++23 --- llvm/include/llvm/Support/AlignOf.h | 14 +++++--------- diff --git a/upstream_utils/llvm_patches/0037-Fix-minIntN-and-maxIntN-assertions.patch b/upstream_utils/llvm_patches/0036-Fix-minIntN-and-maxIntN-assertions.patch similarity index 95% rename from upstream_utils/llvm_patches/0037-Fix-minIntN-and-maxIntN-assertions.patch rename to upstream_utils/llvm_patches/0036-Fix-minIntN-and-maxIntN-assertions.patch index f9ca8d5035..f9a70c52d7 100644 --- a/upstream_utils/llvm_patches/0037-Fix-minIntN-and-maxIntN-assertions.patch +++ b/upstream_utils/llvm_patches/0036-Fix-minIntN-and-maxIntN-assertions.patch @@ -1,7 +1,7 @@ From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Mon, 23 Dec 2024 22:56:29 -0800 -Subject: [PATCH 37/37] Fix minIntN() and maxIntN() assertions +Subject: [PATCH 36/36] Fix minIntN() and maxIntN() assertions --- llvm/include/llvm/Support/MathExtras.h | 4 ++-- diff --git a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/EpochTracker.h b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/EpochTracker.h index 8cb122a7d5..037a70bf27 100644 --- a/wpiutil/src/main/native/thirdparty/llvm/include/wpi/EpochTracker.h +++ b/wpiutil/src/main/native/thirdparty/llvm/include/wpi/EpochTracker.h @@ -21,7 +21,7 @@ namespace wpi { -#ifndef NDEBUG //ifndef LLVM_ENABLE_ABI_BREAKING_CHECKS +#if LLVM_ENABLE_ABI_BREAKING_CHECKS #define LLVM_DEBUGEPOCHBASE_HANDLEBASE_EMPTYBASE /// A base class for data structure classes wishing to make iterators From b82d204525fa991db6f295634c8a324a2a7cdbe7 Mon Sep 17 00:00:00 2001 From: sciencewhiz Date: Tue, 6 Jan 2026 16:29:45 -0800 Subject: [PATCH 13/27] Update vendordep frcYear to 2026 (#8552) --- romiVendordep/RomiVendordep.json | 2 +- wpilibNewCommands/WPILibNewCommands.json | 2 +- xrpVendordep/XRPVendordep.json | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/romiVendordep/RomiVendordep.json b/romiVendordep/RomiVendordep.json index 90cdc120ea..c37414782c 100644 --- a/romiVendordep/RomiVendordep.json +++ b/romiVendordep/RomiVendordep.json @@ -3,7 +3,7 @@ "name": "Romi-Vendordep", "version": "1.0.0", "uuid": "1010372a-b446-46f4-b229-61e53a26a7dc", - "frcYear": "2026beta", + "frcYear": "2026", "mavenUrls": [], "jsonUrl": "", "javaDependencies": [ diff --git a/wpilibNewCommands/WPILibNewCommands.json b/wpilibNewCommands/WPILibNewCommands.json index 7ebc95424b..d90630e97e 100644 --- a/wpilibNewCommands/WPILibNewCommands.json +++ b/wpilibNewCommands/WPILibNewCommands.json @@ -3,7 +3,7 @@ "name": "WPILib-New-Commands", "version": "1.0.0", "uuid": "111e20f7-815e-48f8-9dd6-e675ce75b266", - "frcYear": "2026beta", + "frcYear": "2026", "mavenUrls": [], "jsonUrl": "", "javaDependencies": [ diff --git a/xrpVendordep/XRPVendordep.json b/xrpVendordep/XRPVendordep.json index 1498cac0ec..3febfb34ce 100644 --- a/xrpVendordep/XRPVendordep.json +++ b/xrpVendordep/XRPVendordep.json @@ -3,7 +3,7 @@ "name": "XRP-Vendordep", "version": "1.0.0", "uuid": "1571a1a5-ed3f-4f07-b7eb-b2beb17394e0", - "frcYear": "2026beta", + "frcYear": "2026", "mavenUrls": [], "jsonUrl": "", "javaDependencies": [ From 18249badc06cdabc238503b7c443cad6fdc1854e Mon Sep 17 00:00:00 2001 From: Kevin-OConnor Date: Mon, 12 Jan 2026 22:07:51 -0500 Subject: [PATCH 14/27] Add 2026 game specifics (#8558) Co-authored-by: Peter Johnson Co-authored-by: Gold856 <117957790+Gold856@users.noreply.github.com> --- .../wpi/first/apriltag/AprilTagFields.java | 8 +- .../main/native/cpp/AprilTagFieldLayout.cpp | 8 + .../include/frc/apriltag/AprilTagFields.h | 6 +- .../first/apriltag/2026-rebuilt-andymark.csv | 33 + .../first/apriltag/2026-rebuilt-andymark.json | 584 ++++++++++++++++++ .../first/apriltag/2026-rebuilt-welded.csv | 33 + .../first/apriltag/2026-rebuilt-welded.json | 584 ++++++++++++++++++ .../java/edu/wpi/first/fields/Fields.java | 5 +- fieldImages/src/main/native/cpp/fields.cpp | 2 + .../main/native/include/fields/2026-rebuilt.h | 12 + .../edu/wpi/first/fields/2026-field.png | Bin 0 -> 760228 bytes .../edu/wpi/first/fields/2026-rebuilt.json | 19 + glass/src/lib/native/cpp/other/Field2D.cpp | 2 +- 13 files changed, 1290 insertions(+), 6 deletions(-) create mode 100644 apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-andymark.csv create mode 100644 apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-andymark.json create mode 100644 apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-welded.csv create mode 100644 apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-welded.json create mode 100644 fieldImages/src/main/native/include/fields/2026-rebuilt.h create mode 100644 fieldImages/src/main/native/resources/edu/wpi/first/fields/2026-field.png create mode 100644 fieldImages/src/main/native/resources/edu/wpi/first/fields/2026-rebuilt.json diff --git a/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java b/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java index 2050ed3e08..883febb6c8 100644 --- a/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java +++ b/apriltag/src/main/java/edu/wpi/first/apriltag/AprilTagFields.java @@ -17,13 +17,17 @@ public enum AprilTagFields { /** 2025 Reefscape Welded (see TU 12). */ k2025ReefscapeWelded("2025-reefscape-welded.json"), /** 2025 Reefscape AndyMark (see TU 12). */ - k2025ReefscapeAndyMark("2025-reefscape-andymark.json"); + k2025ReefscapeAndyMark("2025-reefscape-andymark.json"), + /** 2026 Rebuilt Welded. */ + k2026RebuiltWelded("2026-rebuilt-welded.json"), + /** 2026 Rebuilt AndyMark. */ + k2026RebuiltAndymark("2026-rebuilt-andymark.json"); /** Base resource directory. */ public static final String kBaseResourceDir = "/edu/wpi/first/apriltag/"; /** Alias to the current game. */ - public static final AprilTagFields kDefaultField = k2025ReefscapeWelded; + public static final AprilTagFields kDefaultField = k2026RebuiltWelded; /** Resource filename. */ public final String m_resourceFile; diff --git a/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp b/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp index 8388210b25..6457729d4a 100644 --- a/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp +++ b/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp @@ -135,6 +135,8 @@ std::string_view GetResource_2023_chargedup_json(); std::string_view GetResource_2024_crescendo_json(); std::string_view GetResource_2025_reefscape_welded_json(); std::string_view GetResource_2025_reefscape_andymark_json(); +std::string_view GetResource_2026_rebuilt_welded_json(); +std::string_view GetResource_2026_rebuilt_andymark_json(); } // namespace frc @@ -156,6 +158,12 @@ AprilTagFieldLayout AprilTagFieldLayout::LoadField(AprilTagField field) { case AprilTagField::k2025ReefscapeAndyMark: fieldString = GetResource_2025_reefscape_andymark_json(); break; + case AprilTagField::k2026RebuiltWelded: + fieldString = GetResource_2026_rebuilt_welded_json(); + break; + case AprilTagField::k2026RebuiltAndyMark: + fieldString = GetResource_2026_rebuilt_andymark_json(); + break; case AprilTagField::kNumFields: throw std::invalid_argument("Invalid Field"); } diff --git a/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h b/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h index 2e1f5cc795..732d0279fd 100644 --- a/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h +++ b/apriltag/src/main/native/include/frc/apriltag/AprilTagFields.h @@ -24,8 +24,12 @@ enum class AprilTagField { k2025ReefscapeAndyMark, /// 2025 Reefscape Welded (see TU12). k2025ReefscapeWelded, + /// 2026 Rebuilt Andymark. + k2026RebuiltAndyMark, + /// 2026 Rebuilt Welded. + k2026RebuiltWelded, /// Alias to the current game. - kDefaultField = k2025ReefscapeWelded, + kDefaultField = k2026RebuiltWelded, // This is a placeholder for denoting the last supported field. This should // always be the last entry in the enum and should not be used by users diff --git a/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-andymark.csv b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-andymark.csv new file mode 100644 index 0000000000..da80d5fa95 --- /dev/null +++ b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-andymark.csv @@ -0,0 +1,33 @@ +ID,X,Y,Z,Z-Rotation,X-Rotation +1,467.085,291.791,35,180,0 +2,468.559,182.077,44.25,90,0 +3,444.797,172.321,44.25,180,0 +4,444.797,158.321,44.25,180,0 +5,468.559,134.565,44.25,270,0 +6,467.085,24.851,35,180,0 +7,470.034,24.851,35,0,0 +8,482.559,134.565,44.25,270,0 +9,492.329,144.321,44.25,0,0 +10,492.329,158.321,44.25,0,0 +11,482.559,182.077,44.25,90,0 +12,470.034,291.791,35,0,0 +13,649.58,291.02,21.75,180,0 +14,649.58,274.02,21.75,180,0 +15,649.566,169.783,21.75,180,0 +16,649.566,152.783,21.75,180,0 +17,183.034,24.851,35,0,0 +18,181.559,134.565,44.25,270,0 +19,205.321,144.321,44.25,0,0 +20,205.321,158.321,44.25,0,0 +21,181.559,182.077,44.25,90,0 +22,183.034,291.791,35,0,0 +23,180.085,291.791,35,180,0 +24,167.559,182.077,44.25,90,0 +25,157.79,172.321,44.25,180,0 +26,157.79,158.321,44.25,180,0 +27,167.559,134.565,44.25,270,0 +28,180.085,24.851,35,180,0 +29,0.539,25.621,21.75,0,0 +30,0.539,42.621,21.75,0,0 +31,0.553,146.858,21.75,0,0 +32,0.553,163.858,21.75,0,0 diff --git a/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-andymark.json b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-andymark.json new file mode 100644 index 0000000000..ecc03907da --- /dev/null +++ b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-andymark.json @@ -0,0 +1,584 @@ +{ + "tags": [ + { + "ID": 1, + "pose": { + "translation": { + "x": 11.863959, + "y": 7.411491399999999, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 2, + "pose": { + "translation": { + "x": 11.9013986, + "y": 4.6247558, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 3, + "pose": { + "translation": { + "x": 11.2978438, + "y": 4.3769534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 4, + "pose": { + "translation": { + "x": 11.2978438, + "y": 4.0213534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 5, + "pose": { + "translation": { + "x": 11.9013986, + "y": 3.417951, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 6, + "pose": { + "translation": { + "x": 11.863959, + "y": 0.6312154, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 7, + "pose": { + "translation": { + "x": 11.9388636, + "y": 0.6312154, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 8, + "pose": { + "translation": { + "x": 12.2569986, + "y": 3.417951, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 9, + "pose": { + "translation": { + "x": 12.5051566, + "y": 3.6657534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 10, + "pose": { + "translation": { + "x": 12.5051566, + "y": 4.0213534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 11, + "pose": { + "translation": { + "x": 12.2569986, + "y": 4.6247558, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 12, + "pose": { + "translation": { + "x": 11.9388636, + "y": 7.411491399999999, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 13, + "pose": { + "translation": { + "x": 16.499332, + "y": 7.391907999999999, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 14, + "pose": { + "translation": { + "x": 16.499332, + "y": 6.960107999999999, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 15, + "pose": { + "translation": { + "x": 16.4989764, + "y": 4.3124882, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 16, + "pose": { + "translation": { + "x": 16.4989764, + "y": 3.8806881999999994, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 17, + "pose": { + "translation": { + "x": 4.6490636, + "y": 0.6312154, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 18, + "pose": { + "translation": { + "x": 4.6115986, + "y": 3.417951, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 19, + "pose": { + "translation": { + "x": 5.2151534, + "y": 3.6657534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 20, + "pose": { + "translation": { + "x": 5.2151534, + "y": 4.0213534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 21, + "pose": { + "translation": { + "x": 4.6115986, + "y": 4.6247558, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 22, + "pose": { + "translation": { + "x": 4.6490636, + "y": 7.411491399999999, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 23, + "pose": { + "translation": { + "x": 4.574159, + "y": 7.411491399999999, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 24, + "pose": { + "translation": { + "x": 4.2559986, + "y": 4.6247558, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 25, + "pose": { + "translation": { + "x": 4.007866, + "y": 4.3769534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 26, + "pose": { + "translation": { + "x": 4.007866, + "y": 4.0213534, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 27, + "pose": { + "translation": { + "x": 4.2559986, + "y": 3.417951, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 28, + "pose": { + "translation": { + "x": 4.574159, + "y": 0.6312154, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 29, + "pose": { + "translation": { + "x": 0.0136906, + "y": 0.6507734, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 30, + "pose": { + "translation": { + "x": 0.0136906, + "y": 1.0825734, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 31, + "pose": { + "translation": { + "x": 0.0140462, + "y": 3.7301932, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 32, + "pose": { + "translation": { + "x": 0.0140462, + "y": 4.1619931999999995, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + } + ], + "field": { + "length": 16.518, + "width": 8.043 + } +} diff --git a/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-welded.csv b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-welded.csv new file mode 100644 index 0000000000..39f20f6bae --- /dev/null +++ b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-welded.csv @@ -0,0 +1,33 @@ +ID,X,Y,Z,Z-Rotation,X-Rotation +1,467.637,292.314,35,180,0 +2,469.111,182.6,44.25,90,0 +3,445.349,172.844,44.25,180,0 +4,445.349,158.844,44.25,180,0 +5,469.111,135.088,44.25,270,0 +6,467.637,25.374,35,180,0 +7,470.586,25.374,35,0,0 +8,483.111,135.088,44.25,270,0 +9,492.881,144.844,44.25,0,0 +10,492.881,158.844,44.25,0,0 +11,483.111,182.6,44.25,90,0 +12,470.586,292.314,35,0,0 +13,650.918,291.469,21.75,180,0 +14,650.918,274.469,21.75,180,0 +15,650.904,170.219,21.75,180,0 +16,650.904,153.219,21.75,180,0 +17,183.586,25.374,35,0,0 +18,182.111,135.088,44.25,270,0 +19,205.873,144.844,44.25,0,0 +20,205.873,158.844,44.25,0,0 +21,182.111,182.6,44.25,90,0 +22,183.586,292.314,35,0,0 +23,180.637,292.314,35,180,0 +24,168.111,182.6,44.25,90,0 +25,158.341,172.844,44.25,180,0 +26,158.341,158.844,44.25,180,0 +27,168.111,135.088,44.25,270,0 +28,180.637,25.374,35,180,0 +29,0.305,26.219,21.75,0,0 +30,0.305,43.219,21.75,0,0 +31,0.318,147.469,21.75,0,0 +32,0.318,164.469,21.75,0,0 diff --git a/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-welded.json b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-welded.json new file mode 100644 index 0000000000..8c5a52de87 --- /dev/null +++ b/apriltag/src/main/native/resources/edu/wpi/first/apriltag/2026-rebuilt-welded.json @@ -0,0 +1,584 @@ +{ + "tags": [ + { + "ID": 1, + "pose": { + "translation": { + "x": 11.8779798, + "y": 7.4247756, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 2, + "pose": { + "translation": { + "x": 11.9154194, + "y": 4.638039999999999, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 3, + "pose": { + "translation": { + "x": 11.3118646, + "y": 4.3902376, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 4, + "pose": { + "translation": { + "x": 11.3118646, + "y": 4.0346376, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 5, + "pose": { + "translation": { + "x": 11.9154194, + "y": 3.4312351999999997, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 6, + "pose": { + "translation": { + "x": 11.8779798, + "y": 0.6444996, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 7, + "pose": { + "translation": { + "x": 11.9528844, + "y": 0.6444996, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 8, + "pose": { + "translation": { + "x": 12.2710194, + "y": 3.4312351999999997, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 9, + "pose": { + "translation": { + "x": 12.519177399999998, + "y": 3.6790375999999996, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 10, + "pose": { + "translation": { + "x": 12.519177399999998, + "y": 4.0346376, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 11, + "pose": { + "translation": { + "x": 12.2710194, + "y": 4.638039999999999, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 12, + "pose": { + "translation": { + "x": 11.9528844, + "y": 7.4247756, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 13, + "pose": { + "translation": { + "x": 16.5333172, + "y": 7.4033126, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 14, + "pose": { + "translation": { + "x": 16.5333172, + "y": 6.9715126, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 15, + "pose": { + "translation": { + "x": 16.5329616, + "y": 4.3235626, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 16, + "pose": { + "translation": { + "x": 16.5329616, + "y": 3.8917626, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 17, + "pose": { + "translation": { + "x": 4.6630844, + "y": 0.6444996, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 18, + "pose": { + "translation": { + "x": 4.6256194, + "y": 3.4312351999999997, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 19, + "pose": { + "translation": { + "x": 5.229174199999999, + "y": 3.6790375999999996, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 20, + "pose": { + "translation": { + "x": 5.229174199999999, + "y": 4.0346376, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 21, + "pose": { + "translation": { + "x": 4.6256194, + "y": 4.638039999999999, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 22, + "pose": { + "translation": { + "x": 4.6630844, + "y": 7.4247756, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 23, + "pose": { + "translation": { + "x": 4.5881798, + "y": 7.4247756, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 24, + "pose": { + "translation": { + "x": 4.2700194, + "y": 4.638039999999999, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 0.7071067811865476, + "X": 0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 25, + "pose": { + "translation": { + "x": 4.0218614, + "y": 4.3902376, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 26, + "pose": { + "translation": { + "x": 4.0218614, + "y": 4.0346376, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 27, + "pose": { + "translation": { + "x": 4.2700194, + "y": 3.4312351999999997, + "z": 1.12395 + }, + "rotation": { + "quaternion": { + "W": -0.7071067811865475, + "X": -0.0, + "Y": 0.0, + "Z": 0.7071067811865476 + } + } + } + }, + { + "ID": 28, + "pose": { + "translation": { + "x": 4.5881798, + "y": 0.6444996, + "z": 0.889 + }, + "rotation": { + "quaternion": { + "W": 6.123233995736766e-17, + "X": 0.0, + "Y": 0.0, + "Z": 1.0 + } + } + } + }, + { + "ID": 29, + "pose": { + "translation": { + "x": 0.0077469999999999995, + "y": 0.6659626, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 30, + "pose": { + "translation": { + "x": 0.0077469999999999995, + "y": 1.0977626, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 31, + "pose": { + "translation": { + "x": 0.0080772, + "y": 3.7457125999999996, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + }, + { + "ID": 32, + "pose": { + "translation": { + "x": 0.0080772, + "y": 4.1775126, + "z": 0.55245 + }, + "rotation": { + "quaternion": { + "W": 1.0, + "X": 0.0, + "Y": 0.0, + "Z": 0.0 + } + } + } + } + ], + "field": { + "length": 16.541, + "width": 8.069 + } +} diff --git a/fieldImages/src/main/java/edu/wpi/first/fields/Fields.java b/fieldImages/src/main/java/edu/wpi/first/fields/Fields.java index 942af5f2fb..8b13e78898 100644 --- a/fieldImages/src/main/java/edu/wpi/first/fields/Fields.java +++ b/fieldImages/src/main/java/edu/wpi/first/fields/Fields.java @@ -17,12 +17,13 @@ public enum Fields { k2022RapidReact("2022-rapidreact.json"), k2023ChargedUp("2023-chargedup.json"), k2024Crescendo("2024-crescendo.json"), - k2025Reefscape("2025-reefscape.json"); + k2025Reefscape("2025-reefscape.json"), + k2026Rebuilt("2026-rebuilt.json"); public static final String kBaseResourceDir = "/edu/wpi/first/fields/"; /** Alias to the current game. */ - public static final Fields kDefaultField = k2025Reefscape; + public static final Fields kDefaultField = k2026Rebuilt; public final String m_resourceFile; diff --git a/fieldImages/src/main/native/cpp/fields.cpp b/fieldImages/src/main/native/cpp/fields.cpp index 06e5f8ed40..b4e165cc33 100644 --- a/fieldImages/src/main/native/cpp/fields.cpp +++ b/fieldImages/src/main/native/cpp/fields.cpp @@ -17,10 +17,12 @@ #include "fields/2023-chargedup.h" #include "fields/2024-crescendo.h" #include "fields/2025-reefscape.h" +#include "fields/2026-rebuilt.h" using namespace fields; static const Field kFields[] = { + {"2026 Rebuilt", GetResource_2026_rebuilt_json, GetResource_2026_field_png}, {"2025 Reefscape", GetResource_2025_reefscape_json, GetResource_2025_field_png}, {"2024 Crescendo", GetResource_2024_crescendo_json, diff --git a/fieldImages/src/main/native/include/fields/2026-rebuilt.h b/fieldImages/src/main/native/include/fields/2026-rebuilt.h new file mode 100644 index 0000000000..acdc881001 --- /dev/null +++ b/fieldImages/src/main/native/include/fields/2026-rebuilt.h @@ -0,0 +1,12 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include + +namespace fields { +std::string_view GetResource_2026_rebuilt_json(); +std::string_view GetResource_2026_field_png(); +} // namespace fields diff --git a/fieldImages/src/main/native/resources/edu/wpi/first/fields/2026-field.png b/fieldImages/src/main/native/resources/edu/wpi/first/fields/2026-field.png new file mode 100644 index 0000000000000000000000000000000000000000..b4f0295e8eea5039ba8b35ba2d313c74d9e4b320 GIT binary patch literal 760228 zcmbTd1z1#Jw>CU9ND9)eQqtWaAt*>lBhn1gAf1B}DvfkYOP7QQ4AKficlUsF=di!c z`=0ZC?|c4puIs)9!}Y>9P@W15gw3fzA#LF@cwmFjrlJlrlfxv zKuA>ob@brhPyYX&Gsxgh#{c<}<3jt-f5G?vps$7A-RA$hm_YZq!ku#U#&*8NG|EnN3M$9s%dXweP2*)`Rq$}%Al=&4$*wU6(=t; z#`H>BcewY-`7QaR>jp#pY8Fl_V?H6q%?<22hAro}l>i-4z~Z8Vh|%`E)44AzwwzJg)`rnO%h=r+OrhFPrC`;4qTG>V_hX;MDCV z(zm7KFJzUptoRU+ud};>T7rufw}sPYeBR^z^YH@rAjhvu$NxU2#QgPE$cQI-c2_TV z$6bQM4I*a;t)1R^JhpvmJejFpRGG$M%POp$iUIke%2A&x@a6P6VDNZiTXldbI^{7#I{sUiKQ+EFqcVU(m> zIhn`|ae*(gBN|FP6;z1xqBIa?vnk@ZjSpD$LX7QA{66~uyU*liqot5I5K+ZC>g-GdPP zFy<+4NNwG>5lEeMfcmH71vv}08VasYx@Oqbm4M2{rs_`!fhcO7e7t*bte@J&WEKIz z40J`zD#QcT_vo1KF)cK($|w5qrx*BtFz>aDrQidMas*5KNHyfnp|_6ianjUl|J$eH zAxkZ=>9kl%h-dX29Q1Iy!q{m(syo~=L_l(<(<9p?M!9Izg?)DCjZgkG8zm^O^Q@nS z=8#lRfOJ(wH@)z(x&H)D{EQ7!Q?V`avL+$barO%o@}h|?=5uACtiqHC0iVp5;=G8-Ahpj>a@$BDt0r*9^Me=$`c1hLTMCOwWX z=Zw-h5sFq)3`ICg?;uPRVY(LY8jX1#zM4GU^#m_!^KHpeFZyu>M0Ck3*3Xu6;6mha ztNZ&?pdHIDLNu9!HrgZ*IwBloMxDqcl0(r-Bwbp$9dcu{Ph>oO-7XfLZGUdU6!sFz zH{-|>< zBqcM`!{4EaPM;?^Jw2V4n)=X5Sral8xJa{Zo(5%&cSTouO#0huq=svM(dH3;P;^Ub zo_}O?bVYf&V`E04)n?b~VQZ^Q0Y8C)2R39OVTe5@H8qvOt&BksiA45vcT25CRMs4z zeNue5n#Y zMA8$_DEVtkA$%`u4Y=xM0Iz+h&XdH^(NUczO8qyS5D5ESoc!^{;*#%8QYjoROB1zm zd>IjekIH5-H8rg>ijwx(#ja{Gs3R>FO#fn}#6=+~E4#R`kd$2<=s^(V922IbS4-X} zEG5N-AE{dK#UXbjqO7vA(!t7^GYD_uKy)F6+A3|jo_p(EK)@Sc3oK{1Hz%BZL8wh8oHAH|6BySPA&JxyApsI(b;y*{?pp z4|&TVSgyCWJdv14zNOk}QEf{5Y(^9TS^60l#y@&ew1|jJG325kCMG@&c+SYknAw{G z2Cf86Wl$c{Ks>q|Y2Ycw zp>_7#uyT^HjlW>P<<+iaF-bPp{+cz^G&-Q#U~Yb1*aNM%uV3A;tr1PEwRT`TFp7w~ za8*E?aP=<)3?Nk_J8TG>dY7r)vATf}VQ`-s0gg9bAbPNW~+C?FeqM9x!a(MTO4@CPpM--P_ z;;TP+tUXZNPsbH;Fmi#HZ!|#NR7Ya4FqK`EqF@l0e?wzSW5jp5yGHZmNAsTxnr@DQ z<-c7JvWYkvAHeD%erzB|L6^m_#>kODCxQ+VRACw`o(>kG2dKVub zA6M7m47#>SH8MfS(48C747I+PB$M65s@fMygpBpmI$c_CVBg)1Oehmv)4xICyH9A6 zxj+2soT(~u9$^xFJV$HO_xw?J93A3B7^;(cSe??fK+ry=6{(0qRERU#%fFU^Lc(km_2Qe z=*f8z=4QO0(TlBVWPzbl8_hwPTL{t~3!Ehg1qAfm%0f2(4Wxgq#e^IfJ*ga|Qz<%< zFm7cjNWkexWj$oYjC@{uabr>awh%+5#Gh?o=*aBGn5Q5?5aD0O!$evzQ3in&+CbkP zV|Ge^@BMG*rF;K3=Shtkk$Zgas~46{YWWFvTS*vv#-F4MbS6xb9Rx86yppE8o}J%I zXJA5f%i5loNiZSK=<)P;V=c{*@GKs(Am_|q7ocXhng6TM?*u8woy6pEWrUUUuapfQHaE$XeV9)cX@yjQsZk`1R`O{oMnD~>)MuGGrWm}#1d|agl4KUo} zRWk3}_e)`?$jwPd5L*R&Kr~MZG4+Hcrv|)QuWs6rdvgsG$6F%6o!uGz|9dS}VM0ha zDLRd~mWy(XxO@ose)5np|B*mcWjH`;OU|jEsIHq{t3?QYzc32g3jJZIUjB|quR^+y zvu#Zhs(=;Q;m@^~p85stcn%n>&%A#P)T#)|X?&KVIusU+MtcH2zCZvd9~k=YHcc3u zFw!_cx-KkhI+pxLKd5+nO-X#Ses&kA*}l1H=1@zA1`&xL(qyY;rueNBl&jTVkOocO zvyJaM{A9F)!@F+q!uA=808Mx5dL-*th4!sZq23FQN(nY&TXceaLu063H9-8WE9(`_ z+e>mksxwP_H8Z_y0AttSqu1KP!5qOqZTkO8|Lo-6@t5E1hLQniY~!R zpHYX}X$Smt`Bdn&GGSYO>43Mv!=mY46if@d-@K>Han{&Cnnw_abZ5HG#!U@!{d6!8 z5qVraJ@5x|Nztv0MRe!+|L^Ngfd@{X@uJM1B-FjG&wS8aCqY8UR~%>SdB(1n8=hFO z;s;?(EsEMBJ!`fr;%ozh^?OdC*Hk@+I3Y~B1gj42b6NdvylB+$j)aR5J2P@zW4jE0vHg& zkYhQsWGs7^_QP9teO|OQC0v+L6q27Rnpv_45Eu1e%B5ZI1YACVE@FVQq08ZH+BcvQkqG4GdIRVYA7^4wrW5%bW5xP$jjo!R@!#6?jQjohp@W+iM9~-fp)&6e|iU>(b z$3&ll*g-?reDlvqHva++gTr|v) z>{vlnc7i|mMxk~ID040v8tX0htJT#!tH#m(l0N6M@GA;A6))K5kL5p!h>7b&(lawN zv$IV_+?8hgD=T^T3B~K>Ex}BW{Wrzq^ZW%g#4Ab&q|G#p%FfJ8?&o1#T->i;Pe0>9 zE|O9>;HDYU<(tMbF}NMk^_@5&jdiQM-L{XehQm6$I8S zocUnHa>rTtdCw*)A|fJ)no1_kEcD8S|@C4bVtgK8b4KZ6>HJYEFUl{>KJ2l1rkjDDA)vFjal@o~Bh12?zY21Gx!HhOhuclY@TL@q~@qyt1vq{&H1N$(nM&FfoQ z0^Hm>lChUe&lb=PVpjiLGemG#h3Y+472wF`uW#lL`{jCp;RmN|?>F2aY$k!S^IBHf z4c9>h2S9 z_f1XakPMa(&E}}?cg7kEhqNN|Ab@pYy4Xb*_lxu*=`}~Hdw;AV1 zn})LNSh!4KQN!qkTe0nxZXn|26`Wh)6`kRr#C91k?6Pl>{c>iq^(@+}8N=>17xCvf zJher1l<5^LENO;uvMTio=AUF*c>3WMX3VMHw$Djd7Jb^f=TV9Oj=+DN)AYyRlG2hQ zI_HpPf+M!qQSrCgzed(${dR|e0$|q2Faz7gm%o5IgGJ`>v&Pq$OT?E!*zK`)p<4BI z$-P3CH3QbsxN@^p?(j|<6fjm6`%^7 z_fb?x;|4_HncN;FEAZzzg~4`XA8P7^YRhmz#_6&Qj?%5i(z<4Bo9HWxO#xHqBqm^*(3B}6VDXNXjEKqAVUefcTWPr3UnU^TpJp;?_X>WqP0qn3ROCYjR?t}-#8<=vg@+%dAV*-9nP*wz3Y&f z{5E`OSd{5Gv-B(Yeq6z~AZl&`1Vi?RN8eRw7KxN2O;ZcI(~r__)85kY+eIDTOtEHe zJKv|f+$u{HlaUi1gFVj1v~Np{qUm`Q_?gnOPXRVvzi-j|U2s6m5;>4bUnJM6m1Zv6 zDx5XZ$jXvcnt9YPaH*P{7h>g&ufQX|=k%Mx!G7#%Y+yd#72K5O+xyDa6CZ};JqJO9w9m`9d9(ew3=v@tHYK_grg)=Wv^o&(1!d8e=~ zAlkn+JI5qzNriX@)X^Tz4XSGcWg6)hJU3k*fBhoy?~H|RoxvC!5^kOQ6qF-I15t~n zwN2i)F()vb+pI$7Mb?*T-_1M1qP>uF1P1*pPOR!h`QdQCjAv)CY2aAp-8AsK_M+qP zuOXrVxDJmZu>joziTo!|ED`m6lD&nN^v~(RB=T}X{PnKq6?f;TSf3|DhgM=6-#)(c zHVO`_55VBGIkm_hLh=_XpI~0&?8{-JRZA<1rh%R{rz~tlG+ciM0GMDMdl6B3V}OdDuF`XKOj4rJhq+SsIy}2qSiGQ-f1`tM%UJ8X^ppI zX%%X&c)vWnI!bWNHO9ewKn!)g`bAt$xLs@k(j2%Ot;_Z9dnCse>I*kLG5~dS4{zsZ zkABst8(iU8*J~9j$t?aL&6yhOK5+GnffvikEj!j1$%P8x0(;ug^kObSwyYXiksou) z`jU=0PCxz7xi-dn5AozU?P02(q__KUoBb39>RUn>UB^V@Ope0GB<|PsuB+Y33_fd) z&VI95(tZ;8jFL{wYLXR^beq=ROHWit&X&CgWaM-qWI-j5ZWzRLk#FJkKd0@PQ& zx45to;Hf>=vS%e3ynBS;9o~HZc&R?GVGZVd|NTeLG`Dh>{>DOc(tmR@MY0E;stVHn zr?-P=>c_s>G;7zacUf-NhhL4KXh!ViHO#_MxWa*c zpY%x8JEnV_=34fOH){&%`rN4$wHRww?-Z6`fax%ttF-B05^y?h*&X@b2mXXMF6dQq zL#d}An_3E=!xY~%P|JJ`KLPAKI)3*Y^lX1LytjTB9lkRJ(CW-s66?yb-Gq2OkRKqG z2VLY_xgd>_k`#lRAq8UdDoh3V@dlzp-5kARC0;}3HyXL;(($7Z5+MyUl5t`u!&0u3R_wL5BBPkKG15#ki)#L7A~9ZoUT zOov52wGhANM$5YYtlI<_TLh<}B;%X$G{s1jB9+4L#6Ta0I ztCC_v(AB>ui2m51*_(fznae@vIE3UOFh}sj)@#mHnQzrH^4-P3@)U;}NgSrk&A1b5 zw_L<~Wn5+^mvG#$Me;kTe0O{KS?r80dhC;s*;0({vVT~w1jHJp^3=Nu-SYN_i+8T% z;*192qTX#9b4@}3Z{bO&>Vfib@6zcuhx6z2l4SjX>yB!XqHD&YY(G=8!?vjf5`E|1~2`^g@jG+V$kHI6?*PSYP(D#v}E z^t`a>D!bzJ5S&BDc*3byw!~pJ_Dw5H$Ugp-7qtjDWO;b2jGn-H1SPNfxJQ9U_$k#< zllvABOCs!GN}c}pULH>->}>B9yo)t`(CofYKCczo1ezm&vW;zkCv_>-jL3G*2#f); z1$t#Uy21??HK6R-b5-7t!m;w5-#|4}IT zFncs2&k5>x0-Beash@|F!>&-4@7RkwxN}uvit-SAKa5ahj31S+#i0$uo-bpx>lJ~RwG?vzheUI1ag*LPKY#TP z->JSEgZURwJ)ADp$he@*s^Og?SNH2>mP}JSEqzofg?&z7KOe6(0DcoCHQTKy>(S$( zO2Be^Qa{Q~`vg$e7I%;QWA!H%T{-0gXWWc)4=Su5_kKolikLDH}EZmq*cPb}!##=`@wKrUPNr(OIan-Aqp$L*9qePF<|B~r0xE)PykW0p zBAx$&*eGogVWmO#fwOT@AuTi@5?7Aj{=+c%AtzQVqm{R;YF3*n0%fFEDch5k%Di>u z^J-Un?dqSNPo?FvD|RRg1~*yr`JTL0Ym)QjI#7xUIFY!|g%^x2wx{0@O5q>U;L-^2 zJ@?!>?uGbtUghQS2fVrFNI31#DzT)OLGW=}MR2VjhMvYVh!=C*Mx(C{fu zDPS{-_qrG$d$hoIoo>z+H-zY9=RG5wci0@tNr1j70j{(E00dDZ0LnGZ{w)_#Kyl_3 z98^R&Ubxj+LK_|+y9;d(i8hrsiai0*j5VO4d$GF8oYz)Gg?gX5l^+ zV(p9A1M9;%f=>c6i6=1pyLFw9@(T-7@;h1IfzW?x4$1FbM=;GM5?iYz4ZZVz9&2GqPmA6olTKq<5_+N3q$dN0p7+v z1p6+ExXMq`r1SBksjP|_Fn@n=L-=xhP6;ahlrG)!M}DckC7d{-pEX^ z0T6FwkzjE2Z0KD0$m)!qe0Y3g{ap8hw8@boo^g7(m4xCnK2dxmy(Go^s9>Q@Ys}eD zQ`Q5OP?r$LaFPVeYMC=dEQ0rAWY$a!Z>h!KJhP(O>)PhuG=iLYp+WSm+Z?G`;BG8&> zJ-H8_9&TZ;6&pn>IYf||#I8#n_gBJbo!UZ%b1@ZsfomAB?{k0OXV9<2K0WXt zm{DpghFeBwIhci!-3RvDPj%tVQ8Xzg4evj!`oI3^Ro~E6{>Qg^}x0 zv-9KZ2a@3M`1g0N;J{{P`_OL_Vh4NO(AOzTes#@kW<*I?oCaptvwm6)0qHT1XTfxFm4Z(xTG;5>rE2Syz@>E~#uo6! zfkdxb3->4rE@E2v9JH(l5d}K{krluw;$U$9eK2=5fRDrdJxo0IHk%P9D#&9r?*uU3 zUuHyvv^jh4#$!*Zp-eB0Et|&|5sz!YBpnR9LKB5FrB;wy8}UI3$;UFJgOls7%uNx@ zp(N7XagUTsj;_jT2byk<`drsGhx2H`8`W6-9xK-7{jo->HWra71SUWXemnd-aFA-~ zfa`{evEGgc4|ltqq&cQ%X2Fl}emEC3EXFCX)HXU7m3ggq&XuB~AESH>Mh>(zE6ld| z2BKmt?WJ;18E50(Sjse#J!Pv^JMP9fGrAVks}tVx3=PMaGYiWdAGfDN?I($LW`)r; zJa(q|zf~#8$~|Nz#J$AcK%_T-iDYj3H?2IA%Rl;I{?CeM!H^K`z6SGv^(Ao&Li@e1 zwu(>`Zu-*URG{s`2!(M|6;kPtYyZq|DAh<+#GU3Ef5)>q&o_~;G^LSF`<;&K$1q5z z=~vksXE=Ml%n);ZctyowD%C0((|IjyW#pgXfl#+KotEia3@5+;?BzK;6s5CO@UUXb zlV%}#aUFb$-)7ibTs9Q9x@2I4uj$@j@k9HmjB%3J6Jrv`65fbJ>(M6Ocm9PFF}fN> zL@&{~Y_cPJu@p@IVRNT;FiYHx)#Rq_J%)zVA*KNG4`*d3N26-*YbV#M65Y~z=f%JU zALPqy8Tys>fn)bKy@Nxf@K*B%uI55+>5n2@RI+nF z`m^i$-c9RE3Jkr`>QE{jAP3Cz}^vO;Hy3N zbeY&|y4goCg3k18ofjs~6T0m%^W7G8b*cjUg+-|;pxM)5IJMw5C_UA>W6i5T{2@2% z{B*mtZq!BRr{5{yTO%46Hlx7+|B2$>@p~%$?8m*=COwr6$Vp%|Kwsh1O(3AU*F^36tg3_=4d(daHpZz?TkvVxOjA-1O>pzN>uTDW+l+gYFp&Zi0XX*HN(CE1DW)x`wHv7|$NgHEEr}AkVSfTC`-$X)}auNju+od*kLR zGX{Kr#P}hA7LPCOhtqu15F#W$yw32(Z!zFJ$EEe8fR}KkLi`N&N#NVpH|0Rjmyb#V z^+3^N4UOI-qmG+;KBJC>qof9=h#PLR_+21s99SJzD;#tN*kUcIUMo)XRp5zJTm|PO zW`L#cehd0Q)0DUO_o&q9TyObAKae}!TpZFVzWsp8o>yC#Od*%+V^bDnPT~*4*Co6B zVL!>E;@A47mrTVk|4`QDCh^e2jOFWwn%yjb3U~&`8gw(gmbj%!UhouK>>Bz*5Y;Ef ziA~BernmF;yPHt_>$mh59PYt@^jl1VL#@qV z*cU?`Ipxz4RbIl;?gLIwzC!}inzZ=daI?JEApQ4U(qMc*>R8RVnfVOX@VEQ&@m7X`T$|YqFh`39EI?KW^pMS@*}uZti}y z!IH+Sr=1crI}269m?yAly)2^dvD16a|3b{_dZERyHZfaqh_m}3jQN$BK(Ik@&FdD* zPdG0xw|^kBenJs6tA#2-7I?cqzV$&8t#s%n9;v*UdSE8qnTNe9?|;uqQihWek0aO_ z@2{Ei3L5!L$BP?QDO$CMvd9cKg9yT4eR2`E8;%+CV;lF=yxM-Yo?o|*pX@7n^O~tx zI`QwL&Cta7t>wfqEGSduL~_#bIk`_;Cm)*jS2qH;*VT;1>8xrgkZsx-d#b#Sc~=yO zKJZZ^9NL9t2G!^y0+B+UZV%0El#7X!XdIxn-E;otEXbSA}g!|d@ zK0CHjm1X!{w(S1%mbfc&w~?_(lJS(MmvQq=ePeJ8MIja~s}d3Jdw1Kg+P_->6HK(W z`U-|&T?r@Zo>z-3R^}l~%^unh`|I7#Iy~jXIuI%($b-fGpy@4Fw4I6|tC=i|o9HMu z4_%hIN1;R0iM`ZL?~*NZr>3hs4h~kgDM6a^phN2|tSaAjgrG&myH{a^2G7M+MbLq} zi;L74j4zRwx{yT=*-XDRz$X{T4)16-MB8zU>p z?*dWqu6ecAGI%<*DahnkTy^mV#*HA>Dy#J-m5q&VyU|?8nZZlGFKrW`ga%g6NJeDCv*hJA?>`4!DCd|t(B<^*zRyXo2`S%&* zTV_AIN1tj+n|EMLo{SXR^49#J_j`jHej7dwh;^b~Po4eb!&@aPL`Zl9+RFqohYqD7 z$DW9`Y8>r%S{D3PF`doynZ-k{_*k@w=#J9Z3a*tId8u1hvc7Rs@}h!5q7IJNvV!6* z>A%}eHGsisM1RZwVhplKRbQOP$gl$=oj}|M3NaJU61u`Aay2Q;Y8#fkFz?y$|In^*ep<-v0nOOF=Pd z^@;=!=DvZ z=VBAzd$T)6M8h+B64+z+PFF#?c`4>x=AvqRJ-DihxI_frSiLJeCW|%n=WF_5ktVdt zgrtvP(6L4h`26^m&fP}&n<)X^Bqs$oCHLG(Jsk#H4W6ULJJ zE@B-n@ob3XF|7h5u-Lk?bp@{OKj*_685}Z9qQ@Tzl`oNG@wqa5-Qd(UvmuTTnP6=D zaOo{FXh(kQ(Qs6m8%CRRzenC`x<-P_Iwq$(;oYY=y~uLd`On2&Dnx#fVuq#4;168` z;}38VWqqL+5jH}#GYG|2*UtnMno-PtmqgEj{d*yHbO|IU{88%cY{pthq=qhHaVQ~o z6`^ofi#iO~Z(b3F9gAKIii~SJqB3pFMEM3JkGO1*WVRV4+}bofg6>JinN~e+6MTD* zH%eUT2Uo0JTlpK_^oh=jJ1?>amL>N*!zmyKz*flWlp4GaP^Qf#0c<%pZmGfr-JD*W$OV}|Mz-0Q)RYE z@J`LS7YzIX&S9nme2ced4K|20a%73=t4lW7OY6M(y|uyJeSf56zvFePmP|Fa(8R+I z7ae1Zjt7MAezPQV8GYYuJ|0k58G6*ERMoodG5LlPDR(OI=vicnl+U|3qCTI6-*TRr z>-UY2Fr-&tk=@siMWY{OPI5Ra8XqQMdt+P5wv?MMbdwe@n0=oAGxqjr?zYX4jWLZw zlg!4L?P}esSq_nj==VvSyQ&5wYE!wnm9bF}HOz>*|Ex+r^{M@AwbC#l8RZ4V2tZo_ z{IoL4=ad0Kv+31Hvi$w^#^Gf6jrAv|*BZ}0TU_Q~kKo_&Cf6omVQK`sO$-AW)vpae zBuKw&bF7ilcIbNr4*)k17^w`z^u1~x+_ucWsh@S?e9{cUEG6escvdFA^^-yO;|F-L zJmjcF9#onq$B})&^a)Hd3f3N;sb4+`R;S2j4bxmo*fA+t*>u;({T7Zv`s%Olvay0w zzVZMV6ef3o&Y^IS=)B!;0Q4Q{-H-#Q6-qc27XzADK){|`wt~&5H|cB9_}fK))S}a= zfqc8eq#5CA<|x{VR{C{6tjk+Oh~L5E$8+03PFq`Jf@?E3YT(T1P2mDa5w$>boH+R^%#g$WZ;3d>3~K(S z-Y?7|@JGBD*&Z_dZuU8LaKvoBp5JHK47L7T+oFz{8q^TYDV%TUPH*2H{%9lqJOD+; zan!fq%iRipcK!OEgzC^!^qwCvrsB9C9ec2D81GMZ2IpXQ6OqzA>Avq&05oU-qS*Q$ zL`WI)<-a&>B;77rpk#}}9QxvK95n-xvo{hhVOQJ5*7ZWG!mCcKY2sqJ*O~8XPm`sC zGpVzf6{zjM-e$|nf)mLB4TCkOLTa>8SPvX<^PWY$AP{A`D*)X%hTL(1c#bri>PHmK zkGPo%b?wf^Q4h9RuinLfaKe zZRZe*slT5*r_nrTo|5Ex&&SX$QG&|2HS$CVPx`MtV&uT4>Yx8Olh&48v$f>_l_V-JEioHFOpz)v`f3>m=RTkhT+TTRE1C>wnDg1FqJ1qXA z1dDpFoF7xjE8WXy19URa zZyJ!7`}f6CqFu2t4{*;(x5RDDijXZs$+Xt!E4DQv<8=>Q9uoAxuS(%pKzfkgz3+{q z(dO_+sJ!+{imE0?x9^XgSWqIo#uGfLLD#umbe})f#eGfDN_$?2$K0fp)UTq61|EWUIm+UzohG7TaLO^@D`CBY^ozmN zPdW7Du+Hmo(2t{KG|XeffX21HB;kIjVR_z52)0lh*Zg{Mp6idz+=yFMbY&wPqmC&K z^i;Ay0kP$n;TO@Vd`}g;CE71I1P9mFr_nZkkiA^qNVs>?fF1mz1YqC|R&88lRCppZ z>Gu@3oGa&)EMylJR^EbZo6*grR=R%lb?zRsq97i9j6rLtxX;wt*TL6xH?$83AKK;Q zs$9-dBF5#eaCC{ALX;~z$g4!K9=hL4A1 zu)%1H&oA!1Ce2&#suMQx*E>n@)l<}Dz7N7JTgTzpE*zFWAtY~#QtG~@bA)K(9Al9S z4j4XYf%H5ucw)A{k|a_cy&8z?6a`tU3Uien|6A)?jvi0QNtur z&~P*w>F0Ql`i!>d5ST663mDW5l|6_6`(gxbaH zC6VO1eidC{3n7_*R@T=p*6Ovt(7Ip=+@k0?RhO1bm<34xTQLJ)Uvxq*TriMrZ15CWi*+#oNui7>lD7;2c1~?tmjjVuZp2 z2o;^E^Fse-mHHs}H5YKca_S>283n(&sO;Y6d+Gm@0of|6pB}N=$GYJbRk_-$+Y>LA zB|cbNV9Hi|680$q5rK<^_5%l)_Z?gvpc2>Z;X%`z2#tp6b$U^`DXSb8h` zWu)ph*TnttEC~I<5`NlFrZe36XPqzXxBCXMHAlX5hZ$cILyRR5LQLEdE0iBHN$h&6 z>Gs3gD|nv=1y8(!-K_Bu_LvvcJI+$vdoBSopJf2j8LP}U*%XKwu^H&N0U4MfB~O+7 z9(HG`y>0#ev`RqIZJZam8lX(wR{#(bjDRur+70_yaERj*@kA{2j=ekwo!$;G;AS4W zq%?&HK`~O`Aw^G-F`y%KHmVDAwZ?OD&A2wn23k@-vFD<`0ff* z_ENqySH=ECb&rUO==a3YVVWf!t@Ga++l^Irj%q^`C6OKaYyk?->s2wXNnqpl#CpTL5c4z<-Kx`5mx)^f4RbzMl50acA zQl5OYgcYs_I6pz&8lQQMi#g+OqwL6Q;tH-`>UAv>in03*^PaR;=UtSh#tBubLBXhU zuKON;%ft}ft}%-xiGy5dyOE}-QZ%unX?+p8 z$?tu3CvT)YxLfm9)0_I~>bCDcHs9g84>qvrDRWUcM;%vknH%HOWb&u4`izhFa)KQc zSKXqmT6D5xZ0aZJ)jJWLTGA`;F^zMUUGWbb!0x*=3JvrP`3_4NowmP+Q`+s=ZxBim z6kQuiQp`}Z7+O&t6g`Stb%2y=(BdgNm0eEyEASwoC&5J zX^*({%}^4Pul7Q^Mig2YbY9VuM$a!?@F4Es>b3QwXl<7+A`#7gO%;dTNpG;fk9!E9 zw;t45jYR&=1+EJST_v6%ebhI;#C0zcT?yaYo4q{#z^SUqUu*BqS}p^V5{Ds9x0O7L z)m5^8VoJQ4X^Jv02H`6@YB8zQ^MxOUDoAX^-r0pDG0I2}{jSVUjMf{+WYR`5dUP|B za02j*06xm!Y301>eEzg3xDJ@#QeDK8b94Qv+*wjya>mBBAIUgd=v^5Tq=IR&x@&hlQ8uf2DB#qXM?lDd6!}$H7*M zJa@XEJ)D=K3(%!w+_b)VsdW?ZFBLMya~Dr7{~UG`|C{b*WPd3M&D61Z3>c<>$ zv)z`Ty{=5~M3M4?($$skmjD(60w+g2I-{&8F(M7H!YF0;rYfrBJKi}zDG~MT2u;0^XEzQ2-*F#e9I~R;n-h8*x?wdn*HwB3RyF^6}o znQcDHFW_@xw3-|d0|&%Pp?^q%uyMu7>HA0ok1LFSLpCz+4 z2NKf7Aie2vy3ak5-k;22$KybZlPV1ZNZl2yg($L+V1duKgLdHn^i20X%)#ywu+apU z*_VnPLlbX6`g{%?fL%5fO@CiH`)Y&2enZqRtZ(AO;(534oMAPBbsc3v{vsCxyhw3w z2E=#MmwBl_lm+P@rSq1M0QW|e1%(x!;o79X>mt{GAa7*@mW@D1_~ePy?ZxWi<$zb~ zC72_Yul-y^-PO1+OH;sa_GEf3i2I%GtezHEjUM#MF@-(I^%L{IIG8AZEvfe=F6K`b zsm=Fy7r9HXrYf5x1>?JFS$d-BhDoarB8Xl_A*WJcfTW(#9sS^;mojmmKr`YNU>ie z%RMUT#wCs1m12H|_ucK$!qFrX-PN@R*rpNXsQp;S_57lAS}Am8AZF&lhSY4rN=W;D z7tF6JP|_;KzeQcAas^5z5`Cc1SBOShmek;lT6?XvpXb@VnvKC1Y_G$~nfY>0#+}XH3TIHt6=zc7zWBbx(WSR2 zG}lq3y;E!bs$plFd%7il`PjW|sDjkCzeuN2O?gp}NfGTd180w7yRLfVvv>9S^-#9F zM14rJIhRg_IY6a|-UxpkwqdX|yD%c;5k9{8TzeUZoO z8(n!0u^U>@Us~F&<=<^**caTBbumbI_y-5=r#~Ypy6&;rexs7%KO}P=Eu5lKpiDCD zw#vDtIYBFP0=^IA^ltHrdaBzS8{bKKDYa~$L>|9+GT6T?AZ<^Ki6=E_mp=0wY+SbP zkQ>byd8+TKT@JpY&(_UFPFr-V5TUEzDkQ&EBlg_faav1n-}&RUeS$;-By_{eY;ObU z+Tiio{KcIY0E>BunUH*2jLXbPpV$S6Zx>(%2>(#o4-o58Cm@1jpuBU?=D3;@d(wpbzH2~+`gV_iDJ_;oz6}S zPRbjRG;99wgIgjgw3uQd=Z9-dOVstSSwJ6f;qJ<={j1yr_E!}g@cbt(*2WXaEwV?p zqew;hWcmxKcMNtfBBfSeH?3=yE(%Qc`!j>RSW}~n*<;u?%d>}l>^kM9vSE*xwIx|Y z6}KkJ(JkU;{S&?|Gkwaowvx1UlWa{Q6m#2NZr)8QQ+nx*>C@4r<_rh>kj+rm;qJF{ zni<5Lst0f;0IKzx_r=<70zt$%R&%u1GZId1HJ3Tvsy9PdOegnvPFNyAMpx*gX|u}K zx`#(O*#z+l$-`heognPv`y>ewO;IhQA!T9D;Bz{jv{X$NEN;dyl~X*r%{=Oqe2O;s@c$n(N)S=)boc!HT~`s(XfW7UUxOSkzjV{ z%1S$A3tHH8uiZD!5Lxg&EEvag+Z4#b)Duhexgs|uV^@A=dW7~k%xSdW|Iwh45E0X0 zQ_^GUV81{@?InGee*Zj3Y*siS=Fz4OQO4_^h|s&$5l2(0Z5swT^haWQ@{tWF2 z=cS!}9%fJgsVX)xQ5(kd^`?-5Ubg6b=TFi(@~p36mArq|n7i0Y7#hwVDwqg-s~8&T8O4*)n+?2BzgFW$2Mt5+=C>-+R=J}FyFD%}1zkCuLX zbkv_HQw=?YruQDko{p}4Nu>EsGfNi1Bf*k5H=qZz;ahqOs=M5?L5FKv*1CySui5$| zwOmu8+wD_%bF056&qM{d1ur{oYe!sLsCqE!6`_eSg*&S=-r8Q_26R3&!@!(`uCT4W z#fT2H3dL`Sp1ur|a|!UJ-uyk;Jx`3Xd>K^qJQmq+t#3il<;Yxv zHs7Q|-Iaa39O=e|5OLd|U%KZ$%xL!-YzB5IPR%Ld}_VT4| z7zO(kf;&59?|mKM)xf8aIstVS5yLdSI>#`IN#xd2fWZ)rgzlfZVd#o-vNkm&V64oz z?|E&2B2x7%ceG2mnRSjbEsxx>hLt*>l1w97hkYuCH?xGPh;t!99C{_yXhca>N*9yO ze-GdnPi^0PPE+|*-3TC(V(&&LYIjubC0@kda$T#|+Uf;=t0uoVKPKt{n57%MAlS#( z(_%gx(XvR8ac>eEXgenaQDVS&`>zBeDA-@SpCvFrxHu$Flatr3hd6)53M*sN_ulIe zc7LWgI@3bsZfbHCl(p;!%GJMx7nypaW> zzNKr9>3)r{jnl^UI%T*eOxkW{7J93}+*3Ss%hMbtj~w5Fxy9>QCRX(p6cduUbbZA= zx#BlbzGGSZJc99U%r%!QS=mTC;WQWent7oPw9dqMCDS0JC~5W0(B`-Pl2UUPZjF+Y1WR zV18kiI+AqfA`iyFCy(Q-Hw;`o%Jj(WD1eDr7aF~aIrKhWt=H*wVpJ^IHYxvRnIe`hk(lOA3pr4nviAIFH9tNEwkWO;&3=WO$WF&eWU6hv+5MT^ zn;Rj6i^Z$Ea<`~bu1C4@*o2k4&|gVGUSs}5n5dJp_Yd_Do*lxFJ%nr<>=Q;jmSG3h znAi6$0P?jIe=&W3;?Wf%AF_7tEq)hWJ2 z5&+;4g>fQHL5E2F16UUSkYG9XoqIHT_`eaaVD$j&X^1=@pJrGRAAV(HK!A$}wvg@( z5Q6LgGTt!fa(%XfSAf4CKY65|p|7(j1_Enkq1h@J66&sR?hubJ67oeG;AZX$xdPsb zYbTkdu^{pW_PFIm{d@*tgjO5!o{5y^>HWKwm^?(Q3R08EH~?VRjgYL07|B`1UHG~-$ug=y*yRo(0}Fkgti`(RR8%q zo&S$c|2ssIVCxdPrexICeq|54n9i1u*w!XFee;2VNuDA65LX?S_G1Ax=jn+yrVqn> z;)=(yhr`%?Eq(P^V{*Q5Vo+1%#|)GvwOszLL;n?vii^zfQ4vP(GvnSPrZ(Jy7uEEw zacBc_N8-X)dnx38ktGK40ELqjCz)^ z-{?!dhnueJ+)iWZFq`wE23FlHK<=Q z$&-vTx+Q3YJRwqy5FbK4*g)=;?sa57Y9&<}za8+yf_!sc>+LI7mEYsYt7w^XSmW`y zmE*p(-3`xk2Y|`ZCy`Xeaay7RMqt;{UcORrvpet9#>9K$u?<#b*P!iZBp*w6hWnU` zv$>LqH-g*&!i(|KP^#h&W(03wbgi% zXc#&V$)=Fu@))F8`M-)^eFf?sezrI>p=Cww1JMQzt|q+@AF2{5+t;sGow2Bi3JdJloI8vuWOI13cV-xqhzATglx_#|5wR@V&wS-QK3sfCM8}Bo zAfW~7z;~BY+#SCH1?vj>(sg<5@T!kA%|YJ+jW91Cld5j>YguPg%q_zh%QJXC>;dxr z{)OTS^6fQg?X{P{WzV(#yYnQWE$i3eygsqlNyFFgl8pof@5@^`Ual+Hmp+R^P75?k zC`ZJ^8Z~F3kri`3IXBSB@^X=tx+Z-+vrm*^#N(ify(o6<1_t=x2nIWR0F&Xm-~=0f zV@Sp8(~7erBo0#63}_Kr6K3NzK8et<60h zzw0FP6@HF+H9V~&1PI5=aMhzVhf*AJDEbldvt;fjQu2@g1z;dYRp0$QPYmSL0HO6* z(Ii;a0I9bw9HX?(5>DNB?N-9A1xXug5%T+vp3BO^M^F!$C^LDlBpM%wB2JJ;TlnCi zZab0VD}g7q;mkjDp6WYx+y@Crr#Mtt2~^`(z)Jq`9CdX5jUwxzL*%?FkRJ-l~V>jDxy*-fwYLB+2I{} zJm&Yd5ff+HeGyoRq0;KTe^V)3_yK!@i2EtxO22d|{Vp!gEvU%|Fkj#9$A4!m1tL5n8ldlzn}Mxyj&=0WkX-BP7z zZqDaEo^W!XVRwzOU%QB*1@zP<4hH4x)9}Pz+XDvpnNuGPpO1M%LNnl^7d05CRjIo5 zN7_RZBV|R;5ZlC;9j(oess;uw_tKNo=7`=SCg7Axa01!vx*NpAOpY&a$>%>VhSK*F zzZ&vHU+26Trdjg4>jzvFN>wp?F16E^jLXHw-j2=Y^~~nler4x{5)w|MIQ3_D_rQAp zrsi8)%68R^bp(@+iHMlzA}cZ(;&azRkGZDNi&=UPePm4zwT6LoRo;_gJnBlSa*o0% zulT$<{qlfpe*@XClcRPn^_R04I4UA_xRm)dJj?V!!R%yv7Isk!)006_d9Z>DBL_)_ zz_|X4pfO>k+kN9SqRy-D@gzwpgSBVsq#g$y42bOzrJrJqeevxMP(~AHYC0;mAJS=y z_@ANu_fiEIhx(Madxs*wp|I|J9n$9Sc zh!z&QqVHvpi(@q_ibZbJyF}(wewf%`w^0y)@^6qQXGqvYL-yRKF#+89!mj7G1=2Da zM8m!fufi~d{Cpx~f`nIu2?-aT>R)g*p)YneVlSZ6rp)77eI9x#LPV(1C#gE8_-ahD zupG=#)>Z)D<-KJhzwc7c}gv})aAPBJnw5s&@lTESsw!AY8D71wz> zel#=a)v+nVnw2tpnp>_HI?;QY<$|+c9nIdpEvVGhEF1-Lka0LnnX2*ceD15eRcC(K9x*cpaiC3Ju!*^?K)@XIB!kNJz3?(91P>pS=U*W#QM&)j(km6wd7tO%mA|lQz_1t~Q7! z2-*91&Q`TyWjPti;+c-PtF$=9KG@-E6iKJuQ;{BON$;<=(=|m!7chdqexeM)gMw1_ zv**ncc1MzcHHaJq1O)CkM0WjHUS5X9ET#;UY!AJPQZIvEoqIMKLX{d+KV61v@dkAh z;^5(xu1;|ySh<>3k>x`}LwkFBjb10zz{UX+r7MC)>MHNl?H&7>);@fhMp0ajzuu*8 z(FiaE+TIUS{0NEfY69L61t_z7hhW5Rst_UC}VRUFnb@t*u9CelEKR0z86t)MQ&LjaM z%!KK~EX>R|95vwBgd^gECk8J;;Bs(q@aufeR#5~m)2*j^?8-I4Fi-k$mnxnUm5+}P zd{nQ|(?yc7m_R<9vd(!;gY&};gSytvpjvmUHZn}R0-0w1@yqC2kGytYbS&4cDS=NL zxBuHC{N!QazT`7xh{v`kD=lqoIMKTaVLWGq9edlQW2x^1pYrC=$@MtBwzM?*=DxQ! zl2=z($2kck2Qoivd|5tds8f>Mr<%3t(CQfZeTT4P1$lYqM9I*b%LfDU6hj?*fC5v* zdE^Ct=QavC4UN5EGA|zm<6k#0Az$Ow%~ zUg>N@+57>g8Y3SYF6XT+o+-r7b5{cKPzi}EP~TY;b>E(;1NlR)N-$Kbbetlr6BMm` zRU1G%LBM}=$6(#%eMn*a-xjNVdHJ?lcT=J1-LIa_THs*fea(Yu=!_QOYpLwN#fill zd(H?|)5JZlFFi=2!T!2To(!XscOwg@T+hk+K7g!MX3R? zMQPcY5v!r6Xuy;Wp}jNK2I z-~ec19VR$b+}u;kG%k`91%-B%&5`qp$y_$CCQkVO074HthOT}!7!lxUrsu#f211_s)Y0v!~NRfJq4o5U`GLXUyqC9Enw$PQXvbVJI9LOX8hGb#y>^-*e7>Ndqsb)lw23K`!yWP zl()OkKTvYMA{l_gxw*IsOwKOP4uIcYIXDC63*3T>iwp4A?0Cx!1Ho(8NDAU4mq#dQK3c$ zI$+YlCg2HW7uTox8@R=B7y2N?^QJi`TE;8Qp9TA`aR?%(bC~z6$RKk6Mx{pJpDcq`Q)Gfj8ew+8Bw!cjI{ZJ-$&F= zyhLTI$22!xuq&2KhJmHA7O@>_8obeJTCTw6(m|*^f>U9-4BSDT#^U%XuqZI?MjdXZ z@n08D$t`6At;@By)jdlkhFRwgm{fE%5Kn-=>NbA|RPR9b+h_@F7XNgCe3JkoX+HBO zNbg~hT`P_VJco>%FKIcsz5ugI4T@(7l`_=te&@}LOW&*M+WRn^b7^U2aV4ZQ;ot=B zaTE4b}!lj0S?B3*B}xvaW=vy~bJLIf)L!zrN(pQwY=Q zi{w$!td!n@FBxcTNqIazTtq;_y7v1u)Sjk#5lQyP^l*{mWzszyxM0=6KM@KlUGZ`% z4cLNSU+Nrd2EiHjLM+S&Cuz6y2QAVV4)UHbi!|vM61y3%zUI3A(T+ zzIf56woG}n@k1&*kE^pw``^lyNVA>oC)w`j!ak~kb^4)%p@bZ*x-!_UopVjxwwn}6 zTU#4>ME-gB1m)EPo5YNM#zZf@pFHV~(Kp=LCUaGfM@BRv6V1a!q|!~vj-f&gPV%@9 zEPrF8L^Hjad}(Fc8J%=bsT?%^lfR{}BGygoqg7B*d<1b|K`Ulrzwca%6Ln}M4}_}7 z2E{Gq$?+TT(j<@YtZ$vpojY=7b9599~?74IA@Baz5#8 z3rXj^T5BUOC3(cZ`3eZRPBi`z;Get^O1FP@1(j-T>W9Pa?d*Pc0!Pbj_>I)Ea@V@t-VqzFenP*RA0lj>qj}QjYgsk zod$RGtfzs+U8!NCuCgI_ z2z{9S<=Rd;)W(d9M_W(NYj?i2vr|s5cj|khFg_3w{`7Wie7vxOFq-K&qLU`c`}Nb~ zK2kGIc$$QsuI@PqO8^F1P)GQJ#>?S4V`ZIwSIj3)3 z9yMKoI2BBBE1NwKm9(T=X~*1rjZe*M^7aGp2RhRDW8sbaPyH2eQ%P|HUohkhzf@Kq zc`3rVwY^QfJrhCyq_?J~W}iI>BpJE9%N66LMzvKT|5}ZF3`Mn7gLG-pjGiTkggPID1Fpd-%l+?Ou- zGVn5NZCI*l`%6@a#z^9Xv^O;Lgv{EMx`V)w6BXn*Ebqa%f`H)fi*j8CfgEwfB1c1e zg7WzNxgWY3>S7Zue$C4a1w9Rv`=8l0Zp(rbI*!5&R^q3<9%-1pW=FZ#d0Jn>sMu4% zkMq5vsK$2T@?&=NlJJ-ds5hQKbV%5vI9_UEx)D5W+Btzp;hcp)K6E#!;CX`(cAFholt9(AK zhL|^@PLjWoXlyk)yQAaWz?2mS^d>B|2)CvV4j}OqCYn`8@ZiDL_|nQN&?SR zaM#!4XHGQcvv@TV|8GCu@9ghu)Lyu`xUhAikvqM9Ef-AIL!`zWpbN|}cGx(rva&KT zFmQW&+t@!~c|0%#zUu|uz0MUJiG9OARDz?WT$X~|Lr38>XyWryH&a*1` zhWjuH*M$0E(jz&r`c*ZM^q`4aq~_|$-SLVGUZByMJ~=sgWdu#+Cu2%n9oTwX{WkGg zPS!_L7$3WmkA5xx;9&rZ`9Ey|#_RSAylX*TBEQ|eJ>ga7jA`-6yZ?>XyLbDChd-I5 zKFL>Ov&V&0P<3{8a?YcHDZn38aho$kvA`MvnGGwVe1ExGmzG9t{rt1mpoT!#@yW?S zIe= zOoW4q7(cVzHZF+vr_FyX`$cP&%`?T2*Qb2PnTO)^I$y|_3FZWnocjc$Mu0O2 zPg8RN#jb(&wx35@xpw>q3!FCt2N>D07461-&M9c!2S4y2h-8CsspHKolq~$aDDzXn z*Aj|8Gbatx&(Ts?YEQgoALPWwQ+Nr8tVHoaevV?Ipw#ra{pkP$cNCPbj}yMd4u>vC z-{$S~h=S#8ggVlqW%10g{uF(wGLJ?`X&kYrty|p2&34O!+F1s1 zGLPX%S?OCE3Ab=Dco2};PUOqmY3Fd2&x>Y{>C32yW;0)3qCzM;#FzP-48P^!n|mHV zDLc=w}39vUL6b9 zWRQaXbFG3S(~_Pu*FAnR!e2Q0wsP|D5aavr={Nj$xkafX7OYkdJVaBEt3qOj-__Yn zA9+&MzZyR}^0aM6+SOjf6wURnm@`RQ$sFWy>K+^ zoaEE;C z$kO;SXvt|_xtw?J{ApY1WHd#Mz#n z!wPWSiErqvW01$?R81N_%ujDW&_1{zOu=)v9I;zwOXxK#C;iUD*_$PX#}xMrIWdR2 zc;Er-X3_>6bYPM%{u30fAVZXI@BDHQjtuU9-TS&yb#oTWU0=3_`y4j99luP=A|k(u zYL^xWaidF%GqTv=kUFT$hsH4K>8x)z zS~pG={@kjWBCKfD@4bW}OqE@ZwhIg-ysy<762?FrdlZU}EvAHj!FV`#TP~#S)6Sfa zv<$e~B?)hyZm#yUzh2V&IqfWdlta9m?dWXLHMH%hf+1umvBZbm$wmRW z>)j7%K3`(isq5VwHRJl_a@no=?4{@qTFkxGNGp(@_RDi5^ zCL&IU0_>6QW?Ts$vsTl*wi9_w+5mzHdb(?3#5puL=wo>L5p0~T@AM>S_kqedP^D`! z%&LXag!1NHsT={Ycm$;gnla!h0cetqP7{mX)6&3CA%6D4#-I6+#r#b#^v(ZY2lZ$uH*SB|7N@l27 z10JWKBsHWHxI0;fU(C#|kz|IpUR*-7;>M&3rBPY8Gx_jlC3a9HI>6S^Q{Dh>0J%9M zY!nfW8orC0#fN_{umXLZH0NW~`S8^NO_Q6X^OWudz#~asY*v;w9#4T|E~sum*%0U1UJ_`emO|l{YXL8pdtZ$f^-S91^x0p^h<4- zgDbZIgL1o_p#VXYap->ZN9OSl_d}2Mf{NC{S8ZoYzE8V^UnSA*P$ZW)WKPvdO9)##%`|hv;a}x zqG#VYIx&%dWd6VX@YlPa2?Yh~_4V}&403Ynov14FlrsEn85cB+!G&K29vjr266WuI z{;lD4H)lf_HIz);{l};BrMK3Btug~~Mz3tHeR$r7>r?8W8~3!UH*KM3h@~4?20P#@ ze7(nJH#8IPRKHQ3!{E+Z6FTT%<^RBQ7n~#~KROylCN|b=kkgUMweHeP;%P{*70v6~ z6;5@{(f=!saMH#V2nZtA0lf@y8iqKHK<-HaeXrCT!TT6m&@4|xPu}|;Qa;$VH!|=e z@;yZ!LjiJ@G3d`FgYi#8S2`1~xm4+Iu0@0ng<0Dr)+Sp*zYM_klMA__stMOvnSoQi zoCe4lRh}ZTNYTqP1*E;WsCkQCBfNH>E@5)V@aoV^@@rWXrNiZzdt!B;XXMteXMKs; zZ1-^4%QVvys;zZtQD7!8QwwtOaNH$C9ULCkG>AiWm>=9z6Cm&ui?y41b2zKff}*Ke zQ{N*umXqgDuZ243BtU7;O{`zv;nk&7%=1W4LPgN5k}UmdB4B`2av1xO>(3ukjt47f zE(~*C2fLXki;P1J*e6Eo?7r=U0nMan886b<50({DkBoEhNZnvq@TfKwT8znSF zoK%`$(9zSuGIne#D>0(%7150cQbamG0YrcHgMT{b-!GPB_RrAjrv@hz8H1e`MSN+# z4x`M**ixPS9;56@*`!@)U*S>UzrasD{OIcJg8FcE^BEzV;TJkKDb^#WH&*a7gQu2v zSo03(Exk*INjeP4ptNZGwa&o`@Q<<~^0+6IkDP}sAql#AzPb8M8Sr)99L~ecZNHUQ zO$}GGa^Qb{5xlC}YU;`It%(wa?e$@ac=D~zpZA)~J*j*?=KjnPD#DU+CrLW; zq`2=k9(d+GUM{i2zcVp0<2*w?BuK2VqbAfNE$Dch zK!{rwoF&pG3aH)HW7^}5sQE8B7?7r27)#kA!$ zrV50NdAKPNGK=liZq8#uf`US|B$w|ONi?Qp@oz0UtSa<|&mIYDE~2z1vU0IT$DS+s zJM79&)Ng2a97VrrS1hlTAtbqjXOJ1mUt1+8NWHV!#}q8=JCMLNNY=Wqb#gtMZ6AAr z`0={(1OY<=d2DS=C%vy1`jj|ab4OZ`YCyU_Od?{;2NhW_yYr%)HwiEL8K*+mj^81SPO&S2ESN@Y^M(4$V>Q*!iIL892`v8mN6;l<-8)95YFH?!rqWLERkTR zw<3#Rm12FEOii}1sD%(c)dF%W?k`w+gjWDp@NB)X^ql;T5!%A^v(w*%!l}KMqfY@! zp;*6ep9Z-{bEV{+5L{Big@fNo>KdQn)Dhc?sT}Ksn`g#8kM{ItK-$xtL)+x@6K1i* z|1nqB@;~;w2F1`fsjLLqrNOqQMLd~Pl*qLWU`6$K3187KWHm=`5ix#S?m>d@xR5FXmB0S4=bHOUWq@}D5x6N`J|&RA`QPveKb zI+NU4GBpT%V67vY@`Hi`?`pKxuuy6)JS&MEyBZYufT-Z%RxM(Cbrs-9n)#QyOSvu+ zn(ItQrMNwhl0PE6ox5{s^sAS;#=VgdK)UB-g)2?0NWQyWt7$(DU^!Bcy|CqUEJAjn zp>1UAs>qP%%A{!(z1Qi`)GJA5izp#fAq1MhF7i zpKxIH7-{s~QL$T4>lw(IUJEC@WxI9uJ}?<|Q*0urlId~uX=J3!9#4SNutV0tETqd( zbl_}|qgT(I7!JS^91KM%zwb>)K#wR&schfKt80#NebT{h(e(o1Ah016w}(_$iF%y_ z$s+tA&w16zE$N+Re=$H0^RSzc@(1yK6o%}H6JH&d5LdGZaF_u~yXl?vF!drR!=Hh> z4n6R7{pN%J$L7Gp-p;S!n|3MCD*6pRe1fjBY>ve8{jT`ly5f7lt84}SXHTtUwAodF z4yfZ7bF_1tlkXac;If#E=}5X!^-i=2q+zz*pwojV&9PhbY*@Yl8Ln?!m_txD#Rey) zu|HOmc*cJ{{oO8!FE*s8rSKWQVJ!S|9CmuVU{=i9^SW;oJD}OC4Bf{Gx8%Boa?OhwmnxP_RG3_pmHg3k;OcX6R4Rnb`e$H`g zRTaT67!q1t)+v9|^2Xo%^4mStvz7`DImxrpUL-vI;o#Dbb%5Y0(O*kJ2TI-Zi}pTc zJ%?z|VkH^>454ex|5-N|PkiCgUrnuK{9-ikb-3cI%(uUH8VqDkPz~ipc~vyYrZSB3 zjDY>#-E!i)8oNqoPk1l2Y3keM%e~$M$8z2wN1|??D!s~C?%j{8*eWkFwEBMD{4CJP zA+pR59vo9(lbb7wZM@UkDS<^UqjvWVqo=?3=HY+g8ds_XNvX=(AwV!>j7>wMn`c&@HNyqaN+3iGI+rl@1>tC}>S^(rk} zqwJmN#TW7$(-8tSnQ!`j6nG^3EP*!EWpki9%(fAzn-7=Wy2Yj_EuKLfhe_v)TEvUo zSjk1^aX-g&09Fjn0{IQpyusl5RhvFo4t`GN9r_=8^wRmSVUFA_@_2(pyE)8^2cXH8yYOUj|$W1Izn%(+ypsqS&nU<~{QXMpDqPbXdl1tLsX+ zxFrRTG$*SZWtg8a46Cs|aOJdoX!Axi>ZaLwMvcb8KFZ00fN<@!wY4>j?ag@JoP8MF z@lWdizXs~8!dRkB9Hl_#*ilaNdCByv_a=0|?G;Mmb3l74(W!bv@KdO%`Bq~P)m>GYcfYbG7-_v~tl)kJscPfbdo6${T>?^1fb@{ILWb}$u5!ifawO14^@~MF9=xmX z_{3|r{dFlE@Nom8Bj#%GGt|~0>aWJtSE+x5&)yrj^O8963(?z}ZM(pF?O zAI4oYMa>c|9M*p3ppp`f{h=(^h;i+%$jWz@_%Zm#IpzvWy0-}hight}=hve#y(<#H zo53sthRote-+DpxgllE|ryPmLmR+XX{wT~4Go!x#9O%97b`V0b5ljp}l^Ai!hxwu% zyw)JD>-`tI@58y=zKPWCG%^!wYE4=iTH*V;?c6h?w;pN2k18LN8Pi5L%hSs%IfF>e9Yz1=uMC=X!9LyNdO<_Ih{HY#+#4>p$C>y>-K>N{rY zoFGin%F1Ch`aqjPQ&Th35Y6(bk2j&XchniL;WuzRNPEnNTE}yZD zd3I>as(AE^byl@G>qRMu<9hSOCGm}aieXkp)BIsPPy49zWw?^ef5N;~N+JU9s((U< zP~KIVAshD2D;9e6MLyoY7GYX?nsbCtgUmaRgc5t>FsvBdjPE~78jqUXFi?!h9S{2d z@XXhNG`2YCf=amL#`L4puh;8|Li$c$WN8;@RC``?8b6KruxL0~Wp+}&;_?yDn9mT^!7mF8#LO6H+aPHENzIla2L7__fwRFe%C__#QV$ZJ=o=AbtP+VL(Cv&^}L( zeq30q^0>a|P^{>u7h`Di&M&7rKRKVLHXhY^hi2uD`Q82|TN!9UPozV$OLqP`BuMEy zU#8^;m;9O`|2r{nnN=gr<%x`INTI_1(=Y$8hpcy5%6NpqX5AO8Uo8{t5BA^)19aM$ zZhf~|m!`*PvY@swSz(b`)_QP+(|lwpwa0|Dnu<=y;z*AClK2Qy z7T{Y?s)?Z1H<=Z5>%!W5Q)19(E?B`m`Ag z+@yQpObRb&zE1!>{-F7^0|4Ivp&T4{X}06r3HEdQtGZpTZ%axC$6CxH9@tZUv44^X z;@14`rMFo>ViPiihZX}B7BR*`1PJv`Q+n?^e5QVZc%mgONz)aq{qZ(FItTf!G@_t@ zlY!T!lQ(p2?M>e{UQQA{r8KZ)YsPWC^~&RKP{ZZB^W^e~2$ za}eKuo-TO>C{Y*1i1UYt1=RaojfcZVmmNlziRovFdUka=KP}o4SiLvotsxI(tbXl3 zyu93j{!&a=qGIv-<&vau|LXv033*QyEZOqUg)LVE@X z8SbN+TAC$hp*jGYd!y57^k_j3=wUqf-UwVHU{@_SQr+8Mw+&;N>iH<)ZGfes8I%*L zu*ra1N2=&n<>uU2X?3tyEhW6aZvC)$%W;!1RW(J9G;lC*pq13UNrOJz>@XmeDM%)@ z7SJXJ>PEr@wBA@-Pk-~ML@sfLn-v@UiSDx^@Yv*n4^K2Vx&J90te_HnAw7}psTi>t zdN4$~`o}Sy9y}E>>%-EK$FR4XT0y^GRQ)1P<;bY#sF<`ff`*&EaqCmJ`D;*SGV8=K zvfBNfY!BE9d*Gae%o5{K(ZgrGj5nt#-Y}2=9Qj0<-BT>vsRYy=t4imue(m3R3H&nm ziZ;*$ND*-YkWa()Vy!PVHDd|SZ>rruSRBAJPU?z_l{rMupKyqhQ&40U$xg_ktW_$+5}#B$lz8vFVGN%OU*5hgF7Gar5jZWdzE z0obU^h0Nz(TAn1Z^%3eid?o$Rr<<4G@f{Z#`o4Ngc3(Wv@Md@YmCAb8)52;#1?7#s zed$d2ql^e5Gn`xGE0ixSgo3G8L~Z#}!D*v6`byVq2wO{l69R`+q7p!CZbCwslN>kD zLQ|=*IA9LNI#kvCyJ;Zq@O`7gPtkwuoF1zPbEQG~Gr+5%Vs}2#AKD!=nbmHK-f9tX z18A?jbg1XfTw@bXi;yKLkPA9@27>qi$8#}2xby8mg)6}e@$l{kzvkiQ^;tK>Q9qM+ z<_B((Q-|irO?xwNXeB@oHi-lvOwSM3#-=3aXjW2?=X;$$Rh zi#YfPVBjtZb4iMy`4cUhl}DM=TfQ(2tBK>mEmII7;5cUwrcDzlX+ZtJD_2#CK|6T& z?n+lCUI6bcn#^HW$YD}GV}WUE$P5iaFBAd054om((OiMs>BzY`qJROFptCiRUs{S7LS$y?5_k=JU1$iRA;2eB{28 zP+yaIsL?AeIpV}0ExJe)JvVBv!{D%FH)?Dq5`b((fK(cgG3@Jp#gEw0(E~8|G1=8C zp?AAqhoq%7Z;lcH8$5O3bk@^{pojv_=Sg+NHX>P!nD1o-2VcCL+OUS5`&2U%k)bTm zUelp8@9%iKc+jb2ED9R}-V~tBdGmz;d{zqk7BNAhFoPh8nRkYmbYFM$U54lY>^MR? zoKU$%48Oro^eT+}{rN=?GjX_x+pkIG7G46t)$tJ_p2T5fY3wIH%W$V{99Od4{}?#M z5r)EGOd;v?3nThVvVZz*Ae*}2iaE((a^htlmPULp8Rnlg_nfr%wT(+$zf31Nkq)Uf zbk8XP*|tIgU6QA0I-2Oz=x#4DXt*A2KGy=%fGBFeSrfJx%;KH;SV>7KQ_ZJ-C4N%f zoWxLYVC6YR;Su55dFDimakt+ct%oV6$2AOyQz;5TJF&a-U*Fo>BkR&HM2zfx9?{>> z*3aMGU7?J9@*$)(>jUE`OzR8w3DboCa@T0=?GwtFpKyg=qTg%~t-?!>Ufx}-QDsFVM64pYD4C;S5 z@z8YCTA8%a{AL3#k{x#pER$S$VyzfJFdpT}CAry`ID5SC52Tz0*!&aF*TeMz&|(iS0dc91sS~6asYY<_`bn)41vDL)a`y z_r%bjL3J7GV(7(d@TGUn4__i_YoX->l~ z24g)Q;K>eUo>PMLh-nL3JIwYjKJH7?{^!?s@pS%A!Ja7&??6p_S zIp&ySXtbI;S0nJ5o0~7Y2)ufN8ZJjp^sTJC11Ji=0_@)ptzQCFG#}<(cQUO|hK)u7 z2Z93hzcE_Hr$C_WbaQ=2>V*GJDTwan{X2R=t$AhPd3hnwO6tKzR#MDPVaFUDbiA(L z=dMnYWt&dhK#CPf{Mp39!u@|$A>O9=Pvs}J@MF5 zG`Q)FaZvztv@|pM+Ys$?3%%gteNQZ|Zx@56BDbTrNh}VE=p!|C-#P-2R9%YPJUK;ZbtuCKPobG3mZLzrp>@69fVzNc{VEBY4<@Q?V##0zZA1%?c#w@LG=Y?3;2rX4!_S zI^UbRLc_xk7f`&+9j>4VK`2UMdxOSwHi+J2rvuX0v=W{3gJp0iKiMls(qziEARi1` zZwg0q-}&sL-C)V%NhA`|00fVDp6tD4&;o)aK;r}IEX%L>@EC85FxcucnmG86RPyHU zPnPXf8Q(boY{&TOc3~lJR2A;Sb=50Hl%*HO1A<&zIXA?)Fvm=e{>@$T=O z(o?*>J<(=H38r`85obbAgLajHy&o);RQsWTU2_PL10&DFcR+BRqxYjZXn#89tu{MG!+fDrXOvD)1;D5Y&&!rS4c zdX?G!H3^{bT_gW?zucDHW!PL~n03rQjT}(JpRJDl*+ZGZk^Gsz=P1DI+mVmN3c~GC zur5?XZQ=1~@PIY-vtV{HBI^j^;donIO)-^0`<3CD=-m(vRYVzkleOcbMyCCJ-lj6s z%^e3Qa1`9RD)CUtr&XJlO;Sti_a(vg+-`sf(glJWc8;M^)0Jqv@dxNCw*j_JQsj} z-60Jr@Lzv4W4E0(w%8wK@q|a*WuDGs`^2gNi0a;~iSVj{wj`V`C<{%_{0d?eE14(gY~holJHZE2ske`?TXqodGw z*IgCL4Eof2TrHg3)e0JH)axzp;nvQGeN;FuDKa6X zFeKPlifCi7gmfSrbS)ttsm|6FQ2rV6IA(c;6jQWc znK4ErbX|EV^!>sK2?+tt4-j_i$1TC*8W#b^Ac&W6T=pq7@FG9T>$YRdqi65IGU7$R zR%NnK9G&fZC-}BBo#*v8f)|S!4Shl?Jm#-{j)k8kA-eATn2EMqlXMyrF%_Aa3a_Z> zYCa8hfl^cfb)Lfk5QO_N>JR$ephOF~Rs6qzHKE63FOfK{I1!&5Z4K@D$P7Jy*~Kst ztfGyzBJ4RFtrcgbLp&%l$vKFQ?^~Ew&iS6*#dS?vPFox4c=>tJnBh=Wxp!2jPGZIT zMV+_8pbdb$b1#|dX^uub>1W%QDh?1tTJ9rR`A@NJ1+MEUuquOi(8rxIuZ{?mRu@_6vORy`9h}kn9kCfLh|;>oI#O!i4Hc>G&@!8RIA(T=nNT zPhWU?-p`O+GGwPthf}AQ1bSqPNyLN!Lje*f`>v%O-ldhYeMJczZc|3&y3$3YYdvcR za%hpU0 zPB}BO_?oExC!6_&l)28!>N9@ztLxR!CYKV_79hT7QNLXUEWXpa6kLf|BMTnnu4nA;iD(D*CZVM3im5w_vN@mFUym~NeM9bmO>*iCO=24KXX>nB7U_h? zW=*fNK$}uiPmrl0esuHB}4H=k$7pa5F@kHdxZ9{cad$3090(!?{|TRla{DMM0) zn$kxwD(Io}{7D%5!y267O;4beC9A&GSqp>z812V)Sb@JzSB^&vl)ud zITLo9gO9Jq>=K7`L@3?i$KYQ8yZp-igZ&41hn-EQ^J7$~J7DH=yBdhbA%LP5O8BEG zl~#`NKWO^3W;b5Q`a!Md!S~NwDD%`hYq>@10}DO=%cEuU;LXonpMii3+5PDNUO4G) zI`Q8lY&}*^?lIH}RdRi0fOh|zYq|p}jPPA&RMa+tvlrQ@!2!zb>|`Iqi61}VeX_4x zVUP9>KL0Z#RuTPs#v46;EiQ>M{Bq#yRsF&t7kPnAW~)$4q`7#5#HEwT?d z4>Drv_JUkyT+rb{YJk!sD{$Y?_KDzqtZBJqsYSW$>VXt@*53@{#UZ1}CR?9Lzmhzn5ULH4U?XCZO zP}FRMcf#|Zr7$7YcK$HE?6Bja>D5ubqBU9&al^Vgn=s!aG)<1rsiHU$Lc>;X=7miB zgm|wNP~}zz%nN0TOwM`&KQ%y9*jU__!>_Z%VNJKs_W#7vsJ{|MhGqt2qO!5aq7hHO zoqi)qzDLv2;gT7kuSxjc&RZF1J+gTB40(N7dJz5ZOd!;i>|R|fFBxr-x?f!Ba1E%M zmO^O)5#9TLq%02KnT8G7*K}aQ!J&R)?0|(QmVW9vG&Y4DqfxQi5?~y;IgjZycn&j! zwb_C3etI^n6*KPXxq$1^-on&a3^DDJO>zLL={yPs6)m#i%dVmk?T@lj4pW)PWC>hy zodMv~IFfoQMt%+j-@(zs$F_ec&t}uzkD0-?%g$*ou9*iBjQGuqvPx)}%=9VpA`|(o zHy{JHjBP6^O`;+Mvq!I6%S05hnqIuj1rT3NW8*ada|vy7c}^X9xt-1nreHJjgBZwN zW;+;0H><0Q=BB=+lLuzYK$?txrr)`&HeB5J`p-XMfBu%_JvIMpr_T>;x}S3M#!11k z|DBq5lL8kSao(%}{(jif75oWehuBzH)J+NDOg}urAXYn>cYT+TR=Xgyib}TyRkHhm zD6ry<*NPA!oMF%_6{k)NT;if~qS&G3!XikST5uT86WtCDCuykGR-%FF-+5hm0wVrQ zi$W-${V{Y=AX#=Vwp^=q`UW!qL*)Z*60qm{h!P0}O=~^I_dzl(tfHbyc+7731^J(_ zCL!X1x{wh2ybl1jfqO+gkqMG+VnR!EOE)+-SbY>A=erExN?<4twSf=!u~f)fmi%n0 zAjuZ-$>;y*M;l5(3g<&`JDj5c^l+OtuU5LUdh@TsiY4oziMs@F;ci7F;n) zUQ{=c-v<;wyXG$|2p3U0N)N-0CcWO3-n<3xYezr z6zO$mIS&IgpPSpAjx#{49Dvqv5U{va`+Axm1&oOfMpd*M?be5Z62p_1_D$F7j@gd- zqat$D{3DZ-=PDk@D)-F0E_@GH(8vd{kB2*}D>)m&YO?xv=Q9bpoLT*MeAu;mU}fXE z?(rYp(*pdv#Z+en2nQvkmBrcpGO3fij^wS8H%NN>P(Jz*|J>5pS5?uHMJAOPkNw0y zZzuG_<8e*dV(_pk^CwM;8LJ2a#A-!%OR;?+PCiUBe_b)bA-ve{Cytwsf^awvj>olc zcO089+u-PMIBYVjZNfMp7%!rUdz#!XQ=Aq9MDU!K?wB1L8;_4=pzU;!!^_|Qg zsH`m1YWxIfg+L>L2PuEqP6p1pGS)1#kEo%53H zqq@(K`FZ`jyG|k>YB3Q%CR#E1f?8C6HGo>UIFs02Tlcik|>7m0e(zf!+js;(&bDozVDfqYK;pN#{>XaPyib zRe%R#xNZ0E>0dEFaIQpgDo6xMS-gMo6Vmb*c-0it3pCA#uvQ!^+lAK*zgP_P3i~s> zi0FU(@u$W?3mz}*?wF^Q6D7zzhLMIb|v!rk5Bx?cPqOW;t%wV51yoUk^T zARx5({>68HR29+Tc>BbJG=Q?pQdn;)W$b8iemXgN6E3VL1%n+=&Zyj_q!V$~ z5ko=N@wm?j)8V|xlcIsJIu!l43N_NmpMFnLsc`=ucHwf@SIqs2pwD1qs82Zg7V=Px z50}H=F~uc@9fceGUV66Y)ge}(3I!w7j;#?{h^rR-D?&dC)uV&*(ssnBe&Y1>5218h(t8 zLG$(U#WSuJ{qdG_+kM{?wSHS}I3R$0jwBRAt;(p^{ZhjUDAyc!Vp~4M%seNwb!+KB zckVnC9?HM_Zq?b@+pC)Xt1EQKv_DKFPh$SObHSt)d8H?IWz;z7k|QHCKEGk=T&Oe0 z>+O|O5uTsuL5xKC zB*iC7NP84z#p7pW9IE~4T1eOSQA>n#d#onI;#mI1jw&l@U{GlZPu8RtEaneuDAQjx zpKknjuYX>N+*+mJiGY0{{TA1F6~`Y4bGYTF|EM=(y#(@%HXZ)R>~v!BJkn~$Kn94e z@hIXJ3WiTXLE$z(>LCVfyTj=O(n?&<4**lc04NW+mjIrapdTWM*q4Y$2MSOA%^d%u zYvcDgUBKkT6$oen3$dn;-(Nt6)_#>}84MELZ$`u~@F}gcumZ}y`PS4w^ZxZ18pibu z6JmSLe$`Oox-CuigG>T&b1Do{Q%O+WW#M_p{Al;X{gsXQ%Hit$TaeNvm!77TcYs>1 z=OVPeT{_(tyDryHgliOG?EZYuBL?(LzA-_a;2CM$^oHyx7@^5vY3)cW^Ao?3h~tl+ z5OXnH%*db$F48EwD9j#bV|x%) zsqyZ$Jc%GJ1y3m<0ZT0DY-W|`w3{gO<=++`KEnp=lX)+s-q{i?Dwr=rt}9G6*wFXy zl4TxN0rOZV7uE>( zbc-j()yf#(Gh{3axMn2BZ1byka`Q4mY+;cs)L^GW2fH-a**vNWno3!;zWfegu!KZx z*U&pe#<9nnM<7VCewa>RJI#zO=13aEAWV2$tKO^9B$AR7MHo^(KY3z{yFMARSuZ6a zMt*TR?RN{o_CxszG~ywy2V%}ozsxgB#X!-&BC+~XwP;OA;OLqOidTe8r=S$~2lJt; z@Q3s7;Be`jXnA?5k7EU@Qc_Y)yQtx-&ik>?Mq>XCiKn!!q2!LQ7*!7n=!1@~*U3}t zot@wK-NDZ*!%R`6#ub@S{LZs5w{+S{|d3RT2Ny)a|2b9`>9t}(_R)L&;}L$avy z5%5WhhQktR=!*tc*vilOs|7J4Byz24QA4>K_hp7GNYjC|K|R&=_I19EEsDZ)%?BnA zxz0g+&Db&GYd^?T&GEn*Wp8h9x7w9!C4*iZDnH6p7?*lL5W-}?kfBAyrg1w>A?Y{j zaMt7C1%>>LlX3k3Bfi~;pY6T%QBGMT?qa26a%x-XuZ86lGt)yV7`4#cqUKuPiOuY5 zuA<^&^O(xB5l)rpwEvRfot>GHd_~r9di%8OIEAM$SPzy@AJ$o63z(P4YH1Z!W-~ps zrGa3?2DH*Z&N|4J9NXWzoJ7r`0#BM9K%1qdph%Pcs~!Ml#U^RtA;uB_c-kQT=$S16 zVVAbcc4byp)(8-KxVv<1zN2akf2k-!ediXi_RGwO7|+E365Mk(xGy0RTa$VUg)5zpjH|98#Z(8=y^+jZ55xj_5Piq z`rS_19ros+?0x-^@xAf~lyp%^d!|?ue4&!gj8!o;~W(33$ z;y}=uOr_K)=78S{xA0FCts@U%&l8O9HW~-x>&K|%uGGt8e8VAr_T*GnFHu|s*7!hB9TUaC>vzY z^JYjYpnc;$rm@l(4+x21dDY)mK;k>1;V!zPvt5;oo!Su}F+;~vFu0yso&Wv` zbmsux)Z-WiWREL#-5t;=9}hSTlIy*xPtqLe{PUI7d=8z40o2RSHJg{1I&f94K68Ev z(EDy?M22KLe$c2*>lnH|l*FMxsp6Ev26}Qp{h|*BnMPI4?J6I}OCvc@7L|;bF$y-l z3?+Yj9Nz@S-)JMQ_p_Tgxi+S{MU zX6e2Chu7^$Bj1pR5yBC`w*y5f@%@3paP-%Q+%hR15f>5Z2y;&9iA?|*YXb8Z=*ihImxP%oI~ zlrKd-r2>zFe;5U|@y1{~eOcXKRGx@fLEwNSPL(IN7aE9nxd6zVB(fFV<2}7gMY{jn zkO(S$K`BN0=A5lT#m4JG!z~n0FNrEcKcKhL`1ldzU|`8PS&WX+W(n(+2J2e2>SvdC zmMEX^%FEDAFGetc)kI^AC$B(A%kV~J|4!6ZRh5QIG$2Sv@YAI3(`izZ;O*MaF?Qs- zr36bc$~0fir+#mB4&jcoP?9WA%#qEh6utB2GH(|UGc`*T&-(Vw_gwJ#ucn0RlN|<9 zS;;`3kM#*$;Wc6H1!A*JjzbnbQMq|}6a`{y4xf;2V7KPg9Bxm&MP7McNt6NEy}TAa zL-xPZ>wkUypw8QB#j2-%`}wxP?l4k<_4WXXDu6s%d?1-i1%;TrI5$`HU1kxkYQ)gq zq$Rh*70S#0g5biTml)N(kXW;eQ@Xc{F=6mlV!9Yi2Jp*D%F4Z>V07+yYj&nT!X?t^ z=UZs^mxe)`;Ic^U1Zre?v}-8P?CM(mRjkb`He^-&aYj|)bn{YKd~3ojY^u{*7qh)j zi{rq{#k4^YQ}xn>X?SY*<#1q4i1$-d8h*8R%vpirR}6o0H!GPx85qYh>WcCp*pIx^ zAr>Xn{`kc}a_e180|Rg307`0EM|=joLRVGHz%r0xl$DV9I{oIiZ3KzSAcPn4FbdK= zmYif=<%^E%wUcqR8PWgKiY*;muUBTM^R-^*{*%e=+FA;2X&J_XX{1@{*1|FA`uWw2 zzYbnkbF+l` zeA|x)dPxM# zu4ldS^&*^BbYsri9PwgfsGS!*z=6&-W7Xcpd$SJ=Vq_oXu~-9MZBM*xeU^H;_RS4s zkwk9_P=K{;2Urf6?H9Pk^X~LVfJbsW!6qlqXxflFycM z!6y0h=a;Z218G8QQ?6?opg&64a^h&L%S6%&KK-~C%K#g=QEE<0QM|B1=`$lLY3e-Fw;ssfd%(AhlaDf%9F@wac{Dc#ZX z@bZTX?9rR9bG)Dtmn7%TP|b9_$PF->5OLV&4_?GH^O=`r;eqZTid|Pwqe@51ORbtP z^K-J#M(xwHcTLT-6@B5&t*D`@+SA{Y0~29?LOjhcPYP6zs`dL~0I;SHO62ksZCUC# z+LX}|kO+;NGX1{pgNCasq0Wg0nCT0=J`t@EtSoL}Uo;kG<{b6mCYdG?3T=kSRfQ2O zHY5r{b3M;5Ke~za#8hE>VpC5wu28ww)%-n_@E$GQ4ge?R+siv0{X3!QAqCRQ)noi^vEo1Y_Dmb z z{;=X(O{Kob$MkT}E~^*={aP~I`yBwJr1?&$rluzCqzrn2&=2BPmi63 zTc4A((YyW$W&_|^I3T#H^s+zY=ks_ZEW*%Pa{za+czg-0^3we9rmD;nH53=($rug+ z3E}pvi?>&)`Dj=IxJH|C#dl;h0J>UjKSHMp?ZRkJFLdY{%y8X`b^TlqWUZT^?LBQ zhZW&nf&*f~#a;JPE-}2^qM~e8Q4?=s(W{H`=9mgU5EmFQViI1&Hf!(o6>A@YJ@xX^ zQrq#=vAF*9d0EFX((O_w-SsA5fX03$3)+x~kthw*y|W^(sC>%Qclj$T%VBdigIfA( z0&KGifN_+seZ2vAuEOdP7`h8c+a8qO%4M5ikOKJ>VYnt_DQ`i~U>F_b6;Oc|wJq?`DA7 z1|+MSc1;Vztq>oE4hkwcsA0n%c-_$f&IW^HdmDYn!?1cvd&RHo<#BVW$%#k5a&Z@T z7SH02Xm;JY$U|v%o*$j#Y4}Z|+vga3=NWj{6bJ|QmP*l$+jSW%#YfS#O=4yc+Nsj6aU&+xCBncI#xK3e5jY33eDh6bG;dP$Zk%@% z5gcfkHZ;zX9Z7JydNjj$=XiYr;-yZLg+)EBbJRX@)2kZ`q>h?dev4p_1(H z-&63o1JR+~N`WwvV;16xQfN`#&<^zUI~lpCqKVUFrkC+8W;0`wLebIDPH9)`3Dl2T zUg5@;tr>x%D`F7^|9VXXG(=zJ7dNTNlX4Fc-47%?QI9#AF-d4$Yu)Y5CFq~E0>Cxe z>(`KuQ{<|(sDFnWK`41`z0Sel_?Q0%@khJ@?oHdZg1e$>xK@r=Aon$5-7 zSaDHarQhF+!v<)FOaBbVykoH4@PxST2XYlB3kY?_0jmOVL~Do0*npshRxksQn;nO2 z$`pA*ipjGA6>N-ef+(JN>`nIZemd481af{hg9r8$H^!ph;Z@TsD@RFOuJ*pFXuExX z%Hi=kYq)p0n?xvw2G=;lI*WY8#pJ@J%ycX4m)kjxGbapJ&r>@H7Qt1XsW% zjgSnuBl`D7Q5YUbJqU5%F_ro$N=)h0r7A@a2HA!YNldI@5>E>kNl9f?VS}BJ|?YF$iN1EA^y!# z$S?O1eL9Irr$vMph33urTtpoKEIe(g&iZf`;6R1nc+|T)K(x?t2VYp{q!CA<_14%g z5ED*;{WV?qYi5Y|Q5LE15%7edxo&QD4q0+Jvw_8l&77KE_&Y}g&;$So zvswTd0^+EK<*MpoI%aa=D)Q86fnT@fgi(GbeP^VV!?8E(My#s5lrX(4dwPA1pkP@^ zfyr1)Ob?7z_MY`=&aWZ6Ma$#nQm1uSuR_F^rwNZsH*=&hr-#s&BlE+)phsMmI&7=O z?lPPd@ccZVP^k2CIzibI%buysUBi+{w-(=fyX=t2kT&f{w(Y*Bv8! z7$pJ@BrxF~E>1~zHtJ>!9*}+91(D6zJ3lkJKuM48R6)bwfAlbS{tHq|uG>+HR$mz99qGRY+^d|f_PZd?E0`30d_r&rz(BJhG)HtoY!R{E7{3189CZk%bd&f6 z|IAHzPoz1c7h16supR>?i{as60io9^yi^xss*CCt^SIgwgy|>@e?F&f^)ng zp>`76E^_2ss0oL~!(b7!9GZww>ur*24eJ0ER+g>8fgfD30@5R~C6z>Gdgi^}xJxrN zQV^>ibjGy4sI}?pT~IjAN+JLyeXzAXe__L3>pk}A4u?41iFO~I*NPp)CK4f$sgYest;Z2QK@wgFk7!jdPFRvh1mLjk zQaAFtHoePH_cxxD%Qq9cnLXN3=H|&S0&;bScx#j3>n<>wM8K}p?4e~@hUZem8v6{n zMCfG`ZlUV0h_Qhlqn}d4RZVY)M^J=yB_<})u@l?nGN*S}J-r-8RdU8x-kP!6^Y+M@!@7R6KJg%fPxWYm79I=G zL7S!F{=6iNq|H4J-><~{dvq`7^kV%z$~~r8%4dj2_&a4SkR5QV!-yp$oAeimduU{G ze$iqIQmR-Tpv>Hu8Pe}NPw`BKq`v1i@>*LtMPN77P$|>;J;7)G!CL589GPtSDTuDyS|0Xt?SrCx{f^ZjklOJ-h0 z6?4kTAwmGDhLCtbhQ#|Q zw7dvHx@D?>o#;HD*GHH?xDq^u)C>7PsFhoausU(6G0FA#`(~H?7S?ql4&=KS&a;e= zskGa1S!t!&rP!8Y_1>OaBHr2PY|9>gC z`&+z!X(<3jflDOJDa#hm^z@IB`ME7sB&geANa^&>iEhrtv&Yo9MQmTmnyU z`)?M*8|f@fQmdXNsF#!CDusn9H_sZ6Mo5+FsQ-$HMMRYYa?G^NR|i1F$pkwSW-yaY zj69382OYi296)Qc)@}iJ~lFfVwX=%A|b3(YQ9+U+&Gvq#V(4`j63T}QEu*L zWEp3pEWbuyO5#VRIis&UjtQ4Xw@~fL{DNJ;K-WZN&LB<8IeNrq=M)xm$Brwv3r!%o zRld>Gsj>oVepYjNwlsx&4+}fwD)qf{??jXQl8d+vac-AUx>i;rQk@r0R`+4_uJGjq zQ^3V*$=&^}ul8IgRVY8H60wLg$2vH4sh*!w+552vG}#DKdiN7~<&TXw@2S021!~5x zHLO~}QG4S%deMK+FN98t9?J|5BU}TG-wH2IgNvs4Ho!kYI!# zKP5?;9~>0M+Fuo!52cg-QflDt+<>ihlf=>Us!Z;fV1;KM9Y@_xPo?elwV2sX(k6LP zwSldkm{49+_EfdsK_)xIKh~=7t=lxR--dc-)>9WZONaxSWD>8ez&o|!!l+qnO<{$E z092~*G3o_G=97tD#@h^hEK%4?L<2l+_r1`e(cypsEsv#X$L&BS67HeRxn^Jua_BZk zW@M-j+k#Cxk*=UIeJ<0Ro)HX`l!3h0onP)sf4qX0mh}B2{t*CX$5Bi@@VODk6n9jd zVLWs@oxSVN8a$$X`*%Tj0?_Llh>22GNp>?C4uM>NI#3Ye*zvkQHux5%ueZCkg|K;C zm;AM=TNQAg7McagFHxXloy1kV5k|v8QL`nbe{!MJq-q<7Biy!hNX4Cz8H{+^9m!9a zA!^(Uy>R1p*|)J7j95OY+`g5!_EMFBS&p{??&%xbk%SmK*|49jBm7B29t5Ekr1G`- zFf2@Y1W|9kVGZ})z}u><_M~*4buyg@G+cQ>pAbqa*utq;($I?Ia=OMv%)p;~i{5tm zxxwtN_e|9g;^v^B@axX^+S$^4r3-095?6sE)v;84B0ME3<$ZnDLi9jzRIGT`yC4i} z;FEpVR_Nm~ClhWs63j5ds^7@98q|vd1*EZUVps3lS%If0=sSAYMh8FKA)#1Npk^QQ zF)CK|t{v0owbpx8)rZXOZakCwfC{zDqQ!q350icwzo4M5psoVzkEs$k1q?|V8vf%G zFQ0gL&esAbnX=_VP2yfhQk=1)-iFj&Q?)@zBoSIVW$u7#vn*^cmH>LbL$`oiX0`(56#DSE~xjU); zhbvlTx(S=Kx@`$@0yGcdyKI%7%pkNk(%rxNf%SyK1Jz_~YK^^z-`0q$hrYiN%7rQf90vijJM#l`rCsCtqDTb+EE{=TS2bV4W>)K7AvD_C)|!&U zna;=~PDg68ayT=2?_}PTNvkAT>mvf}c<;PIvUM(HRYKKW0f{g%En#ehTGXmMqLUWA zI-f!9@NL;IW-E)XkdN1X{`vk|y8(14EMHE6c^=GgB;6TGO(tR52#W21 z#RiTh(457ZER9N_`gkgxn$tY*G45P*`E}I&zc0%mqiUxCBoFRndw}4{(zP=Pml^=E zNxK|mvR^F!g_BlOIxFDOMJ}TBfb19%#762qZuftK-IhL5XISlv533w6bJ9@Ae4Nh4 z&&IwuWH<6oxe|m}HG;xTZxKVO30K&v{Ei+B(jxxW&g6F^m=nc`RNb;HHLsJIvxPKa z>OT=)>yGUG{xi5E5t2?k5G4`zqgMA1978SQdKkrL1jEOuBCO2(aa>{4=Vd3LDX#l9 zbL`0;UA6M{%Hf~gn_JS~x0Pa{uBHcn=8_MVkg|CW{}|6*o-#!C90LNTy6vy8A{dZ_h!2 z3kidMe#Ul)Bt6lhE+GD2Ts%LLO>I&QSTly8`fI~x2CDNuj_tCB_kSn#&_je>)mH=k zSt8>?+fth-eeDO>bXpSOXmk=i23!d;0~nU?_82oCFzQHxjt(c$qO`kd`NIPbKJqS$ z8IGsa8IgND#?@zfwUsqlX%_aBsfQ%f72@x(6B6?Q`@C7Ui5j|=wJzpIRl;@>F>dzz zipgPq4Qhxm;I?XaV zYcUnBSgp~#HfM?7biIFgJB}bYh&>nW52{k2gK%bMrXb41Lm%4UCjZ8^8y2@v=rh># zA1;q@V9*5&G?XZgfg!C2uuamevkP}zS5j1**ZlO~hoF9(CprFhwqff(y9_WSusc*t2pge&8EW^ZDXuI29}oUlRS25 zWZg*oVyMljsDl6UXHdZGiqxiiPrnv^+<4b%^g(yzyBqSdH=;FCbf*+z-GjF_rlW7Q za{dT5M$}1vn+r`!SIgF}r3-iO|>m1tnP&^W|#| zmY|VnxgEJm`e!B5{8>l8Rb`6-^yE}_jqJ|@m@td-@U)q`tids1BwK-pZsxxQkFL0VO1D2 zh6p`uC=P=l!4De{Ge)k)^yz#4F`cCuK{~&iL}qr!%$VhD4GMTw8>{zADsiPC=<@nfq1+tG?}gu~@98 z-Sz+~-rwy1dLcB|SbjQfGA7scthN9)c43}U*!8$e0%?S`?)gk?V+r7SnNYS!I3gL4%-;61?gt(s5%McGv^=)w^1xbIJxE2A$R88!8%TYcOlV&ZdXqjGS)b#&d|4}xg0osxvc1YV zT#kz^pe6!HUe%$9mvd~0Z_>dQe|0|O@w?m*2|Rm(PUY2nI-MZ?o`*=-buR6M0rnpr zYLy^6rhQO<9I5U@^VpN=?q=r$J`UiF%XC90l_s-m#KXkem#iOGS6LL3qyw^+A|(kf zMc)T_GECCfs_Ghq*cjuz{lno(2V&2LtBKB;eaQt5_Y|;GoE(^tk9TIL-DJ)IW9#6U zDsHOtSt5VZA05M(CW%g`rS;(AW=u_CfX=IaRZ*NKVMiuTLlEYDnfUlk;dTi^q=pQ( zg>f*YL?%;qniy~Gw;evs7=P#^T1+J+WwkA_D51i+tO>dv%N0%%Id!!N>~;AK`*36~ zqb@hDHIKzX z6x4H@m#nP>{yYOy#C~0`EeQ$5A~AqtY3*u?#Q(6Yr0c9~ZJN}4N{MiC7(~rnuW4c_ zVlT|zPHh32+da;&! zSBFEz8nr0r+oCZo>LmU&oaWYTVhy|x>sMAVG}NHr4}LBR3>5Hudbnyfvko}zsQ=M+ zDyp85l#zx2sIEG}uCv0xT=?0v`=Q~G`LuJG|DEOe0tk13cQgne2-0y`?1!j}5m{XfcvCMZhli8BvLq!OIy4wcaohj?x{oqqI4obgRnl3KtWy%RK8DLf z1ySH)?t0ng4$M&n5}5k2nxqny)H|r4v2;g- z3LsCG<^^`Cpd@{bt<0tP%0A4HBvk3uKXmc`c;@q(261M{upxx=W*E!pKr_Ej4m*MD zmAOqkN(8|hV-(<~htFyjr-x;?ITkG4@yc+%AXz&*kgS@fYyT`=YT8j)LNbY6juDd> z0?b)qi~dAl<`Tt`W7C+#hOw%}HXAaLM9DK54srwL-P@r%Mumo-e@p@UZxmk+cu6A< zAsx}AtM0HqGS$YW8(Bde;@j?`%u!Fo7T%R;?ry%iv-bVfxzPVXz9ZY|o{kP!P z%$k=~lou>p9_GahNSqWSC*{q2lc3YE({Mzfz)Ob4rVNLlhoeHo9AFIYSX^b99UXVA z6M#C}qZby(YdQiLa&HHSqX>1z#fx4`(d9cWt%R@^vfp|I;b*6??pnJ;5BKw*+BZ5R z$XW7vwYIC`U!E@ac-;W%!sc`}-GAgH16#Z)gM6xq3;0f&{Z*30n?DkvH5t8qeI&s; zpu!rZqN++k1Zbgvn?&`i@KGf;stC z6@w{wV4R!5`htib^enbf($Hi|j$p>{W)Kw0$U#`}=`zec^+|Q5s zk&gZm9$;y6An+AX)x|J>09lvaxn}JhM^IeD*5y!N+4%T zO!p3#QO~~~+u?xa;WMeII$vKH38wLUd+aS=VRo$Cg9G3rTHbVG3V{d`VtzsnF;G*q zXgXg32^oO)>Z__^{9}ryC>bnQ$YDQH=2G)JmkCuC2sk(GO8jmEghu_sB@QH9&Lcpu ziCRR7>SC2{A*JN5U(6+0T6#^Z!4B+&m#&7T=$Qxm{)M}m%@3*?9Ce7r*L00IEL&&XAb$iU#xy4ul zpa(w;k|$8La$8}7++n+*sJ3=_12nbnGSKX7(!XF8_++ZB^YN(4vc<$*B>=QBIi*yC zvLn!)a6HHiIePe8spfv0i6nGw&yZ<6bn=NYL^l}$ZWQ?%P0Q_g6aw-Bm!mcQXMpy1 z?dWmpSUu-nuV@x#_Pk8bckXRTuf7Hj>dr4Z*Gp^To(Qs=yZRlV1>696F2h(_&0Nos zgqrp2M9!ma(%FRTgVS3yIyq%!QWl1y+LZ)MCIhs=j3`d9o87e&1GOvRGL}V3)E$%; z#UF=m+7jos>OF%xNbaF<1$BQFnTZI&tDzxd^?4_rth0vIN&g zy6JHhdi!QqQC8d>G$AQKE=E9>BeRJ8s!1rR_wSsPHB{R1HLthpn zB|Bhhkl<&Ol?`hOFI>^42{>SLITW~NMF<^%r6h4vD^bmUqm(I6aZVv79?;MpPCZ04 zRMcjsfV+70yig$YZD_P%)WMd_FJ@Mj>Z)uv?Q^^=*YA=kGG<%Ecod1)Zz8*EB$5au zdc_;MdQkdZQI26JO-%8*hAjXTnp*kW=?yaS42pRkab?l3)A=R_Z~ z-sxk&`T18UNVUz&%L~}`g>}YQ102z46~Foa;H{*mLx<3SRB`+YfR4XFjrD|kgqGt8 zpetyUeE6(~c(gNn>Fw8j6A{D!=nY_gPf7+jLNecrGIjz@MG`mxMv`1yu=OoxZ39_> zSW6`v^lk1X5XZ!VjH_YERVpACK>$^Vh739*+>D?wd|*w13u8RP%B|j5fQwwC&2_vt%g1H#mM;hoX72TM7RS`NZSTz=^4{QqlVqaE+gnKidNQ2A!D=P0bqbk z0<+jRNotLnm)idjkNJ_VSE}31*e8=i?hY-Uk9I8L8Vp}Lw%^a2RKeW?d`G~J3Sx+e zxb8re0eSOVd1}IBY5Y|_eKF1YRiMoT8VqMaof*jf#h;%^cj9w%-PdH{H(_=*+q zJ)6D`U1RBLocoMxxk#({RURQ|g> zJO_of<|!+cz*ZBjqDA4@X~hPtalkbtNKxm!5OwKpb?wDlx3B=2Im_~BJPU{XcA9-o z7BM<9aq}z*AIQQdYQ}@FGQ;*y2 z&7GSa`?8KF=Oj&MbgyMFMq>*=-G)xRYKyJ;d_V@QN|3Qv;f=+TdEarRMl+}fd)a|A z#b2%zfH9o^ai!3kua@a0&Zmok!g_Y|OXYZumC#9!tpf+QoNrCV%js1oE96@^5+Kn&#TG)y3f&)^F+-+vbkIF0)dEw9`iPfoXYya_5*)Xun&p@%jG;Pn^yXyy@B z4YmW=Nb52H&Nvq*VK`Bu13ts6c|WL7$zf%=d~&^16epm(4?>uT=BrtI1zv~Qs5zdR zoob}wPzBOYM{5ku2YTl*t^GY5%Nft{U1h&fb=afxIPJ5~sVHlol0z+C@6u|BJlBv|8;{ba$gP3?bd!-5`xhcMpxy-3`*xf*_sJ z4FVEFerwS8dCxijZ!WLxW<;2k`(F3`3$cmhAn$Q2Q_}QT4@gx7j!%=^VTP+to*4>C z_~+znm6uBZB<1~C(EkQ9OWzz5`(5qnO@}47E*Cvf0CH=w|4mqZvY)KB#Q$6VZ|T{` zqSR%69@Cq3cjkXXpd?<4As&baajYhF1Imu3vho@elunyr_0F?U&3BWh1@vj3Vp7KT zGov4ccYCl{x;O86ZkAhnEHWi{EyjCVRcFEA0P!ag!4e2odvRrD43}733S04Y&DGX$ ziPy!jI8$?#>(M4KFD0w!O>ntEKnciEX37XDYcL$=XkT@=^^w1O>0-CL+n+^GOUcbh z={kKHiLHI^Wh}!}@ZsQi%xK*Nae(z*nSE`K=4PpBLb(GiHOv;f-`ke1xV?O{}TH|b+O$Ir-BEo2nYo>9$XCcmP25k%+d z0?(BvBQV{$sK`b??Ri#mYE7819V8|;*9LOxLP$sQXsE$wu*m0l`+DRMViXe!3L2R~ z!90P7Way_?#&pd)n>}<{?m#RQpUon`3lG4LVxb1f0dy(+tNz-JXPeYy6Mf;Huc~7` zcd51$L`iy9cx1lCf8V)(&6#aIs8@b=MDv&xW`f@-G?d7iP#8Jp$n?IFPNmJU{QV;m zU2dy2_asJoD-)X>UT|1bpc3|yw@A5gRtGkE$v$QJT@oIsq_CT~_cZ|G<#|gL{OMEB zW9t@R9r^vmjM*?@*)GJF7hNv7EHj~(PZnaiyaVA{R!LP{Mjd25Ub6$dDFFPlw?o#*apVJ#wM}(fs{dvKSdg*_c2pk>^f}A_+&%T77|EgJ7fDT zMjc0*7@5YQ0VRiFhD>@^#!L<1+Y$Qv`YM}KnFe>uh4k|XBY8s0y}nuxp0j3lbXv;e z0F!U4C{!IWsFG|F(cM`h-A2iHk%7}~tsL6K49=I7T$V19Q@DZv$P`ef$YHmcR#C>W zaJp9V@b6PI$eNKrQCPq=ULt-3RQxI9mHU!gl{-JbR_InaQcckO3(! zN;ki1l8;#jrhyKP%Lh)LlK|IHHr@8<3}YyfHnd=z5LF=hN!)k8s@2?bA(6FBm_a(* zxN}N~xajAs(2Oia0rs3DFZZ=0sp+IZ6Oa`LTF}F?s5t`P+N*8a#NDrj%l{s#Uk8O9 z1CGVjwh8~`h716f&*Qi^DBZo4^B=I%%%ckDc27^1IwGZa?2>_yk;tX(vaaPK->AVG;1ZYHJ3^VdcG3d^U2>*vvYJo=;$V`FKq`zH zFN1QJkqR($Z-2s1V+aLNT);Zul)1g6+{ECn3%z@kBBQm+r~U`dPJwu-W=>oW7O-kt zFCi2&jefeQ)=(mdU7pf$C+kuZ30-2}{R3SZ7!5A99I1)?*7=dfqejMDL;!Z)y9yXx zL%{kL6imzj5|H#(59AXKmlSR=4c#Z2fvpSv=g4{C{kR4H$Q2^>DVj0z&pZKFX+{g| z;}k7&H)ZqN1i;@JynYFl5zExc^eFe9bRWjt<$SRxO!&o>NfoSnB=pq54}HV2r;$;j zPOuw3CcRQudU#qF*VwU~YDdt(QulUv&ItZp4X~m;z#(zC1aD?**hPN^!IA$34x?+l z*cO-qODIaZ+4J)MV3Ur0mMS2K-~)R&8Nob>awf6MVJtPK0bIU9M>Fz5;|sRS=t7Q@^<_ch?wV6gK@slWDU15`Xu+iQs0k zdk=_Hj<$O6r2ixI>?ti&qK3O!4^I|$-mLp~v$%CD`61R&OW6D)ZvWh}opXzu=Gz$Q zooBV2$V-&zk`c>ri7+xgA7;DrYQ)bXsy&o2wbEqe*u$C?bEq*PLqy?7DMsJfVW$kM z=fYFA*O;kagc33=Zvj^r>ZkMajxWCc-oej*A~L&xlSIj=PAPnEBv3S_+$%mXlU3II zAmIssHt&{w9Yqg)UL$mFjyzfc@*4N%gTah+g<`6En2sfqw2h^Mb5kK5sWock;rTj2 zCK;JWyep4w)hftVs8N+akQD0?C0SuxuJ^>=uNln@Gy$9+xR$G_p`qb{Tk=-JG4E+{ zSHG_%cetDcL5`O@IBNYFW`;zQe}?!WQlFQ~x!rwCP=-Q<{)FPlf99B#e8mM{Uv-*) zgb#BNe8cz$nsbXxQA=ym`ZS>FBg!*u>?C(XRMSWK)NgSUqZYAL4~;`5z#~HN1rgg& znTXmzRqvte@%E_YNbau3`MGDWM=wNHf34A3VDn*q<-{du>(mtR37KA= zQ8)^HZu<2i0Rh7>aJJ!{W~2)-R}?ojEy>rN6-}MZD*OQ1mgy0>!pNhs{hBE@U6Z1m=HE86W1)2u7x?bYQ_JHOuDTQ$H5F`wumChDXIP7(?G{A7k}+w zCw-arr^x1TaeeJfga=cQQ4s$9u!`~(o&?ML+$WJi#P9!Nb3o7hRLBaD6M|!~Vn~^E zeJNcKa)uy;=JpHnagO)Z9g%(KJs_i~@RSbP;}Zi(bcHf61KU9n@H>_)lWWfFHOMGYSVMyQb`Mg=b5i90SVV-=ibT`|9GGq!gq=N#K5?L{Ovc1756<9~~@pDU)&o<{~rX_?*EX*Qszc(06P4u>2 zO3V^5(vJ@+Czp~)Nc z5567IH6uEFte}aKdLiOK++mAS98~Sbid;9zWd}1swPuixC{dDVAXS`o0*+VBe zBWrW63|4%>sb%#rE(qPpr#w#kOd>(lV|i&IDeRT&lzcHP0c37 zf7hE@taeP65*2YibgM1va-xOJdakq>xVAKXOdyXVbly3)wFkhHkTWazT^VF!TfA5mK~P&;(G&!ErW~Do%5K&$>Gz3Y?NMDmK>AH0Q5NA^wvRyJ`IYx)}AM=<3T?004n|1NP4?a?Mid!Z#O znySKCM{g1FPOBiT!fX5kmgh_5WGbeH(YzsSslEvK8|rmE=E^nUeB#_2Blu zs2aMb29Eh@OoqJxfiebEh@AJdjIp) z=N?KtXo#GRw!kgQGBg#`Pe-7`%;T35W`l|c{jwISfh~_gAjga;t`nw9*G4FJ+VaNp zpg{%}EI$!^+uwKhW$2wptx_pO!U4V=u=@e^BoXB4fnGN_#ca8}B!KUomtO<)*IIu9 z$@%nGY3yE!Rp479xt=Z*hqsg9|Fl#!6a;ksqjDn?q>CI268zLgXpi|oV9ZLOzzx)GD(Gg(c0Xwsy`Rl6_ zP#TlU`EhqAn%MitKg?a0QHbj3^-b_g{Qbv7)Ss`Z-a}dDGovTpnxbaWt+wfh@&XDyAyKmBV6KvJ79z0T0!N=HJS*)1_$!6%7~)kGH@qKwk9gh8tYBxzrXpip2=8OiM~Nq6cQ<2 zS;;*;L~<6w-LThLWF7go>xzZvTNAmz=vtOoWRedJyLNYs4w~_85`Tj`WQ!Ii@sy=K z5Cb6RU<&w136g$=UQJbIi>lbdl!_Y5;_5L6a!r-Jhuw!G^n{a#Tl~8u=|E{iu|TP( zOwbPv0diw3PTMMwoKE`@iM-PnQI`T1&~OPYVZDplg+Jl?fBNFzzr7iXBR&)$T11uo zUnvu{;s%Ta!$Dhu>(3zvdY3&J1@kvMQBC5>Hj-gh}H( zeeTA&J8Tgf_%8a%OS8%9LyRxc7pT#f@88Ck1V-kv>as9HaaS3ZUp*wTj1M2(+R`NR zR*1GqfWZ5=5%251bfMFqc*H)EQH%Q3n5!Klcm3{L1bmlkZ@~9scYaC9Jixvp6KY^a z0A$#rWH!yF1IPQqWuwmwXrYX!bvMyUa-IV5i_tI+$A3e&QejbfQU7P6(!#c72_R*}QAER$v=-@`};5OWO{vcuvjnq5NhROJeC(d*|mn6&4u&bg!4tS zLW_s#H?>qrFLyPA>lHKWg$c1Q*SzqLJN4JD2eUO7{jkAr`Lrb)?JK~t_+k5R2mCv_;O2Fcod9v0d#ZPzrC8=`tgOcNBU3YV3_C2QK1)c(j(7RE3$`?%n~6MTV~ zZX)Opm;b=HUCc#Y6nd7e(*yH=GJ0PKS&4J`QLoKZF@AsbXx}4?2SMoaGEb}tN<2-a z%kSt*c7=$`cWdGq%EAGnDrUf#rV|(7y?#nTdLjp$9jU?}c6&Vl)RhB}fEK$3AXf5* zKar)w?Oe)#+m>6U#xX}${qQUYxUGZNTbwVjiCUIh>M){Zib_<$=sp7-rhXyPPzyYz zghHnR{u(>;Vx>FKHY2>+f>PK&>_XCas}UzE<#12G^YZa zG?9;17im_{C4@jx19;l1fdg>fVUZLz#}%LNl33h2t~aOxAyw%>iXKsNeMY}5P4I8l z|EA@CFWzj{<1!B_sUH&2`a-JHWGn)X5u4%gm${Y>;T!aBx?54Pqk9^ot%ee{nE}ho zx>g4!u^ih1b&(N-9p@lkW!le{>OHPuv90Ab z$D*jWzxQgMT>l5m!-H6k21RQC*uC|+a6p-{eV-@%VXfCSa1Q10yf_7x<;R12f08)= zHm`;9xWUdaMI$yaTKn0}yIjwzbG=tJ=!Dq%9qkYhwn{1e?+`z>FIQt@J5@p~z&JWR zop?h`6-9r-H@bke)xexd2yv(QTdgMrL3F49pCc@y;LYb9wJ6H{j*6tfT%ee>>-ODx zPdhd#`Ucvwt7Z}9XPM#2ath!-HBA881CHO_YK`erbght{g71FIJoe--R;8!?$oQ(u zh3tc+jU@%6J*VL@M_h)XIbsOf?P*q{A@jug`D7xUKLC@}>NdhFT*i3ULz7XEr?2U=dlqV$X@b!TLlO7-FvJPcY!uygWUOG6@8A zaPZWv$Tz+%zqnd!zG9FXZ>Hq`U0xa8sSMzBx4a>dG_dIiEDg*53B#Ff&|nHa5?Qr zF?VwF)GOVC$6ic*pAynlX~TUi$ZgLfqXf&WAWO0RyrW|^1Ry_7gAiD@4~;DdIHne# zRD0fIUSUkZW$y8T9H&>(-X}_cSbMC&`vP+-D;CEBQ|4&1eSve$$oX&&c7)Q89>OP9)X zxFyIU?Vet{!>}>4er))^bTt9+bn?Pso%`286PxQnsaZ6nFb6d6k(s*7<7s?+d{C1N zoEGW&cRT!VFWtJOgXa60mIBj8i8zK~vc(q-Z_*toJOKqGy^erjy82v@hi>;nk9J4h z_#TM6s^R;PmY^mGl~h0|^S^_q(up&*1gQ&0$|q>%QL>cfmo;6wr5j6Gmnm2ZaKEn=hAA3Zx0 zME?g<3eXvHtpocAbVynuZMdis)%`IN*zh=~{fih~_UB^@q^3_m}din}An{UHFUG?9f%D)pfV6ypaHn7d9cfsl;n8Gbl# zg*)sMCtAh>jk_XkM?apk7X?l!q5g;p!;vzsWo?&}Z=+=dE?0S!L{IKCzVwbhLe|M!H1C@_u!_Flxo#5h7-F0?h2rRM8o3>BK$*R<%&Bxd{CbTm;muS?U{rv{LU-UZeKauye%;b*IN=#6|B%>v$UgzzweARby z={(c?>pYvv+aS>S|8&@Y=1nd6QPt|}=^5{q8!*t7SNPR`b&5`aFwN&iut5NUkfWVx zI8Bf7={Ebz=$Ma7bgfgR)h<|8f&BE7zxT9VI|xAbht80iG~xXL6%|#cr|`dGMXz@{ zg>)mR4S-zJK0W_tTm%c6cqh_dX$7eN%ZL~dZR{21osW7@L!Gwy#4HazN|eJN_C^3Bz#|f%)(ee?13-8yE_l!d=&AwO^%{7ZQv!T251Z`5B=%?;VpV^z zXb#WVS;KJ@NFB&z-_W7r)U6_UFnY!SQt^)p5kO{rttP0_HJO0U0N1=k-|msJhol3zg|?Wsgmo=fZS245kD`^8j;$ zbYpRe@cJD{ICIkxrMaex?!;Mr^F*9`1;Ht(siQ-}%uBwELG`h+gTX`j66g#y0K-m0 z|JvRTYeE%hAkN-9?2qRszj%dF?PB_H#UEN2iBVv#s*ewKI)#vmSrpIJZzYgB7tVhl zNq#Jtv2!&wA(kyUA*C;tr=bdR(x_o^#OsY*qFML!B@g&{i^qg`tVAu&tt#wqKn5+Q z-U)}6|BbMIir>1J`x9b547&3@aokDb?LUKu;PB7pxT!$-^*ex$RBxix`UHXGhdFSq zjfyA*6izUu0j`W6j<|%cH($xn&?s6M4x3f zF*=`RptN;|nS4z~%Qq$#3A8b+p;fPLyg29s)*Dek7-e>`gLHlgJlNiCWWl=+6x^>6 zKKJoc$=?i9g~#YM1TU;sjs%DydQZgEj1JuO1f68$f?{a3h?cCV%9k;E;O|P(ve!?k zEWYxG>aW@^{hQ{!SqlH-vUl$fHii?$eziXmsqiy@A{v5Q2HcA%<+E>)F@vqJY#|_@ zF9~CUu4@|0(=5jX9TBG4v|p#yOLaZs z2O&PwjR0B<&{`~pOxr4Qy~}xEs{cXw7%nu7YX2+S@~gqq z5Hs2I%IkRdwq)3n+V9i6RMqmz@+|BrfoR;@GTCnW)hjmr{lDU$xA$*<4;HMZdEOQ% zZlDP>iu$S(T=iwxnVK>S;XH-t z;#y6VE&wORBz~_eKsKZDfJpi^Dyf;zdoBR-Q{~}2&>8|Fu^~$;a+3(f-nmKOO*lIY z^u-@dYor$y?fm4=eaL+ngiXC2*fEsNi1?Bi+4eU##p1XEE_ad9|#5JdU?d5*R< zFM|3PpPk^WgcQDHL7~=(y6X1b?<3&vA2r2y;xfM)ToE0_{ShAhxFhWbcBtR4&f~Qr z{};~4pyNf){~fspUKBT;c_GGEK4$y9dZ6%0fzDX8ZsovvvQ~egg1=!8A<@$TjBNlm zp3`(Vvw5l=C>?nMi58&!EG$bp;6IRHw3fhZsX+G@kvx&Gll3i{6r-V~$3Bb?p()B= z<9b4H!ecI~&7^yDd_4DVDHLQwBhZSDkP==%OSzM5kpeM|hi9jKy0=z1H*s9ymgc4_ zRo-ERqBf2K3sy|lF?UoM_UQ;rWs-5vQ?KOP2ZT~x`{@%USdi5THO~Ji-yKZBcGkCA@ zch7u<@Y9D~sXtf$^^YX;c1OqiSzqp;P zmt2+{HeK)!9*UM)2zMN;^i_>TF?I3)h#(RaNfis(R}_Ok?#b{- z1i!6Z@Vi~3uVG{9FDP~%>qb3r>*LOQWp2*nh^YYzg8qusKa@ z2rw{!RkdW&mARaP%tmaPI=ulwOGf;FQErv%-=%X(J zI%oKs4`%1jNA4~19F53V7k?UlgOnBmr+rso)@JEBFfUUFw4th7envg%cd%A=LSa|5 zdaG|Eq<AaB!tMZrUBbo`#ZaVX-rYfaNxwp>VCJB{{>N|jk`=61gms`h8yVBV(lgkZWx z9lu$1eZd1}QwPyfa=Yp3K!P0){5rq0pR?6&B6JvCxX-!E-z3Y@qRU!Xm|ViwsW;NY zGq*qU#6^{HRidZWI%nxKy1=h9DmD245+>$Q=6n_{+VE5md4U#s5LCFr-qUHX~v@!J!)VvzIQnRdQq{L z%Gvph*}>U)de|4hjwc&yYQ}NcCiGB}=H0*Mk*J}ZoIgki!(rECT1yQ728jgOLjKdA zAFI*YSAm~8(31TQHgXHkX+&Kk@ZOC^{MFhPNoYo>;$Bpr<6s|4dif^P`|4 zGci&xH<|(}`|xrd@{G?mgVK7g$y&SOL4+C1t)TwGihjO|E7 zG&puo(>>M24eDJ1>AN&bDYm163L82Harv6HkmyTy)dYkWL97rW`?|tt*sxNRLHyYGis1tS5wPcpiC(jc92D`V8jw0QGc5qy@K2RqM`-rRVl~>ry9Lh%_ntj!FAOhlsZ9v!MDK`d!M7 z>r4DC?WqwGVz65Q(&h)Ln8V{sE$1C8h_#XN-`)04f8AU|aQTe{E`Dms(pl9z3@8#N zK#2i%;&c|M*8%SAL^T?*T_ zfG-JHR8&|GiS5Qrqd$JS_CJWs#NNceUURo?C^y7?1R(U)775lvHoNmOvT>Q*HTs52 zaf3`bzwk>6`lL9Eh2?m^?04uVT44HqOLNUL7d4mFlEPK&CAElJ-W{&Zw3CO=-0@%w z66dL^?^BjQnsWd&dou78{aH#KcdOF=S3U6(g=l^})p6NBh`q1K$-&UsjsG{Q_O{JG zc#jNaydj4EK6lw}CpEyFJrm$#iUoN=DfJ&6+1JSzj!o`dstneRr*%5jyEe(x?+tmbVxVWGEW^_cnPF6|!HvNc@ z%fpAGS#x-k8zy86Q6pb~akS+QYqtrj^n?!X6!@mo{oY6wu+aCizStnN!intc>;zC^ zX8^RQ;$mxLjj^XlBOE3Aq_X(-A6?wtsj7mK5}E%o%s00$k})kiREWhVG;-i$?=PP> zo$?P<>0=4&)m1~(AiEpC#rx*J^D$5Px%K#u?G6hYEf~ZzTmDugOo0*uU(H1g=N?K= z$Oha39@1~3>9(+4z|Un4AXC+HZO`;42C&KO?>>t&p%sDenM5zE!JnwtaUv$-Nc>qO z%qD-h$#@OQUR#`D*ruwCQnGf`Ydn*+lOi3)3#@(n+Ymx$J2d^w>xw+dW1%%KClwj) z-GB267xyc~+m4h(Ogz?|Z+>V-r-+r%|*6n3-VS+DCXgTqhsBx z91lfr+@i0}0s*0cJL`6s%;vqhj3g+*hfUEkJWg#kP}HoB!z0M(7wUsL4G#|wjAd$i z^QF~sy_xm4^$Cru&k3}G;bPQKX+5q)sr0j6MFj{jVf5L5Kz;u1gE8Jj$ zYl`30EVP}jVUC%^r~Pb!irC^emV-6X?rv2eLB_5?Wiz?jub;c<>W_$-95+XR;;S{l zj8Q?udLz)B5h#z6HytVCZp}ReewYng#SOq+Wp%6P|Bm!Xc4Cr$2+vgq=2F-AIJ?Qb zY%4B%{fyrVU4|Gt%ko#w%b2Iog_q1CFq6Rx4omRx zO}$XOR+3;?4|VC@E=s-_Cyuin;ukq5Ar*pUH~2;lTnaC(5l$0J*Y6)3(uEv^loqtk>$Km%_oHuZpSma@1qEczD_^0Qb!2n z6eULBwM}3Jfmt*TQ-D}zl;oyq0|C%j0%9g`+69>pDZsjUtFDDYGqOz|O^YAZp3MCL z-+X;@v-}7GXxIGv9Z!L_sJfck-^k#mH%5-7t%#A!zXg}o46zsZvXIFkvBIndb{;da431u3##k2(lZ-oARqHL;5_K>`ay&K-gE+KVxf*Nj zGKB+Hh(tm+A1Oq*hX%@Cy+>W^iY6Lp*sDu*^4M4U(aRXIWDDUovETqr+ws&(HT)#& z$uZA*ir8XVPT_Jd!x;VmpnH2S|8tpmB3Tex0jOcSy3Ra=P&{Wh>h4rNo-&r?YLBLO zoN~B`&!**mNPKV_tjT6k5*Tgtl5=C7teKtqnL&eHJVjhDS&SSkb*kZF(qoZ@g(cbJ zcyiBW&@IM3AZ;mx(YlqqtM~G1uWR0x*}$F)cI!S6J4c(=CVp`H?{4_-YRT+(#Pw|N03x`_>nYlAHFj6@sc-dpg7$CH=0KSnBIr7FiwT)QU;w=1~rnN*E|b` zT9TrssCLgX4m1@v?WRTrgz#qzzgRkcCGt20lf9Yo>Vc=H7qQ#Wkm`eW6{ZyO!JI*c$>$0x=Pp7Jp8PFrumEKuAA}8qL_D`-SVIVHUlg;-&@kz?zOw^ zdg|0%(DtRyolFv17b{5IeZv6KpUeXsB=9~|6q~ZUI*&;ef#UDUez=$W)dhka*iw9Y z^KqH=rm0H`E7rt+THC_m-&%hMNl)=sN%A_E4qq}3;-mMkSTGI2(*PFtut+lZd7}$FH>9(n| z-uizg2t{|BRDbZ5S^U%$jpR~Ss6q2<&j6HDY<(~`SqvY0s)6`vSM})}?v$8ed+d;? z!b?XP8Qrx`DNFidGwXSLU)#FhZ2_33oaGzM*M~ohWC&71g~cK*aT@sZI{sRX7KUs#2lt)W-OA& z4|@g-8dLYAbMf+Xiag=Am4anL*SCOCIspN}3E;f|!vsK8yP+@rJ1s!X5*_&Pg}Ayt z`r<2q)mcpMlUaoAj!P(#l-gu7o6W`YRQ`x_2v8>ig~$tlLa>N_^+3qr>tPDp)k0l!ho;xuWfr$q zbsz`AeJ)NMDaTVY>og6Vo|hSbmURmBmyxXWbs9ept|)hBq_X}aQfcm;%2y9=wujU4 zqdyJx7W~9?I$i3F2fqBJZe1j$vP+^X5ot^C(jiJ{%C`Yc3Q~;e6UmgcVMltBF%cF; zChk*)PrZ=+@JF7;DYqwQ()7^!gjjD(;E)~_`wxx>B#X}+na`n>%}+P->mNn?j9p<( zRYhSW)%Gp#TzP8j`bF~Sw5JUy2cD*N<}Q4^+A7MC=CrDPVFDsGz+651d7s||M#gtG z6#fzj;M8eIo0S?us-ODOM%RKo9FQt?Kkw{KQ!A3OoXVT=>TA09S?gO;xzauGh`bID z|M>S=`0prw^3eBJaj?+CpAv~O*EB7PK-D*sT%6CHwMg)JVFgYp>oogH zAA53}=&hOGXC$-dONeXTF6Ztg$om%VH-%D^m7jz8B*>(g7Iu9i zO|7hWbmf9M)TSBeqIl3kpNxkS6SQwzh)2;VRJv@_pGP&$)DZ_o1YSDHPL1Ud9(MriJ{FP|^>x?B$8`|JHb@plV;e{I|Yy3FC*#7`lJ z`!l$4zf-GI)j|n}tYYuj$f9ZPWyf5L>5_E)3@M1M z#T1t-d(**Y^j77*FlU}drxlgHebM!>lt9immJ5>$4y*p})5VG0>4p)R=@dxePax)% zQ&l|j}LCw8c5-+-tg2>E+JQaYEBJlYYavc7?zMCV1>RV}; zX71N)K~iOzkA(4Ut}78e5`pfg|mzK*x$VstS)X5Stend^u+RT@&n*S zDZ{nO=;@(>jlGyIgRAs?0`j)*2@|v2zLndUE{1LmY1$3B7Bev<8JlwW@(x?alh6y# zVMK-s3PEHc5wUu8^_E1DSh5elaGpVL&aeBFqRHFMCQ%=;X0AL=p+UBkE*YB8KvdBu zN8hMHP!JB%A3*cWa(G_Li%gJvlE>+BS%r^bvY?9`=j27`j`2h@CkUeK>SjP$7l%eg zXA27AsA~PL$N%>U`OB;lXZ{{>*!H@B`8b|{aw3(&L)3%1i>84OBdc@k0!b7JZx>a_ z1CP<6m1*Q*7wJ(NW^T$CU)a4nCiS4P{UkN(MB< z5x1d2h;C-!M_Ra3^y#GgghskW?b4pr4o;*yAAKGJ8sWR2@2}6juJ`D@5U_K_wc=vB zR(vY@7G0G)&g&-tu3&ckR46%t+4u^mbTlpa;h#11s{e;Wh8!yW{`W3M?l(xsPfF(> z{!ukz+o427XR2^;LCa(Y!6yi9sdljf@gWfHAs*{%n9+PV=A?7m2pF*HPh zF30Zu@@?#8g-;rgfTW2qrSdr2Lvz|Vb<%`+!~C2Y3SxC<2O1BH+4*n0L=fonDPAw{ zeD2NwUImL7HjzLHWeP$*_#-_0gDg3NBxM@SvSSZ&8R=|CdX%YvjF_HO;^(u~A4&JS z%BcJgtTFpaaJtH!}2Da{BrAcZPnNti~wa`!4+xC%j=HKHHVBJ*Vr30|8T@Y3V<=qf^zfO zXr$=N$sa#Rkp1&NU->4Mixd8&mx*T~S=5sB*+0DIu}anDce|F5_2x z*94cMgxd6TtumN~)jPz)WYg5`HA!Nr;iMt`&zhQ5gsOqY6jD|W_&gxX!*_&bM}~&> zL2iOxqxKh4Pwr+G_yajAkZ7Bpnxcr$QMr95IZv*lyohaDwT%P0Fm-OpN<+Qm*Zvkz zP}n>RkO$sZV{&MY5GXjP(j>@<`$wWbHGTTE6Su5P7dG7qpB6FzViVvgs*Hz=xnx@Q zS+he;;`1&wRJKsaL_$1<-edO>u3m}{<3X2j0ijC0h>(RK$~91v-_xeNG!F4G{YUUc zFkuz`}kI%IHvAdu3I=T$zC!^OiFhd}qUrk|C} z&rlKXdF;9EPyt!Irp^2UtGbmqzy=q?)|b@Qo(Jh7upWUhBkvVl zj=v&-qX7_Dp2IKq)#sBJ5=k5&h4=8o>tyT8(^lIqv;v+a!)+--Ckd!$ZokH5+-~aP zYSGSODm_kc^-B^oLCm_#XTknY@Eh%Aa$b}V>^5o79A-X@nHLh4srQ+^24D@lIt{Rm z7Hc%SUP?CzjRx|1-R&czJ7iaMD&#S7+L>%_uxt*PxSa09tX};rhpQ7zye(B!Wt$l^ zD+#Xv6)Yq>-;+`s&IFuYijF|tZaX!LP2GWLAdG-}xB2>tA}A_t;nwT2yCIBrr$5w; zWqvDX$ZdL;1zE~5ThBE%>@}UA06jXOT=(IXiHS)B71d2u;&jB`B%eRY!2VCK{QP$A z#*lTR@Amr0_-H$ z1Ae~1xraS%aLumn)q~2hs=2Mv;$nNmG;+&pxxT7Fs5ci(ec3zvy9MT6)@WG|ru=f& zv!({$0e;4ja~229=q?Rr_dKXAgeW$o>0UP^DmW*+V;)ky{Z;}Yf$I4e2>kCyY2hz- zzF*8)?RKln?eHKZdZ!exn`HvGg5*`~TbOBIe7~)N&Va0Jx&(GC)dKxnMR6#Vx3HXS zmcTzPcZDz*+e=fdPaMbU2JF*PPI~528n@0(H8lqvwND&1$1k@%TzNH{FS*(YDd=fw zQ-H);N8r=GzCM_Q#5-|cI51lKbn(wZ=kJ}Yz=d{y=P^PWKc)xD)K3uzMBQEisP$}2 zQgi#b7XCPTEB>6<)j<@2PetO@GYRGl@N7Uq!({-pXGyYlt?~h3dzHj4jwV6Z6iLxX z(4`LcCeO>na(@ODfo4+I*Jw}Mw9;L3)Xl>$E*hdq#iK@E2CCVO7Hx?i&cBKRUz3V& z)(N^x_ zHXQFof@~=*P(&L_7q;!=hkP~`6uhHcP*CvP@>?QnfpW>J+&ao85Vy%31Qv80UD}F@ z!h`SJQCfjr3-J8J7I|%gRsm!}uFXjn)@r1C!tq#xiWu!^(5gUP6lhFRl`%Z4sOSb2 z($dDNNSkx8O9J<-2MRjwAGmUVK%D%)`-d{Ofs@X=5Cx3A+Y3E5v0cK@z9=Z{L0mkW zCEi{)5M9^;oN+(|0~#qDT6&4(-}}(K>J?5KxNQfMW_47DG3HZYvk6U^Xvx zbh=+(ec{zD6&k$hpg-O8=Suv#9+c1(#NOJR{oVkNu9*hsJy5j*FavN#wI>ts{0Q`E zKqQ%P20$uj$2&>lbs*0H5DLJbOpv#r9Zs*!(a;P&4h&A0!s8O93Ixo1IIjvZw@U7hahgBqQ%mOqezHm}A-b#;l( z9}cAQo+G~(I)Q0O_C{vx81xkojU)h!`o*uo{i6lS^j4@Uv>%gH7s;VnS7yT1;e`A^ zN;tN_y?&o*mf3ms87mY_pgi8F^ZDZQYvVYRV2A4bV&jB}Ki$R&wY!ks=J(sYvToPo zpRUnGcHz`hO&Ru9UDwC!Ku#0vd&j_)WjW>*EOo*!Ai@d!L2V1EyMH`S3sJ5Ez6#^(noqs|?zOR7|r{h+H_lJU+ zFs(?hk_6`c9+?pMddW@W1cK-dgIsJF~C}>;p}otaoy^k!0C|q#WQkXW*NN;)ZrSj+sHKsRPo2e7J2a zWi78k@h1Tp2>=Sr%Vu87suOyC42wX0k`@r~-QReiZ+`2*~VczMPp2ea^Lu(t>G(5bl|O2A-0NH7*&_n5Ag zhB!R9>-J=abn<~bhHun4r0B}a%J0DMf~8YISf%|y|##hZ2s&5Tu3AQ z(#Ggk6vX}VtP1#eWoNGf0|Oy$ADe)npofb%i&wtBz6Q#;a9}T{>v{o%Y;EPdE>8CW zjzhwqi{TY}7%n66T_Ofykk8iA(wZUX=l2523Si)8DvV_Unz}ulPwf?q^R^8^B(@wJ zkai1D^`I*t8oAmcc}PhBHZ>qUqWZcKr59+}mA>nZxc>b4GtoASgO1h*$#^}mYxuwo zLT^<|hCSxmo^4?N!deW;!Ca(hqxrpH>hDbTWy+h&n%Muv=GGP^a{?M|=IKw=U&Sj2 z=iiSc$?ERbbjV~R*-8B}Ix&Fs*i!V+*aA2r#@3kp{~mr)aiByO!=DWpC1quiFCLJ> zbBnLYHI+a8Lxgo#P~c70>(|{SpC*9ZIiKdmgz|v)uPM_??jB8pRUaljnnfb#p~?vjvlHwK@P9+`@Kufo7CfC zvniRNHiwFe|GdIwc*ewHF>N&+H*gSr3xjjbO;c$noIi&U3w zqYQi4lA~s+$S1|0oTQ}Uka)&6hVA;tD6uqssoS&nLS7h8k^eGwonkP$Pv?YV_gL(a zv_l`(>96<%gtTPWtE&#Rp~!Vm*vkI&+g4KToNv!`yg&tC`o;bJS>;XTr(cevHw(5> z%X6li)6}vg9HoXN3yX8kJg$x?g6(o)Z91rN8J6uPEL3a5``f(%#iOI6MkZ=klQh=M zPhcR{c5O5kPrKNt8T(?)`f|+r`q;Xw9_c6sHj%A! ztqmZ5#XPV3h0jF_xP)Y-ArjIy_D+*pNxxNI5W7wZGpnpzYA)L}1LhOm)a6vkrJ7JO zr#%^!Ax3v^NAgKEtyi?TCp-PdfDWpOo_EvfS9&%gzHiOv-%b)@bmIPp%DvP`J21o4 ze~f529ZLH;FFbjAdpG^0bw{~aBa&u_Kcfq0Qiq{CMX%x7dY*Iui7k+#`Uaj>%F4>} zGQkdCtq5-2`Yv4Jw$^AD{+6C{6M zI;cpnTQ!I#m0b^@Ts-zU0*hPvEUtX`51A$0BSg@z`ex( zD@|^_y$EZH?p?WEoyc)<^)2wJYt?&r57p||75l7}Q&=jp|MqlboS-N3onyQ#`!jt-WMUlKh11gJ*k0P9(fm84OZ zCQWHPi!b+INGfdQcv$AXp+QEK?|}J_v~+Uf>8!+|Qq>|NfH3&<$#q)E^$S~?F;;@d zn>*Kgf$~qk{d4y_Klt{y=-i5uMSdy4r$Y&5x?Lm+?cj_@xieG8Y;*vuqdl(<)2`c| zHU0WkFG}`u_h+Od($|S^xEY|FPQq{iyA1!af0-4i&NUldjp}@bfrmizUE2PNh~^9y|q2!K2n|U^NtYXB(@iwi~(Qsr0fVs!!{vZ#bxZvgj~1J5ro7yyJf6!I9C@ z`r|5K*W^j}HEJ38u`CgGh^ALLgH?1gy5B%_$hrx1DM<{G_n&hRNUF=^f^X$3zpq5o3F(w6mvsGG;3ebBi*VHCt zgxtMUD`2dJP$|8q$GV^tp)~gO2*`@tfg|GAGaQF9Fe89jC74p752*;<1I))>wjgzN&O~TzS5;PYbEsT`b*k+iaLL z{p(gq^A-P9*R@L1!kK;83I+a#^`rI$2C5x|4+`w{%k~&iA+TozM^MUUGdm7VKecUg zWomFdn7ZXsE6n;$sU&Uw<^C?ZOaPKUdBVN9QjBKk64`LWHZEPaW2I5Pc~;O`Ow;E3 zq8A|EC_d_2g4#6+X`;+A@2{v^Apa8qQ=uP!Qp}pyat&9a%0p`4>nXYML$8R&_ za{w8sSQWpy5d`e)$+fdgPqikb+&>|9%B*%yYF)zgV%5`rNk1gy9yUI@7GEOLq=(!d zTLgL(QxXbvwZl#uFuC=aU3nHuV$@Xd=wIXO=MP!TmS{icUSH=$#DaTi*MgFADvfVdU3A7a*^Il-xphMOeIy* zz0Oo<3T>GVoo?5HWP#@IAlcx&1c*Ng3MO^g^CC%N`m34W`;d%4_j{eO;5XmWX)VxQ zGWh?P`s%Q#x-VSp4-f+clolyrD5a!TI;Fe28>CUBOS(Zx>5=ZCrMrfdmX_|ByAS^E zbMN^>eULe`&pvyvz1F+l^)7#@AbIQ%X-({lgFFJ~_fzJ@K4S;=$`De<=d?IqVKD(Z zZK^~!>ke*ZBo;fzSFzX~RDH#XZ@ECkEEFb5vJMag#|ACjdjne8LPb*B(l zhv)H{_o208C}HWd9qkd+fez$S5qR!(j5JB6>snnEAh=eadPQx|xHV8b(K08oL`??X zJ}@k*f?)a}NDnHn90>@CH#;-Gz&TJ;)6Vg2{x&CL#`Dy*PhBl{PG!yjX%AZZu`%?- z&t95n6+3I&D?Ek0y^46(U>LdLZCFBsUTquhG6nzh2ZNVjfb) zVUXn5<^)whg5zzvl-||@?+N$o%)|rEsF(-d!}gsw*bnNC2=;Y@G#ES`zFpKgY!#qw z@^dq{|4!(`Z}mDL z0RZ7=HFypT#nx_*0P{&;i_toXxLr3_C1cDd@nm_yDm)tNZfJCXGuxjRqhJgmy<1^;dS* zgVXPOLYgH(v4MerF9ulZt$@A10Rn39@#>lr3agP0Am3RHOT^VWpaxY6se3}xd{gqr z!_e(N;8{R@yLuvD4zcQFD7H$(2+1sbxN!@^N5k5PGOBVpAmvr$ii-oiu$PPf?tK^8 zuYcf1ZfDvqyDD?QR|1*S%M&zep8NrbFH_Dy(+=EZu*m?~*Dt#}=FeAVyR-cjY;ziam>JnfH*e$$8vPNGPC?!KkBuiF&=bU|S6e#aEx(IaEbmU^C69 zUgzKqgBF39V>XfV`^JrK`>__(r5odxhftnByNM@ob!&-M*Lg884!u-fAyV!Pp{!2^ zju{j2jnoy-@EP~Lc*qzzCC~YCRyg}8bn|9GLd$#8=BkJWc@WOC6W9kV9T#AZ0GIYf zaNP@(TiY*vOsj}fg~t)Gq8&iQ&l9vnp9kFE>QwO57?1>Zy!qttL<`EXZ7G`|2XaAy zy45*(WSL@Z1Q|nX{|=<9Dk=qIY^0KiG#t}(;FrD?Wop;iN$S)O9oaPC@9k3hZ(^$qJ9;g# zF>3I8UPXr1+7vw{eCc5D%zYiY(bx0*Vnk_W)JTmuqa{l=LELJH-3h&_WNF)O{|9Wz zHGZP7yS~kfqs?GR5DBtN5APT68k6EZH=d5SdHg!m4?10Tg)TqNTzfpfw*$$cYRM)L zN;$z4iAp%0-tWGArwM>qa6C#%cDzwoJg1(Z+zFC4acS%C+|Q#{B5b$=eO6FLiSghl zN`~M&L1lqEqorFvJvaiUPb}BYMpIu?cVD)oxR*X!cYb;;m2=Nv1c~?a+PVCF{KIcM zxEw6;b@yY zd*Q*LU;cwQ3w7uYjcw3jWEefcUID=uALFkXyG|ijm-ENU5dmd;DP6c{3yyC>DmM{d)%-|N z#RTWYkg@)w&AwrQAk7yf_T)8#zrCRNa%K_2fOk|=Uh!bvD`#xHdnjkc%wkE6Suy{P zk~_>~2(4qlKe97HPwss(rH;xYAuGit2B(dSi4EfFxMRkof_HmXXsr%owch{VD+J#H zU4qYaJdW`h2l;Sb=$w_V#1$3wdIWV#rRJ)H^OChhu;>!r^#F2<0g~pvHJG%OFE)k>#p$He2t3(uUXI za)m$byY7RNDsT&^rd@!Nn+wn?5x+~rrojog>_BgD`7r1_$TiVgm$L1$R^Z;QJF}~6 zT#5FHq451UFbLh3SMqJ`f$8BN85fyFLtl^upZ;q$3I5L!Dq(p@0^4&CIB~GBut1*! zN=e|U33@BN;dsj8#$8Fcr7Jdeu{(NpuXcTwhUh1-Ub^)tb4`X3Vj`9plwM82%&6DL z*N3_Z-+y`Us1E93&$_S2no(EC)jir{2EL*wWwFd%vCFzZSyA3+d!CQ$XbO&W!^xh$ zjz9UIou{GlSkGsXdiM(ThGp zzC-Hmxrwrg&95WMn=W;RvEe4&hkxWxHq*)nv(FR9W#nh9hD zS9cdaZZxpHkb-a#SYW*jf7G#!1z1dugO{(bfQs%M@btl)C11=x0F&}$5AQLWc5(1r zp(QhV-A2?hmsnmM*LFSYLU6{`6x)0@~fm|>9wCQUM4DOK#JrX;oefl2JO`MjFqX^9g zH+GlU%~3pSl(wm>1!-?0OwL3i#z8g}w>z7Me2<*6*m~M|11PP}g1%t3T=l>q>0w69 zI93Lp4h0G*GnviF^%o}0C4cXUblI8YEY7KjCE<&_C9+WvIfLA` zsRv!w#T~>b-oETGzDIMCf&du!%~o&KS|O=D<_j%GjK;5{EE6MO!=iFW{hda8<5axctQlY<7XgL1rD*n{-3`H(NKMw>-Pa{;K6^WhafA;OY#8t ziVK0K%d`T>(A2<9K2W}bIFv+CDKFkd9Pl6xUJD$&M(i^n_E-JgUbtSl&C^Y>^U>+p zG_$Ch7iG2)D3FP=6NTlRJb44$YTyVZmwyx3qeZoW+EKT)RF_JvY>}N{b;d+O40L=0 z+9xWL`v8rWRXVxd{>)4yGxX*=N->{i3j#QrDpxD6FR0J5AE~!Qp4*35V1`LvGe*78O?tvB=48EK9V>vh)NoXq4EgNv+f)Zt?89tMqn zIc^XMj`EZu{))Y;t}aC(>~V21XT~Phmx3g}5>*{l)+WM6W(0X@fns-lYYiXX(gSxO zfy@u^M(gf2P%oafmYui%Mbx64QWW)u7@e{mUCMY?B425X^|n3eNB?KM;-i7wJ*C49 z&>I`Ium)7*BT|(<-r1Pg`Fn9TMs@kZMC0?(9bbkKkLwB79g`ObSzMF9Y@GLJr(=TM z)1MB|4x;pk?I5?}C3fEF4HBk1nzDz>nqM;LPQbm6OZM`gEYKQ#e$A}1pVm%+HoEdj zHL3XVnbh^;D}e>~XX;K*ULQ^sz2$)I9?*-M)MK?YtTQrQ_h=w zvbrIu33@hjsAXV6P8*$AS+>sC9fssB8C3H<(57$l?uU|c(ew|#|65SdUp`f+(*XX% z@0Raul5&b2Kti&_>!<+vIYMbi)cgDpAjY6KsJ(lfndRFKTiMNs_Z%vESLa7Sb$x5Q zn$eub+PSvL5HoZn30FMoezrshXgch@Nb9u-^ufJO>gKm;ns6qjo}WSA)TTdpZe(#U zE2+Ih8_?nkUzmZXQ1b?|4aH6_aFARaP)4S6JDIm0k@zEU+aq6y8eV=*USMryWJ@z#KpXvGjVS0Ypk5^T zo4%(D)c*A)ur8&ntp_VsJH4WkPUCe2sb*J~XV&S3P$2A5zBOmK)}OlLhk4Ri>fn(5dY@m-ozPhsr_gLo2i@P_4;lsI*flhq7d#x7yOL%i2-)F8 zlCA+IEM)F3Q%+r$8ogERUPPj2IREr@h>yW$AszHB?wzW_qLE>13-2V0Nz>;wGJX$L zn%EQ7r@9;5K8fWdqz7 z()t8-e%k2|APcP4{Ado04C_dkE{0s6C(3qk$>D(NV_0;r~`n7+eHnw{f#&Z2hH z_9bon*!j#Fzeye?ssbDhf(kK4P%bPX0lxehVI*bpm&1#w(gal=)*(E6BBsL}%Oqg8 zsK)v2k3VimyFSS;Ygpy0i$%9}pY+g9|KW*3HN3{!y3Pd(H?HS~K>gVD#md6>%dq!S znbnR_ykWUkd}ip(s${CHWsMk*}%Y)jpytKr$O^zbiY z@1u?ZbJKKTdK?L(XLxt4%vmMKMGw$eXYbn~_35Qa#%F(`96`R(X~URJAyOH7Cm6pc zBH`l%69cPahWHO>qR=}9XFJCT>QcQ{=8FF~xy3)IWjrg@(_@0|Z%975^z=VEuae>D zH4ZxUQ|ciY-xC0#{xj&b+ZdhiDY%h<(^#NKsO2c9e85XSdC6Oa5KlyMM2B3BV%LGlZfb8&AZP@$iG4F#atfC`kNmai!<< znJyU1@3V!`%!4skLOT-lA~R~ys%n;|Ydg9E2_#n*N?pRFHvYR`!MarFI0m>Pmrf<_sUH{!Skkg99GT<KhQ-U=RfJedZC6L+F6-^6RBQMf% zexW;TE;|5Beg!#?-slr=0noLE+uJXPru*?k?DhwipL^#9d4KKkrKR!zi`M$lmL)=S z>7#v=uTrE|whHKY^AnB7?A}RO|I;T}8f6X1Z=-yeBM}+XxEE%lS#CNskJ_G>kf~Fb zM&4v+NPl12a{&K&CsL3bTggD|W%IYZwLi@o(TxTIYOWIP&ffXavm` zT%4T=LfYA+@7=w-{KoUVoI&mD828^z$y29?PiKqgj^lcaTvBK8dscM~tty;FY1onK zpNdiMkB*T=w5G3>1dT95n@C=TIYj2xLWqnY-jip4H}2n8-74EQ6*6Bi1qU1-A73}! zo&+b`!khT4x6HU9rG%AtoIr1n`LX!_3dFxaUsyi^QsvfHKmVWDBxNjy$9j6W}t8UY;X%EJH z)RRr-?**Oy7^bXdNisf~3Bq1XmX&_#*e?hxCn=c;jal{V^=R;YXn=v>v>O)yeIOc} zv>(ot2W;GrZf<_diEi$rLTdf&IrW?eE$)lVje-Dms`ExPwa<^@$Wvu$b4P&kVEB{@ zcj-4}z=U6|5@zdEoo-WjnJ6w+iNZ>k&^hfTYBNTA4g>5v*XEODJA=W##V?t@jP5Yt*+ck~7X3*hRFv zGonh`FVxvk8ns$!Z83a7qR`V}e8Z$l8>Onqpfg8msy;#(Ev&V8%`N6$X(lX}>b=eH zDG=W>TdO0Rve{RjMOAy;b9N#$g@R`jN$S7^-y<0aF(sG`2Z7cAzG> zS1+dMn^a%|=1@aKJwua8 zg;vsXzLC%Uy9pmSkY-DbB**uzmIP3lSvsf{9j_jZxp&)vvmQa` zB|L|k2|9ZQpW454`$vvFtYBv>GMJ6tr|&*!6V&a+MQ3aT&3O=<^P%MfdKJ z4b=5{FQ2*$AaJ6AAVhSoY|6i#mk+MBUs`zf0r6HbhF8JLYgnKbr8q znn1E&_8=~M+;?hz9YKMsOZ^h5=j!(WvMEr5v|lP6gB*=-@M1D{b1!M>Mj zJU@tnw#TD}zv)cZvRKFZm3XW$WXr#-cI+^e#Jy{=oxQIZ@jDr4tpPS#z{lLL4UWlX zzqR6FDU(wfp;g%=DIVq;i@)h(9g4MS%+G{B%;XbCl~Ugau8Zov5;RK~x>7cCt&C&i zujt3q#cJSG7OmUkdB&}ft*X;hR!wgfuQ$PQQ)~CS*sDjvfnJARuRk(0T*N`|4zq#M zfA)HfTYbh6G;ax{nqxyXxCjX}ds$v{If6U?_F{Ad{T$|bh=(B+d^qr4w|5fOJ@+N_{xNc0jB;t94T9UzwI=nNP zd<6`3Kw1EEqd93KZc~wwf%k@(AQBt$1d;^5e=t3%cKZ*Y?NI;3fs1?IKUGt_n6wPO zUuYVK^13``YxL>D4GcxxZol=A*A^V|+p~2iz&e}j=h4o*TAYC767QbZ zpBXrwPfnlo1SOP;_x_o`b$#^vbYy>rmwpl6#GF?l66&Jt^`oww9iTkBdK+@1hdfN1 zqnAzf{`3EMOiI#6S6fym<3>X!Zw3h?LlnV)n*RQGuMRs$lc@xpQ9-n6wy&v=cjs;V zRyXW;Qi`2AQpmJ+wyOzApFXu+Tk2ly1BWn(HzaRL_O%-)*0h!J{=zEb4dD3=c$@6} z-|3pFz4^fs^h$)<*XQP%fL6WG7=0Gv#panwqsSt|&HkG?#}SPntC;zp-rry-?z;2( zx0RM~b1~!o6xZd>$EAAA#L%ax#KC#z4cHDUw6*CjU`E=rQMqD9F)9f1zTt76^Gn3oDMH)5$(FF1lT>}yE)H}W^C zkAFA&7Po!ri0uqrAA-K-hckXn8>P*s8s!y4U1x|C3_nY47|Tpzy9^g`^Sxm`>q;}c zv<)nwB#M{O61QUixI~r_>8i2ohltUCypn(uWs6IxD!eoJXHJA@>SYBswYAd}8R>8+ zqg4$rHC0PiT4;JcB8$D4@4{Nn?>8E&a#F>1BVFCrG%Le(?3_M4@9{f3E0GX5*3WoW zPN!jbU0VC1Gu9MZxj+Hos^-!DifnolP~Oo#shwy5?VHdy90Jao?_Pdg3+Rh@iXgXV zCKQ%)+P{PvJ>^z-ow#_rfG92B_KF;bVqC}%^e6fYq-p*`7?oPj)^awiOOu}u20S3; z&RV!0cTmNE#5|mf-he~=L~J*bEJ|J+s#VJ6KYID{p!`sK-FKMVwR^=LFNT4S((~=P z00G)yk1WJRV(&m6!I^VOJ$+E7#xKDL0s7!txzwB#Sx02MxbKlMqox-0t zrFx=_*+<$TTfFFq6$F23I<_Q?&^h8T@n^puv?oCi^vq=D1)wHNjy<`OXmNgizBoiF z>%oM&O4|H&;|cp)3Ngbk2TgzhKU-Sp>+6e*fx6ynIU|kw$|_AKIaEVw*qh7zq1|?= zHQS_<5c!U=Hc5NXf8smEc2rut#PHozs|Y_G6PIn8O!gF31+d5Yp zDzgX*qHEt4UdtWF4ZP5~xjDMvOGAnA0bZaw@(R$J`*11MKDX}H@dozzn>vEJ)$D=- z2A(w-u{&b{6z|CXES=!f6+<6`Jmw7)6S8((GWTwII1tkh%z zAhi2onckfx?lH>*ZxrcSo8;J=zXUnq;BdIN;GK=&Cq3`ar_B#BTyD>1cAWtj#*FBD-XHs0)nx@zrUD=|Ih1e0Rf-3A!- zmo5v#jzE)B{Ag1Y*m3n9e@}o3&6b-f#4ViDuIprTY(|R~2Rl9okL_c7)7i5!H@V$& zNSIIy^p@PQIXb7N@w%Guo}KNiCXTjTeCzJ+zN7zH8_`_Wr{Mwbcer{s3!HfnVsL|m zE|7jB^Z5IAqBghg2#XrjF!P~KmnL+)J)K+SLHWwp#@90+rGuJG$72KwBtHO2s@RP8MRFf{5v$!WEJ~*})bs?%qsv zNEGn)x^h|Q_W;rEatrv3k1^bSrF)`&l^rO_whmm)49tSmGmj8edqGhZc+_wg80*NP&$FKNBn*_Zz)^WkIT%Pf~;8# zGLann%kBz%EpY9Joe}G2jf7793~|Pd*#VIo*PFwKCYnf^Meb3@=Dj!BnHAxqPQ58C zv|*c}UBl0T$xX0;DibsD18(Wbz!duY^OQG)^&=OmObww=E5FzQT)->Fs+mPBQ2=k| zs>1w_RZlARiRv{y09vFIT>-4uvwRg zi)75NyJzP@Cl}83fo1PbFwtP=4;Og0o^I*w-%+Abnnsu^<0I4&(7EvKO?B*FXon;8 zb+j({iVMG7V55g6nXmHF&+~vl29xy2kbr~tpA#SCE>h(u$S#??6L7w>G~t&6p9a@g zoSq)v?II^-j^6CF2g=nc!wDV{z%}^AC_Ongwqk5S!eY`uSmm*xhO93vvcGj=*a|-7 zvkJ6`lGSZN&qzk~a=Ob!R8iI3c?W0XkU4wkLu-!q6VRZ$29s=z`{@qB>Ouf{CFU9) zX|TCm;q>Fq}6Pd}?DfR=dm7Ccj=ds1Azh&Am1u~~c&weRx?@jg5$Z)C{I%_e*E{>qX_uV829^JUKSivsIufQ18gdV!o@Vg?OVjT7~wE>dlL^_p)m?mA| zCfRWjub-1h?1gh=kEfH13#cZm0k03qQdJ$)lW;_oXv;Ql)H;)2KBhUz3|zHE%=%@M z`~%`E-lyQ62@;X9$(^fY)r$|+1d^q<=Z8is`Mo7~PHn3B*8Y1laCE+NsA(4jQl*93 z4czXXvptrxwMR)7#b$<})z%OvQAtR~{jd0`KM#c@YyM<}%&3>`kT(N?kNBRIpBE-~ zz*h*yJ7ylTnnfNiVrIIIpA41=ihsjwW^5hbP8x*gC zMj5Vx9e=X*Wl$J!Zx5+yZ+*>~5+US^O>i9lOhDv*C$GTXtwHVfZuZ1+kYTUmG?(kRE)ZmW27ie2_Vc30kcP)=V=XmwDcVU##j`MjSakJb`6d~-Jqhx@ecXQ z(!z_KNDFHG?eE%VZVA|B$GKUE=x+HKyduV4jGVWjGu{?pY`+^}ucBm#Pf{0b!;ZEh zE+32#&?Tj8XJ+ZPG%n?cKVkEDj|@<~OBde*YL=K{C8CPi zK*ypy_0JboHh?&!jA3dCJ$2_@59VmEPW_xvHR=Z8bA}KE{4_9(1~IlM%ZU0=+fPoM z#$lBtqQwH^YrX4=9$b_r@V1U@2thdOrSfF=Z``m9Z%fWjk4;&r%>F0Vf$6^tv!4Q0o%VX(zgJpP-hCgukAz#V|H__^^pZ-Vd;@6B7p(%9tx(6{VUP8b zY)-ZPg4O{)q=>y97@Xki-V!bVdjLM!J}?Ck@N=YLX}$y6r0!VD8v>6Fpw5}&w`e3O zu;^^FG0E-OO}*x--Prmrcb;@|gdg2!0e7Lmc`^B2N%(D>wh%$TqFJ1<#`cDNPnIMj zQ(1yO=!C5bD-eo6=X#l#y6B>Xuf| zPiJ_xzh@7VFcT6e+3Ou-Eo)BT1cjtn?*BDz0%P<6%|rls6VibK`jN?i+|&T{A07JR ztzUc1`UB%>7v70?uVuS2SJfM?4M=s-BxqI+#1~N@_pdbEa5A?k zAtfX?s*imz>o_89onJ%6$(W@`Uvu`{+!dH@%7Hg37q+jPitBc2d3LH>$9~NKI2h!T ze#y0mb{Z=5JrRpq1~HmPkhvpRUld1_U9P5-{}o7`dg{O`#JAs;t2tJ~WwzGr7P+j$ zPgG;D2!u=Km5KfSb}ys*pYCY$<%wb>T@Q0--gi{IC)l2{lJ4W<)fP%-Z$-z*BVQ5) zO?TH;*1aJ@SDSqLS7V|f0ABCB&tYq&@xk!1goXZX@Vy{F-nl4;n#boV(&s6ES2k>M zd;DtezYkij7b*jTjMPv%>6yy=R{Z!Ma|Jmfc$oUnzBM!eX>c2K-~44CuoBE#wTeZH zpoZOgZn~-uG^&ZFk}H5FZ}9gdw5-4-$N|B(7!Sz#FQJy&`L>b;RdZn-uon=VU0nU8 zFUJ%gnzPK>;b2R$F}3MmOBZ1bPe7<83Op4My#J=ZR|Hxj9zUzxOoTYLVvM*UF+BJo zp@>rLC&l9N!theV`+=aAdlvZZZ!DQbXTz9M->4U}J^K=K+R!J72f9)r$VH)u3n0vbmE)^U_| z^@6`GC+(}BwEJx6{XNj(HgefmLW~=5WRWMJ13lA|v0{`EdxkhUzy{NsQ00$ z79XiJ)%5`W-ycl?Gyi|fm2d(`;x2x-h6fab#8TUVr4SIlW)Tt58bljrj)K6y4-<+s{IBpnips;&1_u%qm z%<$x2tVF@?RHdLcR(ZQ7EtrBjCR!`l*D@$cP?0uZ$&c1W()Ysy;a)NLLA0jLDSJAcmUq8(T^9OGSrD!z?$IHdDjt(17xYAFHW@Z zpm*~BUo1e$%aZ%;_YWT=Z|Q%kuu0aiTo&guZ^Bp6{2mNqBOvW?jg`ZLwaphwNa7V_ zzZnS==n2f=7UvME-QN7;r!q_eItXJbd;S&J%n<&Fifs2ID?1wV&ds}yvoK60@ZGCGyDKzYmV zBQ;~FnT<_E#-Bp>8y9wk-7nhSCR;I!*`aXVy@-2mizcYH@HDUfi`1(_WXIqXoH62; zg&%BPXTQ3IWsgcaAlcI@gm{d!&TW!i14h2>n|&Dr;|>2J5`$GoQhDL{AYV zmo+qj7(R-4GE=q{Uw$m`wOUSoDAlkddAP!rn>8SQQ8W*<**wn=Gms`6Vw~beW59<` zxul@Pf)*1)N_us$%$U4Gt+GMOlVbl=qx!WKH?V1c zLG2Ph2-`qrJ!aZgz?vBEq|fX4RWH5>wz8{NLW~P+m6U6?oSk zBvLGEIP}};;1w;ij=mwtKI>JNCHUsJg3^g(W%C<;P2p`UPd`EMi3MAPmJ zkBz^vUk=Q&%xP=As!KnjDsSWWBiGvkVowSq+^ah<+5aB|Sn^!u%L^aR# z!uP@FPUa(Am242J4`gO38~*@KMSp4>?DR1)4p@|1R!Ek(e4gSI!W#`{b+-DFe`J0h zA$tDUy*&SsHV(S>Oru3qL+c5&Pgqt@^drrFKA!F@pGt)#z;3`);lH8W0jSqnH}|b= zgvMVU%qp%5{R3Qvt&Q`G_`?#(uk7}^qKg|OYUR$~tfOhK|1$yhi8YES4DY9zA;H9( zc|}ptUr-Jk2x~U1vX>-+*Zjvg68xr5CuQ2-74~6@S9u%aFnQ+g@iZO%ZsWn2O{|kV zL|mG8G;VRo#N@fldQb2;q3iztU^6?m9TGLECiQ}&1EKGwemVi81Ago=IK(#*gF+3K z2|?K}haXB(=c&}H(o4ikVrNTck$;`~9Aj!2dHb=lrj=EsAM-v0q?ksXdyQRuo)k(O zuM3b48>|h!sjhBgvkPEOr~TzFpn>os2zs7BRS605X6YUOj3)4QE#grkL|^;G&=HPx zYziABDmB;c!HT^aFgJs*d+fEy`i2=Jqt6*1MV*lBbM~U!$fibF#?&DitOfUg*HdDFMr|{(=xKZoPJlAJP76g%HGMnVN zYo09q>ZthB7_uMr@$U@ARIWrdGz?kK!HAkjf*`$oP^u8{ko>F2g`>-UN^j&H;d?Wx8JfcNYx`JaPU&}iDw*7h_U+U72jq%cIud)r5Sb6EGGx^XCalHox59Vj9swr+IR3xfS znbp9<-ZB-^U%+__u1M z8NqtI#^(0t(l@}Jo^tkl${t^QOiVFX?AA>X)c%c-I^^xN_R4uKzU|mMpk|SNKY&dd zXb^Z5N0a=x^5_|R-5Yf10pwV=6FLzuEZnX~Ly`XoMp&6+%>;|R>r3Y<_n^BbE$-ds zco8w+@)$LK9wD=pq)}QqS79 z;;c2)NJ=jcRpTbY(}}*1;j=ScA68!_sPBL>tz5nRY-UgK@0OIm=>AOx25ygEHup3D zj78aqM2lHOeO5(>#4wU zE!k|y9OW7KM3HZ?5zAapBVHYzCM+p=3w69&^RJ~AM&#q0k;0y49GJ~50}MFoF$|HT z{41es=SX;)HfJoWuh-~!j2L}ne%cRQv3fDa7RN;BwJmTstV*dU=z}B*2;KbNJ+GgY z43k=xGvNQo52C`yfVFo$=Qo=%?7mhf0w6z%3RD(2zf1!mqSiPZpFz3W|8CIusBF14(#W^`as_Rb=ep^R3=0A*;)Zi zZePD?F_iF1{!K~C`y;YuoSif-yLVBWhet;>etS6_mY^{>6S?F0p;`P>K#ES{w9&5q zk(S!!;*|iqI&8*J_wqOnCE`HvE+l95NbU6ICVQ$`z<69|>z0#;md{t5Fs* z581HlUMNymvcl+wMn+z1BHR-gX@N-G(rYk^}Ut86;TMFCT4& z_L~6fV_lWX<5DT&Bm_KM=>9%T>mr*{V}Hf6i;9na`2$CITf|Q#(QG6KKSY@GkNevY zlXAdaeBqb~lEl=Kan&~r#<-YBhyK!u3D8MLdwuIC<%aG9&=WsuZ6*M*Cj-V%=(E?# z&*FQC^f`J-&G#1D<8X-cG$$WQj%cu5pZLE~7rWjE$@7;voDJe@2MZ6qC%2D5eqE&L zKL)HKrsV%(bIf|`<3AklL{Z5Zv=l@pY@K=$H@YpUOjfeB((0FtofZT{OqCIFum1Rf zezuZ^{sW#=j4|U9b0bn%5^G*Xv#vq*+-Y6TOab1cX|7RvB{}{;Ril`9qpgD3ZaBj@ zrwzpEp!vq{-?~v$w{G3CHsq8Zxr?UhJ$7tu1%19fq3Fi4wt5YPI_$( zJgd~GsV6YjXk)eI(sJ_i9qdxe1W7|uplQwQhAogH}h;kF{0Z>RS&^vOm`0 z#LLFUIk*FcJ-7s!Ea{Le;_tisYi3l~iC3|ttKU3rO~%=bo_l%K@ullJV`zKwL`BZxr-c&w!K5gvuDPX0^Jd8VMt2mZ%l0f}#v(fy-rd%)pUO$x1}5f_ z+LLxN?hLp1GL_fwU9;7Mn1pnHoZL+s$?FLow6c?0JI)%V@l~oswC~W*fRke4xK9X<8 z&DCWvj6bZrj+?6SwpQey7Y%YbX;Hxd0H@H|kqY8Q!q20rTPzcJegjgnrhiehc%w_t~PNBC^gH<`DA8VcS66wzmV1(2Uq_LghI;- zt^RtnY%i3F6jzEYncx;PZ=Mttc^gi@A_DiJduGAx*g2&ucuf;(Q57g1 z)HugA1c~uzu4qjuD0H+mBc<}Ukw^EN_zc*QN~yp-%e4q`gIF8~S7s^!Oe*$`e;RpQn3%bWT%q1hk`@ zCys-K1r9hVz|ygu2n<4VnHI~h804NEA?AJ%Hw=_{rT|C~(!K~}y9&TM1}Xd}!pKQD zF}`yuS2#1>`Vzfd_0Y;X4auwv!v-KoPvSf^$^EW*0?6Q~lEb$l4<%1b4yd6UgV$uj zXmWTX1l;^?4ScA}pITgAfEb*Uy&|Q0C+hVAJv(YlTgmeOH-My<{C3A&dRf_?C4X#g zZpYjo>LKKgIB_p?VkYt^zIxiY(}`8U5ZdA(ir9F!RPtvRuV3N*utz0zVGHXN_&zKE z&SWaJ%V)(AC`OCb7s&Oiz2BzB_5*;&A_^Y=>&i-pK6d7v3pjVfmnP8#C1qt0aAfV& zU}-sd^~c|R4F2x>?^X4>XOG3B#JB+%0Lo&^mQ<#9cC20aty3n8YE@taNc)r9d96O!1Q5fimHrX+j!u{hZ_;|3j;8W(P>=YoPr zz!NMg>I-{R_Y$X8a3=@|3;$u?$#!D0R^=vsuB~kWQr$SABIqB7?}w?@zd1JPBii|y zk7W`jX;UE}0r+D|%PsY)&pmAtu(3<^nD(6dEfbQ3hQ1(KT$J-Se`S&P5BQzEy^fMG zz%#KG-!ZZCbHZHYI=)y)b_y}6E*Y(3=a@SmuYycSw#^fe0B#U0W<*d?Lya=OJTLSN{-o;g@TlBcz%qhfCyL6ti<`5XIQj2GUPScK zthH4K&Z4pR-vIA>{;|kQ#vNfEZthZGt^XS*32k8P-VKls zGcYnMLED+6mujh^! zgbRMfaS&(>wVVXyGKv#-OTspcn<*o}z5cHxz%u z$2&&0;|x7?Sb?8odIMOOb`XKM0Fw8VAtvg~A_$F%M1f%fCQUB-UN7fGlMM@8TLNziwyS?+9?b^4-@B!Xq z5fC<2g=v2X{-QbgvEP61tx~uA!9qr?`0a zZ_h!W7W;$g*_LP&cg)+^pd2uF;M%u%M-U=hHJMn41nR3A8)8g?O!vRbq zzs6>d1OQ72P^VsDlp=-3&~#JRHYp68Ay5-z@Rw$lwHAX^7)AmN1O&=SckmlS&No9v z@Xy={vU;+g$;0rZzIK{9(5Ng+`g-A7s@QtmDbetjcuzzk@Py&RiPF0ThWuug`vsj6 zI@l;Pa~s>w!RYBUD)EYnSW_^R4j~vmEQP}Yd;jqGn2gI-5Z4D7@4# zOEDXMVip@CaW#zUF4b?4r!gN5p6B$&hAp&{9kGfeVr$JUtZYdkLp>;breq?rnu}C#w4y&CJbuCrNzjM_NO*V zsFP^lsEbPE5BYofV%_zbgCf0}M%*i_VVGHzcbe;!M~DS2y-m~uRm220_BM4+cftz- znJQu5ku=X_*sF$NO81M@3Pgb1Y~IvQzzjFI>KZ25w5*&D+eUKIg6>DdNF>rIVdFXh zCManRs#QUrxPWM=M(;O{%JAP3(8Q=8>owW4iqfycsmJ|$ey@GbP6IDRQv$9TsjvZPkOnrHTtlRnT?v?N6R)YkpZj#bd z8UL96-nRSA#8IYuH0!Bz z*jnbPHNz2NBli83jepN=%2%WwbgG)K!$9r2Za5>I~CL`92*GFC%`#H|g6kiVd zU80_R-c*ijoS&NSQEu0NS` zC-#o(cuqk8{tM%q@K#i%7;|^R_OK*DE9K9#r?Yq;ruBe7SmM?TfI~;kP)+17kAola_i$5WeH1%yjGHh%_e%4*{0W zs98O@T6;?>PEayXYAJ#PQ9eF6{DC@8fVN-ti^ko0I*t44F&iS4-rlVX2#J@0%_(qE zUx$92X<85FGr7wDbf`oAcIw?%r+O1h4I_$67<~c0L9WEfm@-dSuH3ZBl&7Hd|FHEI zU{QAM8mNK@ICKn1OUKY5A|=v@gaSiI_eh5{f^DN7YrB7J2UTE>xuQ;&wWdNu3rad3xwi?I)?&I;;<(0))#y6vNLvK;B4oFc4o=O z1~)THz|bPRK{7ufwTUDKBJ?d`rQI0Rv|t(|qFbobTQDv(pzxdZ`WPc)|l&xZ=CcwG@Ya(9BnLUCt-xWt{&sq@Q&?0wqdzrPMAgMN=wQ2_t)-g z>ybAQsQdRB%Zf=>qh~;lZTW35=7#ON_X-!=mL6iA-8Eirmv8_A&%JgJn0V#E-n5?@ zmX3|Q+s23~-`_YIz!cXay^Z$8){Ov=^_I5893qu+yWI@TW1lD zS`W|s%6)W?_(C!mPN{j-+*F7T^t0r0<#kgsQLbS*Z(u2zU*IBpd+X8BaUsVzyue`E z^f5J6D6RI;L$X|-jf_@)Zr{2EK*V`BCyu3Ca{ZOak}ts<+0L@wZ+`WOdpuHD<1MBo zct0J@+uTGq*kh0B7Hlz=IY)EL0imo?u6o~bjo=#(WC54_*=^no3jzkS;s_x7n-1t8 z5fT!PYo$;H{nGSxZ%-MFJfqE{NfLE65b>iM#`)KJ&ixMlA`W0 z){@{>RI#BG=$l*du`lz5Vn^Iz>rY2ztptY8b#SSnHzt^;m=iK}A;1fD`JFPH>^86M zmyi?*8jlfUwd6(yS`j5Y9Y-T4m&bklWz!7<#EWyKZufq&<112&MS=vCmo=9v(2C1^ z@sLG7M&~=p6v-dw*~1yYO&@El%NO$28JDy! z)dKz0K?A8rwQN0e3zu6GBQ9f=qGg%Zz@fxQ60I1w6mrR(Seu?G$Tv@{JJNeR|Ku}H zsns@Rkpj886}`Dz!{!lUJylJO*HsVYO6WL`#XmKx(mF8}-n zmd5FP3%UohBg@O%LP~t26-%w#Ixhdw5^Xo@}E)J^63f1=i3hFdDBaK zIcUL$!vd}!@)H?4UNSdaU?}R1kX!R=GnSUtvVspbl;<2}1dr#yiq00yRsD{EhyIT7 zFPH}X;nKhulDB8%LeVL=wc9dVMKTx|*A|x&AJAGTAHL>eV5#TFTaw#&Jb-4J?eFzG zp)I0%4*F5wDnPD_~P#rijXA zqyJb1xUjJc^TFv(F+9FknJ~?b9xQ_uTMB_-Lg_n1#YTdCW17PC^Q!)dDu|;=utZW! zZucAY@4%F066dRZkQj^SS`O>{ZAa44Unjup;-m<#wO@T?vqA?j>(T;xe9s`Ti( zF}?Zj-dO%#N(q%J1I1ZZSycQ3b5m6AEwzSM;g2H0x5zk=qC;z!Aw1%FTY++@z z_=_%gE0sEOL)(&WbCNasQWn^@B{w3sH9kyo$1(zFFz~L1ap8Dj%kj%DE7lI5s%F0L z-CC0(#WJUtw}n;Olrew&Rl#Sh%{>wc=f9g*?LCh|a>u(^2i`G!?s}wo326|>i~Lyg z#)32I;vU`Mj{3lzC+hIPvc~)6X=0&Qml8^RyyB5A_UGv3)-fju#}$EHCS&6L%i(%- zhKq`CmSt*6IyuupHd_^1tlK5AYHIkhTKgXfDoOuYb*cBa+4zTMXB%TQ$AX# zW)1W8`F>~C4zzRE+|dY}niHJ!=HZ`P%k`F?>VJY&v<>s9>MRNUy(I81K2czcv&8x$ zf2~OqReSQC3B?=e-F$lSK_5e5Ki=mzJ+ip@!&gyAgTmL-W|8Jl6QrcrgAIEa>S&)@1J)mDajI4*Y)ZgU`-IYIcU9d2|R~vLb@Oa z=SREB8)clW%-HS)=A(-;V8RrCQq z^NBg{aCD*7*6Q48iUWvEVP(sVFRL@;^;Fi|=H2EZ3Z=2jyaSu}dG^?H-X$Iurw&d} z_^bcC+B04b=i$)yMf*H60Uma(h)IR_*vWEE_cJSRoJ%;n>0l8Rn=9V-p!OZq?wa94 zaf@Pz3VP=6Jj1RegF8``zK?vKSr-}$;j1EctJ zN5WM?DxM*mTIZr&kJGdRR~oS@W2_=!R*eO7P^@ws1I*RrRFX`JxX~CIdW3x z6ajdpeD$A-N=g9B{>lT1P9((k!9$9QS{F-c5I2+9X}x&ZOFea`ggM%4R!kzD5br-8 z(DpTEvR-ZU8d@2nmrQ{SB^ z-4itfE#Wp@UcvGMuKf;a0H-pou8U3dmWXZ%n)u|%v++mIp7V`)@;$6RH{V94q&K1X zJmz|uEt!-gQFHAn)OPE?mSWc;f}Rl{+MOI;xcaMl8m!7Peyg|QxNSor7IN`tWRz%w zl?@s?Jg>~@=VUF{j{6C9%|Z1~4N2Yunfj_|8u>>=#2`vs1ng@@_}heoa~ zX=E)Kb%_21oKxGD?yAR_1EHsu?JdmGq!TVPDj4j|SvU|@fAn;ScBxawdFZFUK&Jdo zQR7Y~^Rp*mg`SAae;mg>N-guV6!6{4d-Wtpoqv95sZCk2@W8)I|KEG|-#^-V2pla_ z#7S;jIB!~j)-`1-W8>^XXUU2wNx)&btpb&W^!uCj2a-l0QH3D?o;K^gw0u;t5I5)5`8zTwsL*?B0%kC$y>Ck?<9yY{Q`-M)!^}cG9U>E5Sf$|9)}dCo+d^it z9@R&n7R)~cbL~6m1wZ+i8WQo(?Sb7oW%T$}foVz4zjEj>ESX}`zI*>Za~n`pxUMSo zEN*IAI9GBTjaL?j#WJP%XIZcZ{*0f*~X_Z8}5Zy+ER@AO==ZNAIv-95J{RI6cKwsJJ`qBtPHBV?M!%{`8H{&nQYv%^)fQQxi{~yT= z%+7kTCn8zQAw9RYZWBpM_do9AfPUcK-d>UO*<%1%mgaqTDOTR!F;^2Nc6%6O^s`*c zH1KH*q-r(&&TKQdk07|+<~AMVb$zdUkfyYA893p2U!nKK^3h;UY zI@ii+>xY^GdQDew#naka5BmYJdgnJ_ev%iOUPZOdi)Z8=J&^sI$vtnkTil!Z;7bTV z#WWAVynqHXur>TZ4#|m}&rdrirh8ashIm{Osrrllo;jH@JNTcS=Jz^>hG>b0?854j zbv@=UGz^6RZHDw+ech{C?9G@h_jd&Nrzq+%$}(ZxyVPSc?_b4()1_oWdoq_~=2`AX zmpB*QiPG8bhAwojR=NmNzK&o1CKTgrI4a`hn9F;~vmEUi$*geqiI7^4*6~D-xCHb3 z5v`#j=Gb;sS!IP<8Ap+lMR15w-7j#~)I|@$mcFmcC!MSvd1GyEk_ySvPIbwV1<;GY zxX_20lPzv3&?20Zc?jkJ--&*36yGF_uhukim_u4JCpfI9Ah5tCpgvH$Fo6JJF7B-t<|Ba>tfuvE%afwuq{tmM zjSDa1!F8V7DtaYFJ-uj#4sr2Rl6-Djt*4UwD;o4Hx zm}OOWcQ+RjfN6L>#(v~w(_QSvvFxC!t^im2W}%zdPMwa7HUl>kmT2EzY^z^GZ0`Q{ z+jBsR9{2XpV7if<;HSqB`v6neCAm;JCON@f=HfWH*SV<<{`pj)Yw5)Jwb%mb2iLM| zAnjV>I5MF2j`Vm%pjRb6kvw)DhufJ4mn!B{H$#l8%S5D0?aak1EqdMT&R2yb#A%cZ zg+>(lYrJznd3>AGXn5!_l)2!k_=!5_s7^`;(WSX@;btX##;O+f`euGYCbQ`aZHaap zu~Bg_G4Nt{dWug&3~T$x;&gP5%aP!b%%A_*h@V$v_?ju>K@SHmo12@$1CbQ3hCd6i zjqljrn*1!{Pjh5W<{F$0Mqj~X4&|LaZY#(WvnFT;*zdmVPV?W-qyl(?3(m)36TIo| zvWaMHhdH>d)qP8^LFp#9{@+B4`pW?}VnR*REp^{*NR&hEmkMKxhKtLE27k>P9j()s z?~Q$wPUtGS5>2o}m=*-=HeFFybxyP$u7F+qe++dvO-OBgoHM{4C$=f4LOF08Oj;7oI@nwHLEw$t&P{Y&IJ z-=!jqrA=M|jW+v5*TG`fJvB8Hhf%jW9$-D?%oJqofc;F{h524Z7)~C)SiDayTW&=H zjY1z8OmT}>GxjpF4=jotxE-5lygV>)iZ5lf)p?qDA~mROu5vyTvpn|@xvYqb{P-$S z--n5h538%*pV4q1lqsspS10n1pmtce>YDhmt`^7LXz$;jxlX(6!jpC8^oZWn*x%=S z1fgCZO=k61H-8=+YSy+)$3^y!Jq{~D1S;orJMjm+xpaZgPt^*0RN0SyGcLVW@eXi; zZ|RO`I;O7M7U|Urvo4=4um~CPr%DZ!e1XM31a1FGNQ*H#NMYPSN_m*1>C(`Kd{_z6Z8|x+mtmd7aq6H(sTB$Eki+NEro5W+u6`tDs3C>3~W0@lz)EUjohBZ=nymPp!6b|FIl>6)D7|5#VFM>PXy=R2ade;)-wHGR!Z zLS{=%wWd?jb31AzEg`YqLkkeCVodKrO%1^h)~H-)(UP>8!2Jb1~7-J$}ljsn62t-GjA${S4f# zI%AIW39p^}xo7mapLY&Oh2|U4c&e%SNl~+Uv%%@*TFx7W%>9OvP=pl3y-QBQXvIF& zO&p#&jW|g;-nrVXR8OlEMg{>Y)0_{J=_-fb5qzcDd*cjebvb+-S048Mec5FZgn zKa|z(XQX2HzUH5|2lSkIdwBfQ-UGB#w3@8v6ECN=JgYQ*jHjX^>(KaW;Rc#?T&$_z zC^n=s6;Dho`P0z%v49TW$~pT*pL4i$>-q9&?@QPt*&D8i6-%L4v>Eg&YT(C$-Q|0k zf09d}u?+FUXXYX#?R3lP;6T%4h(WYEyxrk>pA}muNq0 z;{P22|BnaAf+6#V?&#Zr`x~W4)OQDgW2TsyBbDV(q6pc}s{B0z$54x^#x$Dwk~k1Y zfp@A@8Q*GI(#y zf}Z9Bs^B9Fhg7{^TS{MACpPUSFk%R;>Uce+^NuYPfd)2_BS<#WOsX@@QlWmI`fb5e zh3}JIpW$P4iugC|`H;n>^BXlvrhj)yW`g^e#wp@_S;L7yvi;M%)BHhDP!Fx=>^qYN zg@OD!XUS;#T^P^C#TBdCh-Qn9gx+P)dAnG)o`aePdv&3>qzR_?n+PfqEp>Q8lPDm~ zqy14;-`QEcb7H@rWpv5hd(IeGcof$xm8Fo3>t8(tLh*Mu+d73pAq1}N)81lRFou>M zDv6G(m|2U}kf1BlI+7yJ|4vV`yXuwzn$^c1hoO2;zMCY9WrCO9$0QL*f@w0#3%}Wz ziw^%@%N+k)g@WzOXi_;!{F7?_$u zNdLKzf=jz2oUiX#VdBK9&eArU!_I?N_A~1LWp1?IS84469FTXz@r{mCCh@5N8&DDC z4Um5pkqnXZhNS0;RtO?q{ozk$s%GQ!fL;6vW<*yJWyK|~07xdV7ze}`c)2{^7Q-1Z zpI*oO@mZPgGyAa`cBmCis&wSWeEvyR56AbSm=09lZ1xKM_Iw&(+OV`pO5#C!Cg%;> zuSv4Yg%iaJM&%S8E9XPPxk9l_8A2Vv%Ov^-cPAlimaaVMtMg3n{T&d&K5y7W=|6vj z2kicI{$bqd18%f*Ta4MA|e2cPogGh)w(G=;HOdGMc>9J_SpS1D&2ud&D- z)P5Rn(IEy1`fJMyuV2_fDe&)B4pO8v-g%okmYiuwhc=*$r7spDa+hJd6>Xi7O=MfL zl73s~IV`4eXBsSbo&}kuP+nz>yaT;tNy!^mKqBs8NZhaA-=w2cxjYh2%7x077WOR< z6p92w9?@EYF$AP8L`jK?4}+I*BPqm0XPR+q9;dfQrJ7jy8QL#@6*05#B2Pk&%juZSC#%Ze9hkFgLfYmr7~_@=2S8Oyh|RtO84; zZeMAF0GKV$RjGn#rW;F8ZRkO-R^FWdz$16v{hU2tTaO>e+fsgdmn^Z zquX9Py9!b3k}GpL!Z;Bn%$r*dUy(_r=9@+ z74~KJdW1T)-H+^mpBx~5M#gVLRtEn=(2l`X_49iB-ZY2~^0;dtb;8UxOvU)}?sN)jH67Zq{g?95tt3N28v~pp! zx;yXyx8Oft3~PPK6Z7+FcXR4+TWW%qKfD+Li|qth4u@~qXx|mT%c#~izw~jK6{a9h z6?Dk;wzc(Bf76yTN+^^wC_m}-1EYAz*}NeR%rC^_b@gsxa4;XH!pe>>m{9F!m)I`s zxMPetcF;u%X>Bz+VTEbd{?d#^J;s6{V8Q5tGD@kUuZ4Lm(PMOc|7(UG=Bf5qa3)5L zAvJ(I2H+RJzCC|wynJUr+ZUFc2gGm@fxrsyeb6Z0o%ymgS`ZZ#wZGu|`fiB*iXI8{ zvTk$%eZK|(yWvR@y8&q(IHX+*Z?0lM6odpwwhb=tjHaq!B#@2qs_*d-QUq}503rZE z_JW4q0mb9K4jvd10I8RoE<{ZFSN#~MtpK!;+9F7=D(R$U8ofcf3g8g`5@T`@<>eha zR9pgnvST!y&aVSi5Q48`4Sr$bk1d<=djA;)3jM@6;5S5GFz@?2WbVe8gKV%@&I zW>qfn_}vFM-1tH$B#zou<-L2vL1z*niK3>4@lfJx;yn&v-_>plkN z<`}pRPg9%$rmZiIj@eD!a!qVUOB}BBZ=3&cVVPNF+*Qzk1PV(Rq6gNyeJQIgZwPxt ztc^0}l_xA}0SR?L-)DFsbXZ{+JgX^62WtKU^utC#tnVeKGh>saAfz01ei&H%d)B3s zrdWx1v-7qns^|~>_h)p{zv$M)5xtIWUG@NHb#-<1_;KIL&RV;!QAzu)X#H87&W!H~ zgcyFpZ#q-a*rB7Kp)mmvFX)6`7dLAEMu>lGRpt6cH$FFq9eO?WWx-X5qj1FRVUIYV zGsWvC#CJ|~{<~qAu(F-Wa)>;yzgWz2-pU8;V*sKLNz;UnA(bPnC+8x zDue~CJVS*4xElNPCc2dg`R3iGeyr6S9|kt?%&SuYw$PC7Xl}zOBTSeUKrxoVR)x^< z_;*kK=e2&lxde>IBtVQMF6Q+aI(1a?d#!0b9JFx0=I?z3+P=Rb++Mg}lS&@1`czdN z2iEx8OM?OEvCU0Px7qq;5K

3BP|iNIY% zBO@bwZsM=H00+YLycb&!Kqe)U0A0#<;FMT5Ze#r<7e#q!re)$S_gqg^3iOZv%j{-e z%M$z7=oc@?kC5U75e=YaWgs2jFCluXAxT0y5naO@ugN4ud6h_*10~Trc?j$OL%_LJ z;kZQMs*qu(L_zSBFNZQFI7jP?&f^ePmWtVhQekwsvLvNLaV-Tn>t_SZ)tqz2rhJ75w9!v>26Yd?pyH}&b)H3h-UfWc6IV7s70&ldQidAmGL?f5 zMPOd&W~;+}PV^^AO=sEMU+8282AA99(w$LsOF+&)JRw3n^ zNmx-fwIm6sx_3NJNEDCOw3Xyqd9P~w$KWe7v1lzrp5)_F&caLvZ%H0M=|-lVO%rkv-LROZZ5n?KX0C-#&b{=2Y1|wJ7%;!3QGQJu)I=3R&BGz0{q#h==4#1R2qc zJviNZ$c5)#PAxnREG&HQOq15NX7qab?!itE4|{(<&iizhTV-?{$727Dls;Tb@k;|< zz}m;#9iHDBk!P?5+@Fm^vG6%8BL{->aB1m$aLLPW3a2aYFV{yz-q`B^W06opc>_RZ z$W#HhA$b){O6jwx?9V}xt@$wV`ne=QGqHg1#v5fYnz{2Enr+F^M}fP}?cszX>H(Hf zYOCI0o5=Tc{J;erqSN_~=40iOZ{rD2M?{dNU?P*zz3Da-+#|mi{!3<@<$A5uIV!$K z#!mUS1OUv43pBTLl_I3%3=i*KMA5&eQI*T!mqm-**tnk66>f}^xxSHoy*TJqug?CQ z%!x?Ucg9N94gLR^`pT%N{w`eU21Nz|X&8i|>o3v>BP}&_gY=Lh-OYe>OLvzzgmiZ( z-Hjq3-Ej}TcddKZaz5x<4$L`c_V3wyKk*Uk6O5hf3>}}C;n_Jodr(LqooLweO_CQx z%xT&G zc4a)*RRh5W`LT$q`32g>M#<#|6cJJy=&~{0$q}pdR{LOm)Ntqtx|kR2Ju@ zV2mX`QXfCO$BLv>=d<^DFzzxAvc;Q;lHuaetDq0nKan(NBQD9_?EKrxbKrab2YSIl z0j(eQ^Ks|&DLExFc==JuT}-1R>18e+qEG2pwb?lB^Bdzi6OTySj!C|GQZ>Z@+Z-;_ z^y3~>6p3VG->LPY~LS_k6gWLJqxT@WA|d{?Bv zng)=89!xkX&F~O!#IYY`%i7ZPHHa4#KZ>f0A5K%DUw6*gcl#zVXhUfMbYmOw(=;Z` zS(DjcPDQ27=j#s1NcvK}eQfdUMw~LnSdD06CBm61YpU=tmi;)!n%0S%g>Z@kw z>AU{Bkr#uPFGvFrZy38Wq2Ga|GP(1gx<2Xe(KUDoC%L<<$qt%Sr@3s7H;bq}m}hq4 zpPJ-96j>hLIUOv%(YA7IQ#}37^oe+C%V7pY&Jh$b#Z}Kt4v}s-pSL07BzdUweDvCj zqc8_xG*nxAY$o9eK*Jo{7CI?s7ztu@Q{?|JsvURFl96_!iI0F)iY(XG)Z zU4vBE@QotuY^=$fRZ^ z4;O53{vGFORii}axAUtz{3Ea$OjU0ynzo;%{rglHKsC+oC%*`#(B?h45xEz5fT(sz zR!KUI7$vWfe3d;jRaZFXT13%|6GTW6;9JWplIEZ3>nuQiY4>wH z&MN?yB8)`WD2EZ^U{Dm-F?r!maROiQ2Up@!&QXC_4E&3pwMoG)hs!%Zi+r`}SKd7# z{(R%4(q`ggAE!uDeNtbnkTK3_5>Y`vqH?6wBi$vf++hQ|2fL-p6Nv|}{QVj&RTlZT z4=EEJjuWmP=HvzY4{^MbjR;*evs?Iq(i1hrhXfBR;$km~7i7~uj8u95wtqMndsro+ z-u&}QU!czX9rR(v!)mfhk|`ZL^zoGf<1TEil%b@|Azmrh0w$bCPe(rKN(X95dhNj$%h}_IVvJD1=_@vp ze%Gd?;tOfWx^9aT%fV`O-z6r_MX&%c6Bq}@?c$$)NDK$D z-v35`47c#hQwHg?_@IFcpE&`Bc?!2FGe!A@Hz2g43tSnut1eS;!~EWg&O+!i=7xi< z4fL3%O9WV^KBBWrLMBpIK{#K-1k4OVjKBW}UkvLpF;So-9F(JN59Il5t_qwOtR=XY zNgWlmJZx#)Tr;5{b`ExN1BDDM8!UFR-9^lRoZdg`QVU@mYoGS~2>Cf9=_obU#c$?gU4;g3<$sE9HtM z!LvTkG~i54cCgM|dZbJAq^}QedqIn~B ze-E3#aWl>o`{lt&?_eF$xeZ?&k5!BuX zHMhU0C4XTM4qke?Jb2b@a6m@bZJq7JV8tbKGTBEMl59zT0_7$X*|ZT|<-}9W){EL; zGCOPQoT2ZIpH)7xzN3`p^4=x`HS1=Pzt9Z!M}R0K9AU!9o-%vO+&>FpNL8DcqoWWn zYK?)hh^o#ObHlFVBYXh1EvWl{zrV%Nj;&1w>>9a{({%%O|CqcHlLH zdL!1ZsjKBl)_m*f!w>HY`J=9WUbOm6(@+sfG5z(g+9SqrHrRJJ&=sC1a4`$_v$ECb z66?~)Hup3+WVS;dn?M_q-{SOdyS{X>w6v5_RSU2`=$lLsC$CA72?zYi<{$%AU72;K zOt_%+BxhCDf8UKB2^+c92xV)z|CMWIiUT3fX|{xrB5WC@<2;%>?288;UA^_w-#=IG z&+7+Jo^^7zoDv5FnUX$@rP$w{D$74*d$i`IGN~^|C*7vM@rFRQ3COq-YD3hD-tRBg zNKTJBu(#a)kdKe8QUN~0KrPIA{i(*Zwl-?!po*eiP2jq=9SwfS%iS+&^|ttXR}JU8 z`~t7#hs7<@uDEE8XR}c?aDwxXN|;M1f zV;2&&T{&}Cv=xa8!^M-p=q`4vMC^GwEo$KCf7h65GFAT*b#`|4nHypvPoHR1jynfg zw~0E88%nN1?%(E{-6Vw+nybjpn<~eugsFE-t4pl*CE~qUaPgrOt-i=K~KQ^S7ExnIUoj5p1>|Ri%8wRh?exBdoI$7t2Ra$fMbI zNBT@U>f5)kxCI6DZyjL`7|$*zJnqKVrm1MAG6jOUoz!WcX@UoF=L8|dmnz@veg8x$ zS&wFhDw$e~^nyj>ij_}S(5rHCN<3yVllEC{IQ2T!N5;Z&>Q)CipJWm|=3;-Cvj#W^ zANQxY7?19NffoJ@_aH^4+p0eXuemaMdEF|LeWd9)Kzmt}g365rtYQIKpvJ`5Nwipu z_DTJ?35h9TxzAHqH%runTn_3qy9_*zp#L{~E%N7y*@-SgOxzMbI7XGLB8@oZV^b{g zWCSxCTmEuD?xl=MLiZG-Y6%P7*vfZT`?xgXOTlJ5;3-UFee~v6Nl2GDNll6Y#59_t zUo2J}^Z`duKqt<7q|w;gJtJ_x25f!bO`*O<`=h2L!XNmTRM%+aS905}+2SBEU7*F< z=*NWWz%TM+2eKT$94`;oQbfChgLbr_FJtf>1 zvCj)!6wA-k)g9UsyIzF?lBQTAb8FH)OLI0v=r-27f~Ze)?gYY^J`w5F!wm_!*V(DU z(u+u_>lavMHr7>!RdzObi^{Tk4KyKhHBOn>Fo#7i4FB;Y zmpD=#M-XDEY-JlP_sQ0qVb>|!Kw_&7rR`?-*TdE4fro?op@++vUe1SO?8&I7iK+3| zVgf~*6BvP6-XCV;FNiXE3*3wzgb(T%A#Nnxn93#gmfZ57W|g96w92R^py-l+J3_isi7+#+7uh^Z$nw$G8hINThxaB9`iT0s@fI z&s;Gfz}@`me&CpBrGFHIfrS~4AA2y$oLt(JE?~p7;Dg7YN^i~&Kii#Zrbq%ua? zp&!>TK(Zl5^$k)VKb`{rOV`AR?}WWUlmVD~=|ZlA;hqJr3P?HPUJ{aV(e70P zRx+1Ov1_hL>|bZZJ@LD30n-HJfDXZzH>SN`hmwFs4uB}B@8sU)zYk;fdyzKXt6Rbr zOVN;rFbZcR|J8}}YZ@r0R>doyS?={zLVLZ@?jsa=e6UF{@K{ZIBWq67X)j5) z*mz-j>wi9o$06-~PQKV_h$+}Sys# zpI>bV+ReoYl%Cbb@M=&~PG0`^dvV~sjcK-?+l%|N3oKT3)aetuE#LnD?KeZ4ejy$qeW*ew$r2g49*{se2bQ;j`Yc%_uRe*N?7 zxUJgnmDlxNuoW!xWHxQS54)E>Bx{++K4BT++TlLIjnxxPmBO(f)fG%ZqU)zxVa-7^ zWNBpqwh)NRRa8C%?vsG9C_~pvY;Yv(rH@g7zE7-`>sOJrlpiP14=Y=rgLLRBuYGNV zNa%u@A=4lemJpFg$D>*=emLOFM1lgQ_yE`xT>i*~5{+iq-25<}3eNTaD|$d1|0B>0 zyg0?RSf0gWhWlpK=MIoI_a82#;=P}3^KILI{}#PR|K6H-AXJYf(t(Jd}0B z@f#$5xQu@IH5x<1*U)3FS*bTrz<3+tM`yX}EhLt1K54q>bI7&`dEOj799*Q7RcLv9 zax$?`V!Wq?zNYXw622{QIWqt0&z@@o;84pca;{~*(`)zeXHQ>+q=KzOODTen{%9bo z;l?vo3zd&Z_q9WSclQK5%UslChWk*8OQ$FOC!PQ#smR9*(c#T=X&Cgzu0sY&iXaki8I<>{nf*e_~m_z7rn?{I5=K zh<_MD&&j75(ysFXPDi&`f{tz9P7_u{tRNfwQuA$?O3m4aMg7F=3X>kH8bs*YxmHgt zn6i&lBX)V4>Wzg{VoY9V54m1LpP(U!&}-G$3{evY@yUbV`s9Pv1_rRC9aU zCi&A(_ke+NCG@l%&U_dNI1C(EAnqkGX%oo7c*?1A) zqFx3MR(vcR@uO;k(xUiCmeE~(gll1N`tubKjjqaa(ERTyOCy$Xk7HJ)mjxcXe-#6o zs%0SRe*8fwdEn7h1n&ihGLv{UdRp`6h!>o37*%JqPGo;PNJfCH%>UrC;)AxBc&ak_ zp%acjr}~Kv9`3_^tfzweKGY-AvM?`uGo3oKMk+Gs>a74E13R zsUI3^8TpWo1oguY(mfwx@IS&n*g`onXK3Rs5cp6<89E$vbgyJ0e@vScCU?4XbY7A| zr3v0Fl{!n|zYbRq_+1i4dI3oToj;mg$t9^pO;yXr?`;uYzC7ZAB~`mEH%q_Z$j1h} z)3l!FSymdf3~u2iEVNLBI8e-dvjH@1K$pmXB_*f#-Q_dBJcN}+625@kU%WaYK`AR? zX3YUyErBv0ml01;dF$8x;V?zIhZhcLWLNc~7!r5@CE!ezq4XS|+e;I3ya!KorS;*I zR3jd%n?XZvy?sJj6pGqFkI)bybhpq#1GRNvx`*OK*h}&t-LHtyA-l#SO~!wrxeUu$W^2=j}MGOonra!5*y*~zDZ$D;=~ zX@GP%D;mUyaJaoZ0wOF|PMWE!*!+{eoAii*(URV`o>kZfQ^i0xN{TX_ej3qY&?dPB zghDM2Kt`NL(TIKA?3XoH_=;MNZNJ!{0+99JjB)5{ zSS^*E8~HGmzJC0%2ZA8eSBc4_#I9Flui#cSN5q*eJ!K8~;?fa=31foY1bs(*qT!zA zqT!T8Oqw`>%%3?x(X+2^nAG3uL*A=aI3OUiHTnzjWn}#!U|^eSW#b-*a7yRcOWKHLm61W@8bUd7?CM+(13|H{zQjpAnS_Q*vS<1okVgM zGTpEWn}Aqis^HY(zSaag1X81A_U$;!Y33KN&(gnTmRToqI2lI;R6nZMx<$;0AG+qw zt|l$c4H+Yb)wJgPdqDd>l$n@&4~3429QPNmb%B+*G!DDP-(c6%eX#oUr^F+q8jS@A z^J6%(!VnE8qEkin2_+fHmI!+7`za#nj`?{Vba`4-6lsTa`rEKy3sSzuF841U)Aqb`4PObG ztG{}(=N`S_A{>uHvFF)3YkweWjj#SY52kC>zdoHH?p%5I{7LMOumm6jGxVjsnvII7 z%D&&LB3%bG=NWlsZwKxy5l>RPI^)3Q8ubIj;|Y{T3^-uCJD&k&&SNKBS4@GhiNVJk zipX_KNB{(gCL%g+dZYot)6qy(}LfnRmMbqRIrSc6p<_5CW~6uO@GL+m5dPFb7M>uCW0TD$H{K z8NcxjrQGr1TP8{|Urcs?xexvP0`c9;Yc?x$j3#eATI1-IaxCL1{dy;{qdICyadkI) znR9xxt~%=P(jYqxaDoDOb(WsE1o%sKCszC^SwoH-R|#Sx>hGsA+%y@+y_(Ie7b-Ym za$Nc#pMAhK)1t6+{WK-gM-HMo)Tx0ZRdT8Qdc5SIK65}MiRH0VAfa*`d>18Esi949 zBK$XyNOX0on$37^I8{mb@QL=aJsKu{w&g0+Rd?kpsy**wl&fYJK)ieHb?IE_<_p zsd#Y24_tw$CM-Zy&_&hZg7>{uYJA;pwCn}a0XX@{&-TiL8kYW$%0R)~`CJKjCCy&v zhieCOpwByURFZ#dnibO`ugw> z)A1!T?5W4teREKg5{AXQkG5-$;a4zB$@2Ar@&M_%r;TwUjd4AsuBX~P(HFh1WD5f< z=8-`Qw>e0cs*%6@Ldyxl_x}wbyg32D3|70K`KhSATN#p*#6=x!)e`GL z>vve?DTQ3{|8^S?crt8FagFi)JHYK;YoUUnj==a3b31h?iG3rDI1(7k^zb&Zl5?AM z1ONWxW~zjFj)pCV8CPTdu{5Ag?p3kmFc<&v0OA@4syic)|GwlO9>yx;;^Ht)b{24Y z0Yl|_z&Ud8DJ2^UA>i%+3~RzD0n64$i@&Ddr=s_lrmA*m0ICF}EY*w3$pe}C@8G}2 zC$_de&Q9^aY$qxk6MI-ZSNXzgF$&m}O0tYs8Hx>}13w72RrXhNkK;gZR1EQes~S4zVT|Bs|l_M zQ^8qL20z{0DJmhhk=aGM{i;!W(F7yRkSnCu*)N$jfuY7a`m?i?W`i}YTw&cwFb{>% zm{xX{D7;KIi&g-oo_E!k2PEl%hmrkX-uNJ|PWM$i{!`a&<|?S_6k!^}p%Hoh2}~oJ z*iGuim8Tw1196%^?-vch)$XoA|0}^6qiStLm6c&SyD(J1FPLk3WPBOsfjZ zji)yUl-Lc@Z8UTQ%CI#K7pJ0u>L2g)QhXB)71)&B-g+&5=j7lhv{e2?b6^uz+wSA8 zO|H|c(KTK9ErXyspo#6jnZLP~G5pWAUM@<= z_1m9B9JN9Pa*MbrSqj+jo7l9g@zpb9fo3g3ALw7)!jehjG zcSv?e1&gso$i`iD&yx1dXeDRIjUA^yU}++sX`fSEEJMs;5)NPQZj=m37yu_bI)Ev^ z*;#E^Uwt#YQy(B_S?yXK(qke9u7bYOSNpm{Lc7&9){rn4O6ye$Y`sN4-VsmZeEW;> zc?Mk<WnLZKK2pM;AB_4M7>d5A6rhZpV6)?+{A2_1X*|QRO2XCA zEiR}~GdoM7P%+-I9}Tvj8T5N|uLb%W0vR!hC>B75;nt7FqpPaNQro<>!Kql(qcV%A z=-i-3))m=A6r*cuLnzsdqva!Uv;Ol=j437|Az`e=5Se!G6h}?;qpb13&x@Xpst~$9 zvbFkK4G!XE)O_YSVT5{J`n6BBp?7@v3;x`WQf{Y4_V@gs)9|v-jlEhu-@uhbins*B$hcL3P@eI}cYfL1ySFe9@Z%@Xqk$PrTC zB*`n-)+z%VMa-+{O|W8lRh87mxi*2YoyB`8sD`$*K7y7qm$K}PteC}-4FE!{hW-yv z{&#d$^rN!;S`NPe*3A!($xAZhKrT^F+hv~Eb)ML5m)Py|uC}^MO%}hRHTAX&&$iHk zlgEwR&vn>i-d2{VH)GnVrtg{NgV{w#({HCg2rIFbIi)2;AB}Ii#U2R?$}3_2Fjw5Ng2kT?4JI0*ohRL;Z=rkzXH5@N}Qxd%j;^_vq zGV$)m3-)dM%Y!Wd0lJz|dSaE7X_@!Ha<`bFyXocMuYkp5Qf^0qNvKjJnTn`!=iXj; zLUCn@#3zy)x%R2!@%5gP4}8+$3;0YdkKI*_s=Ubp@}MgE&sujPjX;Hvi{ORg1P&jI zBdyRe<(~bbT3_pNT&L~dns-h(Y6)`LfADkZN7UcA7JOEZ*^0owSuY8)*9X#>7SuU( zk@@B8N=o4LO7{KVWirtcCX>Y~udCLTiUUHWFkVO6TSkaML3~Ahqe74ypdHl4U?;thBfRrVHUxE7dL24*9q<<{gfv~;-eeqgF zFTjR^c?qL*i5|D7LJA=jO6g+r7(rap-;`hLWD+tc2h-H_t?_ATp*Sz-qt;FDwASL7 zaLRR0K>1hYB&NwO1C+Sh2M|p}3RK(^!6)9PrW*iwtvL*+;NqYL%F<7K*?~nvOT!Ho zHCgsUkz^KX4>S3F*x3^?n>^gwcFo!rCpW?CCAg~cEIub+sOmXT3wyM`I(1wKJxnaS zWam_5Wc+OrXO1L2F3t;7|XDS^5X{ zdo>ZxO zy1BZ;eOd^!ZgxPhgo^Q)C!dgw&o#uKqV9TiOstJbf~~qoJ$%KKxq7u&YF9WLS^}HF zf&;ayrH_llnEDQ;KF_YJ^L#!)=RD6uTsbUqDo>5Ai`3{6rsZ+g+E9&!9X`S@%LBFh1j3n8s^080+TbcQPZ+I9f++)PaGyJ z-jXo4Z@hBm%9YBF5iNvzdy~wG;0+*RiZ8xrA7KdQk*DP+GiL9FD!zqBdu-NSy(TdlJ zBHQydBL&CE#e*(awasNZFJPCvay?zY`{xe}YA2)ecYHeLuo)=PhL4Dz?2|_m zQ&A-YRVQA=7=51utJo`k*<1h~v|vFy66l#!QEQwXZab5+02`!#`c4t~}P0`HmZfYSVt-C$SIPiFGwA z)^;)_vC$t799L|Ihfb3hZAqrBQULDj{5Wob{ zcn+czd#(aJk%&ln4~WkYsa+I%N-wPl0clmt02@g6ww$FZqYF+`to zLgGqG8=k+|u-|lF20HOemy?P-AVRLCv=l&doC$y!zcJH5$Yn3)X>cDaFr)&u6?P{{ z?B~|A05vvd-CE19_Qk(vD=oZ|$@Waj*ojL5x%VNAyc0-mCvMUfMk^gZDY@TNx<`MI zLP1ykVF4sAtpK)l`!YBRvzgxK+6jHH&;nGS@;Cx24Vv3kEJp@#@kJhhBp-)S_5=Ek zT{1Y6o&frUXblj6q7uf_i07gMJpKDSBiM79m|6cvh;T~%q=*I1LwnO+VKKTlm%=f4 zdIq3^x8A(F68W|0^X1wXv1^w{8;|Z*OO$R}ptokK2+YyDGR>-Ud+tp4>PQ6dzvaL+Auz4j<1n{x4tfQ!}$orjDa`E{-$#9H1)3S z9yn+AA`M-VN*n}+|LE&g5vR_7(RpjBm+_=^$WjlZlSbUhRhR_+mh>tqs&@g88<;ZW~vuwt5-?Ww`CEQ6EJph3AH=Y)y-H#K{PV3+eiVEn;0^ zX@Wd=GvtY-P3=?G4^zA6-hF9W7|XNGAFy6HsH~kh=%cF0+R5jc;lXB;TKXuU7|8D8 z6khRyyc#jrCWxlZt)+4-wY*(~eyYEx0xT^}NZrBblnglXKg~Kd|Gu4i4|2P&!L4HJ zh|MsJc%FOotD3zMVI!YdP`hJU#Eu;=KJ8mft3;4gJxiL7{#m`D?>2V2TO=fY0m;`_ zgF!IG)!)7mz^V;@me??(#S4E1)M?V$^>ebyO)Ze#KnA3USl=|47-97}2?$lI>_|#u z29dw00XO1`S<4<4@ob;`@BtwyZAd_Rrk6H;Mwm4{6nAb&E#eUzc%$l8o8Ht>NkSZt z@ULIomd030tFB)h^mMK^lh{Xp8FC}{1SZ8X^EEeVQz`MXpqyWdfG_u_e$Nh1Y84$p zArF3hb&Oi;&%fj&NJRu(EA^#2E51yOk3Xr0jIC;@Cwi|Pl*g`D`e9I3Qy>AC7gzrB z+FIh3V{UIPHMOrcGaTvhLvpZ$MA?x=>d}|A2N9fmQoQl66g|$ilE3=$EBqUI6AByQ z;^7Uf@l1@O+a_DRav*l%IyiF}>@&e;!eP!l2N0(36-~&4`DGO*CHlkFyW5qA8{db$ zvHQrdQNX*_cE0Yf*N)KNmW#}8`9n5VX9kkR<|G*$7QOS{m-dUUE8b*mdwFHg*!(T* zW~)1*654+(0%7J^?%S!#8tZQw+9c5BvJ8k*^Oz~va(+d=Vp25$OlPZF&eI<2tfe&8 zpdnp+tWLlXF$q1_lur#eo1@t2>_yQq@Hm4Udb<>7FfRfOc5+&y7~Qc<6U?s zDv+y{t1CIz;Am=U%Aj3spX%+fH|yCOnJPDj9>+E)N-3yWuGP_24ZJx}Y8(f#Xez66 zyW54@DnuqHZVfbTr18F`-6j1eyj!tka5B(q?UET-C48Gd_fhAENco~(h8{*yt-9c1 z_niQ*%dpsjApLXE1%sQ35Qv7vl%ht*d`2!ik`I}MkW=*faX zJrsakbB%(+A8A?zAc)ZV0)1ZFE-Bm}#GZufg$pEDKogiY;*%2r8zg~euW4)A1TjEE zPt)hVfrAkA!q-}qUp?`iSfWMS_JbfM5#{)%U$z@$c4S<^d)yiw4YLrIh4s|uPR~Jg z9J+!YaML1O6UOSTVjPXeqXzUVhSbHRr`FZ0Kle)y8))ZIkc^sEW}rUOWhAX-{z#Xu zx9bT1d!;B=0^P?ef52?6TV_n@CO(J0ei#EM)jf*rTa?`V(@?H1WggOi(ubxB9HXS4$o8hOpGe>ag3W$KJmufbt-yv5ZN$TV>I z{R6x>A(@JLNlDMYjQoNzk<(zPASJM{))ndqVQk!RQ}Lrp_x&D6GW=2u7_tbdngFwV zX1x$}2RD+}-<~B$*gUyw2IxJMbiE{U`ps_KJ{9o4Og;`mS2=6aAz2hY=EfGkBo}!q zhrdpwi}_M#VIvA#S~C7eRTKK^Rv0z>G6e{Sp;bj)33h3HzFFzEli^xdC{_BuQLm+) zSdl0iG+sCuO*j--AK1@?zrDsSU;U6`Bk06ir5$xfXUJsc8g35L7xM2no0y^UIO z_5j>T>1wqv*#iiTyOuPzIpEk!VWyY}Oh=YR1hR(+ z2(=`pdaLeJtk*E_a<3yq`Q138xZPLZ0|W`PVl1A#6r0ofbjs!tIYu)jg#nN+9lJya zIn&!H3Icu(;xZP76%UV_4fTextB&M-oyXL9T2VSpBnby0p)jOG&u{J_QVoCh5rLuw z(?z49#Qug^0tgv}N=M5(1?;tJn*WS60(-PzjHZdvue*!0p@ybW?2Fx`o~NcB>4GI19=HF;oq zx>7yJu)eL@#$mzlqu579svh`|U);{I#o2vQTN|I%z5WyZx^PLc!7GWXyX=oUzdJIu zK;$w9e3}NC=o)sfo+gprzN(qr9>;seshv$r48;Oan3X=&>u=lmTyHsQdegFm*O1su6kGOO3&EmvI zUWJ^a(KYbH1B>hxklo5U%xeb47QzOJ_e4LKU4C!7`Ch-`bK|*kL%sbeC3b%3cjk^a zprKj1eDCAzd0B%(iXx=2PDAjQ{Lm(to_6@w z;^TT=r5f{Mx2!6PN+`(>#Nsd9iaj`)Ml2HY4+SH5fCXy9tND5zZWd^`@8DBb4X;Fe z8P_AAFKq}WR2KBp&wxL*Z#L~CRJHqW*$7BO?4OElF7LiP;+2jn&xT{%=e1oYR?!A? z{e!x+{Ue4dDkwW}0i`ZA^2#aA(z}F&m>1_*EiQ~Hug}QSbR}ij+wR1>)_#si1uZ}v zI+M~nR69{wG;@NdkflveYL5+DYH%?EjCC=rj_aw)#hgpkFx)NHZWT!{c{+1x%4jQ1 zKkY(LinD_w*_V-buQk>LpM?Fnbha6pO5^jufBTE07%nni5`gFuJ3{wS>;3-EdQ{D23WLDf547~*v?SP0U`3nGO_-X34&|ql_@8HMO{qd_Nrocqs z^oMD9<%e>zBJa;oTpqqR5XUNRU9*vCnC)68+j&u(C;t1;Up1Q$vCB&Udh;ZTC(AvD z%^S<31(Xw?r4+Ac{eBb zkeh2kT+EV+H2q0`2+>NAVlA^YEH{-tJjUNQH_ z|^K(}FbkF-GY!W(WSZiee-)YgQx~weApxovb$SAVb zRN_DJ2{!$v)BBshMK9Oxw^3VGOZ$ldVx~%*rnn-^h92IYj-J_f==6?9lm2aUcVWw? zjK<}HL8-4(!_Rz3TL1DB_}gL$-laU#3_r<+VF+(PRm?^6@QZQ8rNWYD8;UBCbXuWm zH9>quPN-hxHoIuLYwX_5Y8dxh%Er&Tt!1-_v@lxt;CQe5NL3^PrJnx9g4|@An7q&q zR(z@la(l2}*43m@3cfJ)z^};bV*|NpMU!`QcD{8^w#Bin_T%$$u82nOl*0hy; z63lrngbYJO;^h*qu5uu0-F?~LgOLqW_~W$Jy%_uPpQnVciJ>^4NIYaS8rQ~_5l*ja zjm~qO$!8k=be1&I3jw95Ca5v2Zw#V8=@>^xR0J=VS#iy1QNc=~7@D=kvsqM;c%kU4 zOt}>%7i3v0Exm%7)8hrGe+9d_4jUZ4VYNfx5yi9yoh@-oOdA1stMQ6t$sD>*>->K9 z(s*mEIo5a#@4wasq{*{`pQo_sA$sDy``nFj1$|LjHt&a$qNg?Yg)l(@pu?)39jNGy z?D$+-F0~fg6`K*XI^u;+bk5kL4rst)P(=W^XAYC<7A0r)LLi&hTpuY(zK2()7UICO` zXNJ|^p8%D$mNrZhn1*t^XdT7|wm|>_zNxVHj>z?2ATO zD%sS%EKYx~i?N+w*%?hOI2B|;EjAOEi@Ug;-RWPIiy98|h*Vd`TnmAuco_GlGy&(} zm=r9en6{JAJ-QjpNBY{k|a*{ z1*{{*|`fV%={<_?*$9Mh!&>`Fou*W8*=W zf441F$ysb7Im~CN&Je8g{*+XO#Vmyqtf*>OIqc`55g_F=$*P*PPBS5ej+Jw4b}&ix4;zaJ?YM9mTTLerPQ6~#*a!F!rE%O z@|ct4mjg;Z$9=xHed%uBiuz-@Za}Q9=c7Wt!LF?yXS+bq`Qt&31jREcdH^>1kFhAr zC&CLy-b+oNQk*^(ii~RE`!da~hr!p*rdTZ|TsU(+Ht22&oSU)sy|$eX68b|zu-NuE zvg#bqc@(EP%$T9gRAyLNS=Di_CL4NK0i>J+R3X=WId6(|b{h_dPX<<9;R0KY;p1AwCvs~r>nrA}#LdJ6QP$haRtEU_`x`umv#_&+ zK)>r@FfIB9s7ayrI%%?ALslYvP^cn+%`EkFXfIgCqf!+x5A*GS1~!IX8q{2S;sH+dK(+Va;0({jRS_kIA(KZ8iAAdPgNEA?plV%#wy8#KRD zeGW%FJ!oiv95h@~R3Z?Op1F?CK=g9@Q25$}5?`N#?XyIZJ`7G{T>;6jvnGKXxdBDS zlxC-Dd)&?FVkn1z)BR4Sqo+b8pNedKU(66W&wb*N1>PE0z#HD{ZgTH6sH`0V z?1X{gRmRBXk@wbCa_l|R*%a63}Fi{vGy@z81r8F5D*&QI=3MS!bMV*YH@}Jjym^GJPq1}g@#n>GYbS(z5 z#;Oi7)1l#ZfR(6&B&05u3)4JnwQ%#Isu9JO<)4;(5>m!2RRn)9 z_VwSs^{@pCpA7RJ?28NB`5q6vO5nl0RaV)4pCoN|R99VH{q0*KzScv!fa5_79RrIH zHYTtat~zOc3VmGK0SuaiLDV^bMa*Ze1q=Y9jIvQ&H(QQZgw{=1S|GD3($KbEs~NTE@20BXe6?6u!T55qH|MhY#0;xZl;(d6#t5=%dDUZ_ z&!0bQE#xGqJRNoivdI8w50F<=R8{$aB_gm9;<=4C8)B9;B0L9J@+s%aL7s(*o=3qi zegFx+!vC&!Wgzoz)YZ$@MUk;C9&9J~_BT)02xgV;3PDwA>tGq>&Q$5@aeo$W(!Pe_ zl3@o-=jU$mZe_u8f=15cpCsb~UK#b{+7roK`FnVn5=_4@T^y8m&|cQ#d$!)rBCq@? zB24(g0Sh9>k(LW$pjBOeq);BG5$7gaid~2O57Fn6#P{4?EG4h&IRYI1ymGlz?SfWvjZdys7yfOB4o-@2lP)gzY(r?iVJ^==`*dzBWr`yL{{p}f@e+Ae_k{=gh zogsC&4I5YLm|kE<13n%FvZ;D6=aqsB0{7#4y7*pF$9Q{@MUrkRp>C8;6bc)gHz87g z{XbUJ;5KLJC%(!)7N-O)nkeL(m@Wj^Po$T_pOwMX6@)O>#2D6I29R&FbLXCC&fJZ7#IR+229o5)n1P z{GEtq_y`*F9MyF&bcjp@pk53#FtUtr?%tLJv8VWa-#`tQ(&Sm_6fxIbBVVL8)jed9 z7q~XvI3?3V*Mb5~ZQPQhBdnY{!U7Mb9E!dXw|PQ;BNF*oF|6b5o>0SZR9cLcbjBYFlJ|CN*v>wMo+A*2)z!%$lIya((NJFREg%iGPL{Ob;? zr$b9HG>O~y-vo74n!wQRg;~`zPsn*-48`yX*URZN;4iJWY#35b z!~cxA$M-T#bz8%LI3DvED+17-G`&s(oLd-HUu_fezmoio!Hh5%bmd1ZzBL6x=PrQ+ ztxKRM{(lfnOZ_@j3}YSy2j4vLpZ(K<>&x6(JE#f|)RP9M)o@G8F(BE?a4`plSs(>a4@L%fSGB^yy5x>mkarX39g=9XEx`>p&U; zBdEI?NH({!SF$^opi;AAV}bn6m(I!TXJ^Ji;C6r^girj7Z*P^bhM(iE2Bh2c?jgUX z0NM){nGtO3m_-Hga{Q{%`>*IDDMnjY z4ULdt-vq_SQ%Y;3;rCQEAXT7;MbpD)zu8P}k8m27&|K$;?S>H6$Dei)u;)O-{;v!>Yl2oBB@WY4*Kt+nKJ*6n2!t zJ=A3NeXt8AQ21p|L(ct)##YVuSkP$Y$cr49{T2$y2<_2v)} z;oXTZ_f>FTh-0UII*Nhfn`b64uC9(r)B#uRt+Q9s!Y9f_a=%wa3nX#h5$^LkX=U;J zl)|{$&e9Ry9J}w?+@aZ5b+mt7OaB7P&yXM11R%m;U~WBX|32!!rn)ge+bWYS(&F~Z z@OC00xs@+HEan)%8XwEo=Q{yMGW#@YUI@7G`!$)aRDpwnRaW2MK=#0#0BTR}+yG|0 z1=6vY>b^{7Z}X#Z&(G`vVrksyOsC{()(Zi|z#h`pD4 z_g5k!T>CVEXC;1_ z#T#vuLmGKs8-^R*`qPvO z!d0|!ay<6xF_KDW<{U>x>oAezemVm1KFM40Nym4kUB2$y8d01UI>-#2HM9ZE;1=9+Q0ms(W!rm z453gnm5C>Vgw{4yl!A4!Ef+yP4liV|1Qe7t9>3D<803TommbH$M6DBT7rVcXC%j`B zR(2R@C^Hl}+`ppr-^O3&=*7dSS=J2o1q1Hdjz0CO@99f3qrYkArxcx2_J6n&b9aPY zG3S|#hJ4H&xUvNq7Rim4$;%shv4KICA0#m|fMVwDW2NmNbn zk`c5e;V;`a14_c#8!_IR+1K`?G_GQ|iEPgwFQ|~QLo=lqp#0O%Iq)GZ2{Iuojpc}` zK49S~BRHmYB%san@}6mgI7-nOvd_Ih+|s}26x)*UXKG-FDIS9Zt9Fa;3vu?6SukXO>tpK^b*mG2d@s-;^hru=n2oJ$_cuY)tYT0410(TiS$W zGrAeB)tViUJ+p+y%DhMml8d;y`n{jTdmFX=VM5)xX^R>RNPf!&Q|-MqzrlZ*_64|% zE^Qx^{r0=wnlh6;rxMC@91WLDR9!AJ@DD1a8W@P)i+s^h;pnZq5@B|w6}2nmX*ZR9 zcNKhpb4@7VLEtOHUu=H6Lx$*F*Yk|x`lJZb3wysPmw^G+Kz~C_GBxp|REmdnzUqKG zaH^nIM!o;+`s)gCWOvLW{%}+M;5Xq9P#CAdbsc8eAExHJ_l9Z~Xa*T=Ub zD`|&DoqF9+e&!Uy!WC1y(hM!EC~y)KhoxMl4P`6Q23Rd|Y`_Pb+waU-%LjL4G#o`{8)<#fZztbiQuJ&ofXtV%*9-_(`w&OHYT;y*9X( zLc(T5rdq-8$HK$d2`c?j@+FG@%zYX#z?Om%f78X5{p7Nv^h$NGroL`EH5UZCESyoi zm<2qo7^-W~g0YOeTng0sFsSfwO7~f5riefNHcarD=8WqbM%6#1%fb5LTCY4k6Ihsr z{yWQMR4=L5fF&>#tCleB0oFNcY}2ayi8uj)aMyj=Gc1pllT)@mxWF$F79n@vpG>Hq z1pFZkO&l^o*^JGV92Zg77o4RfY1$7ax}c}pN}2q%BOMy@;Fs^R*L0E~GSqe&U-_eL zCv9%gpNKd)yPx=3c~I){nh17%g0r7D9}Y6cI}R{av6GT?B*>t!D=-BF=_zTC z#M{2=N7;$m|-tAEf2s?3A7|9rKCD|%@48b9~HEhU`{I8Z?fc^&x^Uzx`w zn~yX|EFNT=z#WBCIUb{c5JlAt}& zKoW7Ja=@|8G$^O7re^vBky^}mdoUiNyCJ;*Br*Wz`Q%q#IQY;cA%wOV^;d>4+GV*z zivb*hAu*@>xLl-@FxUFPfZG#=s~wVy5vobfYQL35UzrvkOqa;3OE`uQdCV#2FvYAG zi86(qA&<9XcX&6I=g-cYF1+TY6B2s;+9S*>61DTU)OxB9?@^>zuQ zW7Jcr5sPGcJ34a>c;qqsnn~ls?-Je@FW|!jC96zKRM?zhcni~<9qcVsvF8(1JT+3* zmpOtlMtPL8@@w487&W_c8axxr4DI|*(8ce6!c=`-V)kyS--Ln@};xRM? zP%$>Y7Z!3u31DhA8mJTzCh^oyUx*Ob_MyRQI2&i7i)Jh0C;n z$xO3&iP6r_PjoXsrTWsMEMrHW#=4)8a_pu#=@O`tkpq)J4|K740F@LXOlJQjPLv_c zP2Wseg#T2tL`Njlr=?#Z8bi@IGL-_tOBzTFN}L)v;F6fliw`a_Gf0hZ%K zp=nc`QFSPK%?W6^U*RXZA=TWw+?T9y_Pk@#@~#vK6s8n*nTq6ZDfm(tlV;x0a~tcP z)HBO6U|6EnP4V(~82iHXoTEP3Z*g%>Za)qDh{h~|K*+a1b zH@!Yv@;dnZkZA+gEqu;8_6ZKYiWGNkOMLZH!h#1u6pK5xoJk1%26$So|98R`0bH-; zskLbo1)+kVBYR*}4VbfRg@2?u2^2S$X#zcUunHE{_h8GH7^_gM%;MUJUE>H{;q zjf9dXHOZ*qldXm_CL9Qd^V8E_!`DZ=p(3B~<%aG|o`DpTPqnp5PbGsb-M*>^xOgTF zGaBwECO(2Ugiylh3D{DlXcbVJp*NQK%VObgF>5g#?dha~5TK6uX31ngS1s`#O9vjq z?xbmGASkI}YWG1?^%ZKZjE1zF1`GXgaK6{x88bMtA?`=(GNaycNhCi=FMv_8hZ+f- z+b#J$YfL;G{GF$y8a=FKafJl#r`h4;BtXm|Jh9;vpZX)yJ;EvLE0DK? z9a`pD)r(YkOUCI+acQb6*e3J=H2gEI1(r;g&iya#j=-xo{|4*BneyY&avK`Dv3ZjQ zk)SmT&hzwhDt~3G!16h&VwCTn`2K23D9V8hnVLJH6Sjd|i`LC&*sdc^BM2d!??vba(qZu=~-wqeoNXYD8P(5>vk_vVw&5 z?7MJy7L_TNnyOiYCYxfbYm^-%e3c|RI63*y*h$8I)Fx&RjHRZA`MFVdf4$n=(Dbmc zDn*Km{nP#i=~Ae6-2bg0hY^>Xd2VTN944f_Kv@EiA$kIZwbtCg!zm;_?D_Dofyjjq zH{*wdpw#5$o1j%kn_+%TTq#YUQ4LsQ`R30T@#VYO&;f*ZL2e^UyuS>=T|dpex$1~&C6Tah3VXo;%+xG5{EoQcW+fPgyeXi z(Zs1Q#9C`EZgx{TDAASTMz!pV3q=(Y9E~b#o6lJ|oX+=jgI~GMtJ&Cb2L*1Qlj6qN zMwSOQ-i)ZwjW(N~epT&Gsp*}Oka@WRw%_;=uhRh_K-%f^)&bj)$+f>c9C<)kox)B< zQ!lw&%K?#dObdt-^@DmY&H?cga=Dy~y$K+_Oxi)@Xw4-xE*17`3dQY)0x%T$qc!)Q z&JB>v`Xh_H$jcwNs$=)&Zi620puE=jLfkH;KcwG{WbxAXB6+IlQ98|Yk6yFPvryuZE!jBywk7@HZ3ULcjFhmzp>aiWf(pYKZ>1;^Q) zR?ZH88KSi{5c+Z&FZ(lPh&eK=PU+#eO2TJ&NqewBL0nB?7PpK}8c+bMc zzEZ~4?S4eod;Vl5TMwSxxy1Cc<$x={&#(0}mAI zJA4+ZOn{~soKLvvMeRui9#AW0tFuzSq6*8;W12QW@gPZWX8L`3o` zc9q>a3pH*5sFsW7VMPX|5w*solU?Lv5cXn^DPyq`TfE*^b~$OHlFJW$D+*Dzz_`#c z*SCvEdrC*CN*ATT11o4o<~cS+91^i?{Z`wjhTa18%z4E5$^o-K#AT})YCWVG&cZ21 z10_Yai&su16%n9bz=JxgoSinx3RhU+BmwHREmR@?J_~i67IwDEG{CQzW!O(C3 z?zV@z&R(n9m|)81TZkCmc~+%!wQbNOE5<9(_-n)f~=Ph zcf~iwnzz9{9<-s)&h~}|-LyRzu8RDHKanKDqm??(5a0JK_k5w1r(yj!Py)nPcw}Tl zk+d7Q$PYhVtaf*SC_ENhU7+8nGB2q^CP}?SC5xlG6k7RNc&_VMRa}gr|S5~xh0NSNF zG)AQ%n78uz;+%#LM}qK@L(&YUv(+LisJRLAN>UwqokzbZt#Ry(mYjUncF}=g*1x&6 z4QEIBiw-83@$?WL0zQ?Yk%^~dLRBlDafxEtP6BiwD|KNTrI%k)YDydY0@d&04*_R$g93ls4lt zH7|q)6N~mk(QJc8yZsCYJ#2<~W!Dcp|3sHRy@gu*Xb*MyWL;iwWM)ug4p=^;U8(Ua`T{||MJ2#tjS~WM|Ik9 zc8&=r5f1s@8k5>$*Jhj_Fe;hH%3obX?-oUE6ZUUEJVQerQ~HU7w&IVlpL7H2LdO zjMsW;*(+faH0x@p{?@wEA()u2sAyE_2w(~29@Nsu*0UaY+HZyz7Z(vzEZJAVLIMB} zArord#B1EV&4^H5d%<&=zR&$pPXIF3hk=nGZ~a|qPVPL?SvCeFo%e%xOALT7X!z%^ zN6_U>zeCRD@hO?W8uk>hx+#^4q&>Lk z3I{A4N64x%&nm4 zX1KPSh5)Q2$cC}^fDM*1N25S0(ROq2ySg)G)#jf~!GR2 zV`+k0&HMfmwVX(Q4salFe;ceM1m{Upuy#{A1SVtbi{Y9+fM+oDIs2YAoWk-~Y}5&iB5QG7+P9@NYLu=rTS5yn*Nj?obXKv;peatz0qOD;$6 zy4o#btalDb-738ezom`vsEWgF`MHax#U%`5Jnn;b39sKh_NNrzyNK%F|6$1A0T;uw z>F^G*W}kY~)2&jWVCawp7F{=#1fxS!l6-1MXs`(b+N-3W86KY(pnp9(c4!(jF}$^I zu`>{`p^RKqKEt9Wcf76xRIfYCLTIHj0EMbyw#N=t5iY~_3)n5KBw%= zZ$6?u;uk})`?Yi^sv?$l=u9fzqD_rjVpO6E^`Z0ShrFVsWQM$f?CZCy1`284>sxA_hPg&zj89;autPd1kdE3Dc507i5$dmuo^MDVW zt_)^pR7ZVBs6SPg(b}wMaQg>W)VeoahuFXA;tLWkTN-yShXj}VzCNI5LQHG73F{7p zm8p|68Ew^blaAOHH#l;U3))PH9SHu^V$Pm47~TC^94jb~=hXCWGDo6Oth+>2PK7_SF6jI`<@WkV zLsQdyw~(}AY1;$F;8o5;G4r|k?MjC^3&ji?EH*Q_k~pFAMEU66VYa={ejq*F_Q#s! z((V}NShF=|FRGK9r$Er2$_~27?;K{Rp@D(aMoM(0kZ5&j6?UjTWVLLTfKScj{vf@z zzw)K78~@Y?C^t(qQChjR>@|VWo^|Jcw>I_k|f($35e9CgTPPG72}f0PbNuyf zSuu4FHh&ww%t$V|1pZ|{%@a$t`_y~3yBt!gL}Qn>Zxesa9{rs>R3_lt(l_Gg`&N7Q z&hF@jD~oUx-Tg`K1pdwr7th>AgGa;8nyMXZ7|r8>U+{uv>1)A8yyL*!3?)d0kw%GP zVPjQ*=IU*9!Lf$`HLfRegtX@p{TAopcyD(*2gFE;p9N~2w~jmW{lz9f6o~631eNti zU4*XLV=&%**oYSkH;$qd4!DN44w!a*)nToIPwbdHAv7u!QK6_9kcc8Lchw=-*D&ct zS$+*{(U?uS?ns$X56v(clgFFE0XwsZY!H{bBn`b@s=fg`m`-0W>ivLesYjzim_bDX zp)3l|pTS@@C=W+-e-5IIHqvT_bM%&bX$~+F$!N4YDz1lxz08-Sp6^z5%bWlO{X*v(EA*3N{4dkLwl-C5c5dGfgXge#;^kSgfqM zY^${)m|_d9@3#7*&H0@-2SJ9|AaD&~T1{lh&}miR57{K_4Ibl*4HuG{zh=Ar&hB2Y z=}{M-+_b4gu&6!sY)fS1iWEa(FeOrt_KpsKn931GB%GCqa+*QIMwX(brLesn^%dmo z8r=?S3rx}WCupFZ1zNnghU3-@~w75B5zWp^4) z0M+~l)A?72x|%KDhF}sKe+=nk0;Ks%5PFqJpM!`>&!i$7NQuW#`~J+P!|Z)it^2_; z=mQ6$o2?%RUuFZ#pb+34#vvy!!==`z!9XdE3=7`}a|5EnrrtLjNd2*7*g_JYdIyAH zgOs>K61Wy*f!0b{9!h4wX`$R>)oZJ+g~gD;l%UX3r}8x2@hYPh@cgcT$3O8M98oLt{&AR6}zMbsmDqFk{|n|I6*YFdYx$( zTt070*}h0}OjQZRvYw3uxB}N}ND5xEBNUno)0RK?tbNH`1#qpdnPSIKR%QHiAOw=x zO(r7zY}(i}9)#vs>&9+@7Cz^(KPAiLj5LL)L(hOlDdurVD@(FyPiv21D#Jo;HW1VB zL*R&4_=6P=P{cFmRY=d&m=7iN;fl)XM*gd~{(ZB+lAd7Zh|43NWkxmepPm%VHuhY< z7PUB>n*36AuGrr2KwliZ0nAS@Fo~s73T<*&YP~+_^y`lzLqS0y8UrsOKqa8yswdN< z(!*+>n0V8)%5ZMG&=&DRf{5ydm|M0$5Lr+HkxmkfMYsPfG>s7MbrF=7Ji7YdDo-Vi z=>tP7^^%&pOGGQ_%TrX zUIo}7a3L&hwQTXfGK1+Si>E{Bmfu&bo0fYxX#_@SI9hUS1#Fw3ZHuF9yB5Q-f|>P* z6r7{wjUxW>TFYmnb$D^szCb0k``$l^d_t9)kr50|8G=_8J#GRb+fk8)^tW9?br1-1 zsDehb=d@WP26OYv-XgPbBonc5yw$E;in1Dm%=l-s^REMe5uEOm-l$DGuG_vM=W(98JUU*(ZIV_vRnl5l^NLNGFGE;rHC)GQIghj&p~Trj6Z zAvQ&|=`jr?GE_Tfb6OFqdGcC!*~|iMv~hJCx!a1*MeZ_6>r=Z!;kQ84po7JjcU)Ij zc(QXHKI#1GxBTMM=KA_m?dA888-m~gO)`wkGYlc)SKd}lYVO?l_3Ia+P9qX42wZyF z^a$Z0#o>Q%AyuLaEmI2%3-sgfx*k-)JlX)D{K=C23yuwg_w~Zc%SA+z3t5$c)Q;0a zSsI^HP_xwA-nyXQaduqh6%~cTCsbtn4n=RmMj$(oKqdHsY zy=!@cTB1~al(paz)kBl8{*Jxnd`ztH4hbi;(oz%kaZA=(9MJzi`RktO8j`!^1uJF&0FKJ5DSXffc1zn#6aa3>q*5DX4sH!- zX_O*u3_P_8;Jf zDh{X#`{?x@V7KMK`(9F&*O^!S{~Gq)!!?)f(TJ9X_ebk*e(C-X6Oph6+BFb{gnQY4 zIGHQO{5t(~J(5%OdhZh`Xx-Wmt3g!gfSkgV>6G1+dAIBylyJyarMbEK^(p1W=+K*I zmkeF>EzddP>G(Z%rwc*hG9m#!0oa{*d3gtq5)#%R5SNqVV^&OY$zCM189u%r>Li2_ zhRv0V7(*vEjPu&ymPy!oq+|&D?rEZp*|L9J^{MVed5-*tRTaB23TZgTyBCzi2Q~tl zl*!^13WHEI1PE_zbfZT5c&ID`Csv>5{f!p;8PM>_1m|gB^%KX=o(R2zG!1-_5Oaua zfp*W<8biqHf;R$jz9=PO6aox#MPOn+8N?YdAtb@0X&LDi{Z}=fmbS4Ox;mqoLG5CX zuvFP|i@IoAK>_}Rq#=fg<-n7|ik^*_ME4YVbY@L}Kh=XmQ{u$B#-w`5Xg90={I>DC z0Be?+wzv%u7+HScPcr)K!pl3W>_5UDadkm5 W)(7riNbS9AtQ(aFs>R?D{Awb6 zIThWW%ELIpKk~KNU$>2Elno=lSDyXKLfh8w@cs)fh-p4!;0G~3(Lnhc=Wt{6UG5|^ znF&YT2zVV&>6?XKXx&YEIswuA`%K>nhG=2quXNrE*yp zx*kfNm%NAX|NkjX0wrd@hVM#)t&gp(`ZiqA8#@{aX&G!5!Npe#2DecjQ9o$X4OLX| zPDcCy)Dn;ii`s&K@?s-~pL=FWYf-rW)>t=;oiqEH-7Nnw4u?L!^Y-Z7&sQK6QWucN_ z-AUf4@3x)sQ(v1&tbFa``XmiwgVrB9v{aCeM^WsVslme78_MA8Q8-`<`zfC{^iAfS z!BUg&olC(?4jZtN`OWp>DwFdmO{eE5A!1aumYZ0OXGj!=v=vt%JLjnI0v`MazPHrc zu)@bc9a~XZ$<&(=m6FWwyQ}5`qtF!wgIa)F&}Wb( z-4D!v3R(yb1V+UDRE9oU>b%ENVKFajf+tcbb{Aev&(AjlWrKK5bZZIY`wWL?Ysem< z(q~L*-zHXmpWp)N8{<&feou_TdcW(P0*qz7JQ|Qk=igp4ZDeOs-_JIs%b&)ui_OPu zUu@)X`V9w6cO#Q_5z+x!!t@iCgAbxFkJWQh-|J=689=)5CG+~jrK1q|2fAh;>+qOr(JV)>ZJ@t(Q;)Stim5!SI#@ zGBOfEy{;X1`}o8G^`kbC6m#&46eUosaISBK!{hK^072yX6gs8+REzdOYYl_#E1pL*62K$G*dOQ-q5_QwSEo1es%E} z20T;fjPgz=^B|-aaMxJufVHQzHw^cr@YutmFe&+`XSyDYk47{KbG{10>)z*L${^@p zkyeXY=6+;AC*$OIgiaU4+&m#qcE(Yz)e8NJWj@A4p0=#%KI(OTfFa7 zqwt@Q%RM}BoS**yYnU{Te*4V6==?71;Nn$Oz+9fwphV9Tr5)<|+E47o9F1zhWv$}+ zkPI#@rnm%!N3eY7`G1&FRi_F$&AwhtB+L8Rxo!2vVOH6Y!M6*h**lhAdy}Qj;MiUx z0wTDQ0_(^nvp;Xj3Pd^B;_Ki8(9&qk@9-K{D{Eg?{a?hq9S+)gF5Enxjt2+rmYLY zT|J0hC(y3TS3&Aw#A6GHL;oAtdo>HvXv3a!!@q^5$=nfLpe(=iPh*>A--gM%VwE^CY1}r;UD~&tTuD3IIN%#Yr)@y)@W0 zj>I^K9`XP&)g@N{Ij(BxXYAgbaHQx>yAlpFN7c)cCLRYNeQ{cZ@B3fiMvB z=YH?gMM?3HMB+a?e01Wb&w~ZxK#u z18;ds0tbkEPo{Hd0wbA_+WqZ=CU%p5lRSAwKR=v+BZR@M#O1 zp`NP?s=G=2D2$-HJf){6HCCDXq&{V`Z0x(aKe5m&mphLt({3nH(fLQswZ`|hucI)W z7xJC<@0DOV)62Rn{?P;wUhNQfy@mFa7u79eC3X?T^o<@xAw!(Z_>g6JYfKGEc6-({ z(h6}G&Bgt?24lqW36Xwqzp&`~_lpo)D0-CvD|%&Je-x(njI$S3sN-*8d0On`ZQ@hS z$x|J?jf5}6s&Ae(9=`di_68rEHw;!fGC&W|$P}PJyViX8vwG1y7Bi5^l0fPfa3H6CH4skzrgc(PQ0LMKR|an%YBL zfGnLfTzlUUuv|Z1%>q~2G2dy_dhhCI;T5|1oGDGZxNtv*X6orw1SOF1p5GN`tNpWN zS>TH4$7L&rUR_;*a#8s1as&ABVnI?>P%;PnKS`G(q&^QRoqz!fNCc-Sf{PVwb`n^b-OZZGV?MdX8RMnCoY_vpXk zu`0Fodg!Q7Whu1|Nyf*acKe|JEz%}EC>wsbcbsI3-F_8Y>h!w@96i%Orv6x(So;Jc zKY3reqL}OXy@5Xgo7O1k4`xA!N1i&s>*#WK@i_$jQkE0ZC8yAnx6??k7tsF<(km;`s4hbye=SUH)`)wcguQ zqV4EM1mF7P@_vM4{A;B@CnY6y4W(hhE`AU?e(FTyM-bK2)ap!{Oyr4b0RLH?59rQUQ`TV1r0Qf%@bJmsf)|E>Ka-4gej;`MtFrmOUHCW5# z{3lyRSYsnsA~lZ&)VZx*m`IxBum2I4@wm~)T)CB*7CMsyr^oKnD7~I!k{Js1&EZCD zY?gr3T=(?#ff1J(s?38a52LxI+$7^;&|9}egj^II^{d6hH|gFfJp1Le%oPoni`_ok zB%#=$(V-w~+V65L>;X~Wu+mm;0=9cGtdBy78V@JeVdq;G7S>60t6TMd57&O5o&8^- z^OO}1R1c01Y!-nqviroXXE*o10mkHwbAqZD*z*mWoT+4BPs5}dcpE0dY zaC^}%QIhBWL#%^?m8VKy;6BpGn?zuVN7Kl3rs5h@K2S8~jqRUc`PoYhfj~fGNKY`> z^2}v3PRhH_D)f2i_fXByjq{PVT(LN-^;C(GG+rLYKif(nA0VjXuctpK6fSr>5Sm^^Re!MN4UY}f!OcnRFlufCQ2x=|| zB-l)*bkIu79*no7$hoeH+RA?2wBhh6=%Qmq-@GPtW&@Af77m@=V3JmvJbM_6Z%LY6CzjE_j&X@IaYXjhl?%~M>c7g zVXyrA`(H|H*+uwER=_A<2-(ReN>|UPKUrXNBXuKFF@(rGb3_x{w;>H=GSzZ^m{IW% znO`nhjCg;5kqCL6{TkmGcqj31be<$#j%M;zpQm9vho#9mj3{>=%sMj#T%On{;7tKD zsMM4(KCYq-KZWHb&68~scWfGI@wlPNA7ivZGnsNo4{@rSYh7cpfGMeVb$Cngzm;Z^ zp^V4v6)w1+BtMw-!K>pDnuY*N$^QI3N!I&crC?JzWq`FGGm$BD0lIK!lFphMnqdVZ z2zCw|EuQsCr=NkMBEviGktQ8fZ1Ujm!jI$Ex+0#KE>fPbmZbTpqE|?S{-r)90aAd0uWoK8ZaRCo=pZ)RY})q{JU&c(&P9;WR=1( zNC>l2*VOGSj~P**rI-WaP<)pbpE^Z9uiLaHS9u_m;$4YO|M&c^~ z1#E*-_;Jdr9J(X$+oOB9p+6-~!v7bRYi<_u5uZSH(Uq~}4)QPB6bL#|1nPdw>RjAi z-%oz~Ho5Uu{DEH_r?Y>1v4RUTKEDGL!!9HEzE*!UMHpiw2$stI-{4s!i3-@he=fF2 zeM5Qq3p)@08v`)VgOE{tU_-;Pb=lonc8q0Y7;qHA%B=wUwXyK+nWQ*P9!iNCWWU!3 z!i$4si!BcRD-%_-)K-(St?zy7(b4Z1up^e^RXfJbud1ssa||lajY`k+S9<|yGb4&d z6NMidL^w(#JQuZjYpwqlVSmb+g)g8V`kKAFC>*2FIzzRigH;DN`AQt3VRK`B9phfw z#YsafQ(D6=uSw3H{C-(*f`@=D?0`Ou-md&DTWcp>^M^Vki_t3CA-*KfE z_E=e>TLD%0RaY|feyhx_L~e#+6lsl_&-ccIzu^=6PdDCylv$@YHv1aE$mvUFc9>8I zUX5LM^XAqTQ)fRdGAvJnVAi<-1Nw&>df86NO z!@;U~p$81{99`@KzMQoxLA(u3?RM1!`k?yBJ+&d#<{2~-@wOG9D?RZHfLkc$0Smo8 zM4)q)9_r1cO$OuQJ*fVy6bklqHJFyK#wg=99_ko{bYHG4B%Gels8jf}c~D9Ei};1p zCU^As&k1S^vzKER%eK}wd2Ghk^5{UfU@LDUOUv{HAZ5FftM`?-kTL|{*~}tFnw400 zhddu18BQ6`K42Kuu!!gd+Aslkj*To{J1?zDo(D4;{FrVkHvEorDjWZnB+u_PkhA%{ za)l0&+r3mxqL|?TlicY7d9W8eje7j}&r5$knV`0MU@u#4dP~Df46 zf(*qbKJCxi~%-s}&bmM3+oumM zwtC(DfJ&}5{H#C>g09*>{=itHcU$d3m^c}n?7Yu`!-oR{C5I8yKmNw0)FHvTDvk7t zpw4~e&(V_{bQ9U^qa^ZxhagVH5pCIoyq|5wJ&bf`K)eR zzU5YtO^0r{9MW#<6069ec(LT_VN<42&9v)#yczI zcmeEJ&LBtxhj`*+*cAcM1KoEp-H9(%tS5<~{~9BnAVGff2n?jGtsM;ASN+9E3m*4< zi+H$#EW-|YW7669KCezirzXOE&F9~#B?%EMzU%X`NlNHaZUOT?lIQo_?Ad&84Oxhs z%atEey686-&*Ij~ase7SNhnNMEom9is({e3Z3_(Ry?^G0*`cvboOIm&dCTzp%`a}Z zSsS2Z1SI&?v40;)&c+>L?Z;?ga1C6xUgvvg3W~B;d0inBUlhGJ08#-}2n-XixA{8% zGW#7f^DKB?EV&<8Ubt6?(}jLfsN_SU4x0A*u=OQ^3NVWbITXTE2+xWa{Ba|E)zc`< z;&GON_+`BQg!6sYK#co&$FREQH(rq1NsQm&{?HzKwlQ7YWwnfijwdI2l|^>T@UpPARS@s7G23I(DZnZPOQWz^ zz;egdbSWZE#p!PzeE#Hz{ms;Xi7*bV=9821PP1{Dzmo(VPSXHDSOP7&fY=MkEHf}y z$)g{c`pG>TLLG!*WOh>YVd`M7Rzr-l3NCV01)ojWF6Idz@YGKz0aO3O|x(2D#tndKim10_KJX z9jDBbudQP&3JFFo96FaFxRpM|kKQ5rfv^OV+ZRuYBnj>j^#90(1SNlNJDM>ML_kYkhFe`6~wPumwfA{OKOjB%p zulgr|g7tT9s^+@@`<%J|$ULs^VNe)OYI&%PyXudtRe&n4d>O} z-4SwKSEUnK>VLZz5W>oeSyI~KeR){qIGfLrLNJyeweGnL?i?p&s^7BT7#>cD!z@`= z?dI1T+XH8MVs)LpZ?h5*cdY#;Z4U;MR^pqem#5kPT$WJAUWFm6 z(6vFsOav?7hu}C<`Tx4=DqgUu`d+YPHu$CU_ECSKItu7sqA2)c>`N1zx>AVpx3R8afn8Kg5)%>F(qpIvUUR9E|WY8TCd0hLKoXr@Tx zUoG%R`Zq;S08A5~l_Km%vxhK;yoMv*6zv;tL&-I9+O_AXkc&?fjp4%=Vyzi)_$&e0 z?c~gDW;{W7k7PK>xV%URIMD)Y_@ouO3PX7m=%z-bgY08()Qf#voh?!>lh`r@Ty}3S z)RB=z=HFrw=5ChD^Z2ZP=NgqfsQAv6lt_>HMcx5~{AKvoaK^t-+@2^Nb!sWHJX!0_ zdd`cBe^%T^{_mc{TNAJvr`()x(hkr+3$Gk396yZOHt0!yA%c!v~`CCQ0qxo@lW)J7un#IUplI^K&uraSmEwVY;TV&XN@ zi&VeAsm)?GvI;l90E7X=IV(j7xb2bF>EGP!h=mO-0CUIi$VfbM+UMUqJ%GJqYik>i zkGFq)$n5p2w0Knsu7l%F9H!dk5=XPXa`Vw|BV{A_56HF(#iocg80O6)5p=bd^7(xG zWB~88^R*VPF#1T1{{m$@!sO?{(SR$8>1f#)%I^8oZ>8#!!L*ytkhJC*Q8Ij8O@7Iy**V(gTe6h;FsO*TBOt=F;@h4z6VGQw(?JCEG z9^PBRj*p|he=8(l>T3+{nXOvVg{jjRXLEs~u!g=?;jA9LBB8!Dp2R4`-l@|f2XW$= zoi54|K@|qrilO%H{NA(Qt(|b^Z%kvJg{IXUExzmz@rs(TjBZ#3#xrt6b7LbneMJG( zYhtR7nZkCVbtXGl0wE7H+dj4dOcQ5&exyZ3>JJ%c9TKB`5#(I^*-LzVlNU&fp&H?B zcs1gh+>oF@loz;LHU+2A2kITLv z?ZvHLY509P_sP8b>jB`-aO&25u?lbN4;jV(xdV2^8&A)`vN013iog{yAI2-8jFh+s zA?HzlDYSaCypQEa{R-5AF*B;}KtM04OgRhUX!ksAM+0c6-LFpH@Z6l&S#*q6MurH# z-N=>FoRQqJ&SQ>PE*iyq^6!zVt6i7=Rjrw1ck*m=i>D%Mji4`|&!?;=fM|_)pKXH~ zLM*f5ckd$&13EM+sl?WQYr20=$V2HH`x7PaOqzMf@%F0F=w^Mv==PT%KyN3ufM5=v zoy^XD9EbgNUmFVxrUa%ql>M`g5;Wc7OT-=JQOnq;pdqef-%J8`V+jPq+(We9pY z^Sz5#JS9*?Ib(aAA`a26xL&Ois3LRCBzh*|xcaCn5nwKU!vVrqA=W}ANQ_u`Sw)H5 zsH4QgA4=GZMuLamXuaupXrB1@7o#vC>-iBCT9bf>A_FdmfLw~c$GsGa%%5E6LyeP$ zdGTGmj0^?B5=#E5QZ>z;PQ!)Lz@LcCM$D?+gtO0JcC1v>1FBAT=!99i>e*!&c59?a z!3y-BM3-|L9BxsUB2rN$26?%ZM{Fq8rvl=JAF*mk2u7pC!=BiaT_7YHnqlk95; zKoQ>SnXu5ag)fc5EPv;@_EaE`fK-$}dm{T)U!-RD^OWIc<8fB-3TV#fgr+&Hkt-^0 zz0ah{PBIC?;4&>O>Do966$uTSZU9Z4hKdc+Qp}LR84INrhB3ecz0UvZ4G^s1 z(+)UL0`IM4jdW~f2s^{Pq-(lhi|g&xh3Ms~n9o_c&*Af=HxIs|t-eU*EHO@eA0FUS zN>q+BsqdN`P_h1L+l5n|oco@jqoa1~5Xsll7a84aAAyT(88lLS9Y@h3Ugzyc{S+)o z-Q95c%jlKM=!f}d@oWqe&$ld@q`pS`g=X)c!F6>J78XeYN(LS6J73Vf*!OhlS+)Kf zfAahghdW=O;D{V{A?Xi%f8EMBF(gN;{;PmIIIe?(rdyB;F0*PyzT+&(CG5+)B^~$d zk>~fDzb7IS*JAfO_p}L=ow1Gw6r9p*f~*g=-=)i9E;~ouVNWpBbl%y)p0?F|(AFi@ zN>>xy`bi`3*v;1;ccW$N)mx(n05XZV6Z#F|8IvR7>GjI}9mt-0x`jB~yW4TSzX81& z+TjAY{2-?ls#@Y^m^UE;ZbmV}Y9=!MB_YEEI{9S?C4YdrC+eQu9@_a=Tr5(gYQzeehuM9>(_)gGQW9g}!a$IWR!KMj>enj^z?kh+9xMd}#fmoP3eb6&E@RxhF zR^`(Iqn%juzR%h*@u6uFS204o{_+1Y^_5XoMO)iQcek{Z2M!@1-5t_>=#cJ|1_9|# zrMsI$DBUd~-3`*+eA|2PJH|K08vKIIj81P_V)HZ-f@VmrA{s8h zArZc5Ht&fX`Lpw`PO?=`00T4+OjQ^|cQRp-Omue8pL2CNxre@z=9>s_LiIC2*a=%Q zB8Y9WqX1-mLSGD=hnt8y-)IitqR%{gGI5&*5=uIM_!~7N2(48F%>hIy!X=u4e+l=t z6mw_gFWO~v0-m~huxvkq^cg3>k_ZN&c-gx81I!My*>9;!I*AK>w#Vl|YE-S5@w`=X zn6d5oo8=ureqVnIteWL~T<_0-+jjR9#G$)#<6Lx_Jnlv#PsjWrc|LaZGC5x&nVGC5CU2Sjj-UDW!_$RT**6`OrJWd=|n7{ zyZJoHBo*hd3!ip|(~eh4z~hUM=eM>|on5M)WB7Sx*C8JCLoVzc;x_m*!o0~#cqS|w zbN-O%>W0Myno|}TT;Wimd@5U^UW;?#Th9Yn0zHbfbrpD8V3W>)UjmRx2U`}Zh?bX+ zbH{6IQ>*qwpf4H!X-&2)`C>W==zAP8|MD+jym8=rN&<=ko7}LkoSoBgcM~@SzE_jd zl-@_|PZrrcfUW@O@KmY3qB*0|MfjbXPt6nxhfn%TMej~-yxH>G) z;dPVsWz*sH#v#5CDE^@VivXx;{9hCw{#28+&yiPYW@&HlbK2&h_~Rqc|LIC+VmWt% zmv_7o^$^`C7JjyBTATF1`fSlPJd&!kdBS6Fr&h%4^7*wdQo1y!NcKy>^npcScPLdRL%@m7s*ug?a0VdwYWMgh+?Fvb z(rA;%<7%%-9R*LUf63}C`I?3v3pAw7M2!1^Ld5M2A-eiM=$gPp52e@B*k)lmq>Au=lvB;l@O+5P|lspH_9pI3TP|CSh4tL^8*0|(#_Ma+Lg z*ytu*^V&_$qNybu>-BbKjJd&YEe?*|JzpxiyBZ4k)bssNGl{kW%tY_Vzx|#suWTsF z*29JuJv$*p|HWUoMSk~-Mp*c@HyjV&T-yotn9U3dG2=%h-q9g0&sRL_O z%xp&qZBi*&$D4^qswq(T#tzIAqUV*TrIiLmc<2%1qXOH8&&f~Qa6otCta&}~+~R{{ zKLSxzT*hxxy)caNvLf>RKF&hi=2*67~_C; z_x{>+bHNmFD2PAZ^E&M-ruKk&8DOVD@tqq}57ET3)QJ12q4m0Pzej0M7yN+I+mX?I zyA(+zeA`3WN@i2aD%lK2N4}34=Z0G#JDSecb=VOy6N!N_p{3R2;jWrwB{7|NT}F2I zpNTP(>i7c6eyp}Bh%gcthhv?+{*LuJV)%kfw{>?*3ZoheH; z!7%n{0_p_e^Bd?iaDLC6%5Rp$sR5N|O0^GwRfxha@b8 zIbU~Ph9k~Oa;^MEN{H<#eTAk!3~^$Na4ICC_sn}Y>4;mR8uQ-3Ut zsCL#2#H2X`F?|^RR(S8*pSE!`S$Fpo{EiJ{(YqiV-P-m<@8|hbd?G-(0D*h8Hhj=s zuaeDq=6(QC4HL^KzJiPH3;pb95ni0&_NZFwj)_RP&vHv8G}r4 z%y2=3{L>x))v|6zD0xAZ8JwK2Ol_8CQt0i9D%w z-%EYe?k1&*@r*? zPk^#|IC_|{BU?IHP>Rj+c0)=Z;q^U82L z{hN1pM?eL54ye-T|BRzigZ=WOs`G=7+j6}H7F{MNZ$UzdKRb<_Tv)f!dbT&5`)Ybh z)YRp&_0x|muag$7@yvJ8KbV*-lrrWQXG0MOpwOnKP5=FJ$l~JCv7fj1+s+`I&iEb+ zbs3BpoIW?~jz+83m+*Jep9>1EzVc1VBVo;E2`i}};;hKy=lwSN=otbBSjOk(XS{9ObEO+9OfI=uNgnoLP7; z4RSN$R~wM_;1=xd>H{wN8qGaK?9~E{_Am6Z{SGggJ%taWpjuRLjlds>?RdJH?$EB? zJPtLc@2Kk?N*u7ZiN(lJKw0hW;skScqF|-$%+-A~s0N7&zEVrBFbv*qOK;Hn zYzv?U1q?Gn%MRgPl~tScDwEADk6Kayoe4qC6I&Y?VC9g+5(^QSE~ z-g0NoJU_+)gUH;(tu=`$Gd^1n*7fW>hsNg5e-c2(VwbxJ3YAS=!tRkIv6>wg&g|p= zsQHSsllNlzq2)Pv5{Z&}l~SNUfehDS-uw{Ji_*sIh|g zc6_rAUg-T@OYc(mQYFKfr@-_Upl20j27U zq2OwP+6{C`_I#rcXZO5x36dnKV1a=vCu4#rp>m@uoe(?Y*e`p;v1n41T4e@riAvC& z`ui%oQ4nqAM|Q>~>yMne6hb3}27Ynevnsy_ucxEO?p!Fun4|r+>uNqb#$smd{A;dU zv__H|uvXbk@pCyQeOd5Jhx98O&K$NZ0rVfRBG(Ut8!xZ#TtHCaK zR5_&Gg)OwWSR`m|5(`geN-TwqW3#hT^50zkDPMz{gjf+LxyED(d})BXySQ;#;qPqw zTxGw!=fab?1kRnKsu9|!B!F~4WocVS74!CyIj^wD(A zLnzjPA%)2h@V+?@L8~49tSqeTeL|+nMW#h8aT(rEdrp-8pNvFx;}bUS`O1_xLC)#f za3!4Bt4f}xVd|__EYiBon6G}PxBS|~0{1C(dT?qG?AMc86SqxW5V;)g*i848HtA?ku_QRGi64Dedp zd#S-aI)g!-B#xkrxQUAIV9B|#_iDS9`i~=MM2h*<$uD;o%Pp~H7DOt}T?CgaKeHWd zf61(%)3rtp(zYt#7ZiNO?g22<8tUqCh@eiuA8NL-3x)6i@T#WUmIvCr@xXmMR*E8j zSathyT9UWCp6POlWd3lp?)kOJv+3=F<+4_Im;}z1h6&tcn*&IMvi1o1my|v%yzK`0 zQsYT%FO0x@`(0OYVRwJS^#iV&K& zG$-u>FCX*jd=&i*Qr14)+qP1>uc@$y{Wgu|g;J@L0}=;j=j7uiNdSmT1}$S%4;Z0+{?0Mr7*&e< z>5;m7GTl^}-LHunI^as+d$m=5rtoovBOO@mwoa8=rh04--@(e~{9E1Nb}+Fo90kM! zQS#=oC}>XJUQ|)JbRUXM8XLyJVn8rpIyfAb4;#C}&LEr$C<%=bPH)w+B=V3WG`)Bo zTbY@W3;7U7J^{jvExTHT2*6(8qx~)v?rr=bZ(eC>DL@op0fXtVfa6(@v`>evfl0|0 zO&%qln`Do27Jwn{8coL=8F}Br+0;O#wu!`~)jC`E^78Un%PdKXNc906$&41M<6EQt zmnjam3zBG3!&3eMUna40kM%*X09M*wF#_Rsa`H7|6t&7SkRxYehxzy2HkI?Io@b|* z>Pp?~-^(qM3kyk}q`JCi+Z?KDliyTWk5+waYvc2lMH-?8Y5%u*VYjkk&;0rGWttYz zuMR#j*bIf)%Ow;=3$A}$jfd|KZ3ZSzO9EXC8Se#PM;(k0fNuAH3M0s-VACqGP+!w6 zdp{ZK`=b2sVr)bGIWKQooA3nX8-!b%y3&)GI=F4MB^i^xCv%mwKD@@!8hzJPR1^(L z1yxi+vboXW40BEC1WLvTd@NA~Hv-j2d5#0+`GN(ku*S(VXs~#CY%m!5t&)Sgf@a=! zJg#s@MucYZdw4B3TQ&QONn=>yT3M0s+@RO+j~FA#7C~=zzJJdYBtku*-WrGOPyPPZ012RX zyBBe;CUTUN=T$WKDzd(27lbc?y@o|vA`#S$X0cra|0y_4oGv3mo1FtgT7%(@ZpEgA zDL)8fEc4WJ2I=0&b&2_Fv~eP-F`tze?2lm zQA1(03UUBvV57)(BPwV^kg=5pR=^8O}{o*cS%902{FY*{hwlN)FD$0g1ts8eSL&# zB0mj8ZG z=mya*Mj(QQT7C3=aD{#NnK6@!4ZrbF#uxKQdwB?2l{rWAJzZ_v-(MmD{AV!8`DP&b zwt%TY#{2k$grM6m`k1twYMc0zbK#*lU@EWpeRGrj(fi9mZN}HwSCKAdIhs%_p(gXl zjUhXc!pH?Ydb5xo|NC^=ua`uD=DbxfM5Ls3sHo7BB@66N8itqX6Q=J_t9Sz6rPe!Y zG&nkgbsO=~jX?7q&ZJKsS>~+LceXq{(E5n~XZO0W)2kvxnRB^fPFR(WCf)gd37o3YzqHlC+Z$Hrv{M`T-XRI! ziIO#$(h*8uP3AJrn;Q-*(D$~l+1;nL zLfmKI@JnU5sr#IS2RsAzVep+*%u|++X@5nyj(bhr(2t*Zq`4cf>>sZX5G5lyuva+w zo+kY%?w?;P1zqzHjOq(TzapM1%Fjn-zq@eCE;Z%I?S34thyU*K5vvt7I2t9thw{D{ zN7%D&T&2q#QL}6Iy5d8vfPkAGGXZN%G$PuD3QrHiOXJZ`CL2Sc)uTp)H>MN>H^gDZ zTP5o+!*35LA5-JkASe)9f?j_M3yYuX^nF?fpGMfZ%Wz+K)L)v$YY_+#J+Hp#J>-aK zsT;?(ZOOBmCXxn^Y;6OTH3k|$?bee21NFVow3n6>-Ws8q`8reZ3Hu-~FS-Cr+@ZLn`|$QI#d-h0x7L8u2z$G zb!`0zAkST8XY zd@uw_BO(zhva%@p{J_gLW0(Z=xSi-25&wP!Ou58hX}>srpgRkVCC50^$sTCI>-C)J7$}`uCF+UU70Ss3dCHXr1b`j0!G`_wx2~+ zCrcgA$AHDQ!>`*mCwb`imvTeJ1J$3o?#_RYwk6Q)^>Se=HQbs#5gxoTDGi>x(W*pP zmR~mu<@@dwlVxgtX{TjA|IsM_O{t=;&T09({?8xqp*$BymL(?2f9qP^Z-W48Nu_pe zkUtvF55~5;&B%G7@JBJ4b$ApZJ^*gq3^i^O09YaPy376O>>Ppno%wt~_~l}I=$)YWDhCtO z-slexLj!{$k-M8Zhc!Y~0JAF$6e8(ciDfkYWB{7Hx8<6?{?8AF{KB%>rO+>zAm(r? z-r$73$$b95hnQ;IRuWjIK7*elhm*9$Ib#P4XoJE;BuqOw=35iO;#hNu+%UfN45rSv zx-o4Y%cy8;hcT@n2TOM5`EUT+T-ZZLmbOl6B&rz<#GWs}68pl2iD!TN3aVN7BA%z={rLuybFh0k? zC5z7%W^`Pd5w*Vc@@KR(X7H;r47@BN!fTg|MUs{9O)az>(D2 ziCC^L7?|Ci=RCXu3W$L~stff^jbna8fQ}^ek`si*uTNKS$i@SDFWLlFl*Eih#jF{k zSUY}vO9nZ^sqn6#`ZmxPQMfq=^7GW_E`@@dLj-Tixr$+c$yyp+S)^iZ1d!8YUIW1Y zazA!;M_PT!1=!?J!)n1XXs795-pqjcs=DW>SO|Pcf$7zA)?}I2=Yt zM43^{0SG}^1$wq`QE(5d5-Uo&7i*3-Q44h+Ihzlf^jPYq*qX%B(Q65^LqXKLHpr1o zIrJ3NOf#Keha!MvWJ6GQ)8y&6m$2|YO#3Q#3F||Re0&Mzg(}ZwI{U z5H;u~0Sgl9l?`k<|6$)+T2V22eT>s$4Nx|F`2`;C+=H`^J!Pi+-bshWlxm=N7IFv| z;4*x~5&r}Rula9=53`$I#6eS;{Q%*J$wl3%K?S7=8F}#=*c;?r30Uv9-@k*HK<%Fz z?AF@tyl=a2Y#`6G>gn-*BYEW;l&39wk4i%KKQZ2VE;>&2m3{glm7L<-Efpk!6P_fp zUQ?##RZ_A)S`JY0W!303>lwdv9F zXxb&a4Z~%F&JYn#AGK@#HnzjB{*d`!ZLtceTLKHmTs7(Wu_>F+Z8Ki_#rNsX>JZ{o zl9Q8!D`jf>47hPgwg-&|iev%pt1KybSeS7CUc_ZR11~4g z(jtjQB*ghyL1W@D!=kJ_yU@((V5$W;-<=*F=GfcQeOFW`u!Drxg`vx_g!ObTVozXf z%L@SXa-Ne(U}x`BYEfpCK$S4c5nFE@PWpF`HM6lzng(R$q=}+9syG7y>h%W^%0#y< z`P_AHg@^AujDJ60qV=OIiBqz#As6)AJLv~Dm639P$UG$%jYM^OPq3H0?3N|Yocy>; zWKf9e0n=jlrgsY6gDP(!FD!TJ@}8qYtgQrQfN_8jmR+63o}dXFKM#5m`D%M&s4Nm8 zj~XRpLZf5;G{_cs2U4(w%$s5{8$pmMH)Rqe7 z;Px#Tb!NCf`t9rq&wY(n70AOUvzM zcyelD|ALmGuive`9Ifd$O#Pp3f1iejar*kcq^GkUElih!)yL_-EBtqV2s#UeQ>pub z4*-p;N=rAcTkmRLFa%p>DA%pl2l-#txrw0lU08pDi19%Y_+A}%tgu)EA4Pgg);gM) zQkYJ{Mlu1B|9^HFfW-^YrCbL%7aV{b*AWw~4z{cqNFF&s_?uZcoqUSG^^Dptzr9M< zjmvw_x;C=QvkUu5mbta=rpnTr1Ct}H% z^$^mA9*wCLjf#ImM3>QJi}IJ)>kUsG8Sej4lpIXX8WH*Jd8xy9*Z*a&>fzxM-+ZnL zV`oQARrN!{*_P$&OEeK{yV%M$o}dgq?T`1?-2EN-FEGNr_P@@hn1_tx(Mpdj2=G&Z zmXBhVz{0uR+U>Xk;|0G8c5qm2rzFf<{`2 zY;e_f`VNarXZ*gDM1&%1Y=dl{K46HDSn2a{fe;m#u}%f2f<=6id^;&?Xa;uBLh(aX z#pn;U3gE|-J6Z0q%?K=hdi`-Q$eH#87BQmX%g|;G zvRLD*uPGyhH;@^^OF4?3S_lG#%L49{I;;@1FCfBKZ10*_Ua}s+MM0};zu9)f3B^l; z*~8__=z=6B2%PHs>gaGV=kHqwNdDS9HcLcQC$X>H0*kJyUf%)l?8nTP832wK_jf;7#tRiq5^wmyD04+f)6u#^uVHg7Yf_S5e`%p4=q7Kz zGe|AYcf7}J%fb*F!Zg^ z_35kM#L}vJZu_b%;q&x(rpC_BJi$9Bj_oR)dgVWu_qgSTUI$lwk@$32{xqm@|2YWCRn zd4tq}@*u4h7y>==s%EABZ#PsX>&aK55Wldhs;Je=#pxUaaIHaqz)OBxl905y-a!1iS?*~4X6jhm+=oORrdBdWu7I0>F1mxH$ow8ow1-V!lA$wS-b*E2 znULQ3q#xuJS-ANX^#Ga^5BSM;Q{)dOtN)(V7z_xjG$FPpfcBMt;EU>Tb}5%2BRFv_ z7YWwT7Tl~2iIgYfafC^&n;LFwoy1`D)8 z2O`{JMGL+4V6Jug*kDBq#bV_2Ale9?cHzwfeJTU+n4x0IT~?3#>?LQ0rlqcB{_ck$ zdUaK{WT2kzG{)Y9+Arz9;jPiS4Dyr>RaNzA5AZ_f7Gb``x=l`i#Z}b<0^$a#y@j%d zMu_2l7x5X^P1jeXSW01vjYQ(H!~3y$FNE^=!y-z4u zEjAXgH`koS_eCbQkfx+(0ZoJb*|IVKu3z{@N|Wblc4x%RfwK`R)adk%E+Hc-D(L9w znL*K(*RfLvgCmR(FPi>;MKaHxK=Qvp5G=LO+)t+4ELK9sqgO~1_J0B3Z?gYR8=h?e z*FU-24nCEH;xQP~Y)WDf>*ygkiNd>JR2Mxea}c7Wg#J8qwEx#%r}H=$M&Cc*gk!r=u2|_->eJpHYBV1=JcLujDUqe-DYfNyHriDNeNx1ANMH3n!8nw1JLdM7GHk=Vf zEv_9Rh`9Hjz~;V^BGy<>;cJNPl4<$Ah7X5S$^xjb@Aq#(M2{}3ktDFTtDCh{vNZ)< z3@T&?!J^mMzB#X3bBML`-8`Yb`N3F=ZKO@ixgd#e%$F`J6%{%Gd%eRM2#2%FxyS%v z_5^wHdL<&!8MGJpV_M;@9TNxlhv8Rc}kXei~FDjHW%!eYW{IN?PsHm3he zF*0_MI$u3puFU?)McMtMK?1<3EG{no5qbg5MeV-B!0+m`@$b7ZS=GRlHT>QE2r2G< zG}yaB!UocoA%BmE=cR=fK_(`f97)`%GyQG#1)kGqc>FlKXsv_t zZ-ei9jWJ?4^g}I2l(%z5mzS5<40x}y29?xv%i3M|L;zS|3lQMJy2owKd-s3ktl+^3|V&uE-vrr0suq7=(lsehib1--$%3pcCV}6va%LhOCy_YX^MM?kqawx zCH~op`&B@I885X3P$GHx{@wbJUgQc!&k{HgHX%S(tVh)3S;uV=CCg5==ecIT&wUYq0;&d>kqSd7#}P*6@JN>Jid%MmGB zXea55HDnC;LsBTYTh&umGKvjH-wJXPNEdd3mbK|Z!91B(Di7EYbJq~72Vep9gFHru zZoNijTP8IcrZ;cw2{@-O;{BT|Kl~bHtIUGN*^Ph&EiRN(kIBpbfb z8II>|ZOs^Ac+8|G;UMwvR0<4g1_q=7K<7<}UOp)$WwpFn$*H3sE&_=FtB>l%kTOQJ z`nKy!3bT&$6Yp%cV4&h)l$esI(4lfofc=NG`O?H21zIGZ= zfD*$Vl(Zwy1X=zN-}r<#hJ1$} zGh$&+7H?0?j5QeU4dn-k=W8WHZ^lCx`3}9lTPhW_eeGEeXLqD;lIzL|2w&2H2a)x! z9H?#xdDte8*pZKM4TSqCxz^;jC4Pz#(&a>^s5B&*4iF4Xe_c)@>-X>k_U!X z!N%$oP5y{b%N&w53ag&_GqpJDv~HfK;o4HvmR~Mjde&Ssz&6`DJRg71{72_+RCSP0 z({2iM@T3hYw>5;B3f3Fx-qU2a)dTJ0-nM~i0H#mK%`uf%0!zkWP&B!veydz(tTWm7 z;V@V4liCwyma@2B=GXjFp+x->BTOXBPp|H!*O@#YmDY?j~n@@>VSb%0P9 zse5FTXv{Ic7vb8asqeAs6)av$*zBvqo%C$w?Gi7U@PJmf0LO>+;O^N?X3SJMqH@

>-7nRb?(-y9SD)RG7>8&Z4+q}zpxZ? z3UxUq8~k_iRzBeu*k>)Z61>Mqg82^79XDt`J4ylTFAm5tV&7#CP<-W2;66EDgfS`8 z#e5eX86C|4@a^5sO=yHt-|FgSRaUhxuPUn082c?+)?5wT%`S~IB@qtBDe^Qr{uVJh0*3U%8ib~+D^WE53ljwWT`|iy?CBmI}9+%z0 z`FW}v!EVK!GN>Cz?)j0bpUXDez@te(MPseUSKAAFPfEju7|`_rUWpg>2P> zs%7svu-)%H*NV5n9-;eNp{y1CRYR~@wzX;pZ;F>0Cp+0f;(Wb}qa*R$4xVIA2=nQU zj{5tN-@gZCq|IzS%sf431Z9`aE-doa94!cc&2JyTqoKmYiS$R*9h}-2sMmU z&R1V12XErxzTplfp+c1#xF1M;2y+P28!eYoQcce%2a$TDV+vJCH1Y;As3Oazf<&29 zSq$94;tWcK9MJCXzJvo7?D@*J?5Ng5+M5^m`{O&O2173`6>8ukaz+ z!ThBEc^!6yt^#Ia0->ZdZD(?3{}hRQ(I&9Loy;##{v}YozqIn~`nX#q#0I=i^i|}a zSQlo@fB#(nHGO_|>v#*@TJO3(ZA*nRQwg+Ms<`l=7p?;`cdWYVNz$8^N)uh<<4NYC zZM-uJUsx!+-VE%<;LOF zeWA{LZV4+wnUT}~#mD2@6@WVP10*`_?d+~`g|4oz-_!vl$aDT+^qwwUbkikwzRaR~ zy5*9_y)5sTOZgcX;C_MOa_w%dCWnEACI0604LZyfVy`@>sdM;GYH5qTT94IxoEZWS zn_!4NO5c_WV?n+t1e6TZ|IN-KxJE3Oo^gAsP%$c}grTSB9FM`>s*+0SZ728o!<%B| zzUTKCi4ALrz`xkDzy9d!A4X&o$Dl9?RX@pl&D~HLNf5Js@6_apVf~9oNdIP7 z_Wp2)LdKMRz!GPw5&b72BqwB75az2@CM@$RL+~z6!>un!i;zCFsOh|3PREo{e9dpq@hALrH(IB*sPzv7&hcCHK zN;)xxuC97F?;RPdIKrL%B;I<_S7YKL1OH{%OHM?#WNcRcH|8o63lh%4?`hw zQoa0`)T>U!C^-A+RF;CqL9c%x$dZKI$-N15@_?q)>AyN3Ao&zP5w-?!l#@n{DbSHY?dbFcYuWGYTCkr8ast@8!^o8`brQWX~$-?b)ms*!*ZLWv8U zYJe5^oYHAk*<|;)mX(#Lti{K-I-?6`ywQzh=xqm3inEdWrARtzQr90P6;_n6oE`iACn5Y${GOUN=f=)ySCO%;ZJ< zc$f4sWfQu;PLWT@aaDvJSz+0gN1hfYnGQ#8SqdE(WtdAej~9ykqRWaltH5klch9VS zXfiovfum*OR7OIikxXaUaj?41+y8GNqQNZ6@RUqFyh82x|4hTV?L^BI?AymNdZeizA!q()FhY9A3AwSX*umxb>EGZ)4+t3799W z0JY|l_0!i4O2rJGH{59dRyr`IfBy#L>g%lkfNlYEvxO5i#_j3smn*;nD;T?J&5vL2 zb~KHBYr!JhP52C`>ss9qh0&a;Vg3ss`Hia)1*-1{oD}@R|0)08?`7{j;c{b-UJL&H z&(}-;Ap2#?-OUwW>Jl`{>;$vU7J&Xj(oAYZu^rZz_m;bzr7(bRa>du=@g_RNn^vLi zwEf$goT!i%$6TA;(R)|uygNPaJ<3e1_K||t+#8s03ZZ*2RRhR`uj6F+B0=M41U$fw zg^ii}a9mUb^P6iSK|(a_e3Sg~D@Ma$CN2NpuUD+*H@Mo{;6>)BB0?Nn71ShW+vOMG zx1V#EbjhecVI(uF?$J>C*i8n+MIYD7=q!k79Y!XU68z3{U3c6lMy(liCWKg0gQ6pC zBx^?@4Yfef!PkjuVv`OoB6X2rhW>`m^bwL+s?1Af6`I9<%FTCp08qeY8g}o6Sqj0l z%O$#KTn=DojaLNlRuc)OXcyNq|uQUgr0?dcgxT9s-vso#SyD;u(6U?I2!s-;2#OJvH4-IG(=# zk0uA!VXjF)0~$uTzuQ$ZUzo#&Fq490$$&Cky?tfnGVSXZ!ysG#?pll6;BU^h8}dn*I55Kyty&V=Gfy9;qf@pW}d~k z7D4_yUyC($!2X?^V0|c}OW@xFzPq%dL(kf{f%!xH6vr`|JpaHLYmZsfMwU8IoUsxxZ z)HrAqDIwpu^+5%VJoV69p=6lwz(!t>`TMLaxJyv;XJHXE3>IxDNi|babCQs{u@>2c zeINv|sCtpxUL(Xd=>E3^FWC%CNVgY$nGR&-OXpHBR=(b4zYNjbV*?hSH($AI2pggF z(^iSRf#;WEkR?`tA?4>a%S@HQ<55+tXpEAAy%b9>A7>6@2;*6B6v{3CrXB7#>{)5| zQq7t{lRcpI-}#?~-orNP7WLD8v$QzNnRVsUj3`a~Kh>pXHZtZeHZs=QFPERc8+P}~ z{{js9G7N+M8-H8G$e6XZiv84h^wO@KL7^h(unON$1yF0Soui_opY8@;vt*(~#*UU- zuD6GtMYLt9;? z5#Kxsyo{V)%iKSIETReIrSn9>gzaIA`l?><@2E0`;!yvknsH6c-DN#8HAkuOg7DeY z>F@O7`RPNp+qypjC>R6{t0ScTy%Vk%!unMd>dtA?fPdU&*iGX@sAD;~e!8d^8{HA8 zYpGE(%?avpIA0C0dy`1llieX^(|Nr^0KQ9_RZ>iWiU3)_W+0)@XpGQ!Htv?mZbq3c z_4LG?spr%W)0_jceBM<{h?#jLvL#w=5(SaQ5H3$*=F4_$2d$Nfp0?s8V68td#gHQ@Wx{sD0TLg32gSmEbNXW&Y;0Z2voo%S@*}5yr{0_e z5}?NRd~qubt{^8ON~!!SgL&(KSaI_cgyuFj?e3M&lPkr9hk@>782`7j^_7K4+~7W} ze0%lz8fz8ip||shfx+bn2(|p%(qEqL1AG9iWRz6?kQpwr+M$H+D?-MGQFu9Q&pjP> zqG8_f|F>dWezhOWLL9()Xg3%EYbc8J4$Vk8BfnB0qyoRpXI1MV;d6RHS8$N|5lG#2I4L%^E6RI5f z35dmb(6B}3#XuBDKNC0MqA6ZIV}%Za_Tda6uSz5*;qlD0Y7bdrS$FgLP@Ua-8}@8z z^#{#7p!01EH^l$dE9&2rKj{y-FdoF?b>5EF|C#dEEM@bNhLj4=r2s?9_DIcl4cKl}SQ|w11$ba(+SUTc`iuLNdmc z5uj+Yduva#EE5iee)PCzg=wz5oPFqyhW!^KIS|r+d4>ZnR`!bx@6#2mE5|;!#R|Xt zv*G3KfOjESUvTF5PqZK%`9q8T=K`kl!yt8Vo6}Z#tu{V=Z>Px9{^UyauZy`<)@-Ei zi=BzF3|_1>rrfq?tsg%e^0h(%rUbxm*5-VmR!ABj_ibx)wLF2pLkRes#)BFe-PfHr z#*p=E6jv?Y>v*Y4YaPAkj2ud{Of@P&^Jef~o4zSlsJX8XVroZJB~KwtXs`?m_LN#L zSA~c{peZf-$3OGl58_ZZ)E%Ia4S-JoIM2892bWqVN;|xs% zb6zk49CgG}5Eoul-x}dT6VI2(GiG{+(4`d4?celUNI`;{izY~rUjo$gfd-HWu-qT} zF77yJPE1VX1T5PdwD#@B!Yi_AzHEjr@I4f{xMp!!@bltkw&^f83oh9Gn(*>@ShwM} zf$2Mog^EsO$?)c1c8;juS2VCc%* z)Tqi2DUT(w?)0NtQ+k5VFYLeutm~Jo<E^t72h0(xsIZ-$IfW2DoPW|3q+u2MSWwT9Ws}tSamVu=chu*=?@@E?do0Z5z|k zLp{c%pV=eR)v4$}dzR)yIybA=eo*ekxpTgOPX?zyJu*MuRe5CE4asRL;wSgf#wVq@ z(0{XXmO6aNDutWDR~Es7F&<3cxPO%^%=(;9nNbG&Ti;ia+!)z#8UDZZZe>x|>hv#u zr>n;!DT2zK1d>`>1G{53e)l7%!mm%1gGMtYwWt2ChH6>J`O-?w_n##`@O(B1BVeMi zvgRYj^iX}_{5T7w2q3PWSFnV9Nm{QAb})4y6&{*Jw(rOHhl;_+{vpyI^b%FdiQ%eL zd}cng-v%d+kNxuB3mk9z_LFgFsK~MvRV8iWiA5vkstnMqX}1c=4LS=Kvs-9wdRHD{ z9+_)GG)+zhA}<0j-ROWMaMbz)lrTZ@9)M;YV-~o*dLp|i0&4EB+tIKDs5fo=vO7SB z_Njq(Nt`tgj)h8&&@|6=LMHU^A-_%1)!8gv)KDzycZ}Ac!C*+;ZF{!vR(5aa!FRnV4!lcj@C;`l z(3YII6fgwD6^2-;(NWLxS7&EGp5dDQ2W7ZE4P#C{Nxt}g?Y7N)gkrJL=G~4gqk5gs zea{lKGFGB{xAFFI^;SzmgNt^1;<(A*cDY&B?Dyp4FOSnunSvh|y_cI1XoaO+WwAj~ zS>ct~RaICyt_FhX=SYgZl?}&}CV{H0=KJb-V@jO{Jv?zzQEb}S;I^?~{9inH6mJ2y z47|z3%F17P{>zuwUN?9C+`mRO*tzTe=o@3%w0XGq@hi7_AMR;!#lc1#rHuU@@TSPU z!#>NAC@mHX%!i&^xF@?Ojo*C`4_T>W_x@(GJA9Uldz0h>%{7VGwL(+Bd$I*)!UAqV zkjWyhx3Qb46l9d}tDHnOe29kUJBH+Dz%Zhl&|ISyy;iqk06qyi?g_E5)lo&5u7sk- z)&|S*cn~Db`03civM;4%sCO61trIVeKbw>WC!=OVl?YbX{v5mIF+x(Rtr|2cRxN-F zs-}ULKFq^P8b)s)fhN(RBCsKLU*hd*g;}9sU4%YWc3LADGN>yflkTD^BNj8iVgw+^ zv{^nnuBh2rw)d}u3FSXuKMpz{frYgzM|`EdV~4x)ea|&9ZPoBDOlcEGw@nD=DGM z0}yRJ9ZfAQyaO4yv@$ilaT0OcxK`)5Rx!1xncp~V%T4W#wQZ=C`NOaHZpp`4>-8%nQz5?z&xC>>secenUg6oGa^85m> zx^sB1*9{J3W4vRh^qBV@@#^n4SV*z%m+C*V%$92EqiucUO3rxi(JO+4;nZv10P5+< z03-~llLO>XVx|9d8-TJ91i;3RB z|K0-`w43m%{5}iJCn0ewuY3vtmDnZMRGKtu$2{X=s&AN-oxS}G)bne9_s>wHK6sYzTR%GOOZw_4Ib$C6-;pbCw-b&?6t|62YZPhTC?^!vU~DG|5-3S7b zLz;n7!k|VLhjGQz7M(~@rOi<$!oX&$2vLhIeeX+Nk-4~%xW12T&lIEz|m8L=o>5b`KTLP zCvCWd&*#^onDkW*y0Rl z9%^|chWMV<70=~`?!w5&BNlV2oZFGph9AETXZ#}f@<7sZ%y)>J^n?4+94;5mr-84+ zI=td*@&O`~LtasPHNklOGjCO7aUpDKl-$GABbFL7c9@o4(NHjUjMW<5D#6KrS>szSU1LG%j( zRpCmmJZ;fx6Tkf5wSXgv6}{V41u5NW2R7V5t_M*gm-!;ClLD5i39}gd`+qxb-nz;L^vBT{JYWh-eeVX{o}N z1!%`WVfAQpRa4gv?>#5A^Dkti;J~!9z1F%mSfBsBU zmAgz~?kFSb0i$?P*?V&R?TOd)^wv8&Kg}!oJnSOI_uGX=}et1qsNQCZy|t;i!z&$xp;aiwL>V9oU`jlb8jLvxv$}9;P@D~wAfMw zKVBZtzu*p9-3K%*yQfmXT_h(nxMV#Uhk*P+EgDxs-Wuy_vn;d$Ce0320A1Ax4b-FS z8(DH_8ScPbSuQ)&qy=+|N<;ZYgiP7zh7L!aP@!4#RmdHX^YbZXqEI!Ts+fEjEj?oG zX6?m4-P(|886iUiihlt*?%Pu0)hxD4kW&NEwLz0t0tnnCy1c{6i;)@0=1h#Gj%VI>P*T1(Hqx2d-AGm9a+?hcsmSF=qI#bV|`&>*I zeuTl|`AbWY0pDhV4Y9R+=u>4H7WyKF; z0K<`_&?i7kmF2=3V2X3;C-6(YIVlzgKuB;dFq@MM?Y!}ITMo#v1)Bny^d-Rk&vdYs z1nC~c{cB+JDbztBm&9M=vUL`vNhrL6*6&EYnBOypmM zR;8QaDdR#W>o0zGF&2f0j}y-T z#`QoTm!R9>8Ifv?$k5Ne5o=0`@mkAx_g%Wt3v_ zE)y?b8>NKWACy;kc$h|xP*y<*soZ64aJW9s6(8b{ewU6ClKvzhEx2v<+_5-~x-4W( zXmo++Ct<(s)GWp%bF++E(w;n+xZ+4Ut@Dvbzq4ZdiMdM*0R zKPktqF=+R`ydd%yJX^`!EKF)$6TJsF;RC0YJOPhM3`p{1#s=-qwe|)Xbql-oFt>fRjX+hVK;MV`6OpfYf#k@x#Xl46_ zbT0f&Fol<|8TjOIZ1tyN!zs-Qp68{{`Se_Br9Sic&Cpw+8Lypc{)5$f7}%B>oZlyf zs@4XZjy^}teu%iJXP~pS(P?l(c}dYRo<)yyj?srXI=Xy!b{0feGrw8Pb(sx&*aG4Y zr3qtTuFYIelD^AbEz5vhDrV1-&E!8;Y#~xd4r~g@IHNolDKdfdiL~l-xz*xtjjg+tQ2Ax{JV3eR(CM^LJDUblMtwufQY?ClA9*P+E+Ze^UMyk}52P z?@R_$5NEvhk(N-4x?^}8PQ#B|9>Q=r`MvSv?y9cos?X;=W-MXr7*oc(QP`9 z%k(^vxLul-xVtz5wwsK=hTBK{_MAJ@>$DLddf#~+8quFD0(S%~N!NQT7Ba4PnpIf| zquULC#hUCjGrCr$#$ZQEDzasdD2%~_q@RN8c?i1eQMXl zZwS{6lZT3jjP_8+U>(#_bVjiOAE(xB{3S;%st3 z3-k#usUvRY+}1t=X{c*)OCo=OHI3I#f$=h!TU5E+AN0!mHmY$aLRv$!swas`Q0F~~ zvt0xeCK6tb*!I>3?cUTQ_$J8Jp$F>Y0teu>i}yh}j}KK|(-n;F3OUlM+o9lGOU@B; zLjJMC`)*YADkg^Mp7)12FWIfFp7}PRx$E1l(o6wkd4x=dZ|XM9{P1(v5VH%OZ2H>T zsb|l((o%ODS5tj%uGc~kYN;V&bzxg_3JY62K9+!+wcnB6B(7s-=OfD6#pTP`QZmoJ z02oPWp4#)Qw5eE$>*1(*ychp98U8$v<~t&vG#sl0zR|Mp09Bg&Y|Y3r&G}KwNbB0k z5+BXf9iN?QG<*T!x#zOnO?Lia!!@jn5tvi!>vn4i=Q2vRHeK=SHy1(}J5?H;>v0(3 z4^<&Y*QbJIXUX^Z_>PFre_U>&V#pvgAIZta)-0{9JLIGJYX8n%`f??>H8wYw)ViKz z)FmAnlRtCd2IbugZ5|w?UH0@{2lcL-1jM_$Gqiv^u{H#fYizudo4ZngD15=eE&I`W zc3x#5#J(lL`89shFQo#UjveOZQ@I}^Na+j4jq%?*DWYy_va*&=C;OQEUi?;@qm#fU zKkRDnE~}Amd)G#{a85;6kS!48ASzdG#ps+Yd+adpCKeARWhp_3! z|8Xwc>XWf%m{Uo6ccyM_Hi<3`7|}8OMI=6V4RyBc)Fc7uvKsPtDWDUDRbocnh%M}Q zcKQXb@-KGS@kL5h>=OXetyZpmV*+jJ_uaPz&1|%sh8wmf1*7BRmA#dmo796l%7t8} zpgt;GB1wBKsSZM8W*CN`8V&kIP^D`nLH%V_FTd@J+`O*D!{}$o)ky|4Zrxi@T}Q># z;j5dABa6TVXffHlsNLp<*|=NS!n?^pt#SEmZ+7v~Ic{PQj zdz*-!(W~O+_l88lFK`VBX}j+)TvS;Y_MLh)K+~CmniyRpQ_#sU6You8q~o4LSIn;0 zi~+c(Oy)b-s)ef-4VgBb8*P;vL+c5_Nx2qKgME23JE8^A50m_H%MMWTh#dxi07_l$8OI0W`0X4T?-nk^OO6dPsIe!S+gYTT%G|@Dp+W0v zPJ^$6|EQvf>6(2G8Ll6y3CIz8ZHG%UX#c42^$QBffztuI!o!V0&(%5a!?=T`&c9|M ze;-6)SA1U+n&W8{$>M@?z$%IoKLyF=wEuQ@J>2?T3QRu&w`yJf*x$>jO1XfP4FmSU zg)*e`cD^-=qQlF}CE)>{Z!FRs2re@PGO2yK#zMOV`)ios0UXce=6{q zPQZeT7;IC!(FP#!X4*62@)efjNW;!_1kz({qFhxfOQj;TD+h_LpPikR2GkSo+%cT* zIUS^dtFd{MN`eFMVV(%7ruFoC3=JT<4E0^L+GL%pQeSztE0FNU7-ahPTN) z`p4_TMm!dy?Au*?!g+i&sX5&|c1w`zk;iz2?P8P#7;{HVQW|?cOC^G*JtiQdPA2SY z^CB+Y5xcgI>Jc_v)Oj)17eClU#c)-JiXUtrR|rmHTjP3M^*X_83QGewxAJ*zN3=I4 z^gXf|a=Dn=xy8*OMh_J^Aw)g0o=igoA&Io-Fo+V;k&y`Z%OGpaZZ6DxPrl}Lz=3oa zRoWO%*sTLP_7;Z)!?9^y9=kK{M0rb6Ov3W4c`tMAKvm$?Ije*m*(j;6-_O`i#X8UV zeg~x6@V@NW_40%sZByUYpKIpwZ|g_ef5rI@MoplZg0xG4G+=Qh7}cpD7#19z5Q(;n zSh<*7^FH{Y`=vF8JegAFD^B2FKm+`tW>mLdjZon_wOgUKTl8`*V6ysa)ZRn>;)tqq*SV`pqQrg7nEYncB6J#?fCrnQ z>>D<%@Kn}xsL#5}v~UITcUbm70G6GmFA#Mrah-SfzRCN>RQ&3FyFz4}@lNyK&-1@W zv>v|X*!@K6RrTY)^Zl;E>=U)i z=Kz3m;c;=eV)7M7_NetYKCQCM8#49zpouZ+^m=>u121j{w)*e>Pj2bo31zWMN;(D- z#La6_(OI?(Q+|p4uFTr&fA^H|K_?-=eTe~5FZ2e|k5&h?J%0+g$gl|9mzp1a$i&@O zKG8&{x&cOt_T99}HV7fOngB1Wj=MlXB#yQ9i{WS39C08s<|)CQty&?PA3PzQ(94+^e)BmBEsroymuQ3cJflq+rm9Lt z2U!jtRl$a&A|zKjz7mYhe80+8PrB;pvx+E{i!jndV!>ZLf#p%3H+yvQ@WcG;L`&9= zWgejVGv8|$!L@d&e=Uz1;6xGuSvP&epgP%Khy3kJ@+;pS zmrKi1-x69RB+dH68lYyp;v&;n!ZBR%p;$Ry{Zqo!G0!#0OzMKF$8h112(k0GNIS-I z(JL^&^@3PNk_}9z=Xz@GHgi9E@<&Q5W`HUhZkS4Dk^*J>71)4)HnP)xA5}E>z8V)r@^lWSxk_ zoy7Ktmu$2r`Q8K9d0_&$Npl-1#uBkZM8Qk;36*(rTtD6}#q{;)FVV$=H-H16-+EE+G4kvWE)G|9O1)+xdszV}a&=^+M1%`c`r!-;vucQIp+0@ur zF#kFSiPq2TQ_A|xtq~m56%P?6_AvWOP+T+OA)7o#E780~aLs)j2GZey&$Og!<+gLD z`fb4uoM?57_g|>`w?)cs1(JdvOV$OjVhKAOPx|{?y!Ari16X zN_JhH;Ygl(d3L57R(6`%Jnw$MKYtM*Un`s_V6i%okKsE^Jv8knO4fW$PK@`Mv>|F;H;g5IK3Bj}=Y8Gj7-z{BIO#iI;qcE_XK|RT!Hvh| zQ9nwMS|JSdam~yGVU)yl4SF)qzv7BI7S=ZYa67FsPjlWWDlTZA7Q|wpOka?EdrIuA z&NE6>N^PjqKd*vwIV((Ov9g={V2N=FLC*C*kt1-i{{^c<$A9-hnt)E=UzH^qZ2`Vjz>Uw6eFG<& z^^0p{K#t`?a)Cc%(li ze$jA*!}e}l!qfGt#(u;O>Y&});4xQ%nts~=rMh-J^aDER<`!%_Psf7q!R5+>hB$)2%Fm?t~tWequifvl?_gr~L?4#+{c5%oMHQ zL3qw}5geaO2ATp`L2sfM{a3J9c6>zv5C%*9*Bm=stj~0;3^$~OA36C8Z_o-jV7Mg{ ztT*qzwVLubES7~>>(7WIl!T0w3rk7_k^N}7L4*aU00}MX@U*b{S%kI6ip{QE?TgR)`#D1u&VZksrSad2;t5d^E73pPj zAon}%zJ2n>FO#v9#7+9@ichxT zjhP6OgtknUV?0=z9f$tW5&;_RR@SlG;DsB}&Klja&sRc3s4uUq@O3g^4xeUO)op+? zk$=wds4<(CmbUONY-R6YKHo<7-7(*=h5XRu%uSyxV}o6bzkQBuoTP)LWdsQG!$=1; zcd`gSvKhO1TSHOVk3gSwo;jumQvltj&p(KL7x% zop}k}J3#7y$qKXTPC*PSzvq*4(OzOEn2y2DRCVUXpEd8}97a&0Zfj6^`~dv_N-^fz zE3<*XqseXeG9^84(Z4%i$wLLb!Z6kN|C8yE3acyzQE$tI)$P_h;ITlk^o2^rGvBu2 z+5x;?C)p?#7JtgWZUlhWeV6ztFCSpavK2rgE?3CJ*#YFk(u;nJER=21l6`u=YJC%P zfl4EZX8d=3i-+AL9Uiv$5Z2y36XlG8{DuelX-bo9?%7;Qj`2ZI<7d{m1ot%8LkZV+ zXX=dq2n%o0e|hA}25bV9mb@0)l_W_3P7KiZ2d{My-&lq|$z$1nG%S~$E8Vuy{}L!f zFCNi)H!h_1mkh4%RqRCnj8e1%d;iIQlY+&V_XlC8ucWJMi+XCJd>~2!Rn31FB(H;J zI#Jt2KNS*My2L>rqXUC{!j9 zY%Cptt5!DWvtY;-G8;m0eH-xwnD~UjP&?9olx`XO2VYo+N(-e6CVF|+Ak?rY@0U_& z?~p9;5<|(X)wW*t=ehLpWS>!3Lo9M}_N?Y^&-=K2t}{G52baolD3>kF_O`#m(c3du zbAXvPhUDjIKf=4hHs;nMyf8X4-k@jS?m0HM>9I1+XFYvA_=vioxL5_wxgXu2dE?hk zoxU&GW*Ik6R3qqma{@4ZbZzjUU%u@hMm(wQKJIN@AvNK?0Gvf#2IwA*cchgge-n+! zd<;3Kyx*lTFPh8>2>|@ow;VFB=nfU;Edu|qS0(+6kO%tJW3k^K*zw&+{&S=-j|fd_ zKB`uY$N_lC`O|pqDFbc0HkU>j2L8&4e`!s7hm>VrZw~N=gzxb+ zx0a7U9;lL6{YOACORp?1=0B4 zg|_KL*j47QU-Iu9$OsYyp3>P^iOM$+0nx6PDxB?SSW$L(q&KMZ9Frh6D!FdFaxA=-` zlthZHc;WIOIc^M~lhhg)KyvAVY6NUxospowka;uY&g8(Mj; z6?BeRm=Mn;Y zh2iD?D7Dp?@=Uv>wc?(lpOP2jMr@yIj3pgPO9ZVbtoUQYzz-7V*$GJj z!FYI8Gp?tHMLe!W4ZbtyyixE3$)|V|p+-M4vzA|twS-}+kN3r+=%-~Rn@e;HUWAe( zgkSh8xLFj!op8sm*{Dy}qC(LWut%xy92=i0hLM>qkc)KGUeqoG)BYPz<>uK=YOrWS z<7@P8_uWQN^75ZA_=^-?p5wYml`Pc;YTi_gpd08vEmgU6%sbvLrhSwS%rrTF6GbBc z)yUQHBi8cZN>S%0S>v`}9eks1uS_>p`#pfpVlQ$}Wb}vUTPYx>sOB-gnjd4rw+g*g zp3y8)xDtiM7sRu=#lcdG7o&b^Et*$eMHt`ssG-cJEt73Zl`#1TrI!{*8O|Z(P>)z3 z9w|6YodMlnnj(R%Hsm?sKO)r%aY~TMg`7vAced={5t6yN9bK082{_10cuVo)2b~Zq zRDYU|Hu<8ry}W|9b;K^U+5%PISub054F;4yI3eLn$I$a9%Su`hzqp(!e=3K9YS!D< z%|O^6ZV@zqQGwTmThzHL!qcbdxR>*?kK~( z$%dO)fDB+WSAPuph(J{unNX7m`#r-)FLNLLPHfNrpc`^q{{mO{t#I4d*Kz0X{?73J zq`{9GQ>hL@4SIY-c$AZRzh0b4JA^W@q!u~93au?~5wHb6zrfJW);g~$O0GhGmpIu( zQHHKvb-#F~ht04*9Zviv$)4pgjv$=9|M-DB?L!9AeP7Cay3OYJM+;{6?4Zb#+*(bLISv#$K2KIvOG(Okj4p_-*J0aKq>^MaiD^A*^K5+SeB|JK0yz_Ly z<>)?L4EZ28(nMB%J)KJa zdrE*`^W@LBg7sscFEUAsfXrhKuxcBVxZO6DAhaC_^>_;VR^~I!0 zPc&N&^DQdeQu_V=>jz{vb-ilJ`hiHjw5@0E<6j=$8)(okAK>_F7v7D&Y%KYy>vp}V zFGUom>514MMm`=$(GmCnPE2+xf=b!lKH+qt5FaU7f{tJJEOF9>w2}=TnYWk4N;EoR z5&r6;tm*7d{)j129Nk=dSbVr}_NJNUu9{We{&rJd0kd73a54IE38OZ>xBsX z_coV6XDm!@Qw>ogECSaHB1GB&{N=ix-avxy;F3kXh)*2V){>#c42EU6(AqN*&AdR` zZ|yA?Y*E~6G1nP=S+T#kmC9v-wde%nkU_D3TqQx&@|l*-)fQV6z#24czA>0;t!6Mp zhg%a0#)oeL>(XuN5h`Sm#MM-y9_UKdt#75e$$fD>hkFu6^_5Tm&7_lptixVXLQR5L zLsV;n;uO_QVIZu@tzvg!g^hHH7;w6G*vlh0ojBo0bNXvbyU(d~?)7v$+%!zhj^+O7 zD{1Mt@T5=_f@M?qixf!FI){PpA%k!awyD*N2O$KY-_4Q_3PjqlZPlT6Zwd|0c4sWd zOT3mo3h~$rNiIO~#-rvvW{)yB0ce#__uT&>x8Ljf2<}Gk;4Uxscaxu~K;tOyPuO}i zAogA264yE+!63tPvrxP6fZP>3^9JaY&)XP3br4HQO27VJGlR$O{_aD!sa?XP)L-jQsl!-G9HHEj3wVu8K}4zoF!4;R2w|wNLaRQFP3>EPg(BS95f$#S0;iP zk333g)t^^zm3KBR)jY89O;z_)|FnJHc0@1hW=`R?zj`1%A49F!+(2vDxEMk*d$<3G z1-oV&z_f`3&|Tw+Gu|s2qe?9)Oh$zm{^5IuBtfH#XvRi2QS<^oF{oZ288mb9#a|QE zoGp$Bm1FzK0~k-UKzaL2QFLPN@rcKxi8F2|6XiL5Quv?{L~M|f#>^SL+QK}+_0~&n zx~>Flx>h~H`hNbRb>L{b7Sw2V@P2#o6Ds^1T`}oD5haf3l-C+#u~V( zdEn2+_)xDRp4;(9$8PQ8!tAt&y5NtCerx1z4}ot{83Y-T8(EGTGMJ)L#VUJh;m?E$ zEcRZYYNN9i1PCc~HY}<^p>*F`SyQfX(O_sE%=5hs3TM*bq_MCS)``X`_~S=~TJi2F z&X!1+N+c=tZUGajwSWU$3~LE|Qta{pfEVNu$sE|GeB&PnSlHa7o&ctX6{^2Rtawt+ ze9(BYI+v}TqypP1bG@tprvPjQ-;`;;?_>w0(F-lOBKJh+yIcmgCmAp2@8!SEd>4>N zfJ-HG(W~B=T}oT-7o;tIS{}vBWCY~mu8v&iQtO0r+1;F(?AF|zvSoOZ*BX_%|D;(? zIzJ%s(a`Y5&-`Dr1E6Um)BvCntLwjT6Z?N78#`q_PwBziG(qMiObKm4#y(~Z7eJ{u znmI~Di+0@jwZ!($>;%NAb`9{twW}>axANqZm45L&e`aA{{MrRX~Jtr$Z4W_VcvKbtHJkncy0KQ45e z>-~C!@Z(a@Dp8g{qdiNlU5njUHQ(NKvN8x8ND(*1(YdSXpy#3Mg}Qe=A@Db643a&b zTK~X+t|uKT?a0~is!29|QN2VPAJnJX-gYrq_W@~J$D&5z1e!!>c3_=Ijm?w>v!*XE z^`e8eH685Lh23XsuV0UR$lven_cRSJ0a;3iy3BoQ9a%14C?B&R{Lsp;H}+yZX?9jN zA_c7%HF*X4bCvrbir0w87e@NF5*JdqSimcIbNxf0Oa_3UC3I2Er2W_^&ZowGASK?b zAjCEm|0}+;zAjU(f>(Sc_`vcol6L}oCK4*3#DTv}U3oTaaHQAA@GW-C08FC9>%n-V zf`<&2grH!jU}S~fxlk+`SRPKnTjUzQbx|cDCK8Qq!@uy3fj;>h4Vp4xuD>Plf$Nj{p@w#zI}iD`IBDzZzf+xeJJ?@n;{=(w-|Oc-U>G%iEj;D7 z6^&&ojQfzGi1O*97X(_5>a~A-fIwQ7CjjW;BShOSSMqh9Vx~BdeYzKy@d8;$ytmU%!sB1e;RL!DCOPl_`LZuO^_2@- ztB{fJPnEeD1iZwe>j9bQj=Ri@cKph&ud8`!HvV0-_!svyDMe)io|By?-kj*(RZmj8 z4%uA#EntfBdC!Llr+2cvxZw`}Xa;Ai(6bxJ&aZ5K&EsgFz2~#%VMopM?|u6-5}zv` z+5Y?$)W$90V-!_ck)|Ofu8j3ks$7@N)HmWn;%4u?gipQASxZK96X22mi9sy2^huec zn0MZJa&E+{K&jrB^ekNS69nk+HmKdr-L0v~-E}!@T`V-6p8%Ttc?3$$O@oPa{pcB5 z79OW9!)P#d7}2#=MUc2{3_9;MoQ=v6C)H5_tTd1-U;GKGQJ(@~cXMkdcY`^y&J5ia zgr9x{BBV5N&4}5kk+%mUmEK|ABBME2+zz|c$KqDQFy|PXa#8EoMMPH_7UgI=;`Al^ z4~_22%lO;P-!;B#bki7K91|K4i4Gbfg?m8DH63q|@-@0Iz7UW|h$SD)P9&DHA@(0G z0GyC*=80^$l+x?1Bn-=6R?4gwD2d4qs7aHZqn}MVB`6yM#HJdN3p7QY4YmdQa${nP z%efU3>(ri^FK{`gT?+yNn5*ft0;j-b@F*=%n}5G2c#v1{@kdzG#;>WOa8kZUdcS>&Pjm(> zmy>EI*kMlYiQXhXvPjGGpUZP>1~%1Ed~#h@>dvj~OlWGzA#Nd8@{4;)wb(&KTf#eW zWc6pgVvCz*CQjABh+~tiZN35zWF`VK&Vqxi46(^^K)N#2OyiiSH+0BGZ;!1fxmXmW zmG?m4U#JfUW(jo|Q0C$@5>Rq55neBqdg1YMFAqW~NB@h8cF%*;KtVTCQ(E{0l@?hF zbjh->q|WT=tmik2a(%>)BD;CnM@8uSYlYf%)u0w~lL-A!!&bZnOfRKU!)|bE?*2Hd6BpRtVzw!zyvuI95*WGZ8vE@!>z>Y zK4(@Qo)M#!XU)+DI7g{TMtl}PW5G_9Dmo?-(P*?I=(j;0!E~%))0d8I@0PAO1VAOJ zJ6P1*rQY?*UCa)Kne5U$F~1={^JHl~i0k|`Q&o4f7B%LU5i*|*gbo@$O5>bP5zy&w z>CCqp(*}-W22~5*bCCdR4q5qmAr|&|z+QUZ@{g0YmfU_iUgK%krwu=B1|BcJJD$=Y z>wz^40EN&Eb4cEx*U%mZ$ahyuIZ>OFJl+zkRuh1a_kn5?O9l^M2sS^-V{{`m7qc3_ zoK&_15pI&UmOLPT@;_&BDPBg-oF|%iVd7-}7_&XxSxb;dz^3|NS6nS9TV( zowbsck55WsRWT4`fxKe|>S6HoO`2_Eiap*kpa*|m{6+PX(zhYS-4TXq?)UXz#hZXQ z&1G@PV6v+|-5UbbqQ0n>dk-X|^^Kz6PH<wc8SJs!^8)704p}vZd)@&$(W*K!u!yGkcT@;4Y!RSSTjC+6z{5p^TRj#Zw zSzjlM8?5(>M50lHuSp#;X(Ws^0aYM`wXsphQ&=u;EWZHC0WRw6DWU!}9J648D)D0I z?b5=N%=gBEmq9fJanvP;ezaYz%^1^81nmmjGj-IgAFX-e-J%Z8pjJVY-JU~}=lbda z2^6UbO8y!I+h%N%s|Gg-Su2e3S``U*$_WBBJa~()9m5Rdtx%khy=acFI)#QboLM6W zUMn9oYy&OrJjwR?mrXA%Qa@dno!0p)jzqL}jb6)-wTy`5dv6@=eqxfO z8&X($&IcuFdGfCQc($CW+v=o!YF@X4o-PBl zL5Gq&oy|l48UBjmx6#y6Ydb2VEvJ4W(MFN+FO+tHDE4p|qLvS&QYiT2(HD4?xr5K{57h4wDjQDKAnS5C7qS@Gmt5jf znS&S%Q>^h*&^2DwU@mAmJd$c@urW7VHt9)mYbFg6x8aWM``h!G5i#ifxEI8r+xj<| z8evB{mi<(QoLu;5|LPiDM`0dG2+h&mYCzoGQA^u?m&}7WKoMs!HglUud#RobT1csS z5+`|5h@bl$7>GJZbX4Xgv-g3y%MCgRfN89y>6Y_Q!N|k9*(&+v-v61G))VhM1HYM! z2_o74Q7!48!z9VB29=PEz9t9UP*;;MR#T|}IX|FFX=*Sa=u+5^`uXsGU5DuJfC#X$ zJ|PPv!{foNnDe_Zk!}wAXMj`sO3>u?B+lT`zFJ%B28IyXL$&CdZp@ow%4^zrQcbg6*vD^y~<@CYlwAe#!6u?v{yob^K&A z>dvEaEhgmd2+x9&G00WIwvDsCzMkBBYW3O8ro^T0cg07zQiOnoYmbA$+RwrT!*h1= zrYxxq=y|DZE)I0)&?;ft9WkGhq?Drla@F7(9d3&f&WdFKCjK&2)cG-Q8 z7ZMSk5AWvSfWb-&9JQ#glpQT`rnA3|k!w{H%#YWa)3%wwX4YKmLJ#n30IuE6TyA{q1asB=R*Csq%Tn!HM~*c+VFBU7(a}+(h@|t) zaUe2u>=o7B(NSipZj<=5$VQbv3G3|jP@Ow~)9n+BV(a>au(%V?Y{Wt3704BSY=M3C zw8rU0OsqP7Sr!e5+_O0<+4>S+1beTWvr!1lHF%c1q0Bu2VMLau_atnKLnd5Dlz1&gg|A&Ti= zb+GT>lU4wgzTP@z;FLT#EXB4-TF)oqZE znI+#Nib4?T+K#-P6Z^b|TDe&W;fOwZCFP7#4nr<;LJlkBH9TQKpp7$0NBPHbFj>wk z$)Gvr?;0|S5kG1>03CN3uZhuyQBDV?AN0C~QKVwA6~)P2i$^gpJPRK-?5{H3F8I~6 zyRd4TvQk*UiVcy!uUz0{&Sa|UK$Sj-5>e(iFz&mxB-TOZ%o=s>K;_;C&&If z+cjGQ&wsk&GfV?qn+tC5axzAoh&$k%zYm$@`8zTJ58)ZT7P1=lYhV-5_BMr{OP}ow zdoh=TNJR^{Xb%;Rx&JGLQlUiq1qobetC>_0l|}UQ>OjiNd=S_0Sqq8h{4a$kEiBeR zY9W*UJg@0M`q`|*ATG6*ujz%OCO+`g0t4K3PBC~b}oDEs+BqBV*XwI6;m`aN6`9!9P6Hm9_tfT6S007R-s zNPs#{|09IB?ne{RzH_Ai*i@XI-MbXI952-$+ksc7?mPIa=}mX!N+1qZA@NzR61QAOq|C`U*a7)D5(BxICU|WYEQ1d z@Zj604*KlyUZ|EZZa7-T{8#FEHA2&Yb6Rd8`Bzx>0?h)BK$%-s zU5m`Z-ay%xYotvjgYpI)|BxbMvOhRI2GCX`fDxe@WM`7iu}+;T`rAcowh-CBdsCj% z3*5@AKUN)Rpq&g=^nal zdCH>NC{Gx@7Bed4{OVbpoSYnk0s56Ms>Ux)tJOYT+_cRZ_mw}AFw;0Yj|EbBY1&hO^T%^NxzKFAwj^BA3z0{dyZ=Q~Q@xEhP!*B-*1FL?Feq-Uo%w; zlQx8fd{P=;lHO|Ay?+(-61T$%-S24QTzXevh){`LTM<%L0NIDquO00*$IC|cT-zs1$xp^=p z4gu>HPNgr4Zj%6fT8es3K3n^_KBU0f^bt)IkXD)SODVj!wK4<(Ap&vN5fH#@Tg!=Q zdwhIp&RVIqN1=ZVatm)N%+v&&En?Y-)DE6MtG)iY6~>Ug6tc*`M7is=sr-8HM#hxH z0g;c9>BxikY4A%c`H+R>-dAhOP=-8KSp!~xsBBHR_GTWA9}H`Y|0v(p0;Cd%DnM4h zS5=J+jE6F0<#gqg2f~5@pw*o54YEjE&J0;m(7u=#K0Z1s<)QQFPWhQKqbX8Ff?KVr znaZpzoJ^@5Ixz(8@fXsa848)d>OEM03^jWYJ8ZBLrED=bSIPFr&o?oAoRQ;N|B^E#xiy>s#gcvQV$ z?t>tpJQn^)A-cVe%dFSyA@>k`|6hS5eP{}!5BQ*N7vw91uR$^mivEf9l z_|rhY@VwkAes-TrrnWU&jP&vYVhvgf&5S%6E{D9)*EvK4* z&E(i5NbRSLr|*mb4Yve{M3PH3iow?1(0J+7=lfVKx9L{HGc*O+NItr-G5W#)`L+zN znFX^{f_{MiswQcTatvX0x<~Rd_qMr3?opz0N22mwe2Bcd%lY~(_IgrWNE8#i(}tJb zs3NEf_8!WfDBr)gy)9mAsyk97z!pUxr3nT4)%^?e}0x~ zJBHZYJJY}3>Gu)sBRzinQItHi!Rh1=Ss{Svu&^3YXfGvtSS`DSpjB-II#IM^ zjQNPmW@y<$i!?AR^=<3zEMB51I6NSB|3{SZr%&?+w-hP_RW6RzXms05`rYrNp32ro z;2T`q&s}4DF79Nx{_9vqDZYb_TzT(^nGwJ2=>5s%KY%>7>)Y`SgVo+xx|Lx(#8dhL zNPWlZyYN!*Bm+0B!VH4nSU`?AUR5cr&+^HfXF;Mosd zB~xo&ja12wzWJE}Xbd}iUWhTG!!VeDX`0Gcb29r1LIQeJ5$g8ms<^fM;bdoWRx3ma zvKrLJTi_@O+08v6Jl0Ad$ME4R&MuzUjPkRBDi=7q$W{TuW9X!NrbL2BQS-0eT?UZZ z0@$Y9cQzz+lG{8pCX)P5Sy?NCf@ufD*3!j~4k8svP{OhMkak3=t*SK~T&4s?aU1pOAdu0BQ zU*VkKKo#^zLy8oS05DJmbQ*Ejz^deL*=Y6sn#u)GIyX!+%2^?#$UYGWj=oaBHTmQs zr1A8m)YNevEF4waM(}shEs3$+Libx|_1ZLYiRBorY{1TNr`lOh+L$SW%l5{7IX_)Q z5%lDXVnT8*xnbRGu6)1B|6}Vd!=moG_it(GoB;%B1V>VkkS;|~a)xdsq!mHBq(Mqr z8iAofU=XCc5fSN5>F)S%uIsvg&zt8scnJqH-`IQYwa)W%8fTgmw!I~b1^J2mkQqr^ z1(#-2h9zYBuSZ(=ic6hsq08I-a}C}B`+SEGY>;~wkbfu;kp~woHaS#`fSsqhb0qu- zHB&?>n?d7TG8E>4M6E8iVGXf|4mT+{akS=*Wq?p157Q*hVE5n7yT5+`g1b zP}TFApgeQE{P)l`kSf9(`A4~Tc?FDBqyKl|q+vt}v5ogTou==Ld@v7-)!Hp_RJc3- zrw_G<&r}ku?GidSg^xl1V|oF49KH7vUclByy~x@C{QArWEe(r!4frBv~(i$48#xA%)v?Vk$kNh0b-z9wJTBap zxxDgnQb+GWu@lRCYw%vM zcEwA^X_bXK4+~Z#P#6ME2YN?h9-j^HXt{@(Y3_wP7Q~ms-(ADq0t$>G6aH{}j%P{i zqz!4HLdV1PM8(5D#aIhUkt`)Wob4l$6w34OS+JB-;Lwrv;Rx!@akl$nAMze}k$h4CBv(^~&xhqIE{xmw5$lhzu_f64-u@ zIq=1gUd5_OoQx*8w7_(N+ZJY}X1*0r4={6sd;CgU$W^FRhA=Nla>gqQ$xOjB`5}>r ztXw<=XUOkdPKEaK%rf{d;HZ;hrQKs5qJRwY`G@P#j>8X=OvmQ7EHgM!c=)_3d%>Q| z9}zaXOg3SUrw$mUP@HM7v9M}mq?TA(0U00sdmt{mP1t>-3|)?G)pVGf=opN5+61-H z_$D^5{zi4Rum!c7Cz(H1pKh+mQP%z)bIiodbXRPj+6(Lzv_zqd0E0! z7e}QIL8|a18NXF66X>332#g8ufZ%G#&WnM6Nxq^)r(N-7>eG>kgwyR0jb8+4Rx-3E zUH@lriC{{=AH5#v+x-Qu_F1pt^{<2mSu(s3EKBr*m5r{ed^AFfRj6` z>Dly9whT8u+V*p!30OO$!)ckTh$%)o0d3<-zo2SaGb2v@8S4XOR65Dc`DkM<8n*P5 zFay0Y-Q_iyrTQm2YeZN$gb1YWs4}VE@AmQjRWjI3fGuv;{J!_t1O>Jg-ufGLgd{0~ zY20QH-Bzkw9m@%rI!nlKRk|w-wX%qHvp^}Px?!2*2hZ|_k;-6^wIlutyFQE4N`tXK zQ;7FKn7n{=Vdf`xGc90EqC?Qp^5yms&2+s`FA|!fUmwE$&KC#qD{e?FNG*p0MW^p* zK@iR*NLa+4vl$y66#dMrW-`oyhObj`sKV z2qm+nuISz39FKoSX)Ic|>1f`^7T(Tyeys1hxux*Bxm9IfPe1?XrWo_g7c2l#U|=Bj z#rST&;50w5UsTrNq_qs9HCM>@y7=TZ-lizh)43Qe7a)j{pPtjXVn&V(QBLF8tl7FN z3y}vmxEzBI^go{a(sD znWyM05q(I!A)EDZ2A=U&1qg~-kC}Go21Ir$4-^?1tsKl7P39l@o$%~(NWHu}Thu)r z4_;>6&Ze2xa@(hAyL08+OZ#X3=ww{In?-$-?3?-F68$Yoee3eHBoR!;egi3UTTjPc zyoeYHaUbGS1RGjxOO)2<47o5`*d2ApMWtd_;_`f90gj^7*!*Qp)*u zuo^LjHyLkf4iV=pG$O7>HBMUc4&p3XL$Zosz1!ynY005?}MA6SCK){3VLz zi(pJOULy&O2%)Y?cQnBh5NnnEkyC73mFaTDX@||&I?^;=h2w8S;3Bawam(I3-DiHMJ?%m&hf zm5HaJzM>ePdEG5^-9`TB`o4)2Kc>PPEVr3P5!%LlvXk3wEHS9S<})Q0J0w|g<(dEJ zXU4Hxnp+!k!&O%CnqWkD&}Rw-Szi7y^ET){x9@zatw7S-*Y&#pYog4t>&Y2wesz)b z0FSdlY!9II12whM4}Adh^JgG<3Z4bgQ`k_G%>Nxx(OfzAY)-`lXX`*Z6Ydo*UCtsk zA9W?FYMy%Qhh8Xg-mA%0$}<^UEq^JRy3Us}z848T0@ND%o|OBFT6<*tQB6%_jouQC zkG2>1@WB2iZMM>v^c5*Win@ubFI0WR?V#^bZ@Z0KsAGHbRB%W1XU&d0C2PKYL~bET z`9_5XE>6K(^40!<>O9|SQ46%aths%%ywP-L-XN~nUF0#c4Dtr$z$3XLzz>f>Z9cIX zH!nQ(GLN&QhpGPV2CB^u$tau21OWFd$k2j04_(Dn=3tmFn0 zQ|Wj`0LcsHNkcIik%rWZ`=)LzIMs>qU54#4<8L!CU}&5xXR+|T3yqM!tr=Owft(Lv zlP6|s%?>>;+5yinfRw_%H9}w;U(|M)YMKuRT<<9#5OnlqnAE607)_ieP#)J&pzlDm z0Zs4(v#)&4=%v)x_E3T*0$dD-8C+_qq4z7oG+&a>oy?yhOG=*AwZ%SE@0#m-}; z)WTUNq%Q{>`~0n^hT-;J35Du4sDY(hDS(e3p!oh>jILhJ3uhcw%-@>L6zsu%+|_hF zVO@IVeY4MfGVOhHUOn4^p=$8SM&2*z#|Gf?9aW90c%A&1&3vYWT`5y1?-Hs-w#kUk z@ntlQCKb<-nESVdp?_XT@*{K;>UId&Gs1=%k%rz^M>0Xgoj5GK7=zzPA2eTvbAG%! zmX7=3ywl+qU|+X~9Rp`L!ZdHR1O2^<2d{cOU-hVeR+ruZjODx1duPT1ZsX!{MN&+6 zTZ}rpBQ|OQRiguIbu{mOhS(~~Aqe)}_z|r^C_PQpM zfmh3cLU_B{qSfyEwOblts~$=2^Qe`%Mz3Q&p}omRj~QsBJA|p*KEo#Ndu+@*En?T`2@>ODf#vzXtx)A_H~{vpuk*QtW*)wl zO*^=Ch7*{)uNMl)xRn|7TZ&|SMe!QRZA7oz$X!IkpMQ0Mg-00FSdH)viniW7 z^?BN1DHAS9A*7`OJ32ZV6hE2zj91~A=CzUp4k+zP?Pd0}4a`nXJk<5OZRE-sW)4Mz z1~C}FhWtGh#(X~xh=LP5&!Z=HQ$lJ*_q}&WchUK)7v7f^Wjw|vrb~}8tr|a(E-Q(1R2=u5(mBUpori;jq z@XO@{^)nR4?#dZK9L179CBZNGA>uUaQ#Qh1;S9HIPHDJ`O&l^a%fFKI>F0|;X`mv- zS8=rfkLan7sO?a`^uF32(Q*;lUto#YrnF(0#3(eH7D8g4h#SOZhf-7c?+*;1^l?Ol zmw-siVs7{qSZiLg>jToF$0`x_iVc<5U7-EBWN=x_Tut+)8^!|Nf9iBwV`I{nPhMk& zg`YO0A2S>UEcep8E=A)&RyIinod_z&dEP@;Uhv3d&9V(L@1>AENZ>(?4QQ(o3fPbP z33T)5#$mWHhNe0#jg^~%WC*H4%Iax{m`*xxT62?ugWYIm>&@}9Oe|oFYcP6%E%4xu zv5*F_>tT7P5qE9(LEZi^@BgPYVTg_5NsNYgc+Lu*5Ja8$fV8>Qgr<8r4nKGg6kXCj z09&GQyEswK+$GtV%jtYjd0;5m6+1`n*5CcZ)G_7wfYB1?$zRXgHCE`p&@(i>pvO<| z3GfSKMPdEeKgeF-!%6HLv{oieTRjSzm2_0ZS17@Ggl(!kFYIP)>$R}-0?&W+>Pe}o z>yNUsAlj1yx{~ON1yE9Mc80w4!CX340P_U@tF86g5`#5;?q9y+Y#!7mZu9;9#jAt) z4{`Sje@AoKU+AaNpRm(?P*Av}T2G|ml-i2*zf=JLB}~0ez$IM+>{8EJd#g`dBERG$ zJ^Lf>J;D2Ida6DCy~1)7@5h zl0^1X+WrDHjhNhpRtLc_&QF{}fV`1}YKkjXh74wFg&3;&sn=LOQf&X0BYeJI`@puh zE1KC@(Ez4;DE}bNG8~u#o>a=#w2wjWvcjE@4)N$nWBHz?~6dCSE^}8SDbP|BQ2_LFw%Y$plS9~MWE@{e5^{LGNt${9sI=j~` zLu}O2r+7&;v3>svoQ>IkmM~z&)SCS6wy(QwSrFWrdCvdIA1&~pBs%wz$(Ix`EbzXC z-enSdt{o0U*Iyk^e&1?22J4v6&uIcXso1+IRG`%SZg`tACnH$XmdI-=Uv8)S$hXhB zZv#%|HTcZl3!7plgfLsSUh~hBx9fDLSAYTk!f>=77HsU(TB$K! zCn6E&P}UR8mDbs-e@h!(&LY!5l>y69Z7w^EJ(shz)cy~QmfQG9F-n1D3_9b}GueNM zFJe2v|2iHhV67Tp^F^q&iJ;JN6J%Jn$#EEP;|c28s5>;uqQi^4RAF@}rR1KKDMSow zOpc*LAI%O6{ChjYS6vQ?xL}QWF^!$oQZnP)Lhb2d=QjkQC^KN1V@5=PcabWl(9HNR zj;yTF(0RT4iQRN<+>UX-u4d{=w0@;BWf&#*b%n$Q-_&3A%&wF^>cF2rR<|uk~P3evhL%H zW{>l)iy_nGJWpd^irNrr*vSsW;k&l6`gBfbJ2m3GrX|SDX{fK?uSyN_v$W7%d($Eg zR;2^4u)1H~!Cw?7{cgHYIafdT3?Md5&`arMYy86R&%&Gn zjPV&ipj}UuRlMRp8-$JdaB7v9_0B}JAGlxS)Db+Hhnw$IgucOt4O;SQ_;La^=QB!d znixffeGHd7hU1WFbTha+fxUkTqQ>snInk&B10fR$7=v!12YJke%yN#JN zR=EK!i>aZm^wUKz(6hz*rUcy<6UJO<^2N9eSh*12;cr&{1%!vr+fyOp<+OOD&Und5(w}p8fa>+UWjvN1$L$c5B@va#-_UK z(OzM2sYW9>=@`7tP@95mWB*{zUB%yp?6>Q6l}$)?hl_-7*wg5bf+*DM7&zBmmMx># z(p~d98?;%9!86K-Yz3FxAcZTMI>s zP4AW1?STDfu*7mMh;TPfC@SnPhg>LI!V7hg-%-|81MLX71pSe zj@)Dm(V7%Yh^CMoSEJn4)hovgzi`PKUy%wpyyleEvA9;8!|J0N6%xix0`Y2T!rJH1 z!<8e_uK|V*#G_ROveQ2j&{F#8sRXN~X}|FqFWvP5x2`}2}$+0F3=Bd>*XG-YQe!Ba1O(L)S z7s4;E-hW9ZgQ>F0{(TAHs_KMcgaevJrss!$J?LJ!uCx56&6*6^=IKe@$ zEI2f`DCU;cpZr$Wrf*BhFULxn$5y~*d#c8R^M3+0V74*GmFhAjjPa!?)$j*~h!kdk z>_?v?ZEteLj~1Yk`up=$%)|e;=NCTAjKU1xTF9bJ&Nl9d7dE?O2D# zNM-q?kbQ4$StV6;BAa--4j6MtFaV^oyXx zWr7jc>+EjmhU%MO(TXguy{Y8ADl<|IT;Vn<=$=>cf~)w;?alIb!?*&!J9nlF61O)H zt{AY^Of~K8D+-8 zToh#+7qbaKn1fT7Vi2i!-nrQB3ypf`COO#RpmepQ~{J^BFtyq%swaX;rlYHJdi9A+lC~*;uP8)Aiz7Y5D>PjCqku zQx`4}Y%Ti^VjNgEbTTccJ;M(QFsV-@;+nzkAiIR*pr*n;t+Sb!R+9bxOpbiMf;i45 z$?-iW=)h_HK`qUKgx>vjNv=5&+GbpNNnghWXGl%RdoI7Z4H=a~4)PQRKkqAJ^qDc> zSm>@W#t+_Rl=LoMw+OkuGYzkPcga&ezw%@GDpp}^%udBDQ|AY|kVY!E1mi@!n^)P# zHGBLGYik3!?2i5wET8`KU$b3 zFp6!;D)SHbTdm)8h5wb34(GeRE-85bw|~5xD_#~F0F9yD#LxeXj;WG8QrD^rE`8Td zWE)kN6RbX=Tw{Ih7kor}OI3@+ZlpkP%+yQ4IK%RYM#Flsnd_&^3N)mhxb{!dAbzer zp%<}u35L{IsO(GWxb(vP*@8<6gjYcieEkC~M08P`uOc3qdL9r}FiKkdU_E1@jIKRq z*HV7bb>{qNqx|pzYMvulmy=_Vdd{kkro?af$JSKM=T$r~4+zxa;y4}IyBz7xz5Ay| z;txr#9;d?HrDmiEp zGuOQohpTkXPW=j{!q#ZU1#d9H9CI+19^+Q6os8pqVfej$mA~2{jfECy7u5nd`Atw{ zQ~Xy2nQho~KFa1*fsq@|9*c7rAJF? zLbpm|;fVVpC=k3icpx;>=QJ&DN<|Xo0ARAl7}eD@0ydH!_XwSy>1@ajMKQmDh+Fhrw@+WQP_wTlf=g)_VvUnS?g1mqtgGLHgGC= z4WK|$k@Y4DLyjg41`DyP31ypP*iG`io{a(a6bnOs{$wt9LiRqYHuJ6I(f-q!q@}3u zukwtutZ#ebG5pG-2SU#+SSkJNI>=UbRb@VLRicgT&!pog!JXG4GDI~*(gkA|)yZVO zHKd~ILw}xJ9gvtQFu0rJ&Ytv7^eqQ$aEU+O<*b*f^j~{zb@PK^XHS}T>(BnWB>;cMXDzX3%>tMR@NyH8t}Po#@_y9BkmXsLO$%we7gEx-LfzY z(vgVF(C9+7u2YoJ%a~R=KG9s%(NlmEMxyou$tJf-HwdwdxoKb~7zUC34N1`Asc@Sg zZ*|D%xUO9mEB_vO9#{41Rk5m#(R~t+eh>#Sb-8@xnU2^!3cEL~ry^C?c1b-#vVgcb zn(QtjQ-^IN-_s?7IdlbvmKp)B-q(*t5EpY9=|W3C+aZ_(S5W9x1v=yJmhI?fUQ|!ucF+`7_@1*1iYeNYg&3IxNIXiU{pT++1kKU6J8Y6Gc;T$_iS@*~yLk-_-{5{7T2p21cDzQ_i72_Mu`)PBB7qk=#XWT~ z#T}e*m&&vT*>o|xO{tW22U2KQ#A}`}TVu%6q2mtR#4$tAZBL=mZwg!}9-H1?>tS0) zxn#~MlR6fX$;b34s&vm`3P)wpvwRyBm{unB9#vVFW)vC)hSjY^39BJV_!{kr_r;SZ zPyRB5R!%LRI@bdNPCU0^1WTxVj>}fns0k6vB%kcX-}#4KTRWIV+4g3tJig`5=Dp_D z3Tvuq_S1|!BHsI`Kb>YQG9x?FFymAp_=jJw?+Keh|kBZeTd3AV*esF!Vd z^Nm$rwiDqj>8O>UU>W@p_Ll?4tVV{X@uFW2xZ)2EztuUUCgWS1gqSR{u{x7Y7frBn zZ#Epi^A7n(L*vJA`1wN?Pwa$j)a?QNj1?1&8ISnh9@Tz$cq}-80zOt?y1l4jn7Us8 zdwXw+1I`fodb_d$MHs1Un05;~3?oI&ROA^h*Mc6c+yZw9S6MC9Cuc555NiPs=X>lj zZx9diMW9?6H=bz*WlNKzrmJhc;=qjM_n9=S&S^vADF*l_9{Y1iVx}Dg$H-?L7%pt~ zGt&|8m=y7XIo&5z%bs3uY`A+Y>yNfC?CqKcdb>7JQ2Ws`_}gnTwOAYK&bF=MYRogw ze^b&1o#ez>r5voI{j}&l1(-}kmj|=VTa1b2jPKMbH$O#q(*dYtgW6X5( za|SQT0HhpLwUB*9fPte-Hk4*s3Y6r?wut=>BO)r-d=9<6x4;5IRfx)&SEuV^sbxBg z;r!hz45yWb(U}4mGSX$>d_?whoPUiuJ?ci>p+=CcSHZTyHGJz!K-p`@5ixf;+l~WK z$NS>q*a-&6Vw|;`u(j$~qw)ea(pN!#RRV^_mxM!X;j1X?ka)6bB{)WiPu%9aV^)U| zzO@@B9s6zm$a$>HvuzAcQxr||Z!7Y-ti<{#k>mQ8yU{iDi;s>0F3)*OCjy=h4trpJ zy_qjL75jvrUj?>H9iU9N-A-b8+XDKCsw!n_z7&crQZBSSr=GAke?=&T)(HdYm2`vi!Dl-+zM|d zv?omraKCVBIP93#(r^!NMf~dn!~!@$O{oyddR_AD_s?-8_p^xcJ$yTc`YyBF=JVlZ$E)2GI9e7lGgs+ zs(}Kqun?cmW>=%Qv~-lbT?0>^L zXvIPrnF|@}{v41~#a+Ad&?UH1^8mU$e@2{!!;;$d0__TOGY=|%?{BG#oinqf^-BOKgD>Bg|R74tL!`-20tjc;FxW<&C7x2>O5xhn!<;_2ZIgr*8 zK}%hMbaaSt|T_%A%`|T}3RE_N>%u>I4lsFv5(CJ;g;D+W=1hcZZfX zW0BQC6rdX4s7QL@zRjn<=^A_Vng&}`cU&J2F=pk!oK3W(tSKLR#V06AFiW+o(-32Xc>tenB84>bt469Ac7Hpndv2m;+4u zhkyT$9delZ!T2M1$^zGqXKZy?WwLN_($H-zB=|80S3rK=M;v0c7-|c|Q`w4K4Pl}! z;VC(BV^a``Cr<2T;p*vGbP+LL?6V2gsg**5ELv;l3-Mdy?U(*alhOYwuP)_`g=9F8 zK~1Tw40LpKcpw;>!LoIAUF9S^VN#u_(M-Tth#Vdzci~=gCXgc__Y*OxkWffyzA8@!KK3npOtsd+ssl3njoq2_)+x z49IwXp%{5nw_UqILL`MPbjxg$f?cG7i1bMmVdKZr`s0aPH}?_L$i?~rBO^6_&kwM{YE)(c~Uu@__xEbHn%{}o#^6^V8F4IaV*+l@C~ zsn~xsa8rgx$Q%D9JT9dewnQXIzQY}L0(Ky0jv}*_gr;Znd;eSPNb-``9%PldxowaO zUy-1xWz)TyQCw1ORC)GZ>G4Z`rH|qHFfFE%wD%%cEWW=61&>DAaWI0`q6&hD9H#Vs zINLfp@;!{Yk1pt9f8dOE>`VT7YE_Fu{x_)YH_xYM zATnLeU|vtADny&cV~oB}fLT~JDcf-{Mu1K^-v>9R7k6PJD)V%2jg{^Kc7=_rv6GBq zSR~~)&O|2yQ~-jcsR`8=q!7ZVe5CXuBn)`7E49of4Mw;X%yyznJm`1iD0Bd3>kVWW z>e9z7B9)HHFf_tnQLQmlQ0t_Mw2;507JRLug1`Hl5Dq(DZAW2Qu&ZD(YgcK#c{mw! z?fPZ|439uGy^RzLh8rL~+wmefQiO}zEP3fLz-FwQW;kMsZ}3I2Q4(t>2;opyoaGKk zNAUwC{yl(tu?JhSeO5~V1~pNbi%FK&)-sswI1;B)Hp~X-#PqXn8=O#@H+UU-p(_DSQ5rF$(Su<`3!t1ua-%l>sb9l_c>;9bgl@ z3rR4NGrrqA;FqGpRDkz%LiOTbK#b9v)0JbB&IiLrl##S7BA}slijZUQgjIOw$r9y{^7w2{AnxTIrGRh5?_s#WgC%xYsknD&o~_JcU*X+p&O^88*n z=J2b_Qu=zQg{i*?<{(Cq&$`;%Om{LcS%0fnJ~~+1TaJ*K4-VoZq}SMAQ)HXV3L58h zkv8RZfBe&W%+%Ed zOT(hYxiZaB!JlV*6$?oSm@Mp zM)9OJ=DlPO($Ewl(#_aM8ux|oa-ztxKIaqvbOg$mDZt(VZ26i8dAX&V0cB|5vyPQ{=GmP8PeY+9Km8!^RBOyuGD?0o!kb0 zfwd3H$JRO?9}YvTQI1^bw5y^V8vV1yP?sy+wLuB#P1$-#qu3VO?J&@oygfGuWS3p{ zd5jSXPBkU50v;|7oy(obd%%x&F=iS$Z|w;5Tc`2QvgF#nj8`AHE+?~7vAO4>7cW2D zJh{V8o-=M?(3ku!9Z{Yu(33Cp+Pd>GqOJ)yY0k;u=;%cRuK*F{qY8i1m4v%CtX?l{ z-?cty9B<;-B4412@e+|>m%@w_L%@G#olhInbW~;vjE{ZKj?2lbKTQtBpk2 zs?UmJpmf#y0YYINUI3SRf}!6i`^X-d^21&ENS|m!bP3J6mX!P4&Ex9Tw1^c{0NoY3ST=H)TVMdC$;kl23pS*XD7K85|=-jOp0%|gi z=sfrwGH;Q$V>JG%-F-0G6$;n#v-Wwa8jF{MoD#kE3RT1nKBEfEfp8SI%Y9Qw{89iO zjJPwoyqi8{!d0C(nf*>*8mr&wa7|S=z;+(`MMd{GVMh=FFD~w~2`jt^@O6|}VuuLz zY`p2Ci#z!X-PlT=fjWMM1#;FJ3YFpX{(NoCJGO8ke!l$qB;%ymYY6pS`@G$%{0?Mn zpR%l7WxnKvDq8pTV?-sVFfyav?V=q>66+V6*F3|QPG*I!x2-#^ARbLM_%@LD)P+-k z)kpymlxv@t7#8Q=Ny@mu%9C!yEX*+6{$B7rN4Aiveh?Hz60}fr^0iF0B813qwn@X!7Xn(_z7Se z#6(E?o6}C=1sxJl)G`qC_mK&;`nau*MattAp#p>z_!@y)N;F#23s=goTD$_8vP!qF?R=BoxWX<0$0fQ%F08KoY!6qHA8#Ds#Wjs z@)7ug*jDDaM%TZR3P+h=q7SQYPJ8VMGuzeFL3_KIiDg`q_=>*$M?lm@FKkTkcN@L7 zcz&QY)%onX#U)L8;@f$@dBdCP=~JB!+%L(=Wr4hvT3F3@?shlnK}q$?j82O+!=+k6 zCrDM^S{F#0bs4J8$H#q-dh`OJ%Kc%%KzeyYVcGfyMI-S{NA6}y5=(K^v2F_Mz}oJw zD()xh@j|~Ro5qR{`+Vbjc$&m#H&gD1u)-UT_o%~G32!`!*@ZOsW#suX;P-0QmSUE-t|ed<6A&oAT39;6eA23j3=}2rqly z-}_LPtF(A-CP?8)QCERU#L}PRQ%wnR&+f}xFk_mHDS>-skF6%V?z8xXO6SHgl&q=v z;Y3V2rMlUCO8@|cVg*fS*-(opL+GO2_Lta01g58l-b zcnDfYtasyFT%P8&XdIr*wtIvsw|5dx?U=nGKcM_nz2)qzFK9ctojmu)QF((lhmT=! zhvI$RnW<#&)8FG=P;|&4dR-re?F;p{=r;4u_;hXl{DyIC zqJKEsnylVnmDt5B0eQSC0q<1Hb-~Dz?#z5AXwG%;Dl6;{u1z^0xCI9T?jf%(c(gb( zqcWv^VNLM2?lxzg%7Z45NvJN?;W&2$7f})jhO&HA{0$REWtyvy+ZimL@D&pVUH?mY zl>Zvyk)8;97M5uk=(ux|FDbWj&}6`jTcoCRM(1bfV>uVw z-DnKs#07!_0~pcCqa2gY%nk3iA2i(JE5EQzv@8jJ$A5k%}xX9dz!Kc8^e%VFZUx9FO@D zi`$+Y>)NU*A3n+28S`x0vM+fX{B#x}W`gH3(ac*?TwE;E?46u1kqbKFjw>%YZtC7H zc7RgHN9+Jpy9}K8QJ|>-Umfn77)Wbt(!DpEGnUAYy3AFyE{sw)k$ni_e|2`2>)br^ z!#@4`)fT#QIxNpE8S-T1enI|z+#=t+sQr%Rq*EC=%przO+(XC<0FwG=yFm(*zW0#j z*8)im-_UnU#_Uqpp`q_?@rR7aSSExtI9}f+lLyf6vFD<+xaB?myvrNa)mCxQ%+IB< z_{<$n`9Qo9$1qH*uYm)BHIEa|i8NA_UM_kIp>aN*@RNHv2GyXp2YYiMA|Q$ljgYFS zWn-BQk%1F81C{yU5SFP<2CFg?)YI#ArHWOELqPL2`@{o%r&9E`9E2Lm4}?5Cx{Z}2aAM5s7x+h@jSj_2?@(Y&Jblu~uH zwL{(va_XXt06lFz0NhyCF3sgVXv{EUab4xs-h?@?_mmb1r zVa6;8Z*+TP6k66PTcP1EkVZBy=?qCTTCM<(q43#b9fE9p8cz^giT>dCu?LJ^FFva! zow5~#{5<{esd!<%j$YQ~vt{`wkx8#>t<+UlQPv2vz|9@O)KO`!c`$@ipyPC#=4a~$ z6>t=1jlUAp;oL`JCRfrlo|(6u_m#!ZSmJ4RJ?RC11Nft)TSsUp9wz^SHjC9#vZM*S z&Eo1LV(EHnxM2dbjxej68i%$z(o$HUh)w&cBFp>!4Xvqtb(m!Uk!fx#r)8?wP3&u) zpF2I8Re5;o#(m_)tZriJ=D1@K1}ixyete3%jr-2KANQL+=$;nk%uOsxNnQPyWX7=e z^-38g-nxOrLm$t_71uJGOmuX$$`e(4o2#>4g!TdU{<07Wy2 zII6Fx*aPkkDP&1hm&%tXnoT@q6|z9XPj^r2l;Wng*ehwgcKdy>(*IFph5mXMr#|g1 zPld%GpeXwDi40e;&CdfR#(@4jA~SV8U+lMl7Zq+PR+arL*;6dOaWL9*Vl|zy9jAP$de@ zY>%<;Q!96uU;|OCX{l?Tg9qOYFTZZ3+2!yAb1mfvG_%CdjmC--ikrT6 z&2Gr>xV*hZc!JA92;1(e*vZsKCp~#zR)brEjot$5;aQly)1IO3YshqgoN%MKuIjsx zIh(atqfUEuB=sS8s9p+YC#beghEwXOpLSQ0sUnzU84(NS;e>2-&1Y|=MgO*$NVpt_ zS7e$G4M+U*5gPo?Nt?S_{U`>|&J{$A>TPFMn8zI{F3NvrIp615W0-hV$x!1prFvj2 zW>4(=)9$-WH{V64*9CJ^@hH7fw^d2$_k~c#xlypIa> zfP@ady>uYF2N{!m_fh-vqjD>EL_ipvK*(J7s+f9Z zq#|^%(04<^ORc;~^di|Y#{VH$^SwA&3`14Fd|RdP z%BdD_<(Zb*x<6i#R%8k>NdbFr*1`kZW~J&;=xAj-+mg4IsJ)OMD@cf-;!n*%$ED!E zhX+^TfQ;DH727_1>)B(14~K`9D+nt^_&J;E##}8NAA>mG5NiM(yTizgW<#y5em3ij;?F8HAl*-(zHJ*fJ*i$d)tL84LNOG93nGDjhPS&&o^@B zsjB``F>&lf++WUR|lfNca=$0U^`byE(b!Bs(c z_(`d)zru?*+GdC+Oc1)9h9gjJ1&7|`C6PEFg>jn_HlSm z&!Y@KYIfVOP88LZ-wT#u=r6)vwn{`D1%xTDF6-O#cHB3*n^2MWYd-;ana4Cq1+4~| zQ5L!=iFvgkRFa?{U~BxLi6L$Y8SzNC*zdEZhDK|me`o>%>#7At)!kr^bimbkI}MPF zr*%#2j^U)JyRgslzS?FQyf$e5zX}&D5K?)Xnxm2dUBhfTP0+3td;26c9=-)V) zYB0Tf;}a52lJ4H;I+gDT=8x%3;O^uUNE7f{S5H6Rxw+oq_69!s^Ir+#2T6krXjo{= z&fb5tE&6-N-P0H+IsC;2jrb780}_2IyVU32X}<}q@|J0p}U6;L6Gha>CXS*xzBxn_hpSN7HfHc zIs5GIj!!req&hgjUX!0Dm8@I){ssKwNqtfPOZf#1+$<}=xtfQ_CUr5kh-K@r#>%uvYvJ&04b z&Fet)-Hcdm2(-3Xr&bTK!s|(=6%gtgf4sBpX|dDO zH;-I1NPF81zB&dyoPS01dwEp@e<^2N+8c$Q0B#pv2{YNBh5=@0x`bJXA&Hbo{6E~= z&-0&C;Ko;{V0hP>lsSa`rQU48U9=rFMQ#Hf;tBgtPEI;*jlcsI#>bWS$M`6Ys&5|e z+a7~mJFP#WMHYwVnOHF04INuv(@$C<^axaGp8l4!`Iq1h>`mDvGSGfszKCr)=cak$ zNdrG0=~RY$nqj&wXpJr!gYdWZQB&u7O0qsRv>BNn|G6ElE$41~ykENV(i|1_JI!ai zJYMA91v9q))?ytU*aXIY+61kQrvg!FBo~KExJ&+k9>douRaPQDnyn=h`c8cWvKS35 z0L8fEdHM;b7&v8!j9$J%!y#R^g@-~1KV6#0N8nxF)o*P-pE_NrUwhxW7yXjHx5GPI zk#WpT^?mu5Zqf3V@QITPag57L{y6R02hG%XEh%qb$%vJPNBL`*sB{>rYDrdq1?R_2 zk?wEr{{aiBhIA3Rt8I?@V$x~cU!E#57E@};&`4^ilkM+@MSoXC5O>k%A5lkWRX3z6 zMZ}2WEQr&<*Okiw4>I96In{{3t2g8~j7G8xwqSrHACA06==Z%O049|w(|n}-dM}<# zXnbKozNm_nevHjUuj}4uM$GikOyi?C7rxpQp051&_p-Z@&cRUmB9@YDsNxK$T@z(o zZPi-<5Z}eWv=;)C;Si+EE|c?$I^0OZ&1{FACc8loYdwoen}@+Lvp< zRlvy}OH*J5`AkeqoUa4sXIP&EeXY>#*=&lYYa__iBr#faP=&h>cJY;Zcy3`m&Vw<*-FIbT1@3?zYpDcGoW4+KxjKgwXK@8poDmk* z4hKl;yWs~PNFQB_ug33fYduR6=VNc**YvmD3uaUh{}0-LVND+8BH$Wji0;=k1^8c6 zz3@A{ZJ>sPKz&@AG2r=;(SAc_u%C5Jt3RPJaYn z2?~oNpmZN9MOlwqwti3P3eXe4Ygb*>wgT7Pr?;nQ(XV@{5g zpiGx#b0n+$m^kJXU9Zc4EE!q?lcac=jN5pX!8wxpXz9fH0(NO~=EcX_@x{Apu37M`W?d{6ZxkEA?E^D9^ z9(-92BPE77%a`q7a~LoDgD4n~^6M>In8Z5Fhr9xFjJhaWeYAy1m}ykK?}{N;JQj=7 zg$H~$p4u#p$MROtC97b{T0Ogv)%^I6jAfR-@B0X~X$zqrn4in5m~>hUq1SipHQZ9! z9HdQc&dx`1MPs? z>@0tfwcgIqd&%C&EDbq=188$Mz%r`{RE)zMAr8+6q-j*twB}}u>RM&EaDT-#5)~5> zCOHEWz-f?_#SW-TRxUpM;jh|pN{SY+%<#*z$;s*ct*S%#L-q5SP?YhAeT?GqZ>=&zp`U$R9DuiP_Nby%+zVIKNq(CN+~hSFCACJx=98NA*OI@fF5 zHrQ{u;p}G^j{~p2)^=JB$}A`>I{tYS2n)%yu}nJ=1xCi5>~H`zNY>j=*SqF4rQ3Uq zfA!lalVui7X(V&zy*!u#DC^FZEg~e%TG%!&)O%<*?3CKdHRN{=ZIX zU%B9qJT6~Yo2V`nAvBtts4t)99T3XhUs)egBk!=I5`SIO0sd!_R(F74(f8cXC?r!( zZlSOLQ(AKo3#0~l=&Go^G>Wj-{Z?%5EpFWujkp-3f=JP|$801hA(Q`Y`>on-9I}*H z_^9vRX?})xN+K?)IXb|@&6^i-5RO1b*4Uq`ivlY3AiS$#|4~rBn4qN&-{U%bH5A|B zKDr3HuXAt}DJwrt_g?9HumJ929t#~^7K9to)^tCr*ULG`G|>j|8IKzUV{AE;0`4^^ zHR@Ek<9`;3=ju7u8)1-FQk7x96J?ln;Y!X*%;7SYmL6w+pO@{mgH-4a3TuwML@Y$! zr+T;BpFmoVy8NG&n95XE(^fLCcT=Y%B| zW5Q&3)m_e9C7?Nna4KkVCUT)`vT78F)YOO0cdGu{L$U>UbDd71%Asb; zJG+q+Wbbvn?|2*2DWQeN#L$W2)s)&yMb!8*yM+g&4JW6du-(3MqT%9Qs4RW2jwQJWNMPe`P%~rc|Dx$*Aki!u#{^!_9UGWdiu))bQ!L-=fK6DM}JhfO@gD9rnD)dnDV=3h@K6 zX$_cYk0|QG${#pf8+fe-!|VfIi$+`WNZEIw5SHjRfuxLB_=b3pw-Skxj`2I6U^qmC zQM)=*8=*9gHoJIZ3f~IpzMt<+wE?^2>1DGxay0wRb^x5~pWo#g+TtA?5NjfD&Hk^r zAG$-7#RSR<6YX3OJ2wD92to#CpIy}Dar7aiSF=;C7sIqmYIkX?6t5l&uJRvNY#%Rd z+tLHeH9gh*o_lw>Ub}6jZSh7DvmIZpMOA$eF8|>){B}ycQmkDe_pKu4gWiz z(|3J!w+*9SI4i6a_uEqRpHjpn{JZ>!^iqTV9sPDE^9|MX{YbRSTn8w zpbj-*Kye{>yI&<0MNZ~>%7!>DuK31|jUC_v@K<$@=gI=(Gt8$k8InQ9enF92z$NW2 zku8bDVMOjmxWSU;$^8(RVRxM&UC1#r%&a(b6VYGQXa@{4i1)WL{EwQa6(HcLEwB{+ zJ@KPt25pfVqyR5|pQQ&4tvK^%(a*mTTc+WK_;1x#iHDC>bph@ZV;)A2WQt6461ZpX z0#?%)&R|Zg!@QJj2LNGo2NoEz@WDKMm6i-Ox=n(T&bgbHVXGcbdE{#{ zfQ?JtC+q##ByrzOFO+pU`a=hh3Zli9ZX=})5n1ojLRqEYts_}0cB5k(#5yl|_4zLO zHUgxM-Jv@DaDQtNP5uAPKhd99Z#q-M@9wY;)~Za0R|C02&`FwArg}PII=HU@JRj^O zU>=S81RJZJ7-Cb(ny$9^t$zpCpZ9sZPh##Gs2Ls}o@WN^6Yc=|^K%L><{%j{nic57#IjV3MIOVkDiY2mX(zOiNFB!_B7-1j?Mcxd^M6g#AuQ95Hx3P zZ7nTLZR7UgpJOgs0AI*<&dFXQLS+8rZ0Gkd|BJG}6EBO^OWy-L((nEutgTn8fC1uW z>qu|(lgtUA3H*MeYbcp(Y_ndU$$c<0O1)gqYx@@!PC}ovLwD*Nn|QsD4W`2mpuqCg zFLjcONQg9Ek5Rb0X03rTMy;Ku*GalVb~;$`#lz$&*=QGPhgb5%$7i)Ox{GfT6#eGj zjcoUd1r~@y@u+geUJL&S3%4$KR)7Z!`~ICJ-2{v0o*7Jc{DojZ6y@y*@ulJ%8MNrC zLaUgUuVDFpElGOF5g2e{)+Igfh1Po&Ud>qB_nB$if%k``nIVD7YH`uwm;19VhiK=m z>Pq)zYJJM09DtGo>4Fhu3;fPgm7zFn%m|r)T$N|K9FbP1pu1WIJLjD=+=^rJh0v=O zxt2q-1248$^rf9rD1Z=e1^Ul##*3za2qP?2O(28)WUMT84p|(j%@8tIfW`z2Rirh2 zR=Y8jDXWm1|Ed+}F~9zXs())pR}F;1(kIy5)A1`lQob3s`bRLBV{3 zDXcF;4yYT0w_DWRGQfvaMI-gboc}I<{Y0m-M08N-MEf|(?qvu}G#L~CfY71n1v@X@ z@<4Ml8{!BLvM*l<=uKb_1FWJd8#ql7$KV_HNG>+dw#D_9l<<&O}ivpWDghob=AFzrFPM*ICnvXS>jKb?0}Bo5yN*X84?fPqY5hx%r8 z{q1XiGvNyF`34kwdCI=the8Fffrz;FPlB6r11uHaeNS%7i;I77nT_y$h?C%J4{mw9 zKYaWZEToz%5)>V=r3nl#lFIA%D+lF9$rmazXBUl~dyc6!#rJsJr%TX=*s z;3`}b??Gb02<#N9LqFa{#Tt7QBwBBF%)cBIyQ^L$p7vTHNph5NT`8?wyeXxv7^&^k zNYXgjwikQ{*NqS~KPqQzwQ2Wg{rPK`$EK3E=*Ss{=lQzi-w2GI8R8<^=le|>AS$51 z@HB?nHVEZnY3nuE)83~)mOQ!o-(j~}9I*r(GPD+pghkOvMP{-| zetR9r5s~}FwNN)4CwoD>i8DT}XrDf877JyE0p}yfKeDo7lIvr}j*gC+&K1lQW_;|1 z8V@=muBUc^Un@+1mXsd` zG#)bXn2NR`M}=vf{$#;B^{oz8{8dT#w*9`9Sh2(Gnb@aT(m4t&*x#9|UQ+DTq3^#{ zGEJ`(76Ud;pB(f4eT}HfNaLY?)FD*3M7}HLgZCI(0|UM33d0Yx*^Kn^shPA%>9@c} z!FI~&nka|IbNKcf;8)f;mmbyuRGh&mHim5PUgS|GvS>R4MkUY{kgLmIHM|#j{S{{S zH|M03egPc(7d<4l(Z2}I^;#CnGQEAPXbAzId%$Z}2I=L~uMxdBXGAUg%+;C1tgLi- zJRt$3BcS5EUxEl!HQk8b5aGpThS(Xd0WvHj7uXkb4Ndc zuv^gJ=#+*99E1UTB9YK%qOTML&tEMPJ$C^9(DBXg<*ZzKL3LZJhRsf;UCUphWDXd5 zePw(6k-=TMy-uX@Ab)|S-h{#MF%O~m%mcn5j0T~H?hZTqH)4MS?79Ki&G%T+VqDzf zBF@%PvU<@(alusKS0|MP6^f<=%^#n!{arw7sw}#)Yks3{uNze$6(~m_Tr4wPffB}8 z%l)<3S{qZP-zHpsWSPDx`o52B(x@On?FfD_Qnf|C9hIyE&w=QJ6 z)*N(3)2sEhEKkg!xjD8gEG@;Ifn0sDGG#x+ZEZSh+S^TObuW`5JXAy8^+F~lun3^1 zVGX;@W!DzKW}mX3G+5*MBDI_$2JK@pt*w#&oXM+W47<_pLXD8CRWQ2(gjj(vBmU zCyM1^KbhkJ^>&g`%;QWwd|z*wJ85$t^x(Oj73^=_Ax2KDLC&lMuh|?S)xBi$uLe^5 z)8Qn0S4A* zV^XCXe^xg?XFk=VX>ZPQQXZatH9{_ocryqp< zTmWSQ)k&auzDEbgU#Wbt-7(ny#{XK0!5QPrBqpmagQ- zRO|e(=#~jRjA4~gULs9<`&KuItmND?J~x{-tjPa0SZ@)WmN(F!w>_i6S;$)}vjQl) z&e``j&?t+CsJ2D#;l0chGcM>BIPp-sKq=f_tg|}S#f8*nMtbCh;V#EyWLL5U$aGiI zLEy5s96r5%A_O)t2Jq;ZM=aPIm0%o*wQ4V)-o>sKur}AZY$s?+)&6+a3WymS4&2&x z05Pl9+^TkGd}yZFa0V<%6=qf$2=a-*2rY-}rdVNnM(mCy$Uc~MaczcDBscyccsEYK zW)a{lcSdIdW(DukTMwab%mP;AVD7L z7#8Aa2>gf~EQft(fI-5K2e(0MBK)-s5gpz4A`|+rIJkc_KhWaTYd5b&@(Tg2&~INc zyeG#9ovE6fCEpezNga-83gNZCX^W?~nD`^?cyGQkgMca9liw8 zhUifi<-4G9PS~r~+Io_?PXy>>+ zU=@>me1RFr?uZh+gGGo<-&q(kia{AbgoJ*QJ}#iD_#u$9fSFsZev=64flD`+d%as( z&B(q$QOYIN^Yh`?ur@2T4=Dr6vVn17A1Db4YT-MWy+}a2>q?5a?jdwZT71>QvguBz zCxE8y4`@I`x&v7Z0b8r%W>3lqmqE`Av_XivM9Ycy9WpeQlt?+qAb zOxLdGb#~w*7iaal$DHT%Bm zFAIq)tn5H>jn|H5Wiad2SjBzHdfo+z?POW=7Dc3wF>a5ym~nsh3|i= zimf--02*P?!T(BykiLBI&y2KBaQi=J*2++JggNUNDVW^<$@zDt%8Ul`kKqv}WJ81g zRI{oukccS?AyN8O&60{#i}Yv)gSU||CXZdx?C*stzf}r>Kf|pjeSbfMJ?Ee6^IxOG zR8kV-E4qqPqq8c^Ebuv*0hRg_#5h(2D#T0Br2wPFd=|hkve|ILy9jfaTlS$eyio;; z8-7@p(cG%_!d&Fy=pcx^E=EkvKo+K2zloUT;#^DRf$@S$4pDaXd2%K?5W07Glx=i2 z!iBEr{vW;|jHv=cl7CL@6>OBj8A@w1YC0b4Spc(;^_wsG%|Bqh$j-&uDB_=g8t#!s z<`s4k)8rHI7Ua%^vW2N`9J3W(dZh#Kk;LE6fP4;IN}ph5VmXs&uCcyI6`zH&@kc?? zl0OFsU$<<4K)pdZ-d^17CD4D0Lf#Ne&`gTweB&HwCeHFkB6pDfiK-FXAI9isu(HAd z?PM1m#IlMh zl}4prrHV1)i}y`RtAZrD$2e+Q{A<=^u)JD`qjq)S+lwnEdUOUCH_yw?Q`|WcmzpYl zUK!?toNht2)rO*K#`qp}X>k(m?5GycPV77Bf_OB6 zwenPM>y@RL=Zc}%cws;1R$U4m^9sMf!irR^Lpwm#b8A7sn7gDeJDav~tq?rTuB!On zW5~iLs;0Vk{3f@yHUS{)zqg_UeOLiisWn@HqeUz}hx62l(%pzx!jFCn0G@t^T|pKE z8!tz}+b`m7j$s2!=NMwS zxB%2Wmjj~8>EtiRYQ35w|r4x%S^_?xb*c%3gBbAUP9nUU>euO*8)90KAg$f-T z<`_!xO5hN&>n674)=6<~qx)k{@7-PnJ86Xl9oH6RROWYA*qiIAM0L%1e zSWXzi;SS-~hbHuY2Ykr-F>7lRqdpI((*Uv127~b>lI5FE|0LoH+DX9FP_bQ3ywLyM zfI}XHts`|!^S)=gHHq6oIfFhqHLz+#^_Tg}aAfl5DQ@Hyd0J{}1d`~V1%|p1>^?20 zXX}~1U{N}7nJOv>or|wq0u%?L{m}?GIiVKXUtY@lOH5FHO*tL;{!ixUOdcW1j)@bK z7W~<&6#ql9A|_Wy;mbEnlKKwt67`K)wm$y-G=nh5KwII7z!;6VFx=T@V`)j^I?5=K zKBP>2hL4q|QB5~)QS6Ld&4vf_utWI%JLd&(JgB*e#&3O8QdV{Vgj@h`9hY>YRwF-z z!(@P;(7ZqNwmrt(V`n_KZpr%==$708BKT4q67Lnz&vc-M8}Z<2OiZ({3|f7a+!nlh zv$FRQs4G6;bo=h?ggDJrZ_WPr7eU1e=PT&G#h; z{ymhGkUbi?m%<0LcdG*C-IVbmh2uXEmPK@_SCFhaPFsb+XIg(`a{a^e1%?G5^uZkY$Hs=A8Pgb4*Omzbg>HI zR5)lI$>uP?i;r*m1l5Yez0Djf2}b=5Dp)s^U5_ge_bTng4+=8_eO1f!_EtlBLG=gA zF)LPG1L!@rw7yA)0)hj%3vbu5;=Pb87bgKS>-qtJd;`vB8^neMO8wlV{B}V$?|S>* zZ*wbrsE#al>^NP*FxHC0`Ho2q{nB!T1Iil;HSa9UJk^Kq+p?cKDh5>>xK;R~w(;N6 zai|Br^z_@d4Q-V_dpmKj*!o8prAqoSd+`o8q&20`QzHHl-%I{e`MmfSm=defhK`zk z$_LE>OAVs0wC6?to-V1!27xcq<(h!LldQMnw>JLQtni4#j;|%<%eSqIJRRPinrmaP z9x&$Iyw;#HHqm7)FRU1arI{LS+WCnQ_l%LJ{ay6V9D9s7xFCqZD~#S|X7qWrF&kk` zN>>U2A&7(=&7ZXd$Z>((WG~f6bwM6hT70s5>?J-F|x0 z2eUq5Q;=tKfqF_VlJC;)T2M4*ZJ{Hxbq{zXHvzZIw{;CXQ5_lR3B2~J;w~Etcd4hr`AxlJp*=nXN|9(gWYXpa@-oa8^TXC^$VNxxxR}nx&pvfHn=53G8NB7HU zn^4&Icz)>7FyI~F<5kURS5#-3KU8t(+ zlBsW(TIe7uT6Ojm%_VbMdTgnHg= zO}$UP;4hqe3pUw8b5+Q?a4ryub1GC3So^C<;uvN3`8apu_W6G*goYe!RKx4%&!5*V zIL`qY+p&^;^ADCAMDFyE-Kr+I0!7R!+^jCCFxDkJ@Drd+cK9TXS|(kGa-Xf1 zP;SHg)bQR)6fajFdL4Se@OfO&@Ux8qt&CHY!6?(KFidA>XVKhz{rZg=(3F$YA>q7{ zKzpW9B+SLR8itvA!c|bhssqH*=V^b%KeH10Y6zJJcQN*z%Z1j6{|D3>X7gmj6Q0?(fqHUxFm-0KS9hO?$?aJAN!G{wE}=blQf(+J5+46`+#1*i&6;imnO4CwI{~n75Q}1= zpNxcCNT$(@|ExU(g>Hte&j4>E(|^mb1X0S-hQpXiaFIy#4&zd&c-g8&{by~`k69zK z1@g-Wo?QR#e86S#cFM7VQ1{E&Zw29R*15`~;CRK4mK>w+0D5xzR?gq|6GYk#Sthrw zaUdwcbZi5BVEh)P7P;Wd8#UJm`@>TrsJ6Q{Hkb(?yi!m}XBUx`b(Aq$`=!T#No%MY zPTF6AVp&pw*)xp~rCn2v>*jLrtw!NL+cHu6d`LrIDi436h0rD#5>zKyW9`@60%~p0 z2t(Q*;H0n#nweS@uoc!x%g-o|9tDjRTw4vI+VS0Q!z8N8FKBPtfAqeS>pA4s9en$P z65WA}D1z8QeR`chFW#CY+7CL}u+4{{Nf{=3#NV$w$i}?(wT8ZX4nYb8Fhd+=`o@3! zHzJc9E!zh~czt8&oBih(G5sm~oFZC7{#yb*#a2a!%&Bzyb3!}bp){*7gB9m1ZWT)V z(WstgbhhXWox{grmePHe=NX4UOHG~ej5van51+p`3P3^zZEl~uZ75I#4yBw{EmI+! zQCr%Nu8vhFMjBw1JUL*i>R*Z&?yjokpnSaQ&0S=rRQ&J(MH6Llb~a2JL)}lIwy<-D z7ogXvztXOUFKglepzQ$6Ed)jIH@*v5-dIS~l6wCiwp6rdED2RITH)}e+4+GOe1Ys= zyvEPaZY07%FsV1HCpEeJZCPuagpZ3s}^0#uHsD{?>cd8zx|*}R@V3_Ow%Lqp5vYR}j*qS|pMv{3N1;Fkfc2-F-VgN=E4fAk1i+y&Xy zD)fZrj0%yFw9%XI)M+|Vr?1JgP-a1YIMuMVUvpI_C9?O4+JAfrpmBh?bP*sqjdF|) z+kT3U^_YXIl=ozF=lJS5e#EkU~t*RD2_^3Z<&8Y$t$M;fLHI4-%9xy}qw>m~Y z%>OvU38>e(!q!SR%>k)#E7@w%8BTzp1n_klrUBzdH*$M-WI*bEJJEM>3d}d#3D`h& z@4O)GJ@yi2W0NC?u36rykJVDnBi?tmWQ4P%rKP!2S@mn6K$+R%=X;a3w(|X5G035c z9NJc%Beh3FU4;(SaB?Vc@j;>h7LLE*;cCIFs! z#~&H6qo3YK@Z=f%H4Beqi@_X^2AxW6KvgRgFwF?j8Tb~8*=v7P5c{8ZGKf{b*y8LYh?&RK+f^(=rJf;IWz^FBNg{P z0dtGV7qfcV2!{YM0aM#AWop0Iun?T7f#Q^t>%SBC!kga84|DNnAz;`hR{Y8Ui?mhh zCanVHl*g5?&8*a9&j0PLp{y_F^;cH{?cAy=fbe8gG);rhLXinb!W|iH%@f|JIydDO z0t^$egQJx$fgU1qs8BJaw!NQRYvx8G%5YIKe1*LkdG37J`h2+IBD}EEj7#<5aX$^k zm8AF2%l`m$`qG#=?Bwrg6Z2dg{j# z%c{2}H(o(viBF|kS(0IAOYDoCGdiivqT!ym(+Zvn824?w5=vhZLmB;&&+gH`Pu{p@PFVM*x>VcGw@j3NMeFOLTR(AKggc<6T3MKN-XKkqrcv>4Gv zc<*&ciJsR(#&itfCcvLn8Vf|7&I%e z>o>ja$I+xA;&$=n{8d)ukAn%vER_TwP@R(F0=aw`QWSe2_m2UAu%m$?At>4e=fh>7 zZF;nX(yRY{b)s0-U^+YUP{ z6CVs0oBNVamMlF|56)Vnp{oB}3Kr@`CAaJDc9Q++&MI!&GP_@pE)QW?YU~aie9|~< zZlZtjeWfV%#9KlsZl^{cIcoTEWW6+$|DYZ^n84!YDVveH2jEhw5xF~yB!fEUR_*I$Nn>0|0MokTfv;JQt6B>OB5uEXE%kVC6gN)#Wd44 z{hPVns0Y!iHOr>qnWv+yhNa00~o**bkPVuO$L~Xouo@F!PwPz&pbe*mKcVZ}I z>QziE2SrSjNqCMTgI&S>SLPuimOIzA^NbQKdT+Z~kxJG-ul4$SBFL~#_gU;?K?mX; z5F%cde#lQ&(-H{aSDv?iX(C5M_^oNLtceI~Nnk8uEH<4Z-D41h=A*=(u-V2I5D-vp zhlS-Wu*0>Z{7NEO$oTPaX7g6g{!=X)sp3K6rSH(s%U0<&Lenn|!xn!3iO+18hkG|J z=!*ttjHP}He7n2R$2$eq#I?QW3;1#p_!N4Fq+qI78o;FkOyETf_LfRCA<5jp6slE7#%!QPH-v36;iVc1puWRSZAxT0VOPc;b zpeejloxJN8@*iZ;zvkE_9eKk6?9;7K^V4&F@AF`Og#E>qA34blnBI+nG;Mrue$bP~ zwApBy?A$pBaSswEIQsQ(Fy9g;)?|MEz4>>-nvB$BW&6>irjNndR|n3BVFG0{Bx`ocm zZs>7>Ymevobucj!bcW+>aLKk|wxHsOa)+rRQ$kcX80%sRfYW7*cDx47Jghv z@Hhy)ItC;pCXJa(grF<88?PNT9R4O@S%1*wf!(z85Mr_1i53dI6ER;@9wma>m;DM} z)2Y6jGqIXm76Ju=Koc5mZiA>=prc!KZ>E+`t@^bPlcw%f=KU;UtR+T}chUL5Z6`$i zJ(hyxBwQPn-fD$5*_AmKrUm>H*Ik!M*gZA7o-rLxfwR2HWRQ9J-<0(f7~hW?kV7*V zskTS(!{mWS8=KG9@;iEi&WP5J{p8+TUQpon&`1z;6%*!b-}|ek{Vj<;-I%S~VHDb# zjLOq9PS^P*C#BInEls&e?q_+P*@X&xI8HadJmq{Ks)xuY_Pj0WOdl8Ka~z{`pgu( zbUkbhEM(W%&2d5x{{B7JvpvSzb*!$2kb7^o$GYW~CFMrv!xf$tXqujFw&W_~v@wCC z6cnP)Mi*%@`Nli#Cv{r%^n9k1k%EUO8`u=pySPx*b3)tk4l^;$lW4SV$l&)t*~Rw!_8SizM+V-@o{TE5TUTpYjOSy*I8D zI+bg$_>k(?DcvJeBD>HD+y59&>cw1`5EMZ`3pFE~yKkVF?~b7ID-Z9cR*r%g5myPs zFj92ElK7B@h%WX^)17oiw_1IE*9CL+T;oSb+$iYvv+NL`!iILsHJuO0-``G?_a~Ky*U>^_c2CcV1p~k1?g!66j!_Th9b(y?e)mK;qJm}F88zm_ld4~_1 z&M;ail@Lh2Tc(E^q<>Foe)qiU$E0xW)~RrT+9NO{%?ote$|F6_NBs!p%m~Yt!#cCD zxbQNqppdvB`@U;@fM6o>_Lg60$E94EeTUyW@51y=TGy^$LCC*}h@rnlo4)Y}_u)@# z0HHBiq((vpaFka@8h?AE1)bTQJ*;%R)fD^Rtn&2rLG!8nNZj&^XHv5Io(}ph9;{zz z4ohQb{G5jS!a)UpdTWq2v&_y;ogz&a8yvR)nF`8Nx|3@GBfCs44cKbt=U?M#!jIjH zizA*3M!9A?0&glqvR@2-kk3b1vIlt^uyTzaFFglcj9wFw2H|A3@%tPcx7_Pq8+3P? z{)}EM4&|`3-wvI2y3E?EoK+QTdQe8EkH-7mt&3%l z9xDN;{9l&Ph>yC;%&FB}R));g^&@*u9QLx6HxIAZ#8FI{7nC1cNv8&(UWu{p%!vE- zunN{7Vp*6SldkRYWWIz^sG5HEhw;_oHm}3;>jM*(3fiI>Mht!7ZQ`@snj`H0HH`zQRx#w+`ocxzJCO6of*h1Df z3dB<-mOXWGI8HvH0R&HFM#CT(KbN+OEumtc_tsZ_-BGe6X2y(PefIc*SE;TxCf)tgaK;|)_z-Yq_5XKjJv%+hNGmC214VW}W z?y!Oo%ewXZ=KdH(kIoo{4+rvOaKUOGKd}o~xsSH?5drDn9sZKg3Nm&PhO5`lal9Yh zm25=8wGNGe^hco3jd+Si z2SCX!LV|fHJt|Ne^C_`x80|#Dm5mnX-R~Chk%gc}9CN6bEq54Le^^Lhc9jDI@k}kb zR3I}9_xH`YGZ1slwq_2HDO)l}kHec{HjsuFVK~H!C}kpIOt~2A*_&V$8eUB?X3{Zv ztV!j(=Oqsu3oL<|KN287Y)tM-_wX>=dR(Jf!t7R`bM-)$mr2Zt)e@6(#bl?yFqaID z4-^Ym&X`3w9cxt9T`@J}8o*cg#v?X1x`1pWeeT74=FliVKRy>TD65+?nB>VsQIUOb zLQ(Gzx?m)RGJgyoh2XN3$TD$BVny|6{~W_dI0mX3hj0A^5`({fMepmZu(aMtXuY>6 zoPr;AcjnX_L$*7k!%ce2vNQzUR>myf>m3~o@=*j-ahmh(7UbL=R<9p6-rF6%_jn3K zkG5t)P=kjdzs}=>-nh3Jy&~!X!tCXe{Hq|A!F!7Al{GRE+l3^m3M#$wJIm>$5m+_a+!`Hm3ubFu0%RHF2j>)L$~`C~AATyVD^vFEW>V+eeZdDb$;fskHFvYkPD z)^5l&7pXZ%MRRMC<$j6g%dr*_AKPZMHg~OJnW(;avk#ZuOvq+fZ4Q~UX?l)>lePH< zgHy#HsXIz*K`0Leqq*~KD+SLp7F+K>t8hmdQmSDgKy3G-UP2O9uC2~zG+6;}*Y4(i z^Kno+y~P!o&4ae-$BaTsoLkbp_$Y6t>WOSC)GX(X!BVu!WKC zFt3E5B!$4Ia&=fwJLc#Tbr8|&5bJMti%oJuoks9O;FEPW_k`9XX}x0!W%nYJ5q@?AF)NttHwz>RcHw_4r)6F#+#7YfT8?UMUu)KfO3LNi;D zt$*2qd@bjLg$b|t5BRMG@`SSe|3UC@TIA|pyE+?U>jT-!g^(lfW_ zmHL3FHedARrOU=`(`nTW=KM3i583b$(ec!F#krRTb3DW>!6g10o^|OL=A})rK3Wm-;gPOh0?;y{t78=zyp=VAT3PR1{pi31u zSoM2ZKEoBJJ0@5?MC{>8gpdV=b*oK}nN?|#8pgh^61i=(Kc0kn(Ox$FSrc5z0UePJ zteW8b^IB0f##oNIACkmDG04aY0=r9U4=@rJb9axA8>~PaElVMuJ@skmzbCnL2%RO; zs@Oq;FD)2BHlNxfj>B%&C?228MjSGmt>8y&Qa*&mOYp{CW+7<84)}yuo%zndDi%iE z63AttsTURaU9jFXiKC~N+G)p%qE?j_R2v8B41#Q)5stjiGg}x}BF+h%jM8rOJl7`K zi>rHg^Rl3g;FZIYEIp7RW>mc#sR>MCyy&CYI_l8G(rd)8$($(dWy8b)fh zWVKc`90Wj*r2@A}>A|TyMlld0kj8z?q4)mns(W7UG^cux4l|M<3eTU7yO-`6t}AlM z@f|ymR0#DJqX_Wu_dmE5qs>&IxyA#bOR(=lJ@tUdjL?eH%v0rI_>=HzN<6#bQ+3I4 z9l9{m9iqADo4dp&B`4Nj&#k21uz%e`$Zuj~^2q!*kl)wx1i&(9eEI;q-iajl)bC?$ zgqL3UrI7ziPrt+T>iT9Srz$BCO%cnT6>Rl;p*&&N?LYj~lHBhwTzx$XZeoTK5CurD zGA(@&iii&>P82jE1JHp~8n|`>n8m3R^Zk{|Xv$IKFKo==k7{9kcCc_nk4lLv*z(ws ze?Dk#g>!5A=(6ZWFC~uzY59pC+U1f|QSZnNnP#`5>H)ec=3W*~A(Hm2aIFn%f$qjn zTArs=u1d5pf&B=-`0!m2apECVv*srO&JvKlM-N^Jr+mfEQ>v}#vuspz2{&UbwZc)p+ zFNyFQg{%Oy9|9r72`7|ghPD=;L9#iZZhbpDAUB^z32K?T`iO?z+eTXE&_;~~j=~^m z6#Mpefx97~`(GsuaAh9%Sy<%`g+zzYDG?TW4{a z-7QAsjQ-?5^B_6fTEt#N{b$}^@1yMhDldC3e`{CpQ#+r!q|e&BM$Xi|86|4cKRsoh zaC=j^ivCW2wX{8hYjCtGZ39g|A+7Q_rCA%zl&>3xOkq&`<(kepHrVxn0u8b$hJ+VRCaRCv2>`hJY&d_*Z5D! zOKt7H0_HsZ#Faz5xu+*TWwb}?a*X(}6++tM%%r^7>Sn>(KtAn|Rs>uIrl#$@ktOK( zK38X`)MDprb7T5v1ex~8W5;=zb@5yftdB!a5iOu0_<};H^xdcel&IRI>jOFi60E~v zaUWL@_y&>efxeO$Y^V|s;>XG-32kPuOwFQZf}L5=*;4ncMfJZB5D!3Tv;vgvk3C%! zg4u1qKGw&9B6hnHuyjkaIpjp+vxbwD+Lj3lJ%e}9D??0PP;#^`YIO<^k~&VLGdSJq z6vPF@3Zu5bqc&;p+KwtmSg|R_&@BwkhtQ`QfmjB>y!Ypjz@$v=`l$54e4=yuY#mw( z*!$0w1YOoho-B9=d&Mj%D;*UI3O>KWjb|nPg?Hbp!P`9i1Czm-K+#M%1y)7$#d=G& z3PrxLX@|~2g%##Afaft~0Wzp4+9cTp&pSPZE(W`pj~(Z&V(+G-!*t$NWR#VOT_-*Y zq`Ej;2m=)5moUmVfv=Y=2id-$KcY5W_G(M7-q?;WXV%oc!!G6GZk*Dgb>fX(HlAB9 z2R}_K+c>g?s%S)8NY$?V-WWT3bMqF*f5MNA3@#7<-1cX!fAc{srS7QHc6)N#Rpmwb zM8NYWKpfPJTrNa%N^<1V7rQjk8iuh6ZFVAs$h-Vgdv(NG_BZUb^Tb*=~}U| zB#z^LUPm1ZD9?T-Gor_g%78-teRh|(pt+YobW3M+T}*PC?dOZZpJSh7UY+{9pp|0d z?3n+R8>1^VRq#e)=BaaCy+o#Q52;}%+r44wY27Xm9%ijbabjze+j9>B4U_N)GKlnP zE=(t8L9ZAWlYR!)c{@7_&?PGN1zz@rO+EV!+Zp=-McTP1 zzs2G6g$PeQPeP>A)>N!3RI&Z_s^E3Uqpq$zwJgeVM37kjolYT^C)Yv&W=Tft1o)*@ zSX&1VG8846_N-~_xn37cpAA*1kDi;aPxBS`t?hXCCTaFvK<*0-Ycep2)wowT(KXWl z2wv*eWjm(GuQf!a7D=zW2wU z;uSC(ee&$x@OWKgE>-t}^o{}pP(;TqWJYS$&1W-GKe+J+i(+7*Yy$L7IKh2< zZLjM(hLXYinr}4?RqXhc(A?9^Z=2tKQ!qb%d|YVzAq=l$ipB^2X-O-3TLYPC3#`~q z#W#FG!+A6UjCkJ}v05*t^zf+U&f@q#^#B-{&Rk@o}!PN84MWpim+P zQH>v#gZi56+*2uwll}Huw}cz9^L0oL-N>rY3eDhx9vmI?EMYTR#@lYTrO< zzYqlH!@mR;2{^2T-X7LR(ETmbkO#Q|@zo0OToHgNWW* zEA`GS=quDZ59ny{@*SNzXk4gDd|$PLK}4SI6$$&FGK{PI=h&c@qL?-gQSqFm0_JAX zJ96ZPL~I|QMaA%Fb^!_Kj$rP>_!-`p z;`vSrNt^E7OVIVW)l_5iRs!@$IxX`KOBIyiK4lyCMhWW8MK>GeO*x5(`wWJ@5Ptc^ zvESJd)uVi-ENvew>Vn(0Nlki)4Mzm22T$&{_qc+oh}!QkNAQ)s%@&}zV!T;a24ye_ z;WWgt6%fN1Ze$dq%Q%s6G$fK!M^V^TEAZDB&u_G4tx{x*{gJ_eeyZ43o%BUA3fJf1 zBpPWeJ-W60(ZP5f-E$iNW4ka%2WKB z7uUKAvRzv0XyNj}6jElisFAJoN!O3#g*0L+F~_y8Kq!;GUoDptl{JuuTc3O&*jHCZ zr20(H{fYVA?jM-9>d~~F+V9^~hYoF>y;@fBn?sZ3B{#b~=$njNJjO+Q!*uln{ z#WXt>_gk)do>Ns{N0qkLp1d0G@TYpejxOFNsVZEqd9bTYwA3z{T zg=?418lN{m{Bk7Rc~&@To)K}pNoYj8bKi!1znKv*`3tGIV#=fS#2sTQt*CzOOKv$8 zob{7JkfD6d@OC;p)o=s%=x$8&Y(l5&e6okdIo11jZ!kmd4@VJXTC#obNuI^yAJ_dh z7g=Y_2n_3w_xSTj(M%y8k|40YOVIyff{lrJvC?BZhV7UC)BK%*q_2#>B*Nb9Bzp)d zCVd3D5t@UKMd()P>uTfD>b?f5^tAO4RSNG@FF^&1)0p?P`d+KWsE9L$3&d(eyZN9; zIF{bV%q5pUqV{ZHCa-?xvxr9fC1um@$LMaI)75c_2}hnzpP;T+3II=GC|nFRvy+Og z$&xcn4aX)zbl<=u53`o&Dlf)_59EBjxoh&k{b$v4LN5kF0^^@`&piQi7a+tQKbDiP zdm&`ttX>3yAAfoOpugY3SXYXEA1<8ma>-|6N?pSG;@%BFq*H-+YbiWjNiL;ML?l$V z_1U)iXdz(_F?%WUgjsK72{b?F)r7~?Y7&Zq0-k5{ zZGio=p@n)|q|c9%J$O5hI_jVUGf`Ar%uWMGs!BwyZD3_Aqt)ua7+_*<7r31(+ zTx++qfWSlS&h6x=atH82BgP`n0i3miHRXAHGTj`F;LHS-?6x$Lf~5oGUYxET`m3j* z)YXMToV*;N1O7q_56otW(I)XVx6j|{O2r8F=j@HbblhFhmR~wK|J}0xuIwj(GoeMZ z?s)KhQ8QeB8?+&Lc24{>sU9B`|Iu9|-+YWVZO!O&Q?2II+nz=6R|)o-bAWH6_whly z!MWhY0GHHONLk(4+SJ*)i}a@N?bo61HLq?E>3Ec)Htqv=D3BDmN`$y=I>dmL7y$nL z;KEzYBIV&-I`+Q7&648hj9OW3^r7sZC|ADS)RPd?A<(*g-r?vLj8L>aoyx1YXutC? z9X^t=GXR+sg#XP#;X*%?OBN}nP}F?E1gfE9x>gbqqN-J)?0iN_w>c5bCdaT)paWD9 z)@Ry1fIc2V+FL*;D-9LX6kx~4!UCVA0KJw<5l~XR2C)sH9J>OZGPfkS6Y%ORs$!^0 z-C9m3k8w2g`|xZLILZ`g%GkK!*zx^7NY_HQ2E1HWt`9eY{!~S)SW`R6*XawXwf~Vq z)0y`oo`}*0Y!dkB1@xe;v=&nM<@e&K=SA2izL+2->@95^d45UQz@n4v&8^!)7Uz_J8@pSj9t+M}Fl)UpY38F)n{8BL%V8z?8oKGK9Moc!< zVuuLwvWsu7sBj8WPdm?idBf4|E;o7Dn2HA}D<;5#n zZYWwX#8W^ciie?Z*swVe+-f11-aMDe zLMtP6f8ZaBPGFqmeZJx=UtOf4bMgm&^fZz{aeJJ`%Gc>oYK3X}SpM}h-0OTuFnhPu zatNe^!^;sfR2HsH%t$?t^@M)X&e66uR+d9AmGR%Jp9gaq6+i^vm>SKldqmmI%Hsk* z!IHDU_S8!=!qJaPHlO%>r}OvmAttH^OUpC;M?LBnPWhmp*hd9bCyNgBPr3(nVu3FB zj_z)CKE@Gd@n=M@utY!!_PJ^hi|q%Nm~WD{#TOroKlb*j-oRimulWl9yxfPso*vBi zc4BO~`oB6yL_{0Zfdfh5r0jp+x>*y+qmle;BF<;pG-T6VQf-680oA1*0#Su?cM>9_@u}aP+e~tLQj2)a+VG8Dw{FOx z=zgWrwc{Jp?ZmL$*i%MyQ50-Oqp@?O3>nf@HEF2)uo%F3z-#(7FXcZUh#nQtNv_1e z+JNcnlYm*cIGehtIsf6+t?#urxaXc!`iLk2Qa?90cRAuz*f9*BjO@i9@zZ5%LHIt4yCgpQ& z0JxOjjG8&DGN+qdR$3GBTmpt%Cke)XRs(C0d#6>-wkQCZ;*$D z0Us?R5QSI`9K@r;Pdic&E(*4K%z)k*M+tnNSR~bY-fMlN(HHU;VXB*WUt<7?hP4p^ zWMAQ(h&sH7(*0hH6IaMa*~l^&TizVmjZjjA+D}H#y^yBO*zFWpc_7Uj17n0H5>nGx zl)4x3?nCN=)uzz*w987^P2v)Tr7--_EMit4u4YNDYDR!Wqv+5F;|HTGzd)S&$562* z<#)xWmi@WH<9~bS^BNgYsUO;&CS3nVQqs-YxBe9wzi*@&pDTGWd9+W{0!gvR=H!$^ zI}D(m09f^Tc!BY0S}5f!MC`wHpE9-pO-j-iN8Pu9R+%ZU1EyR8uD-eXxiifGFg;p7 z`HxA)oI(7?x9V<(_JTRspxYAMz`g0F*k5mQ84#Q<(Gg&^c;vC4Gj}8gMCgDaxm$G? zCqQOv>cZ=A)9AMb5i6DV#rYYK@+vatKOrd;3FiIxVgGqhQ}4d09=cdaxD-9FoDdA>zbAWOWO_b&7;30F+$jfxen-B)}-5PSi|04 zgNNr--+u-Ql?+P@zX;>akiGy$0U!UBm;UnK`{Z_J6C~YxMQ7?CzVM4(m5bdDGpQ(I zq5*R2S(?(| z4;q70Onb-={oDEE`Np%R?E>;^;HZNapR#*{2POxsl0b5tf*d7I(9bd7?|+X8+DW!O z8_Y@mvXU5O(%C)fLU&iIMa_eg4QYv&y3V7Or~=c6m7P_#uv3htxI7!1^~&rPMJoD1 z`1`ErvgpJ|3V%~mOkmOTj~iwMaRZg$Ta%x#FWQCRNksvO!|05e zU<<5B`bNAwP3CXU-fFXLtQjKIYn14)$Z4))L5ON>>L z(#I7ToPa$i*10va9v#BZ6D!_cNjTLiz>7GeN@pF}{<<5l36yc3OdtKdp>P z!VgTt<%9@LCe}^Z@kNMui(kMa&;2aF46x$MAO%nR*?0@1wkO>N7(|rE>xB zHr_rSzdY;C6dMNHYVP(BTnEya@5$Z0Qoy9pT`VYPNN+&>ziPtDrEUON4(h|b5#sqC zDzfy@F%g${7A(xB-AO(DY_o9*OFAHC>0#yJUk1*jCe-CCBYjWdx^18`akDHqG)?{l zT4~@%0n1f`(+`szA(UYDCh%-j#EX_fK)-%s)2%{=amFnWTROd|$nURU0O;TOPrl56sN6(T=*G*7J${H@Ho} zkrGcElYc$%H_+3|s0T>;4%Wt809(K$?R^S#wFA^AJ6;D9neAUQhTir9CkZVBL)wSx zc{x7!2=X51ucy11&j(92!#sVjR&0Gv#sJU z+Y$UZvNB6YJs(&79ekJW6D9;E9|Xq2ggU#pq@^Co%OZIB#GE5H;5xZOBe?lY$#=Hy z;ztqg=?8D;Ta95F%ZU)r5GAd4<^1_iJb4N*7bcy_gXWrCj*|DOcPQ1HcAmmJ2b8(6 z%_T52PiVXu&05&4j^%w2u2qZiQqPydrWm-!UyUeKg}TGUgNit$kJoYt?5WJ?o8Xos zg!6z0^#0I*8vMB*A_tZBr!f5VuwHjk(Ea_37b$Sl)dm3djgp%Pv2b=*~W9O}ujjBJGVi$}XDWdYr_Y^H)U7;1|S*l3eHb{9cT ze$7njRNBMkYXd8FpuNNgq8oqj%6`yiyTi`?&?Tp4jVP$T{zGd$SyyOY9z{FR$i+v- zlp9yxEQ*u;yM4TG--%$^U}cwIBoT%i>J7UkuZ@@5BrjGbzii@A{FK@w_RK^}BMB9CfmefODu1%!l{piPb*Wi$8@^cJBwge}CLK*F4?3ZJ;J9nO9j z^JY21bSRWRw>A*XNu_NTp!+7cC^(SvKnfe?Fa*@Dpvn<4F}_+k4b?c%RK@d9k2LL`Jd9j-4m?Suw%QwKz}&cDkw@u*HmTkzaDVR*RZAgnEx z7y)Io;<(Nha7Xrk-ol?o@N@$+RN)z*cbkx&-z8RDoSX}bi#o!GzsaWVOw(VLalShq z3&!16djLk~Z-pJM4O+C4vI+;8;-|;!`{z?CM z{r;XZxoqCA$DpNbA-C^Wfx9+7W43*MeTJDM;EuyRDYs3py7ha;f^<+UEi*I0EKd6I zlM-9`*mFCz{kT{&cO@z?YIH?1YRfKW;po?aM7bTF(sUkDHQa>Jn^U>n**>%lP+t=k{+M_y(celhw~r+ThC+-rVb*H0C9nu@frwQbqq zPtt>aROuKmDQe$kYyrWm%lApb&>5oO3~ua}qK%u;@@`-usZi0~oRIm=ws^1Kk-b<2 z9l?TfT)L^U4!bcW_BWz{G|VPKIv>IZ<^uDeer10)QP#Ot%b)QEWAohncto7tW0Vcgee zO`&0u;+Dg5KQA9BV`H$-sR1I0>cF)sfGGqQ2$9`xPAly9WZ+p8&>!$zQdCECp$as) zc{ZcwphyE+@Pk$}kn2HAqQPA)-0s0anvd&R6vXw{rPyTi&Wb`L<^EBbR*_xFoJF_K zK9H1(yNywhVCC7Cw_ted&93w0#KdNoSBFYOniT@dP(PB{7*;;EhsrRuBE&2(j`d9J zVqxlZqVB{+`T$_n1%RsBUb)>2aqV#o4d{RM@s2D%ULv9M*BOhq%kvC%C_e6j7Y&#oVm=$-+l>^ z;~ibGu&}lK62s8ika?Z%P*Ga}+yEl^eCv?KtIoQi+6N_olc@DE0mQeX2#xLa>zY6S zt9ci_anfEIw~S5&!SUO>NGQu;{Wa%}N!Wb-cUhpU++*7Jn%zaS5;Ei$)(@dHb>4Q^ zK=XYKVeAat2Dbo9y@S3b4;3WnQiLjnf91foBi+_%)Zqwb9dEq_Wj%VlA4Y@){r=rD zdnaP^Y8Ki`Yh58ZJFB)<-k)@>jU??_a!Po<>2R(N*9Ohg|JkSi?AXKQU(Yu8)PA$y zu>LM0Dk}Qq$*1h`5knNL*;7O3-gx%di5Fs zIc63tJ)d{;tNp{lO~jR=eFN9WIOSJqZ}+4H-ae;lcT+VVK8heduWokuhHQ9P3-qTT zLcR$XjKA-Hi8%K?`PSPgRwuUI2rr^4=uqH^H`NJx(OXgMhv=g0Org`RU*C(1f`Q*# zAsgnbm3v=6kwPf72mHN{{?aU*mmrbSNn&@Nhkxm%v$mDBP-ZYPu! ztWG12A_(3^erN-Jq2x2vMhiXsa~F-WxPw-wSu%LH06}qr89i-UKv%D%i{LOSfoN>{ zC>=w^n{xgyh_10*K?1>=A~fbT{TMRLxQtzc07YNTfbpfIw5TPrFe*>RJo@DUv^^n0 zW^@#E_iHwnJuQ_k6=pU|li}YTCGj%HVj;d$f@{xF)b|cAmes-Y@kpJI&+nfh@$qzt z4}C{35M=zt*O}j-r_WE{&Nqq>!byhS#Nk0aQWnAgXD03x0^K0M4Ayq$HJTQRxOy+6 z;;-0rYP^vEH#PgHtvBamwr{&>&!Xg2I$O=s8N}W-3zC`mYOMm}!9P%7aUq*+ETK2U zL;&7fz#c*nb~{Z?_b6T+IKf_{zDPmu$I3!Mw3dwM8)%$Oyk4-ktNAQ&o>E16?KgegpI;IMko`;5s8(DwRL`og&V3b z_3A&o&@v=G1N?@$J47~gI;D8y)eI%5^WJCdX;pz})Gekb0na$>E>?@WYiDlShL0W<<|wV-1nTLG9vmzflWReJ zsX%j(SkkS^gN2CQmi%ock^|dkeRFpeCmcdx(T1Ax>*Q`F{HP7VT}K<4e{Q0%dft+B zR;Sk~$rcdKbJphXvF9~4PBAjVEK~#(ZdROUam2U`Bwb4GoqqPJpZ%@5*I5=BlV5lKHzzVi$f#_nWQ2cYPa82 z$Hj&PvJ@D$-$O8u@!^Wi1ofM`&6J*CGrgk`#%#XLAS+8jG74Q}gRb)!^1$N$?Ew65 z3>yrDM$8cytzNf{TuH*g)_j@ZIZvsdX(tIVwF?y>aP_kUzX#Un=0Xpvk2WDWh+kzm zlOx4Z_SPd>0=p*kT>~;iEh}9Z!N-Q89CVSoiLIoK&8uw|)Cwi#VZVcB3S^~=TK;Gh zj0hJ9Hnc#{WS#eG5YlZ|&0O<{z+FE^Rye1fj;9Z*%(zP{JLvcITWB}+m7wV-Cxg>G2_?9N~XiJcCi zM+b&=3qU%Ag^5YhaRFobCB4u1DldK9dwN=}``+@%Hep=~lK#&12ztyTfMTybQ!=3=Kcm*uhzCtyD+b3ohVXP;0Rs@{1qYX^45X)!NARh=+sv1Ug+3PieT9j@@f5@n- zGXT!XhTigEd@1GbeC#hox-o+{6~*^Ru|fo0)f?KsFFWH994Oa9CWcxS4$;wl-su?;Z4Sx+1XNopn4$4M<98W&P1T%lQ9V2iZ-xhoW$`06W~( zqxlAAYg>=8v1IqT8=>Fb&sS1kEYy@_b`3C&Sv%^X4gl!$ltq^ z8IcKbDx;K&U3I|W+an0;>jU6j^HD{VwhbuMw{MBlqj^lzh%n}WLpu?6cz4Q7-UauVe_VsD0g)U3d|*3#M4tji zj%~?)>zSjub~^W2H}i1$ZGb%EB@aI^x3}Kx002ZyG_Hr=uS|L7^ya)HKDp}Fz0=dZ zVDKe@NmR@FeZA4pi1Mwer#Ut5l)Qd?0rclZ;vyn}84m%=3WRGkU8}opu>PMzk`7mY zK<&p`Agv$uaMgTWt4fs`;K4Ma7ykY}d*SauPCfh1xsO}B`6m-3l6Z=tEqZ-Hs5F4I zvqbsTD{h0n0$)Ok*X5Drn`VC}F%K-qmkjdkktf$%a>w!ugDE zHr>mWg7N^(Rv_~VT#g~e$XJwxVv?^Q=PPfgj)rI?`M-f>+jTTc->|>Jzw8A z&s$9?bhtj#1{%+Nx!!QRw}R_?O1`c0twLVk`)K|$7P5bErPFh4!1JP9#pCJ}DOjXD z;`7%$QsigtNPwZt=MTeFc+<+%UY?81MCH8$wTO%YD;NJ~<%7KcN+6yXu-_b^D3=zO zBG#EyGLPEne$kTF1*crsU!^x~YBOIY#;bp!F^G>j+b9~fzH{|a7;%0hL0~;Il+1nx za{vDQw6wGl5i&E1A9C+%v+kYQPJGCYMM%tRfgkY0PR1)7N3_Tc*3#GBK@PS-59$k% z0ikI%s^VRl{4T2yS}EvW-?h4lB^mMSF{#@a9Aqt;s~u zcQ0rLV6dE6rdUWy6(;xvvLHmKHKx?}gn|&p7?GS>#&dotsnAMRyXHvKkbWUkDDOhF zDdL5Qs{<3o&kgbWqgfQp_Cgv|?IRnwyc!FmR0=IO)8 z2|6!!buo!?sjiMkA_}!oGK@E{O$85(m5~-hey-WTvMD~No9Kb%wK6~2S7QRs9SmvF zh*87r$0}#1hDeHPCW4yYSrb?KF`g=OG5K_6#6fzC*L+=;AnIaF61b8o2Q!7SxqLJ_6bw zI|1y?iskKE-R@b!tZ7b}xYaV~Y7C|!5Ftvb0p&zNZbH{X*a7g-%pSIaXr3)AIV_i* zGwv9Wb1LN;ENfr0>Y%-YJ~clKDBVS1SfA6h^x}3C9=1VqIQKAx54t=%+m-&%g67U98`gypvY%As^8kJYzY&Bb9VA0*pikA{V?-ZRG}F;qzC%nabfS07dA^wbLEp zAF7)7rVh6FPv9+9R=p5TdrY4}-Y z60eHxYM%+LQ?8)S#6gBm@0E(i$nmG&V3QxG1UAphG@wA~q!TRe)#v;8Z0HI;wV7Qq zZ4@jH9`oB_#}>5yj%=tMPdOz*X4!6KJf=Ho^(SE|fVLuNgYqB{6hUoXn;i`O_>_Px zZMM%r3D9Lzeo!KuK5-Hlq$&7IT=|7>jGu|6e>{eB5czWhQAoGp4?OP%Np?aAsn3Vz z?M$hH$)B~sA8?3x-D1z(2H)GYxiSPoON*)(%B}k>o2nftEi!m8XRiwZXQA_I5u4Xg zn8A_}T=j`cj_BaQsl%i-{Oq7z=NA|wkh6~X?I*CGC&qd#g$v&lB!(WObRR{Zkunc(6W!<}=M3^cnge1hE-S z4(Qg6Oy%dQ93S6}UF;*{uP%tSukMSD51nn+oaMT)h;J=A>dRY&w{xDxFWe!C z*9w)g143ZQncu%Vrku@n0v6{q$;XA*aTd2u+&^@%I_mH7_$^UX7cT3xv60xj+R<$B zzO5gmfA}VPYA{)5F&E~|yZMcR*rzwOSgt|s6R3SxdC4(l+;g}qZ|c0PrB~?OTDdWZ z)INkXs!M=P2kNr1?EZJMwz-fyq5C+=CL|-bq?UC01@dltl6WK#9K$J0>b5s2LTj7* zdVi0AAUIcbA$+%&k9GmqtN9Z?|6@Y^Z!?c^{lXvkP0G3TijIc!`v` z_nHQ^pc&aBy@%;M->>r8F$gmkppr%Pv&b-Yic+61Y8cd6Q`A~ zt6*6Hs@9Dv=;Wwym?d+sM2?%n&aKX|sdHyWwXhBC*+fKBD1 z-{)AR4j>F_$e!E`5*v4!@^TR$cZ?68Ts^50cCp;o8nQQ1@r3tL|X2%x0{I zGv&$bG-(DP#}=j54qJ)EJ&#Hg)4Gk7b39uzb+g~%NqqXpx(ga^a7VkCPLtt&HG<#% zV$XvH1`2#1@otL|9YVTOeHTuG-Vm{fsGd2B6bONQVn?h30h@ijQiQgV41vFW{IeYN z^;J%A4~De6M}5q;u4HH9ydt-N6&2^_12}XU4XQ+ZHM?pa9v->)BG}i5KonoK_iu)@Oj>* zxZ}eZ#HP0xAoMT=AV5#wA0h+oo1;li5Ey311b226M`G_H z?ioC4C5CHJ|Cdvcz67EAbQx8vlSn3bH4nS;G?uj@4sTh2Px$WIDebjIahdQ58v%0{ zZc80b8yr&jTtV{`a9+8#Ui_rkybmBlZ`q-Dd%ixgSZtxK)~YkTBAhc`4wMaIAMp`0 zXn3un0NM`_5FG`=Xs`2`{}rQarQXYboLb~(FP4n2!f~+A6|3bH7Eb34V*4{sLu%hD zt}I`#6emuM>gfd=y0}@NhMjGXZPSgXEwyX~P$u_}C9SR8B0F)gI@w;irp@fF&cdmW zW=i_gadqn8TR4->(C)(I@$uyI-X!5_&$nhhlh`F|_;K?~hP;qQd8^^DX>!RVLZrc1 zia{A?*!}y~0C`f|tpjy+!ZvnzZx(Wv?QoX;3){6%q_YiA$$dTNg=*kDc80nh8QOX` z8Mdb#?4dNhQ2_1(AV{giX60mZ-d8b;EbLtEy(^q`O3DVP3cGU=w>AJN3ihwTX!pEbujpR1`4GR%CzGG zYes7s=p!Q{rt{5@(#`TcaS!-Deq!vUg*)j9{(TuHAgl^Ci2%|l&d{i+C{X(cfbrHH zGxJujl8UJvgsmSiaZ+)9d3!k()k_yu!m)BuY&w&KxS*X;MSr{^|3am4a7HZUFP zGG6rrb+GS)&`IY75)FOV;4H@*xroAf4CJmNwC@+z0bt{iI`h_w@>xvK^jWSEYx_wF zjfv=oBhjsX;!mjl*Q|vzkgGIN^yxPJuLWMR;H=f1kA}s z0dr{pUtN6<=-r|k(gdb@l9?gLy-(IACMLK^|MyzJ(e>^1Wm?A6_s@CqgdVQ1nVYxl zQRCbC&t81f72Buy;kM)6uxiw_zpc)F`5T5mg^yVn7@}0}AG})$H)}Efs$mTMB|OG1 zMkus`i?4sHpWEhc-@mnXC%X8@Z$FP=WD7Cr;a`9MDgdJx(f$S?2`gAU;CFd+Ip{eT zI0VuOiiO!5?zzr_sYi&Zl#-5`BcQ(vg&TG z4Saj{(JtNpNNBz8;vASpR`W=USo*k@Pg0mAX}Z>uG(TqJVvgIVPIpayz5LIuM0x>! z{>`IqAN^Y!qPu&0XA8FHrav>g%wcDrU-=GP{!a7Aj4(*Ns8aN$zPt1b$GXo2G zW!D?x$izlwyxWh5G`#GdOD(3&7wYq_T=S(duBQBwFX-(+70s~zHhgO)JJ025Eg?d zfLugG2^ASHJo!hUPVKfhfKgjDZ=`Su<@o zQaMoO1z+E4ap)l;Yo$= zqE8K9WlMP7VQg`T02h4rf=WA4Q6XzlX<<9 zL>zPgn(Dd^h^?IF;eU+E=81-PkTVH@Nv}67EgpI!U0o3tm!;=*0CjUz3}~1F0kt2q zDRXji%CdB*VDyIYK;At0Z}Z+^O2B~vWv?9MPmSqK)-X?l@T%!y$Z&=oR1VnoLu}`K zRi);itYo^qC$l~`)f(%zjgkknT`2rSgCTy+Aa-&Y5SoF?bj`- zbNN4UKeXY|@3FQPYx*VJ37vQiXzEdkiw2a2PamrDZYkg^!4J#;*R@jpWo2WtqCZGw zT*P@}=^H1izz|zuBU1$HvxIJc-L5Vzy@e12QUJm8RAFxhNx?u66l=C6QJ0n`guCjC zE5}XWnFiQC+i0t90}L-SFu2JZ3a+ zFPyg2>9K@nSi(7}a1}D}$Lgc6kNWmZzN|8aDmr+>OsI{dvU;zA!<-Qdp(jKN} zt~#Kt?CWQpmziHzR7BDAba_71I3xpEQ9@N`(C5eV+#yQh=0)}HZvOh;=Ra#42)loj z(C4f2qH#?SV?51&p#UJ?md!)5C44j4F>p&H+21DCR%UZ8THClO=;m$d(@kKoB(8%s zzv1&ZpA0YQk&Q+aJk#g`MqeeyR?uoJI6S~o& zRcoys*{$fgEbJf~{Ppjc!_gPDc!a5`X|$;%lDr!8IE+06A8=ozCGw_r*+lBTXZl*{ zm_tQQBGO1Oh!bZh@B)GrQH09;#6Q=Jm@llrPE-vhhm~xM$9IxB6T+nfcJjmy&~iwe zV9@sfdbIyX=={5?XKP31C;MwM;r1)rdD0QheoYX5y-8yzPm5LDayB(OlZcqG)jH~R zz={opB?y34E9dsI?v~I+RYs$>n%Te=F1{Hxxsr}2K(VvDIFM^Z34m|oTFLJrBQP1- zvt-z=&{r3wCp9%J?+mJj;IGX=XyY70-&9l}snZr7IVi{O(4da{`)tjv%4O_CTr*!( zUZ8dKekp|V87}8lnS$e%WPWCu=9+h=&xwb9vk)WhmNwME@_7jgU@a*#5P) z`u7(P;|+4-MjDeou38P0++<@+;~4#A1rVG$gz*(KyH5K8?KZVTU6hxJ`F|iE@HUlI zz5RPXg>zX#Nm-nr80gtIyNku^Na7t)8beiL8w z2uYkT2&RofOser=IpUr}x^2xH-a`25v`W@H=C!Tiermx$u)qWk^0wAV*MUVcG^_S? ztLwZOhRKBU$%)XZ7hsuV7{`Q|WG{~a$srqf`pWjY9GpC#8hsV1 zlX?uckQ1hc7$wk;%$?9lWDYsh-9twSxP8eAwu)eBVn3JV!;Ker6+yrAnsVfigS4W7P zb9o?39SFk2 z^l$!86hIe(1d3?pme(HMqgV=iu4)__Gr~Xev)gD>BBKZSviQ+at?BRgcVS9-fd#@2 z>(x)ru34^b*;#5QrwPvsQ4w!=xqtTMABo-BdbBR_wWHc>{BQjDL#(X*Zj8|K>V^7! zl}?rJ-{4U(=~mZ5!c*G6gJ8B!kYW*(0>2fNIdF857E~)PE^ZK=H8!M3-5SOi&9*u* z#CB$t?)a76B2+GKhhioJ#rKoqLOn^6U#yG>kib;w>f{Zy-}CUvSq1zc*vl5$JML+; zeAHz5w=PT5`$^sFaEv1K@6EP06EAU;M`;Nc_^UcM_D4WE>@HkbTugdrTt?({YA|b& z=7wAqFY&V99!LX-6Hd0mK*DM|at{y(m+IknzzT)quOXW9UgIeq z(e+N|W;z*CzLlHSvM_W0IFo;vzWE|>XUBbf3%4!w^r_I5zZQ+&n07NkCT?c8EyBr% z`OzsEgW-6kEZF98$w0=u(QyW>QcN5_+< zyFffebc8vrQ-E#Qfm&fVX~mdkToySyTXOxpY#)N-e`D%#bk(9tggva_l3o8zLC2k~ zoiA&7&t~8m$hAxbt7Oa+^gP(eeH6M9llop==Slp)(4HiDRDHB{L_!4)4h{k*`Rg6x zTYB_w+UDd&xBrdSOfIjEe}!QAqlk6gak=$xtzed8_sp7na@!e6VwIS z=^OVQ-E@j@0iCH?-xe5zSkVNTHAUN4Cz#I5teJ0TK6WX0F0_@#K_D$y6rWB(J*K-n zI{aK>ZVDA*O{Y8g8V=1lS#Xwt?`6**Apn17JgexwO!)PNtHPjzr$-Q_uV=y+>!>e} z6w%&5d_>Yv1o??N>xh$ri5tGx7bRG+enl_~L{ohp(yQh(0$+#HkS3{S6JCcBgH8IU z6e7!d@*9GU-FyhtNnV=mxdq1xN)F1BnD$YdBF5!3W2(37paQ zLd4jGBd?h#iahKl#N3o-x3$FRedM^8Cx3N%jPOAiV#$Vm0~L7Hx3Qx0O%<*=#w2(( zy_bkoR9W&KNi8KHp_q@_FY!@_Bt0ztM-|_qPBIB=aUM}XjS+PJ7HpLv@zBas6^Fw4itqJ_ zKq{WnhT;pNh>2bXk$fF(F(s*ITbQ;kqNw~$9r$h|GI7@7NS5mngo3ihbDXp(QbDXX zv>51II2k(do3GfzxIp|!P$(X09k@Yn9mA()s882`dTgd!&wbe{BalM%k&Ryy_WcIeNdRq3fh||<*-2-{fz0_odD0aowMf$^MT)XG4}lvaVjnre1|;L~r#RJ) zF6KGk7F0`8gV{O3RM3c3TyZ_VK3NrxZ&Z*Mz&5ra8F-8{Dw>_``U+Axmgbk*ddZb} zN1N}Csyf4zG^$O^2R5z<*%QzTh7ptXC|yM^yiQ!EHzzfKGf`q-&n>vo)cye@$e<#b z-2%NU8g?w$sHj0ijHVp{U221EY&KyTgy7)+wJM}MWegDIy(GvsRRgT?F~EfpfQ7WR ztBd;3q4LGBbY!7b@A7E5!#XgGX5d2+$ev*3SB_-I7IA+bxb{f!7{iIeu>RI=;7Q?- zMc8F?&VCdnR=9F|ut@glxm@Ol>q4i)-o0t~nbF0SFHJ?;O!(9SsC3fi*7dX)Vs@@Y zEp>n4tqYbUrieQj?#CxPE{Dj7C>GKx(&i2NsG73+7s34q1Ce`mGsp|ZU8&r>wHnpj z;YAZo&uuN-dZT2_n%*y@g9}}3c-ZW3J;9kv)^G~rV2)G;mDVQeLPGtJYTl(s&tMsZ zuM}Fh<9MPPV&3xwlCMTHnO-t@1~(2OdOv+47yfK2sw_$ori2W#1XxIPD-c&a7LbfD z6mfk@&s+AuLgDuZwM&WQl1J>X-&y~R*N~Er7yL8n+@}ezbfCaTx6}fLk(sV9*YN0l_0IdG!;N$v{j!bDFmKv)bC~rXbilvMCe>or1h=46acRaN zZim1hI9^diPkeyC<@C+;!nTW1I4cyPYoaZ68lgU}x{HSsTP!*6nRBL^!Md>ON~?}K z>erG#S#zf9K64R($RTuEBZ3Q%wFO8MTVG^cBa)dSjzF7<=G0AQgUz16s%GME9h76c z_!m?a2`mX(+SB0!WC3hcGT;7M#^BlXU^RuPlA0#!g|b>*YVE4D%=x9IkuSz|qGPL} z$FBGHQB3Fj-W-%~{n<17j`a&V|7?Z&LEFld6!eQ1I+nkWJeh*jyQWfKHhY>{KX!ij z=fJ zRO_cM!=f_DgLeEI#SW*q@=1=y&JP_;C0@Z{Iv3`#-|}9YQsnSHwl;YP3uP6=@)DrNPao!tlhLD^7+2J*PM{b zwVFJO@0j!~el}?f5p0~_H4Fq!g<-k#ME2T{Uxi`Uq8~d?2WUs>w+4L}DpRlILUXW4 zI_h^(2gw9+V0+3+n6+!|ZK#M-YnK&zmZSuQ7~9%$m#XgDj;$En%`jIoaj(F^bbHXIsIc%Zt_8k2bM~)2yMNCVR8tZAMNj3^ zlv+l%$YYzs*o64QMqbpHk!BD5apuYi32GR<3feMjMY;{LMHxf^e~Us3KYya#Lnrto zHMX(9utH4jDh2FGvkl@SX-X{botY&!K$JflPbD_f!(2(B@$ngqh!Pu&`;`u#$>_`l zM)AAfL;0F|g8-P~I_QFHALv40Nfr`lp0-4>?yr7yeOU-*gvud3v`K&`Azz?xK-FT1 zNk{}8vN$DeOg)8M$^r#%p1Zm@5=8XMx@Tp@bSYh0=t3ePu&c~v@xK~H?+`fdie%;dhgFK4k^uhI@3>c*if+b^V3fs_)*u*1?n#ZunU{KMlCMC?BqdD-23h z(-O_n-S>}n{3GIXe6tGNOCRUoeE42B;MacaPFJg*rKVxhecm)d-l-Q$J&FYSlxSso z-&=l`4y@pWvgppoHzeLDgv;TIXyfu)+tK5@^-Mt-v0dNy8Ww<2L#hJFrp2?HpvZoq z3Aypwnv-Z@2V3XF`m^!>-p+3$sv=*KPg-=^;CBc5WixpWg!1awjnx3GHy_keFbr}= z=9I#bof_x3AnZ)(yT9p&C9Pomo8vdo;K$s3RTC%^#$6E06lc;JD&xos5kB}x;vbJE zr}{V_jIZJ7YmaAA!k1d%g7f}$SgnD8opKj^BLH^?EEc`2WsTxK`>vBaz7T`d4*3 zxJVC)8cO|w{bFW=78eyw#h$&S)Xwt+c^Sc{!>QW!<^3KCQM8^^2ic^U30ZJRsB_^i zO^TD@3SGQ0F2`P*D{(g)^v*`d$HO=$N{)6g-7%{$CD%AyJ}lVO+dvn>K=FIKUkQee zoZL3aoSC4w2y+_ZpF^72wkTTKFh%_?H0O?+Vg14)$0`p~AfXEGAUN&%B5ooK4Gjm^ zYMpBWLG=u034IUq-kdk4X<6va0yS}zItR(Z1-4#@6(+!Xbe_Jj*$E5w^5R2-TyLC! zmIJRxEqXNAz}T*7XNQqMnS}@}fkP@EuJh7^Fd;{1)za|sYzoGQ@-^^V>&|jvo9b1g zXsFrJf_%0Us6??g_qZTlPi0@H*)M3%F6vC*krNLfC%k?es{EeM4D?B{>#SXHu)d$h z1Yd37)_?_&GefbD^)Fat5I%gH+42ylplzh5RgIhT=CciresJH?eEwX}6{*Io#;&8^ z)KX%jf6htw=p8PfncN8g90#q*Ut+nj%$%TF+7hLgi(&ouDE+f)-)UrN#@4ZVJDTvD z+P;sFq0Q^|alAWsBIb=;w$k`&0j|C6dtnUwD1c>%FSV(hf2*vRuA5q1^7NB=_}P!| z%(QuZDoKt%wj&_tQ$Mo83`5B0{m8Y1uvc{zVaK#N8VWWa3|PX*%Q`NBReRknM%q^p zw|kigx3u01*&6`SI8c7Qt^>i^ha%1&THZofZ#PRFxmU)se!J99;1gVZLY1gbzKn8_?E_hx7Cl8 zr~*SGB@S1^JQC^1UNXJLur`JiXvx`p%yIWr8XD*6Y^r2<@OQRBScQ3>?O+N;i}|&! z>FVf25UJ(T&CC!M>l9QvAKwWM_Euey6>w_G{etky!+1I}4>!@Vn?I%j)TgrhX<>5o z*YxRc!o`lJdged64}PrzftOp64+r15oD@TaVW{>k?X)mk@pNMGvyF}Ce4>bpP@`bO zJPp>nz!MDlcB$$q!Kl3;`{3&u<*?tS&RGhDeE7LkZ&-KJ;5ihu3!8L=+6^u;aukNi zUvoBXX@XWTv=ucvk~blf-yy%5r3zySwO3#~PdGzNY_tif$RO0qsj25EXdhGn5=c%n z$OTDoFXwL44r0Sj5>5?)sQoPJH3Qen&gdo+yQ&?t9}EaJD2+dWkA)NL4~*1LS_hYc z9;*Yqot~?i9+7{G45_*R06txM6to;|G<#XF=US*(;3$^&^}(T3lSZ6rW*<`nkNhTI zFx?y33wdP^VB0#hgb%x@8hKfE3u;6+WHfEMk_W2$+|%bXIrJ3(vqFR=Q=e?QSn}q? z2VZRim~=YX3x;01$;fAp{xHK;L1>75&H7&}xY7D;!R4Ci^)lcmG78v9VG_F*3=M4+ z@7PNs7QO#pY(}y9yt4N+|A)5Lv_I>w+GUbgZs&xNY;R}pPxlc!lpAM^&Q&$ZsmK=O zE!Pk)@+sg%)D-;)TzSqyVA<-}f3C=uHw)0GM!i}U#~32Hh2a!C0%o7%Ir`

0A>u@3Cu;DCgZT`NvJz{5Xz zryy?{YQuDy@87=^~YXDoG+ z>wjRF!#c-aX$qrAyu87BPHbbPW~zp|?yVF1uh)zW@%LY3qQXGU(I@qu)jPdt1ZEIeU074IoBwg^?Ke&T9a}pYyDgqIfc9TWz?7VKG zpT!MhT^9R3a^Sf2Baq7jouz3){n%oDh!zX=(_1d9a8NP@DHaK3uDH;32cmy4@VUyQ zHTN?n(A3!Yqxv0?Q8n&-eRyRA9Qot>vqBDrIW3<#0p*b0C8KRX5T>#Zg8`s}cK#Vq z$GL|de~YKatn`r6_4|QV3}&0lNZ3rfl|J(PE@-<6VnweY>~rpBGa@Qt2#O&x4Qr=u z!<~Ma2FGq?*zVM=;HwNr$^uw}(CYSP5_tk(@vBQqN;3D-wJ^@}u@SN-4w%r2F#d?2 zzzXD;j?w1{5TOT{`l115_bOkJhCLsN)%{gVv6FL?A9Q!jv`|zyuNfhVWAbi^!%;8m zzj?`_+sI~~gF?0f6O)+sUuQZv-D_HB0q6-m>u`mv4ox0E@C@7);0m-EU+8&Wuf~t9 z_?U4It{%L7+w3&McijW@%YdfAXW`mo_pq1;VU}$vIH@JRu-I-Zg~upP>AXTQSjo=h zWK&AIDqLJ#{A!EzcKu6&8JxOBstFki*LfFPQ&Urbtk0VQY?T=8P~rzepG4aO6dy>y6mfHW0V#*r#@J-02h409~({G!(Sj)=Fifo5nfr~oV|5YlE-?1a!EqdpQmJWG5 zY;wWZU;Fo7V(rKyF15W3QtiZ{J6awc+cx(wgRKv*#EZIJYB*(7S)T*{Szhcan6IKv zp#Q$R5!TSaCN<*h=7ydXHxnpNsx^-Ej&Jf^{PykX$ERQS?UCP1+;#*(Lzt7a32pH^ zKZpts=z_(>RysMM&Yx1go2;%nG0zxc{J2<=RSpIW4`&(PT%%aKCni>*hd^cr$-n}L zpXqjS$ojR^BGAM~ktfshNaq8|P?=+%%c-S>a)9nDXZM~^t;uOou2($+@o@8T2WKW1 z1QGQP6_UUgsFSE&y~~D<)F2EbU6)f~f!1BPkb$5_8B__76lond?}SBVBTa&;)yH$d zcp?*>v+Q9~FGwtqY(8FyhyVE}-n>}i7R5rB(QRO$HvZC-Upi^c+X3zh@G@)k!(E9k z3sY4^NJSIngL8lfR_`~BArY72zHON_r2l)TjC(fNQ05q@_jeNR=tV_#(oDd9tU}xDEu*mTtHCCaVWr@2 zSlp^63RJImn*jFR-T+XE;5NDG6i42jvC7c;3DQ#R)AiL6aJQ~Kfo}tRbek^kT?TebVJ#av_Hc^kQOb~C$gj@Rc?4$|*OwS%eU~Ea{^+T>%k-FOllkD=#fDuFn93Ev zYmMPU#$^NG?3U+FhH)%c^@vLZbqhZ%vW?_dCQn-8>+^(t5zLn8Lk|E!b4^tEYNTB_ zUlBm?n-R5=xXme7aAvSZ`gRrV**())jB*sZrk1(~AA5}P6tt|72aw2VhO>_w_h#;1 z{40iobqISnb-(I~veq-@$bjU=z{R!cx8;hUxB1VfE{B7GVoIuxe$2X*w&FhKPeJ$0 z$H8-L>iI+E>O_^evE}UasQ5CYSHd%+qqZRL>+c7-(gxdh)k^%6E9kQ?#B4kHT^z)+ z2@@ik9e!g*HPiMLdM}*#T+ubmIrz)iC?ue~A-kSTU!lku$Y)fp^WF)-yHl8jbhNkE zc8!noK=YOR3b~GXB@J@iN+Eg?mp%s*t!(l_$s5Qgton)dC@pErr(UfVl0JuGHvyjc zcs~R1SUU@!|8KGu6pBjJto4!GY%A0xI~GJqqnrv8Mf@#p>7WJXW5A%GFli*Xls)Ji z8vt=}6-~S&E8ks~#|8j5J{F<%9A~tHTwYT&Q03qgli-)Q+chFj%AkFIKIap~*!^XC zntJkI4KaM0TL;w4XiiA>Z0#C#24bN}SnD$A4i|Sh{wJt9+O|Oqye~W2=fvA0?Ba>k zf3H8ObFQ{Yv9UEh)3?s?a*iB^)+f}%A}dljYNg$mxT@=6u5L=T8yg!$3|(#kIiaU8 zI1TxW0fq*|={DVWgc%(+cJ?~n5g_92h=xL;mVhEHmyhIqc;NPk*?=Z*;_0v5;EgsP!Fr-!>s!dllv8fVY|zRmyL=8mh} zdW^G{Ipd>ptv9vWDl{!5uH!66umAZFxWIwWmbNPt<@8fhQXcoSt-{+Db;Okc;B?kw zp*~g^@4gzX?XK`a*ln5Nx0k)Wy--qnll|!E`04~8{mkON@1!dy<>YY`+M?g5!wtkK zey28!vq9WPO6vWx0!^KrdysL#^>?vZMQw6r*BgO@I>W@Vx=BXN#$_;*?8qF1eeAV>T23y?tkAZRET&Gab+nl_l}$%H$HTEAO;AdJ;UMwH24 z{$eC|gomebe>xm3FH1d|jtl4bR@~*HQX=|-A5;U4w3qv}zTL)_JCjbaqs@YENT}qr z1lChCpQlC$^fpxZ)cc7f?*=dtegyah^IQ!Ns7T$-r*1*-$+5GcDj+ToH{S!GAQNE# z8|+sbJk6XQv7p?Bz3FogXtE&DUz|5raq{~0j&zy!+IbI6Sx%EVOZS_;DB7++-WDYoBm*{XrP=@AO(VrA%Xa1yWdkMc2Q9dgGO>e=?(IYyz#-ng zndOl4zl5dQS62*s)egb5m+VaqYjv!fZ0*j^&jam9qnr7jvRi?2ePekUwi@Q|E>`^R zQ@r=fwDNWAw_bswzj}(d9VEfJJvdQYGA=&7T5Bf z(Zk{jHZdm~dCYg>SUTTLQ2jz%OYdAnZs=|G+{)?#O+yHAG|=$U*-yxuH!Dn2>Zf>g zu3%y<66^E4Kah)Gm8wq_8Rj>9p$a>1W>$0qW8)GQJ04@m?Fyh@CfUKG1#HLUDSko; zWWKE(8HfLjr>1DMqT?^}zLkp(eAz>Omi(4}49>n^W*5hWdI%EN-s-EpE06j6`uw_> zudu!Zho&lwq>^1G;>RN?oDCa60y=3+L6PJU*5id;Db$64a>xt|p6sPiAnle7g%en? z$!41iy|WCbi@85Z++T1yjbt5fxlSzdD0vXnDEYURsfXy5wT`$os$0i|?l$9&K(q8G53&0p;x+nfQb0 zL>|J1!mZ!O5&Wl9-sG|PyQ=f z+*a~+?*hQuuj;cLLA>jG9iA2k*v-#P^`_#{dO|ak25}>MC7d0J4FZz;p)a?pT`rcz zy?IHI*w)%Q9iSo!z`k2TAcF8Z709w>@9{MTOGNb4@mIx5Jrx}q2MwW8= z6cV>RcV=)z{%^Rw*1djPZFYziTZ(^VU8T^o16b;d0&FhfrE5M5uNI53i%b_fkkXSci3^W#GNhYP!O=Cz z6s^^{J82iYSNTj0EqO^}>t7dAcdM>q^u5MESDEv_A!mso@KP?CQTq6rEOiRyy7FUv zvyd!UK``Tm!C_&;ST}7*ZYc5ERagDEFGehNOfG=R)EHB=twBgNZ$0|)>NKcx##le> zpvGhyKY*=xt}nDbU%Bp|Bq$IO&LxU{pf!$s>Wl=)0if`YTrMeGul#iQrs%7Q;vxi| zC~aJAXtc9kXDzw$`y^q4k;^2_jOG8si>G%RmM)P;)zMY`@(=TzW?p&GUw+tdw9UA1 z=eW5J3U$4bb0Jrjg%r-+7L%*3!ev!bh<{8N5kJ^Xu@JwV~VPP@*%oL+7_61 zA(3AX^hHI9UHu9E_G@R^PKbKfFT^2v9YCHa}tF+?J^X{%%ZV;^DybCCKKM5 zH)-;Sj$1k047Bf%nx^Z6v>4%?8Z`{W-l}L@`^G<%o$zYUm9a`QcKEPke@@QZ8;Etn z#7t5*s3k#6vOnUp#0dpOplYYTJkq%%dbIqyha4MMW|Umf6qAFoZ(!=}IHT%?hl`*U z>X3d!1Zu}w7@dbaHK%SQcRd4fh3v}%xMUfG3tNwB@SA(2{upLuC$amp!-mvie7^4K z0=TS!bBCXFvrG$C>e*K}NLPA-a3504ogdA22Get_18t|@DsR_hu9@3Bo60>;_@F@= zP+Tom@oHgmA;{(Fn2lG&!oqV;p%)zgD%2(E8s5Bcs^Yu*&CvGH!A7o=t20 z+*YMWFG#buQhD6}lXNw@yi8Yl{mTRhZl$cV9*&Lgd1O-k=Rc2EhN37berZi?c2s|B zjPSVcGR$scIb-^$>uYYb-HYqn!L^C2K1Vz@!$lwAq2B?ni9z#&pfNqr=WC8%@)8v> ztSn}hM{R&F^8!~y=)fR9|;T1jvs)LUO z#KjM~5Iio<&I8yFeG$vr!FZA%lGkpLl(*8?-VexU?etGG=Rwgz#3Z;E`At$P3)*z@ zje~&8YBryl?!7*Odhblpa&SAng~h7XLIfXFR|KNwr4sWx^{pxo`uS6s<63?oc^C^} zX~`3<1bce7AjS>9V*Hs{y??!UqDD32H8b0nM(Ik~|GM-YgR-|6hz6!Uo4JR*Hur{y zhK9z+8D%>2evAI+xXyFj9ybK_k>Oj}ov~%u@9*~Z zZPWP@c8x%Q!;R`;pZq3(Q($(&4Uai10kI43LUIgV4a!RI`u%7R1EH%BmT#Z8+rK67B<_eLrg9R7*#8u#2l}5V3v@ zl0cBqKX}59K37v8(G*kB6zr+Ye};ztP1!B%>9dz?#wy$a2L(vB-Df#@edM)q2@0^d z&RN6RutQ*nNxVIo;O1)NJP3_+l%JD*UBM}eZlYi8INGofM$^#HeDc0R_HD5DEjd9j zFJ_?*zZ9$i%T)(z4FkQn@R8xGJvwX9jokNPLCmjjrNo2!4}Sy~w2uB2(Yv}rX(71* z>3Bg7;*wE#d>vi_+CLMONB#|OS$PwF+rguRaoj!s5q zuq3-!uXQjc9oicT)5%al=s*E)Lf}X<)1819O2_x!`UMTY=b%dh-o9I;HndM< z5ehoKCpQ)=E+xt*pDh?G~SYT@c_0$N~_BFIRj0Iz8mqOM$AX4a+kXg^|>%WHTVqs8yq#f4DbA z?~%2<_1GOOF;!6kQ*WBOR$?2N1$%m8*iU;F)E#~!v5iFogvQU-gvF_h%avY6a}WZ{ zSHCi874;m1jkYg3FzUQ?sv~(JRP9=J_((CZr-jssf*wjJu# zyQlx`V0U~~s(N~vYU|?ST(n4b4sG}2gr}K^jP8Y9bhK)i{^Zfrp*a2$$7ViP>D7s_ zs5=~YleyW)H1=0C!R$L+U{y+86}#+|#}^IlXfXS!+h1Hb8>zIYyJpekx>B0WNcOvi zBJXUqAY;Ex-bqi#jn`whC0_Nr7Mg!Cu8`pSihBj)-84*7`rh!eYJ^k>|1uH(8q}n_ zb@Iw0ZxNHPV##wiiCv>q1r`)celpUgEk+dH{)dss4GO21wyVK1I{Fmt&wf~3es+hL zAX--M=WMLy9ccQ6r#ORwf;Nyf3>)n&Ca9ods&)7Q)imcNW(aH4h#(ZTR>@G%1`thb zXiyo1X%+@92x9_(e#&3TK$u_GIniIGEBfsOH3*&WZtk=!JG9$w^)L0 zB%w7|LWBe10HjY$m+YLDM@sW#P@R)0y@ekJAv^G8D#UvYIz7qN#t-iS=PEq-*)J&* zn6<87YM_h|k{^`H0neexcNVVQk{m+vn=OnDA2Be^cv0O*Z(TE(bhvge)&Ah+T)ARndH^+?yk^a$Wb+X$A-$71{yu0Pj^2+s_XQr`0ImS6 zLs7elV=up#eb;^LrJ^<2yvi6QlG~%4`^((eP|a%kjd%J#+x<%7uN5W__Q8R-g)idL z4sq}~bs9hiod%%Zacyc(Wmncqrz27-d#x#sgToc6W%UKO-mAC!*xAK$)mMXVB>LK2 zUidsBkyU-Va(P>$GGekpL`CbA^WkZ{_s1RyylhSks@fp9Ggtj#r5QMlsNYN;SJa3H z;^pOS4^NiVt1!sya-1pUlO$QKo_W55#V(IkVX>NcF%SFazrbZLh`hT>PF8lBB4*fr zp4LAogw@VS<-&p6*5=$g{PC_EEHC5$REfACPSU>1^@RGn5PU^ZpDWU_w8ECEEw>VQ z>Ja@j&N`IIyeNW~tXKU0-M)NS@3+*eb5kjd6>GL@*gWNKU~Wza8?eD z4Uqh?50ak=n2}TSXc1L|&x%3O;n(~9tncAgv;_t#GaHKJVXpdL zkhMkiR+bbwSDKX83OuU{&7awBWojhO;kc5Mc(9UN;TLD0ozF(8<{tL}gYRsHMehb2 z-kNV-t7{Mw$PrkbT`-Y&;~$z&ier|=fV zq}1s*{ZFa=9?9q=dwiGh@|$hF9J^ zq*qAix6ujRgsadN+KlYtY?4sA`pJ4dWiDJl zOH(#47OyFuAvD^Zpl(sFviA2(GJ!7+QkxLWX5bX|WYj~ZIJAH4LGSkaZZcNM4y z0ZM3QJfGbXlUZ{zKg?gsdqtwC;O8i=Wro8j0Mqihvao`tR&Hz=zcxQ>`6Nohlt37-q$6|0&<>%`EX!%iyd34C^{ zUg_NTAWw#Zu^&+LKYo1hvY$hW2-yZD^HK_5WjSyniRh%nEo^bOwTRE^UYT*Ll3;F&6WveElq~^)PCT4|{`y z9s!nxteu5F{8Etq*469vZ?C+pVw?{xX34tKtjK9nbg%1ZETTCG3V>WQqC=3qYJhcf__4Rdf(CMgle*LmWd~Qt9N%L55tbW(|J$QnZ@%s01ffg z7VmW-A7JlC^+#fQ;*Rixg7E@T3xjh3V~?FJB(4f~@8~R#2S6C?1sA`$TuDfGpVaKO zyImG(5i#put-Rq8y?U%3opZgQuVOPxEUw&A87CkyCMc7Uy=EY>&>Y5z&$!1PElZ5C zIN!OfCuhE+pHbm2_-LckE&J9h&&@m!r?ZSdGmkihx<5zEYEQ?o1hEa~MOkR&e0~(` z7AP~T6=OUYYKpO*ym<#g6&opwW$JWH{^{R$kM+VjByi@pTdp(QBiP@}GO)V``GTX^ zzkfEjD9U3u2HMz8pN@>TWld!e83r~)Yy(}08`qsmPgScfp!yGweu?T~di)(=aSWIZ zz3T{01xr+f1vy-wQP!QX4UN=>x}f1g7!AOGB9FUX3ZR`oqUJm3nk`O*{k#tEUf2$OxfA83Dd6oIL|fo zhre_~9hd7tEGe<0XDP#3uy%UK0S{mAxF1>TJ0BKkq(>S2EGd9=%2|b$fH4_Ce*2DE z3B>~YF|)@3Qi=ZJ@=@QW&i*sUM!0#8<$ z7N(syl#-tx$$y?bksw8-MAG`_48a9dD=e=cD7JNhR z$=%a&G8XI(czb(=f_*W zeKJ>Q!B(lI&*RH~j2zIUpx3Su$Yyif=KPX8acJ$txy2}3l`aMZ=e(pt#FK+d2|I_| z+tR4RGf<+P+li8c(QfR4sEC4KoAxvkM$$_334d|~N$`AbZ?~#80 zb@RIo!Qo^!HpC;jM7+RJWT+&cHmqs-?0bUmCsxK^Y-d98%(NjppEpPlZ}b~e&x-qN ztq(=^Bn7Z*P|pmgbQ3RN9!h8vc6{e7oCWE!epvI5t9%HJ$sV;epq% zNZo@71xmLTTiKRhjRV`?CGY4O+}DZAdw2U&59{>89z<4IyNi-y+$`|swVSb?Q)iuj zyY;R{^06ys+Dr1N*up%DV}m=RWJKa?l5_N+cO-UBB$RRqd)<3N>#>uZz+Tt$86*Ap zq=J?PWJVA@X~(m5v0nM;V#1->>I_BvgVJR)7+o)kdd-C$T}Y6p&0&4QqgN5nu z@?`(8$849MA)IL!IA+j04ZNwm-yX_8%zWh=#y^|L8P-z$e9gJBy6?{2YK;swi6;~_ zJjtz?+pxyi9Y{}A^cd)xDiWjY)nsd%_M=q=Sr437@_a=uq7co4Q5&7 zudsLa49G(R1cg|ET6t!;3~e8(z3!_{ttC*|-rT%6{q{|;3@5R=>n`DwEHv`)eI5&r zXKU{4S%v%u9xjt;S$+9kH#ny*h#%4LxS&-c0=Itpv<_FO6e^=Bh7mLRI9Z_ubjWM{ zF*{WfOsxGopA^zIzNo`w(X)sv$HN<_F}r;`&h4?Zzq<#ds1Fw0S#=`GKZJ^?>hJ#D zuzg*v_PXL9Ysd+ak54%mgdG7U<5)%R7&rwC2W?NC5JmVd8ehC@`@x+pC^=p(a!<dr=GhBmc-B%dW#_5X~?sDk6Tf? zQw(hi&2s6nj2Z-bWyp6Hg_$63QTb36q%B|FPN{}wsN2=Rp8~_l(?NsWzSnn{^JJQo z477z_tLqf9LJ*v03Dydw_z~L>|N4kB$Pv$0Efs-|Nyze5qd@Sq^afe%#gh2NnV#UcaxfuKNG!w(G32QZZ^II`T6Y! z@Z|I*N6)sac0Ou z=HWAG)Acuh=GxF?*vAI>dj^KEKDmMDiZcBTjb!Q3iHL=Dm9`-xV)^Xuq1S$A=CI^w zS%g24o<>e(75*S$S%xD@Aj8?U48&w-CrJ7ayLGr0Bc|VHffYWS%(1R!DXP*7@sWMU zXe0m`u0|^?>O}EGW9&kZg2(oh|9ScL_4Vo6S8kpL;_`8Kt#fcq)F53yF&jkw##$2l z^~`?sb!uA~?W@lQ9`Yd-84Fo7`Ru65cBbogo+xVg(ztRPR~GIkE`gFEM3Vpg z_`pDITYeNuBPan!z{%V}FTdq)+n7L3-N97;Xh=>&adv-Yvaf!D5fwD-l`ojpMDxwv z+lRuIgQ=(p#LF`3Pi_xzh$Aua=DIdFt>8KygvOB=;lh#_O2ZJD7u>O;4VAHr5rW2n z?}J$Po)ke$Jw6rG6I!c4A5Ar)zrS#RcQk|TFkO`&YZ|U642Ftnt~sH-Mv2L^@u4W$ zn|>?eeehH-Pr9F&7}`k!E{Dgj*T#)%Y`-euUjx8K{p;1wLm1U#imsXZt(U{K=U2~= zd@N~kG=K|E-q+KKx~&o-YgiuaDAgEl=oc8z!0q>B7hy#-4Ax?hGNy-&&Li< znFqgDE&E7>HcH^t9QB=*kUg!Cly`RKUk3VH`yyUIhWX*t9+6N?KD-DoKw{b&@YFHO zsZz+eUNvlnR+y`=ZR63@PF)&~X8P+-18*Z)bF2&MrnXy7pYFTw@E=>9Y!Pq|y7lYa z#g}iZ@xC7dqaqwSnnQJdlT5hm3g_BYT+tIGNdW4QxgOP*k=ZJ1A+|ky$CE+`y50tv zN|A>R3G!(c8J1kbM0~!PhUzqconfki5%dyd_|5Xe%OD<1ka^yO1lB^RJS$`hopQkC z%nC6@J1EB$aLA-t>VsPbHsgTItRP0|=8{Sr=f$&3B0`rMlI7p@I9YFRd8iiAqV59@psM@YdZf97BFAO8q zSs^pma++1=w91gGku#bS#)t@m?sD6Iq9!chXy@NsWTF)GOAFao6EG5gy+Ercsv;ug z#=D;fpSF?wa-vufJ|#;l>9_@CoRIrh*F{}a0}3~7&JSyX!J&j!JZnZC%RR{5N3bp@ zehN%tQL2Eh^zEO~+Gg#@u3He{;x?VBA01!yXIpH9`+pN?~(MZENf@yD9SJf2Gz$- zkr&UzH2*LWFd3vI-fM`_ovFWZTR-UM(2-|O5UUd_H)B}h&2-L7jMobfDAc}xEVQP| zu%1jQj1fM6=N^+N+5W)%`M4=59~D>}A3s3gPAgAEQeqe}dUKH}>1k-;aV_<@C^Vn` zAm4Z*>ne<3&iC^NR0wN@xKgi%Rb7W zOQV5W7wEHa#wC!&2gjoIs-Cxo;7QbEYgjh8V^*U$8#v$zJ(`ks7J&lrNLCG4W?*t0 zER7~|o*iKPj}uRLCoL&Ic^hnCLWpf;T-Tb{o9HPuSwqMFw;=UK@*sRz*dZ_b6Tu6 zw4>rallXd1E`SgJdy)O;3BP^^V$48y_?W7|bI`>z>e8=YS63Hv>g4eE5IWX{Rh?)U2#cpzU0K{xcHER=)xW zAx-xpsRM~-*-tr2js;=$P55VZ_ftwGXBzTMotaFT?TNo8&{`wNM4U%!2hs_$)4Od_ zYEDo`S-#^7#1mvZxOvbtj$sans`Y^fpsTE3kk*wAr$+GG+4=6>oVTBS;tG#Ul!>FG z&~1MC?7ji4H_3}=dk2g9Ow=f$a!^6C%wJ;&JS!JrKk5@s$)%M8`Vo}yi@$NVz%V~w zAU~1#;-7)@m8r>=C9Rp9A2ZzrWm;)an7ciOlH!y(zFz(_BmaK!B`UeO30>xAt4n$N zrtuMt#yt}bg>HPa<_R^fsuq{MQ*PN#*-s2(q6lj+rn(wBxkmF)7y=8sT_+F%D~f!6 z4;%9yf&i}~P&xms-l5tWKqNdP@x!tw={k%8^9AlvATkJe^@ik8B$8lU_a+UHYrmC@YBiWAamznE;ID_=w)l)8 zGIfNP>@Am%V#rRgA$v(=h)a2>9CtO zix#)E`h2xmY?D8w>A0Kj1}fY&Q2!n|qAJ|Hu+98^B!a7sulVKUv~smaAf;Hj5i#hh z7+HM4rJFZGXf!SCmL*O*p#V5318KkzeX?()HFGD?G_T4O)yywOf;+zl!$VZq2 zr#A=qqY3D5_}wY$mgne}Z6MmS`xd23m&i%5?&mhx949gLZlNc~^58|>d0Ah-KGV=I z*}aFx2M4=j1Iq}(cs6W(h)kwr0wMW2#$F){&ROjEbaSCrWXz+cGID*VqB0U+3c+uf zM9bVoPrl#zMo{60>6fW5^L0c}VXk%LJ=-iLK1ykFVkg-EZ;~J&Q+ts59IMd5lyu;r zcA#RnmI3qmee^>#y6o94F;-^Y*Ovy5sHwp?FWo@)W(tP;O_x$-{Qio1+-xq==K6i~- z_;^>N@4K6(PqEh0wf#JS(?YS%4r_X*b!RnyJvEbvnEXZPWP{@ekwAWd#GF4jqPhWN zptx*qU(0l3K{aC#dDtKMDu+mNoPM4rbINjP?bXhg`a&$DghtV`Bi&*VcrFya27^@Pe@5I=o>o%Q*Jsous&t_w&qSO4o6tRY8p;w$sHQ`rPi zXUdf@K7Hy{UtCxPw+FzdQ;DyR1Z2}lYQu_E6&x@$mM=V2LzJE&oQRh7oKrTF#)Emm2jSn*DKwly+HO8p@0{_`N4}07 z=iMZjAQDi7EGZL4w~L_LLnv4C+D;M)1GTU6Kg*ydCEveCjvyH*ws_#s#JpeLr(mcS z|HCN(p3uZnr0L|t^*p4+Wj-8oL3hcFd?~K^y?uDF`1;g2=>Kr_-tkob{r|XkyC{W@ zM3ijjkdZwaWE>--9FCE5%xtnUON3)&9WzQO+p!Nq#yR#evR7p9y~ppV-q-cLKELya zr;8-;B|=QLNy8lH=7?SSE6YY@6d$><$@j{_aJ>Am)$cv!nYksd~LfKi+RPf^ZY|kj) z(_<-;EAml5K1&$lx~!Q~Xzo6)ouZ(}l0fKoMw?gictWRCxR=*{B*S$Nxp8&OK=5%8 zgy`3c`yVtpuYEey#2y{EMK@N9Yc;$}x))LXp!e?#82DprO-80)#A~#>IvXrJQffUc zCbc`KRV5}QG{q~WF2JlM-hTfq8CVn5u>z)v9$Wn$`&%A6wMvSh`Cr80liq6x zv#mmhChBx{4&0;}OSk2UAdFvZU=l6g708p6B6sR=H1*-0#{t|!p-kkaS+3;5Umbdr zEeT6@{1Cs-h%~f0586EvF(F4p0fO@NME!6>*B5LUWi4gGgc*8lmR07}{$j~;e}SBs zL4ir@*5V)#lIHGC0&^tRmVZkU`0}_&`PGg0rkZ2oiX$yIuWKd2JPCFDgF*ds7~jw+ zw*{gAP)r(8e`Qnrlfi29{K1@o2O+Rh*7#@YE~%0lV>KJedMh3pJ@rFwpGi`Jg_>oD zTOTL*pP20AR=0ctCUv!-EuL2LebH*!g($wG27^HU!NfECv%rgMH^J}9U93C4B=dY^ zyp{C|la%|f>VKrhj8p&G277D8-$oz$S&)6YP@#ARoTtBZJO;qkOFmI61Qa>|4%Dl3 z-*q=w1!ux;nxtN)+a;K*tMUU4j_H5UG-uUroS8bSID4CdK%h>Y9rJlisuFx6Q&D?5 zv~kL=Q^#U;Ezd-M)X3KM11|-#@wb5* z2bKka+9HeIt?g|CyuB~Xs}-xKmx-kv(7B6_ZS&be8G^!?;R~pa^u|W}Iy*OnaksU3 zVqLZ|2KZp`;U?_wTUUBFX6!*Qf8JXo1UFwTkRWx741M5eq{ zp|Ss!*53vgTL99~>WbnaVqub>sp?<<;{W4=dxFLOy!42cXKx_sVP zig)8K&IQCPE}>y_B+mlK(hz}P4T@wG6|564yLxT;eeG})BimAy<<^i~&Yu*pqUpEb zN`+T-ZXAG3}0A`}!-tJQ) zqA<&d1nH3^Km;`2$~6}F5)XS3LN+5UwDBb=C{9rvO*5{6;T)(fHiL7`5=tpC;AKZB zOA!lsmacgPI2IX1V_Lhx%6tXWrL9#wExJPXdPMtC@e~KK275FG6GG1sN%ndKt4&c+ zNA$(o53q{R9}BP}$tlgz5())qLAs|xu<}iSEnV=hxwQw$sRRz$nSsXc>XJ?_GyT-c zIwl&2h=RAW>d}_uqktX|SKROsN=J=}dLzdOFk&O9WCV20J>WZ19Ds;K$; z@-6`3scSs;k^A68Wq@@48*V7C=x#K5e$pqMX6Jr>P29?b&953@KJ5J|E5)0Dn}Uu^PX;JLo1=NBWAzSrgV15W z?}L5x#aR!s>Vwe7fA9AVN+=PJp89IFmg0Qp_fpMCO6PsHCA(xqvEYAm4bT}iGTLh9 zt&-s9x1Xr%OXXh8NIZ3I)oya_lxqXmvSJwY1CyVjsw!nDuZ@L8bKZ*WOUBsN-&I5c zVJEmE+82RP>jj~i2l+C6qE*=HC}77P5GsF!ziK0D*VlX$w82Xtbc%HOd%~|{auCTJ zD01g;t1vuMIL-vM3j6;3dn=-JPfIWQ_JzWpf}7lcJC>d{{S`HaTa(aud;F6P?Yeb_ zNR_LbXj8ct&X;o(1W7;2nhVdEMdU9VIZuVs1AuIO{s994B^_09GwgeWX%y}{_j4mJ z{UL3o#MFNASUBn9N(hr6{6Dkx(W4r6qU4q};jbr3m;@@W1{d61=8E#J^&f1=Vl_x?G#y>n=Rd#{5inuCq23v7=Mco^9ib$05uNLmvdJiYe2 zO%0RWMcCT{5XJ_ckL1Dpgv{CXW|v4;Q7rdej}Te@wE6m))0My*x3A`+v%r*&B{Zl= zFwj@9QR+HR1y=e!iKh|q#j#+)nlgb8x8vCOO=_F89R8ixEU>+LH=3hv+$3B$?$;+5 zlPko|6klQ1UwnrNd;zjhYndMA^0%5=RX7Fd}9_TpQ|6X}c+Uy{B_#^t@Z>s_WKA_ijjPq)|(WAT>E@YP^xEr)I}> z9VENnlC1x^-79OX2YDMr=_9*z&9&pZDo$VY&bY~uRloar<3BI?^Zcp#DHP&>PY^$& z?dRdJUNZ7rakbsc#_1tMLe=}LWTYbNXwB(-{4ON>KGG=5eI1wgEiAPP=ZlV|hI{!S z{NBIc9ZVMuGJa87$r_j}8sv-ABM&W@zP2Jr@6s-@?ATrbw#??B)^y)qbi5Tb;f=QT zjbcGB_VuHCROCzsc-f^1%jWynF@NLrzhA8y(<`yj{`jEpc&U7u5VUP^%^MWUXI{U6 zMOgg%?N^cr54wuLlJc&8aHZ+N75gwP+bZ|nwTx$(;Vd{(PjQyTU~%Ol`$%W46_Ma% zz6HbU=459FJ74_uPrDioo@eong~sOgHYEkcirDIXZ1()1)XG%i;7DhI2YTO$)HyKF zG(W#?Un`}srISR9CS@Q^k0 zHV~cW)RX*C6L|sVBgBY}yXfqHCnr>7jW*R^thh?QN z%Xd!`YlO*E8^1;4pqQWa%cH2p0|;)#Iamw8+xVA^b~OW2cM+x23y2|xGTe$}*S9@T zbcfo9;+Z7y&|??aiG!pV^sT zE6E<;t`m~LVQOili{eBAYVP-lew0A5GtyKASRThWNTog|fV_ z#jO;+U;ApWA@1y1+mp}AB^(ZP!h@bPCnH-S+28O3CkRl@oE&S&AFiX7 zD)ie%B6^~JyPjRlHk2Y}^M`2rdB6Wh?WsPclnTvu?{L`um-D>AK|w4EHRb9JW+rz1 zUh7{tZZa`VhmA@w8$gqe1G+7>D_KY%OG=)&M~3weWyw-o>G$eDaj9Q3@9uRi>rY8X zY2~YS{nSYj1~|PQ<}DJ=7+v4l@w}L3?GASnkAMgg8sAeKqM9%3Tr_>OBhCi#p~q~1 zpajQPywYHUKiZ|l!kWu0U}~(8OFl1#Gayn}RH~q(?7lBK*Ce)$Ocpq4N zoqFR9VYP-0$|bL^xaXe2rY$A%(0*+9cVFi!Lwr16x)hO0tlOYGUlvFXXs|o4+TaCo87-l`|H`K&?w!n6P>9yOk&GD{i4hG>8@(*%odZeeO zq^u}w*2sk?Yz~!4 zDmOh?GD!HXnu>@?Ok|WsyNB9AL0|T$BsAL`_6}ZdNnpW>Z6i2)m|i1E%SV&D(yxC} zc||o}T8ga=OUx!8y;U)FG97MLr!nRJEkE6$Ojt#Z;C3~V_GqL(0vP*f?%_bLteU2? z16q{l?Xtt^)0Od+))&)n{%0QjdG?mO$0Y6)R0UO2ToswB+K;^qu+WpqO&=!jaWMIK zw}g@C_^UF4ET^>A-n~=(Zo_&_SxIRng*>t4DOXg(!=9}1%iJ#MZp8puGqk(vXc@qq zc~7qEB{b`5v#C_x9`$lM!o}e26Ub3iiy@+@VkK&@*IG~5_@V;z&1H5L5|!sx@v|iN zWeV(%9}fd$pGTK5Fmg?W=XI#kKxkdAXb+E&=e%6S#A_p z6Tq6+EgW2)jf{SlbdQd@l$+5@^~#XIsGdUjhtG+=bFvQ|VG?v{YJ?nJd=0K);Z(7E zpU$Jkitq20p9*M;py?pU=+N&DzS;1nA8|LyneKk&$zcuo9S687o@;vC#nxuR*xPyA zF&eZbdycRQl&)SgfQGW5a|io59UJ=*EsHO&Vi;~=j20vXkd}J-RhhuoROd%vKItZVe>-+g|hF?a#4mq{X?XOI5WJ%5RCn>n~n2zy5v1%H(dL ziiFo?_Lk7pv=x8*Ksl&W`-rDyx)pWMv2o=z|0iwER#PPNl&GIt*TN4@G&3hKq} zGl;!RXX~+&+q_WxVW*? z8Lx{($FOt}s^<4216?l#rk+XLbY4GG1ZnHb9mY>WG=MnGFql*b$y?2XO}Gu{7~<4O zRPu*{ZW2(=uql1BY=kp1ZXx8Ov@7p9hW2~NrZ6+3FxF2!Ec$`%B;ACHlQb`r5Y84z zmIX~-axKqocm+jWOqgr_XbBr)SH;*%0}96yA9{8oaOES^aaDl8!^J9gn;%k1EIZmh zb{Qh%o01qC5j3)>F#P2bTc}NRSxivlbZTm4edPULo(N$zC9lJ;#TA>I@S_fCx3Kc@ zbXow$+$tEI`CGvGJ2O5Izk;Q%+O;v!7~w9pE@HG@`rwB(RiF0%mWn`e$F38UTKP4` zFT0hGI=x5_T8OS6Zau!H_F(hk+w?CKR@47<862M%FSfDl)meW!1tbN-K#m0ZWdO8~nH#%D`ZCqPz+Bn`>w#l^^vtq5Q$;CU4Qazt|WN{~B%Pillx90OY zJ^sDd+IGqE3N%$c05pk>ITVQ=81(dyNqi}Y}s)`9U}fH~UErYDCFBkYU!D8hcGDqw~h#r5DO zdN=4Xvf}Jw1$(G5y0cpvv)~9fxoysfx+eDmrccO+nv|V=M)Na|hdJ+N`q8|T}bSn+7pC$h@BGt$If6}6cKIIxoeZH$51J_|C-&4PS+>S(q z+gNbshKz<&?xsAwuv=%zeQn~d_TI2{)PtzawbSFh8V_3LMzHKjOj1s-6ZWScc7i4q zC(Wg-U)R=U3hiCTzL)UWSio}iN%O0`vlEBhZ+jq4XS03Hp1`%-`fH?fko{{Lc?3C(06kN(nCU`ujc8nxtq0dxOZmce83np{;%*nL3>*v8WR zK5}dB4lNVAsk8G=Hm5$9+;jm)WE{*lZU#=fgM)*v+F-t@$Qf5O;OQ&qA%S-?*|%JnHuuL zCJ4+8CNu{76Jq=u^#8kE0r0L-fUN2ZM3$ZJIX50bynH~<&De^Zznj^gp98-VxgVqC zFU!<@Nj3h)XLBLX%7fmRTxr zhfrdxXNFyc%h8wUV1VVajs^6rLL7q2O==~yN4-Io3f`;@io&j4AH{W_{LUXHw^6vbtTmVhA?0%cgDI;g68=eUh8xw z@+9E$Tb>4WuX(v!(dVXw3cDzMBuQ`_LzG@``gn#4UgY}{ns#H=ZjX zWm5sg6lPbAD}Wpy*0<|J*v=b5>w5Io2qU8Ejao+ZE<;VWLls3ujHcH+nFIY{UfTup z0UROd#HD(<#ZMGRRc}s#2*u^upLpd=nqKqYalLwDWz?CR=ITky^#46x5aBa6mw)EF-3QzZ9c*#&<1n{YNr~f3zHgz$?n+^5Zf-8Bzn?WXOeKT**-U$X{9uc6}nyxFavlA zx&zdjD59ZyP1r}DWp__3wz0SLWP+h(1ZLXW+d9SWuKnRQxJzGoEE;WrQv7tHTaG4I zECNvc9IzZMu=&NwxoP{|AP{RzFh(2|Kr@=cF>B4wvy9+IFi!xUh$*A%x(?Ur2=KMv zt;v68v9nGkE6TbY#|If@{wSPp)q3S-Byemq)9cd$O08 zw6FPvoz(X5#EG*i(Bu`E4is>9;KG&*OS6~XK83D5!5s{ftZ$#@cIl-3-{_MJG~jTh z9e(vV)knV`T={HRd`*;>VEykHS861W_!gw;2uTthqc}6r54-$a;=8&1EBe5gs95*y?)SikDoi^9KQ(i zFHgvNKwiA^#w`~&qy>GIZ#=^2***ZErp443mrdB?YkI5-4{fendpcNH zSk#9{+!AO?4y`N*VT~5Ry(2uj4;iiVa*`@>6Sg`Y^o_S^qg~691qIT1B|?f|osxEB zkxSyE&sUd*iP)ar?>QfG^BV>Zm;|sa3Iqay3;WD6Oz+mW#Ci6Is**o3Q?7=$`{qI!4qKjMznFAp|aZ2InvTb`541-r2yR7Gma6*`5)Jn@LCb zyF5K&K#WKF^@p?T#5Wg}LI_1MNoFO81=IoCN-R_}koxA$J6umcS3G;9LytM?E6;$% zE9(`?e?xWT$nJOZMp4~lVt)C#E$U%pb6$%1oaSh-?@L%Znok%J25Y>n#toalSmU2- z3NlDNw3;@=I-)*iMzKHt6`dMlNut|Y?!Jx;`oGQFY zVvpsPlOwi+FNd;)uu|a9?&{9yY*{VSygxIVl8R8=Q%OicSHamU#l?hpApCi(mwX`o z`qf2|WAZnN$v|TkHFSKSCU%5;wecCZdJ)%97oP5ME(10w_Nc4s#p^Gz(3kf4uO|Da zXXsVZRTG zi9#@d8gqrc7HEF*9qdqVbRMVF%89s{D+;0C+Tf^^oia!i*su;lEhXis*JRkMVY zwVPjgE~74H09pfUhtK0L=+HxNl>-&`1J=sS??Gxm$|Gvm9DiSo%S*9T(>nK_z~uEI zWb~PYBb!PjV(8W*5lABMSY79xKtCME*VvKL!OBYR2-P7tv663f&6fq>jNG%bn==w2 z^yFV&QDYH$6+gAy*LY`VO4xby$J-}LjDD59GcgFsjoYOHncGyCeA9zofKK(cNie1S zcf7q{1h#*=yyT*Xf;6lP12~cWnd)Q{7nhv?_QXEC1N*X2+h8m8zb`&{`ostn7JxDX zsQSqiI>}<(RX?Ppv5H-CjKqc>pl_((n7N&DyZd3aocN5kGUPWf)bTZZpp%+$Feunv zCnsyN>g)&2SFh|eB0ACE!f*`o^J$ma?pa1a9$GAUIYAf?y~cjhjV5avTl<;v;f#={ z(4Wo8Nn!q~i9*sZao;$}w|h9SDT%C?IQg)7O*P8FAtAH|Vv{=R7UnlFMYh!Nr?_`w z@|jQyXHk9$F;PB4&!0^NdC6)}^C(#)+zgf`sHF7L%*DvveW*yDAi^`ufmVcC1JwVM z%U3Rk1_z(5lY|rAW|VQfY(tG_*r>?}+8Ub~8NKt*b%55%ZL63>+o)ZJy(xN^lPYs~ z+UFo)sEDICxv`hyqxr=&m?n-TdjH&-kIyDlN4OzoSn<&bn<4#%LFG_Vxjk!4S(_Y8 zBRkEh`e`!XI_r$s|F-tX$egfb19`U7^5*a3(k&A$#Z)T2u7Aft z^Lf1U1C)-XPKTgq^gQ?@o%Rku>m&Np%;61!&6i z>0}qZ&8?1ZTX!0!I%Iy3GR<$ePGr^#XN}SMmSli^4VjgQ>Pe6#G?n|yetTsNOKUab ztWQUGDB69=S6yLz^L+dFByrzrLE92K5b8U2S3zoWu`@LPvoW&sB^Nx<#YljNF)r0(=-hteN+G?TxWX^ z%q!;X&-LzHR)ih1GE3b-0NVASpusfH}k_iuQyut|F(&*4|ixs!wC@#Dv%M_VP7x5PH;c|BKKVg-Kw3lREq zGreV=z~SqJNn%@FKp8ccx^q?m7gH?2`UlXNEFOtO$kG%Pu@IQ=i0~;&=MJID)z^qf z__%gOEPe9r=PZhuk(z$8BYj!MTR4_y*t$hmAqaglKr6KxLkDYs%;>X{OhlZ&FW?m@ zz!#9=_#*khg${E^XgGH~AJXIH2y^S=y~M`wNZH8E^jFd``WJHQEiz2>gVq1NoRm*Jo3r^7FWs5~!1r!TH};8FTEI+MYQ5waFkf@+iBJ6$E=>Z2%qPDr^#l|5AH zsgRum%+8M$_y$P)4E5!Lm>!he+L8oPA+RV+V*S$b)pDPz`rAA>mI7P~0Ov;IyeSf8 zUw>oyEDHKoZB6ZQ4DJ|fGhjiN-mhu&1mo%v#p(pL^Q+ISG_qWR#U{~qS`)Hl@8<)# zkTx1xR&kS+4h(Cvx_M&@#5z@Gi9~Sh5d4@~hON^{>A$GCMfet%ZFv99X)q;9&s7e7 z)SA#HoJ|gM9o)UcCZ@0<(SZl#E`n9i47B5$Xp-tw<#BY2fz*Tb`frWW)TF_JJWq|$ zyD~m55R<=)?t!RoIceym|4as2m(eg}F#wrkvDmP%Ykw_*Tu#9v>c)FG%B>=T6;TjSt9nfP__2F$XxQt;gON)_C-OWW!IxQnF znvbI<$mqhJ@QPEIo}U%%UM#@&|%&KI(>ARV2|0~qD1Vd}5d@d#v{TW&Im}I`1zgaDx z((YzW_7VZ)-J^Dz?Q9v>0w+uwep;lXih1DCE833c|4wtDKTsn_f56>)G@3=Bd~_Hu zWTjK(d3eitsH3~PyT4xnL-%(a6iw3VO8hG=u*ri@HlzctkTy$dN%6d&a<2wcOFr7* zOTO#y-KqvYwri_%M2VZ`$NqS(i!Lk1@Rd`z5u4pTqCeBn+RNVn~|r zrm9lh$Zau-@>1T|C#+TAK^ydiA+@0Q+~>_#8vHr~S1{W|KB5WC-G(XPXMgE!W&Aa! zC^p)ouz1%Q_Ph0|yAW$f*p``08fU$S*iF6b(Fhc&rqyW@8HnSlN2%%1`Ie|x7Nutv zHFUJba1G8y`b{3hX@PD_P-^~46_TcvnI5y?@Hsfyn9ck4L7o7#q%Gj%%FH zECLEZs;3T}O&*%VB|@VfJHV*?5fimFt;_u-kr~T4DyE3FfEjgJNIg}TN#RQF0itfw zi>pYp<_7`L^1`2BOMBD>YCqGgtAlG5V)Ml$ZQuEO@y{N z3JA4KF&&Fl${Q)J34A3%)Q3g=qwDX}j*0%BjyXU)hY#b+AS}R_czX}v=%5S7clV?^ zru_?DAx_7-(&YQjCX%6E3WfCv(lQ$}Cw~Y{n^sE}wwFn}>N6$wXY|@*y?eQ|a%*n9 z7*sVYb=rrgAwP+<;PxY$zyHXKD#7^^s1k(4Bh0;X4z?CT70er`B_?;mbamfA=ZUiH-7zNxo zAmbrudLWm~t}HIH3C$vwD*n%6B8%~gd_$oV)9PNT%Toe)B*02qPEF=Ni%75|MtgtZ zgE?f^PDMUIQAX8m)Wx&5Q1njvlC&*NuT-e|t>-Znt=B`l%k2X>((rc#x$jBMwnmo{ zv+TbqBPqabyg>2!^l<~SAS5Itd@Ri8ag^RoK|Az#O1`aI3vo8AX=ozZi5MAelvUvx zt9{p?|3^PjMYWwqE`Nso@1|tg}OrHPx9T73>X%?C?*;wKy3|;JDpAoPtReE z?O^WynIp@&h*T`duLJlwqA$VfW02NUklM%G)xV>IuY%T<`-h^$fC&N>lE(^8c608}>)$YR6D`k1sY&MMo zxN8m_;Ov2OzdF?TIW*j|TtLaaw=I!s;NJA0qGcqJZ=@iv+}!%c-2sI{c;d5Gl9AuT zf_nDflGaGFK645lNf}D|@|otdif- zZ*);sGsXOr>H7J&uH75Oj~AcdKC!{ysa#;6nkFA-pi@$7Ya_K$2?gTj4NXrf$vX2u zgWvR^m}WjXsL<(L|9XHfuL67`&>_-fWCzfusCiYNvKh-ZhU7WJhFtw*71m+VxphT2 zK=Yhbbb_v1j{QENH;F{B?n#iFTfx*n0-WLjt1$LQ79y)=7S_ew3KTLWwmbWDk(xMj z%n$*^`5JIhSXEx({R3KHbkeTY_UGWUT+o;Lur0QhroI3%toms$0$Y9{^c!t@xYy3&S&%)b8>`0;wR zNQaI3^)UMSnmeB^#eGAMaPdU?UlJ6Su#RJ@zbg}M9`*;83V{BPJf}Z81K-}R%s3YZT@%>-EnHVb1zr)I`Q|HTgSIM7hH8kV+EDl*qba?zW$ETuzECnyy87f`TU%c)>iJ*I%Q}| zy4m>$ZXbmUX}V)f1Cqam$eLRdP-R>?VT1TDw$Q8_ALVaq8}a&cYT@lfq8LrkVXu^9 zqSltZQmS(5NiiGk6~3qG=v1E&yEM5UhyItm6v5>)>v^{RPEHSp zmDV3w&uJs%BfsL`xD}jfE65YJ-8?ik?49TNo41ykYo5+Gh&UYS*D)DA?%tmL!XKO2 zYgCmPtIP$|%~ca6T(^gvmq)9BLCAp#1Mx`f;?Fam-~0*n{#{V(sxpPx8ApwER+MQ` zk+_+)*a8^SGZ{(5sgABaaK;Oa)b`UJq2Ue;(6Gy6)AB88=xP zML?v%N1bSq*iS0*OT0GomuOMkYE$wK$IK?I9>D?N(6vD z7c$yMjvj%s+HP8bwK4rNRZ8Nc`~6@c{P?^<#U;!^Upup77$OcA$&Xrv3Y9rTV^Fhm zb4?kTA|UDI5NXg|GBd3j^4)#*C6r3j&zF?#zis#-sHnKu1Vj~x3Q+cH3zA(uLjigd z49(mnee+8Tx0hD>V(pmc78WKNsd{S{PS(k_j^MP5f%2ryf;>nvz5f-`bV1(p|QkjtXFP{$;c>j zo;ryXoFYmg;NX$FSI?mHZ&AvZD3v^2k!!L1fob}!_e`zKe8m+nw2H9Ojzov5YalQ5 z-Ld!KzKj>CxldW9d|LB|a%p#Af~a*|`Srb{&s|mR4>uxYGR>}m6Zy88cUHs5zl^oS zgqxnXzQ!Rl*e20`(L(v+9TjFoX{E)H@?ig;=H7TGVN z4RC?y{LtHszspWgOsfQ(l9DEoU%hzc$~mv~r&Ts%ZqO|NKJZUgBV^U%Bi=tjB@&*p zL(p~rlT?Z{M^Cm{z`jfgq0eGO(C za&}folB4VQGfKjD4icouE!g*Nbad9QK^K;(F2{YE`hd(NB{9Di4oiG*YKV2FI=rOD z{wMF(bv8SH9JnTbIoF-?oz}=>C+T!U>um>l`g?;%(=3^EgrMaMo>Qite*P|%b$*xW zjieFLW!q%m)5uOhqW?b10zBW$2qpJYFA6Wt%Q&~|=D(f!BJ)>nJey=X)TX~A+msnl6*ZtTcPA4=eROj3?t(+K4o7#GSQkl!Ft}!wIkPueq z09*7lWiMb^>tPc7>z&&4f3HC$mXgjZk!q-fZ90zU(;o^$$`@GW#@IF&LJbar1Cx7EnsO3UGZ7B;e`Rggz8M!GQ&^7b=_<2LLCctutA+LrKp_ zBTS0{W79$P>#+u1CXV5yZZv8gTMF87ERZ(jlTAtZ|#Up&VL!tgu8PYUlJJ`KEnZS~Za z;w;$YMI8*)vDoFAnGf1@S~I>X^w$i` z#byvjUKAFh_U;R5!^1+IJrMN8BHhM3GfAtlsGTCV5Z@cbn#V2uR75_ceia;b=ZQH^ zzAc@mfVsgxl?DzC=-eA&+AIgKY_K=5q11*PXwK^9Kf!GP$CR{vrX1i&b$|>p2E-{? zMZu3Zih2!*ZSH3*v$+#pfCe{RxTqT^+u}Flj0u5#W%9Do*0pjhw zb^;RT&-{f){m{+p=XCE$S4;(vj`z;N8JbUrUhd1j(N|M7S>|6q(x@J-c~&1xu7)4a z0j^?%<+G)0VFr)k4aLm}796%6<7H&?F848qA>6{^=if3Dz-)d~|0gCSCO)jKL(06_4SfQ_Yp<|=0&eBAjTacjLQ#;*| zxRSi5FU24uzCN;RrhPgxY7@s8(@-#)QDXjxOy`@{x)&v{ zMGcAZ{JC>d2V<1Sp~tJzkgk%Ffd^#J&X4~^=+pQYH~NvS<1Gz%JLIMe)81XZYIS?S zv@*RS7;?j+RqSXPud<)`TfHn|rwcH$Es?UWhI)6DUa99zR2{rNJiG zms^eS%VC*?4fXlP>K@C)(-OfCp%R&OB@!zQ)!Z0a<(MGJ%>)0UcZM$aakd56a9X&U z2OvA14-E?#mUL5RIf(q#k zu_MrI9<^KvKC{RIx9z_ka9*1)Qm3W$ugsW4JlJ@G%vPyc}b_Jq8%dV zblGhUnsqO@#v2WF<`)Z#LHH$lHDZA3@8UpF#ThM8>T=&=>mXo1sexsMR2U9=X z<1UjOdqs#0P+7vsr9ojZ0Ijy!spi3n0E@N5GJh7^IaCHOT}0W;`=r?721yfXG< z7`$7NrK@j73#a+nBkP7Uvw|I@zXA-)hH^l$H455}zPF7?a@QY7;Te%+(;RM$)2joN zr_bmwGIeUUfbO0b3hFYt8l&14wfEPcr$f;jr`#bB9wlGGT=B`&LEPREr{YM>CmlNP zY8|i(9NA18(TX1jdQ37bUFmSAarX$>&NcJ2wB5SyJ^k(m;ZLk{^2R@pm76Q#P7A-n zi1}m^%c-`Xt7Kw1WbKkMxCQiw5ar0;D6fT;4=s_u_(ti4t#u1bE{j5u#g<)Z$`amE zfytFWb}HZR^R^i&M1@d43o6PoC1F<^^JRg`qAzi;*D~@4t#NL^(dV5Xa_4!jwA{d` zP(9-hyjUD_e~n3+zome@F5j^B+z9<=LJh4b1Se6AokCs1&^H&TKr4NDpF@49;2My0 zI4idCXXxa06KJ-kfy3<_&|nfc5MH-+wg07Xv!dXgW$O>z$`n~aYhNjzSjX&!k|*3G z@QYx|Xy7V@K=Wd7P#E55ivk9>tFB`~dXth)DPV}8Lx#g3LsdV7pDysP2b91a(w6kT zWtfLRzBKQVBpbb5o-s;Y@^wQ?D*x<6sic<3j;a zkqaF4M{XqS709Ihn|(!xESudC>MjVQ+(>sftBu`gvs#`k%8)$t*qR1oamOK%1Dzh? z3$yNyd4gLQ1AydrlEYu+C$b-f_vpBMssPLr1?YWjMI%B;Vf?4;y}MI*RqZJQX#Us( z8d>wW@HcYDgJnjl&4wuS?mxZ8BG@0>ROED7@^dxYF?Gzqm++_5MHShK6ZLMwZdln) zc_)&bXa*}Ud6mb(B5#O6y4MFJj7QI6-L6Ody3TFe6v+>yc6Y#2HA@!2^L1GEE22< z{&{jZ&cFH_uaV^wP1o+C`Xz)y(EG?Aw`w`#qtAhU@;2QqgV^D|-ujlI@gfyWiUk+L&QUZ6meb1H3t3r@jQ)`%n zQIZW=Z#V$=_VlFg+C1>p?)G&i>;M+a%^N(#8ZY+g1axC1(If&$+X$i6``KUzv`4(e zaF5W#MrRhR2@JFf^baY>NyMvgH@9-FXcL%jG#$*H9S-eJqCIBZuRYJRs&uiDFx47A zS@55>KDg$ofD>I*-lK8eqq*FpIsICXE0i}F6W->okS|poA5|r?dKvG`i=M66=!BoC z-aHMO&;9F-E>ojkhq=f11CvSaQv&C&Fqm0b{Lbab>uenVw?y{mc4}W!mw8IYQ@SQP$JBU%5DCne!)?h|UwnwLX$PneYofKkI7-Q1m{znm>s&)vS>%%fZS zv^U>fK`JJ-p1`W+?<=Q?@%$}>aw z1;}{M+p&?Mvhu1)yWNDcXampwT=MRM6_I^F%w6vY^<73tLnT1K6gEQ)T5yoByEmV)o^fqJ)tIm3jRz_1)%gxR@?-n_9;x2q7r%7qG@7Q59OOkqf`VEy z9=qPV06F>|=1~`8mxC@X>v*K&3q{tvL`>OQT+GuAo|UFwrP93pz^TI z!-Iz{{P%P?pMlLr&(#yYjs>`RMqny%ZmO-*d}e;Wyaz?c$Qbf_hYLyt{>u^Q;evsX!afY`|qrY!xD-e-5 zNZ)`RI#`V%Opvr~h;>L}echXtK$TWxDbE2=%=z!vBfH165_s?Zm0QfG?-&0;?e_i?Z-c+tstPnU;S-n+*0 z4?zD}+emG}P}+F=RGZ!EcsI{+7;5bKD3#x5n-0I~+ZKb{^m97a0@y|RL40@7%8Mnl z!0JzzCvF4#slM=APN&CnY}N= z#sygkB!Qja#4mV8rFh%NeQVdx(rEXEiQa*@_Ep{^4Cu?OjP8)>?wkEZis*YB*o7Zm z_uR7Yc%X4cps@b*({saQ+xKsL{s)kJN}qs4Y24=O;r&j3e|Go**eJ$Tk2h48hwu>) zsZ@2&K<1E;|2LpyWCiZUPCq`dG|qN?wW<8<)|zkSJvgNv#5L(Oe@ zjYH5V=vdw8i(TFS|ET&3uqOBaZ3_j465?n!nkJ+cGU0=vM%2-aa$q9r`zN@eML;2h9atg{Dgd8=k1NO;j~8RM{m6&{uJ-6G7o_&LHx)pn zBhFMMLY!@(Z@IM%IKu)GH$a{DT*rM{8qt^f*wfH$Y)e_MRRckj9sEUFB=v6GdjIu8 z7shs5h^Y03&`5DFtyUV4c*)nk_XCv}!vY9x%nHze)Px518bYZg&*{?SbYGD>eSkm2 zWU_fmK&~yAj@f?oMYL$A11^n`sRM+FS_hv7`c0(9IM-NeuX~A|40INfErBPRw z@NAoGcI<`%!qJoW?}`SI+r}50tDo1KU8+W;o3RwTW&|nJyyUYs_pxAWkndQkQD*{N zo?2xjNSg2HEEpO}kc}__PUAe91uXx5L=XFaQ_Lt13k!40zJ#*L`#u-?*;CN5JAlVt zw<+$IUfA13k?1SgIi2u6FOCIhFo4H^E=`XZcPP!!o2jYU!{f!s{jCuY7lwt{GD7N4 z`pL0GLy~Q6NJCsgio%Jm?!Q0kQhMxO8r`U*89KupFg3hUyq|97aZV#u{igl%p~(#1 zi`U#P{21QxzGjW&5_O`et@Zf3#p=W5bpxDEgq6 zK>!zh&&boNBc&VengF>M(7?^2pXFPcbqp280AOydM-1Fuz8=0+g3)cn!qF1n0zFs5 zI6{EEm+mwIOIx7uW>L3uprT+4T6cQ0TO5V7_~Ym@(foW}BjS(nwB5xBK|Z$p;!mmI z+W=pZjPHJ}{f2Z~0J98Z$4stI0bHe_2SAi@On`{J9y@6s`WexE0IrB3xsJpFHwn`N zg5jQ@1BWvW@6;W^hY!_a_@yz7?~Rb!Ri#05zh*m;M#lg%d%5En1C(rTbEVc2W?@i# zdKt7GY+LXnGu&k60g4~M?2qwv!?;L=y*B3DS}e5~N*_W^!91D>=R}8AnIF$INX}&i zec{6he}np-qO5cftQW6JvkNPH+Qyro7G1obojslMb=`{0fk+zoL#JN=rjd8cFeWqB zBvZ*RvJK)jda%DQ`V5i@hvzgmZrl*3$fibTnTfK}5bXYZ?nQ{dF^o$r8*2`kW*x9# zDaG=4T$T@G39JKhea0ao8GIClXZxeSfPx$(B22B*54v^byh z*Mewnt)DPL$z-oI0@xiuaT^*LQ9z^Fo<{84r9X3l^vC|-)64xovX--lzkUv6N*d~L z<4~o9KC{vN9=~Kd59aHR#=%MAqBL?&RM)5X)OTv8G=0~-c|wAZELW9i&cXm5yt=UD z_XN>`A9z{;R)STUZk3B3f|{sOH1nafjyl|-x2w6K6q9yA-HwFJJB#@(lB!T6Lz?$0 zuL@&;6GDwTM3Pyqt&1>xe>6nFaY2WjlmW!Udb``q4spmpbgb6V0FGu{Njq z6o~~F{Qxwl>$hKmRmWxL}<(#Br<#Gw8IU}zKW#=!F--5_Qk#P*8IazFZ8RJBPP z6=0pHw;j}E+{vcL0_!LBaq7t)A`JdPKPmUrI2Ib#BY z4VMW4(zdUY-I&A5((Di9j%`RcAH&a(R*XT7Q}=T~b9ykxgz5%tK|FFrrO9LeayKDA zt;CRjD~zu)_-O+3gNkp}Rp4}v*@L?}u^7$hgU3U5ZqR~#Ovln2qo>Q$`JpX|%dfv=<``W#}CjfnM zFu&pFmaS&@{zhEQl$=<%9*Yp(_^a3Are3A*w(z9IE=RNO?xxajOAMlp!HQN-um<4{& zWSoXAgpml)n!=+%o#D8rPTgTa(6jjcIwGt2Fo)T!6T4}xn)U~z855%lNJ>z@@ea~q zYw7z+*T>Qwlo2cm07`uzqS)m&Wj)%}p)~c_#9HTzMQ#vbR~S29!(mrH@Ry+;8>x6G zz_|4&!ZqM=dY)A-CCkx%|IS_D-P;WtGZKnxe!lfAYRY)Q+R|0NS|Bixu-SiMEtLj1 z3~l`SwLDuS<@xu&>Ph@Te`fIUlHmYAqPuj_N97p1A^ADsy}<4N$x!QZT1&UQ5HOFK z6O32K{UF(n`=*Ex7Us??`>swTp`R6B??3wOMRmQrwrVwR^}T_lFfZFmJVYBP0~Hk& z-CHFQn!J23;zn7H)$gt%^Hozt+|Pb}Eup>tVa<8;;_SCXXpfoM*Z)InMzs zGaD9P8Z^X#dHoXW4!(~`=AzdLHg|d9hZ2AD=IoC!wa#OIvcd`wrUFspo=Y83>`G#o zqq4)dzc&jDid-@c%hVp?!M<7_92tr0US7v7XzQ?MKD-ymj)lXXRHVhLJJA|UK(b?y+*t$hBtB&`SFuog9vZhC)`xQ1G$g$(uCs~`T63<-0 z9CcWfYh7H`5cv5EyP@gybJ^6gZn~d zL(LI6QjdEeg!MPV<;*oGi|`t%$C*40S73-bq}B$%Q%Lh5tiPzY%Z9s;yD_#)X6Qjq zD_thtl+s)v#?V-%ZUEe4M~!C0=7$D-_S9VYxl+=``k6Zl+`Vdx=!NY~)s_SSYAtUG zYsgJ#VrTg?ybWZvFU1o`GH!2gk7SnSJsPk7HHwt5Yg-uMNbmp1pn^2A6yPMKLerqf zT3JK$YvCXo9I$h+Z#yCf1Y0u-6#$Q*X4X8w?z;$^OP^s00V6np$`GBA05;OQ&Us_ zxH;~<=D1D!KZb=CiOrE3w50iXc`EF-`m?E+Fuxz?Kp)wyDmMNa`aNaxTJ5G+HSmGV!^62@^ZZT zbDTsm7wPh7qUib3H11*pe%#@!f&kgcHDUHXUrYIAO%fc;h6F`kRAHWfLG<$An(bCE zc);34vys^!&;>zPqxAS{C!J=PmMhM1&7^eZwkQj`n-V&iu0vh(OOFA`haVvHUbxTdE`V%e#L7fx4j@X7CPOkk-{$(1w_j6VG=`wP=M(W45CFg%1USD z1`)9k#vWrZ+%UHrRg7O-H6FyNrb+dFnF6#^_0d=W0ZdJrzErP3U8JxOSL>WuyCZei z;P|^`5;niKATbmNKZ84pDRXP#Bl`tl4htin!WQw698&g<1viPR;bPi&w`nn_USM@Q1U8hP}*&e$$6(|vyQ{BJ?@ zk3{x|zbgL1T%Q2MYp043ZCUCU710(7L!8f(9`-)w6EWYLZ563uecXMAP^I5Lx?vDM z_7yW+o+abN=C~LQ_*8w(x-qt_@8Eg3zf!rWYmt~B7LimZcZU7i^#sHi##65kz*rRR zyP1(v52iNwN>lVrtn9k}b2z-jvKWScCSSFM$e7XNcxCeC2JXJ)dTy_RICn$X=il<%?Tw9?a3cMxGMIkL4%T}9v&*|6uAiHmTl!V?nVIPR!XSqI zAadan3I{9eKib)!>-x=@!^2ysyujkTu4cA|iRjN36Q!A72Bo7syu*XMU=)F{c<6?H z!>7W+fVc{}Q~S>fFA&uhRs(=p+8>2&-Fs+Zp$+?XerbV=ASbxV3-FTi!vZbNpPL41Jg8EdV>Q?2aZ@2t_fVHwk;9oV09Q#V_a(B6B%rIQZ*q2!=H(v9A1TP$vQkl4!$m9? z+RT#v_KINa+~E_cv#wm18J)>JqDg`uz!lz`x}r@rYb_K-?h6>)7}I%r+~Pjf+5y3v zSY_Iry0L&494Ujy;0m8Yv9A_@cfIy3=;^t_BUUd*nyTfjPwY!0+J`OM{L?wpNB1ir43#l}a>sH2dYY(}52Dz=#kPbF-8C2a7HQyA#I`;QDCjM#CrODm3h}6`FAM~CY zli$2}<=B={?BiAFHE}Nq_EBm>?(a|c&sRg$hKAA4c=nrzvF7DvtsgBGKi4$4%prQL zZ|ld*Ca0crKK7IlHzxG@5C*-zdS)B-`#9^Ho=N?x8Dl3Msa~in=&S-V{N6MBd`z1# zRlyLGf%Yco|9CEo*iKgiEJ$DLF2I}l_>U+HW^gk2$8hj}4WPenLYLXR@I{&w6m~IJ zmt(b_G4otDXIarPgF4PvrMow^RY_TnZG|UE-_qt~;$R-pLGLpwXuuvFe%+)W6H)5V zfYML4T+>agP%AXCe+E(iq>yKU7QjT}!7^pJj903xLClL{*?uzn!b5wy^(YyFq&Ir`eso<1GF?&D#26Sp5dCKpehUl{@bI)az$M)36SLaAb*GG`m6?Xuj#oxRB z-vi;hA%bL9?C8JYdVgrKCGh(|3-oI|{mwhlI=`ZuvRB2g-TEZc$6%w+9IPN4Hr+7v0UxgUJ{)s}zhV96`ZJWQ8l3&#vipLJKI?=YS6{O}}1N z%Ul-9SKQTvi@*4u9IYd0uVx1bMNH?`JfN=LfBV3m;0pOV2yuD$Tmqw!tpDg#fC+z{ z>6@Fg`zwe5rv!0z98FogHeGZ5uM}$95C^6A6JT4Mh9kaJ>CNHM&!Fvyh%mImh314! zCWjr;0TRu7FNGicT1pkXSfAOxRx_8q>LVs1a<6z`2wM`IkDTBbzsi9)KKFI4=N)P6H z8}cGmsHNFgF{7C5R;1*f-kYthke6l)Vh8ziEU3%;i5*<|(5|Z73qPLB$k`YD-d3B_ zM5;j8GHM=fJVbsvVMhrPy^!|c;3)@KhbWg_jk$4@@ALkPfpHwnA%kikA<&`76{Pzo zJr6mkcB?6!4B#gHa~a+}jQ{?bW96qlBO5(uEpjs5;_Byvgi*W1WHW;(&T}%c-e1~% zGk19tTqmry4t$F7kIBV*!(|gsXJM-QYaZPlCQ)~G+4?i7X6U=GV{_Hx%ibvig)vX&yS9d&Q{&Ns+6mn+fYV293pl61L!Q>T}q!l zojtlMW}jZC?kW7w9RdZdM&2tf>f>kfR$Ap9n?dZt&;j+_%yO@#Ki!KbH|`NB-w5@O z^-uR=*LW4$Z%|GB&Pyie3?XQre4N`6_TIFkG^2FA0bY%jjQ~tKYSJEnB5~5b7yef2 zZLA1*$9FvaaR!-DJW3D~(m9BCTHVkwmUPpD4b}zG3QMU=6835o>8vQwsZCVFI_?oN zA<$N7t2k{MbP^k=V}!6_WRa>WVQ3CvxeGk)$4rqCEkT_@2;S`wc3lhyUA2Iaq@-?wkOn3Suz7o13f3I50@B(3|Mijm1eB32AKGQ^ zq_R9MLFxx!zu(1=Na|)|8NJazjy6-xswL4hFz_e4T|FOaKphqK?a57Xuj7X=Fk(Qy z%Bs{+4G^M-_$yz8NN825zCH1mod;>t9A3ir=?Yb#QS}qnlmq~=lsx}EByeMkkFduV z@)LuwZQ4`+|2F~rYF@bfvpAbtf%@GtbB<=y7-g0G`%kxGx>!~k8GrR%y3^C>>0?K$ zk=UhX0Tlc;j`PgR(Ha8QiFX{c*cVjk5xK|^S>>=GU(N*1PaQb#m(3}wUD&`>g^2o~ z@>^jXug|WCsC{ol$_dJiGr_v_6AT|NCw4ZUm*K4W=e23uqpLB$Eg^BWYBPXE`zy!; zrS8Yq+M?a*hHeUIDvI`fw6rE!M>tm~rqv7SO4QEDN;0fk{tP?ypj5hxvaSqhaY&U;fHKrqi zV;P)4kL5_NRMSIaUU2Xys&k^kx3Th&kZOAE>X0A_vJ5Wb?gtu|({2YbSu&Yp?Tu!(l~ncx2>L^{m)L-1rPG=o}LW=4N4k z+j+--0{*_r;6nlx`ntYJD4FEtEs()+^HBrg{L`mV4Jc_ywOQZ;i=UM> zDA#SAp)8BC@)&tyczf(!_psXn-udGf;~hxfg37ErXw$^1;EWWZ#@ENT(8&XZEotdanzzaoI} zD~HLQyRexj!`2Yn5O0_w^%Y(+~@5S8e;Ifz{~| z1dDP=%)c0zMFHkp|6Bz>Zn>B503Q5j7e@`gy@|pC*0g`}r_jEofg<0p$S}MTzL*1K zt8Wq)j(iD6uxt$=E#yC4dwZtzn}P;Mu9zQ!U&Xu=HOaMAV+Eh-j6`HtUftl)dX>-h zdT5^`c4K535CTN_d0D-pu-x z=lG$TjgmLoGt#1r5Q3M7qn`rbg8`AnYYTBuJmAs(_6Q(5#F<3(r!0x9zs4A^*Es+X zSGfj_2A#`1Cssv!fed|SJ{0$=H&bnd-e#wm_&=4MK7XD?h=l@~vOY0_3&@Dqjajs~ zDrZj2D0}tWyT1tc$&WoTjJ7q)7+v0{z5jVemp**zT*<9|PTo-&khI)7@s`!Ks3X@_ z;sRlnkFFc6r4o05TD((uuAQa#jlKLS_&guwQcAtKSz4F6f@fDu7KRV_tKwuR3~`^^bxbDRMTUjFw% zvF|rEuDbb~cGao?q2}L<<)P4ixf+8xX|@t<(JA{Ee5tw#e)wj!YfH~iGd^cHImdD` z<5viOn{d*-XJxh3MG6t4846jgtU>_w0>{V%N_%zlV&$b$f>p?47}E1FY-=Dqo0A%9 z!wX$zj{A}qqVPz?%uFe#>IWB(^}#uu-P4sXNV}aCdIvOOEnQ$Gz-gy+zIzU|phI0k z47RNkkm@3+;zrh|D1Pa-5iqLcQ9UoSlI=~;qNo$hM`!}J1ZT@JKf<~T;gCjE2Im2I zG#PUalAEBk+-3*ph7_Cowg(nQ89H~ur-i)nuendn&lv8d2>u&}c; zummdf-(xiwKP9xz`Uqc-$bFm$%;)jOy<6I~te$f|SD@_JS%if3$oRi&Ep-vYP4Mp?Bf97uuzP-XX9jeE=8G3@tR5c*Y1=XN?5#lA*k z?Q`E)Ndo|ntPYU{o@v|3q25daVNH4xYX-YP2dEG+^sZaeH9*>xl+IE+eRqrG`FfEWje z&2W#_<&BRy>f$ML&=-&Yd)~Yyq>x;?Ky1=qzVwzr#HzLFay*hm=Du|PO2q*Rd4Uq|K37)In{YtN#p&NgJe0mNqz!`T}?eO>Hg4zXa zlwPt9H3&R4)dXjl=G%!T+6$OMWY|C^tr;P?@C9BAq`+exn|ZV_9ghiINa^KGh}TlQ zDtJOb@BEcTTe!js*+<+Awfcl?S(OU)2*1@XGAdq)+A;YL0<8V)ln%Cz=qSs25PYo2 zU(3F%Wv?)v(at#th)Pm4avQVW^)GiwYcd0C>)Q>Q=YK!bp37bMwD>&nwmp>a`T02w zpMG+3a;yyDSK+|>x!I{Q_Bjn=i7BTbukWK&%T6*8h*uUXQK}T}mW%77RdeOPJ69Di zhN}ASN{O@rn#3hX@ziG&?bz2lKfn9=`2nWyfN@y@=fJEfWCj^RiZ3bTFosDn>!1gz zgI+=Mdab5reTD=o&sL=+otE5jR0>fQ*JKQ#tNm$JfLVK8rkjV>1mMvbkzGNN2=4+* zVKM9jfRT57<|A-wCkr@%`W`hYQQt=Z&y{M%C_{w72?CVn&p&x+RvNkB_U0~*m&?x8 z4GiXZ&SYh{gSI~xyZrIgd2&d#z;>bV4}Y-;bm4n=aaA>9v2Oo;TK?9=MBOFVC_&=u zZ)LK$qFK48NMET&gi2{+maGlzW0$i|b3pZ?dS|OYoXt9A4%p5w3q!^ zLh8i(oO9p!>h-HU-~QdR2`Nv%w1fBQa;bRy_#h=G|Hl2pR|jmw%^pUDGY!7J@8iE< z3l%@pCvgd=TW8W%SlK7Rnx8tlZ1vtHb<{r_^iN;^*y_gdYbNL>=ts~UQGwF(8pGJJPo_qeY?N6 zI0_fPu-Q_oRu{dG$?c?a3&y3S4Ig$&`j*PNq)JwPe*{jRo29C#vOi7eDIG4MMq)=# zxV*mUbeCDL0S2rY`=vXh-0^zv(G=vyIT*8gC zwT*E6!T-c3r!}&k1mj{Cq`-ZDkMwh=hQy6!;jvriCmFO!$P{Ku3k@ya4GVki z4r{~G{BkO6>Cy{ZY^eUZ?|Nyj&abS*{`OJR2rKP?=Sd>-ey>3w5cy+%&-dMJ6z@nY zG;{q56}@7@AyNEY*B%JJ5_r%{|A6e(g22Z`=ixl8Ipj4NB@_q-{T{!S#Qv1_ol>-+ z_I~e;_j=Kn`yM`dg2pimG|1KDoNrk_c;#)x|jM*$)^ zH-HG69ElS_q(32f6#ntssh=s#rxo(RFa){;)h6aaKqw=}XM*7RF=;e3Fttb`XNv(+ z^&hCAPUMfQ-|lbHpv4wJf9hJrWl8eoRRDjg(GEWo)(oe|3@U>oOnkV@ zdU)AKzdt4iL!f5N;IoNY|BQG9SQoO7KJNCx`$d2eU%tFvBUu@oAG@=ZiyVyTF=zpaic$PyUr+o zIx>cZU2u zxL z?l^KE%=Kqa_vg@`Sm+ONBn_iQe6XzEuY>#JRy==N?~>O29^MDt@6-Is$X_XM0~rwk zGs@fziBBfNI+rd9O1FL~leZRMgwEhJN?rj+ZL4|8026cb+?SAU$h2Hp&@T@rUxS?y zF(5UQ(kSVgPYaOo$anppsRg`o&uImoaout)W!#H~Cv;$3hT`(n($q~cqQDIDIvc^k zmp>YZhlc^sQR4>v@$DOS)s7S|7zSJ}1Ib$OIj274x4<$)?oopaNaN9uj^Dq3A0NBN zET5bQh%(cTPB-*fex8t>9Xw7FhAhDM0BcQp49|_-X~tVY?cuRi@S;3!Fp|TU{g#2z z%Nr!kCXv<{ir4_g(I{!3y!LFSY1??*+Bg=~CgaaS{O@b0ORhp@HT}^zWMFPCvhC`7 zQ=XB@+EuX%uDpA^usdb1mZNz!HO@jx$GO&;H8fYi>d~DEv?fT-i|P3O(koxG{{$_` zXh%Ml*v2>`VugC+G%>hCu%y;q9Kv1w;^$8;#9eRGdU^(4B};XUmLNE`N8?xXUfjDN zfVUCLLJ>IhjiXTeK`*9r;@EC{L6Hm#{J(dCUvIFDPLx&$+V(b6Dc^wY)p#;sm!Nm- zl+;Ku%3tBtwi3v3ZikWATK6(k_oGK4cPd{Y;43uh$tL$)Fs*zbHzs(*(XFzmk56(qEESvyLeEkXQL@f>PXmRtOX(<^2zr_J44Y0}#F zSPNnRbCdHQKhk}72=kfyzaRrgrcI$P;s$2?Q@ja<|pFrgL}6b!gtDXLrZ#o%&bsbKiBtrb|PE-07!u<;5F zrLcCj{mOgMIjP#JP66F!4B0Q_eE-mF28DvbKs1^N+`5NJHgR997_yCrTm^!& z$ce$Bm+v@;WdWeIo*~d!tB9q;l*HrR^m2JTw#Bq~Vq)Tt*rnkB(Qxo5GL|Xh&z|+~ zt5ZNmK6m%0o1}lM4d&zG>Ji`TQYwY(9IB|-gxqlE-gY0fl3Ekg$pX~T;hC(zFuK`|uu*DsmLNW63|QR(HlJ+xbs zcl=xa+5k!%kYlD*fV)erFqt3_Ab-vY%N@ozWIh>Y?DiV9H4+!Tn{v1KVzH{N^D;;i zi~21F);~*$%%(@g>OdUsVS-lRx>VQ0;CHZIyY(bjYAEG^1O$@s`wx*ekP0|>BD&|( zlX6LLDov%=y`v67M$p{X=%D-A5BUxzo;C#=r3agz0t7S>>xXTIW!Ib~`6TJ_9@@4_ zbwT~cpi)*9&u(Mq%Ee&(#43ERtbe~*aF!R$_3+f}ex_5*?#vNinc<<)p9n)qzG+{F zLrP-#Ul2UJ-kD(RqhCHcZu$e7V%CstVww=t!1wwtzui2~1fo>6wrsd~)!6m&zW=t5 zX_MAjeSb>ie`+&xm= zc!3f33_~KLwg>&|W1BDa9Ibc3RYxx=Z-zP)uXwa?h}=4S-{JV(VALqRS#3T&e_8H_ z#+2jR86rec?VF_tw*m?Kk{n%;QKqWa-?7wP-=DnwO`Rn2`>d~jGbJspeHVvQ5Sn%G zKJlxE7%9|bm9rM6CGYT33bM?VmKRH+?7p9fqTB2i zko_H~HVm!olpWQuvm>l97<`+*F^hHR*Uy&gn@p^Yxx_7NfppQ9XG|e<_lZ5DFfI#Z z@nZJa#nGg>FNACqecejg_PQ^?8};9iC%fb}5Pn>aeUnO~62LbrjeP*aX^#g*Yd=_-ea}h2+R8YR z!Nua5JmAMIG*C6)gHL(wsR>6|^TH$~zS(<~8O?xI@!qbw&+PH0uYCdfB@9>cC640& za|=7|eX)ZIosR;e`UqW93O5`PqSl+PN zRM#$5@*A)2kmPzFUN5bq%qU4rlXyDsrrvuc`j3V6zr0BOl2PYgyVtx% z3U-zLIm*v=)C_C@*RNl%Bl4BK2AaKSPm@0A*~Jz3^7b`nn~URIOhfd=QbJ0W9@)(Y zlB>+_9nI1Do*ZA1@|cN^LqdKsr!@pE*LU6^uL|ZMzS5V_i0N;MX25zi$x!>0`$~a} z$|xn`!pE<6KUI-1oCnYz^m5W7j&c!BkFi#ykaZqZXvOZ-8J;T7`aium^=MLkmuMnz z(%w`0*7>pmC=$*OPCbwBd!;X_cTi?fs2R@hrGB{}u3;I2;N;{K!}uPX+UQpk7OL;P zye!p|7xI8Q=l&jBTbXnx#<3<0E~a$lheu~P?Fz2nr@kZzH9v90)`oo*g}p{cRYx?l zKo4RxqFs1l&5uNkEB41Iaf8Wj9(_6|k097?^Lo05<5 zfM>zWHw)hvG%CUsPIc)N(2n3#3SQgRI$X2BGQQ0JlXoElVd=k5%bSL{p$^!1Y$YY;7b4)|IH7V?oXgPgIA6LEtHM000L=@CH8-t#_ww?4E8DViXmch zEivppe@w2Dnjrb2`(=MsI1$et17?jjvR1n6gc4Ek@dkOnVU2K{qk|P7nz-l)W z>|KmCJh~#~>Y!g|5;v#3vBJ@7+7Ktz#MrdwUd21rBl#LkYQ1Ut`|28Aj%Ax#353cjAg*TS)JO*lZ-X}s3 zN#txZT&{6kC5oJvpApvLPuUWR$AH6V*WW;5ppeSm&75us*{abGGLp@OSC_;-e&!Z` z$cLlsj!7Fj6Mnbo72dSa59tFH@kbDWsZ+gWU#DB>Z+TZ6HI;F~9;Tw(xcBKHQju@u0%%J2UKcfCykN=FoF9>bbN$?%00?lM^89D5Nejl^oCLMv2 zJ~e{ZwI#AGz*czXQj_h$>@H1GbbSKheG-K3m8rjL2ge)Qe;;$|ur-s_k8BPaY+S8* zj}Fa+$~FB~Y_30eZj)~lt&y%LH~;#}9d46Xv9vMoE~{!%e;A+^3&&!%Pj_Z2{bn0! zWmT_NTF=0@xSRa%mLkJ(_zdC!1Y;dw;|C zU_MXo>56(^r3aa0L#QBOFSQH~Wx945e7;DzH!TOVzlEtm6$)y;anoC&l(JViUD>E;QVz@jZVz~AYxoWb@Hu@SkRpu7GX-!2Of2k#c zjpLnM@4#rlR!PvAGsZaSoFq!Y(aO3u%`l>kJ%?L|*PT&V5$V%avw2EHxXIxeG-Wl& zVA*3Ayk+zYvg#4u zW|)&?eI;5%)GJBDmbM80LhE~_>*C2>N9)<|i%^TM3`~*#q>#4Py}DKly0&%9a|IZG zMivh`5~mG;TqDJnV#_zDv&r9ZXwuw}He+BZyxNwOhC! zN<$W3IxW83^+0$L@bGaU1#AJziz$M@_rn=$d|HnMQA;(veIR5Lv0Ev8!J5|N1M0G! zOiE1yzJxA2oc<;s5PB>cO$8K`qx%df-Wy$5Iti@Yn7BIc0MDXj(unxD!*<{BzVZ8eF`EY6{(BE=3A;Qx!g-YQ^oFt( zPVav5>SYeB4nxWhg)ebIFF&<$SJ*m_D!lEo{8GR{UC14Avri=)m!@rEZmq{%^(2;- zYoRrxr8OkF@%khkLR-yRt?I{zuGv)WV>^Xh(V}AQE5Krq5tGQFc>fn9-EiKkQVNVB zw)h}@6z5ck8W2&UAey`hQVXmyV;%NL##t^#d@1m?Y*|=f-70wu>du8w{_lGSsIK+dg6WZz(;WA){`kA?JWB zi>8mqUk=w{sIYSCyB0uYRw3~|k{ueYPK(NWBDE^FNpBsdRnC4B)>Xm7X@gSI(H`{Y zurQKI0ln9S4D*7)xcZd~kDp$;A-iU^-|53|C2{QRB-;7xCsk{o7!WpmJ(Ym@98L_L2Qx|gNQScJ4+$YFZ!I^XdKScNOLeiCuW znnSsCfOX}sC9H{;&m(MV@U1L3DE{K>3?-NLRGd!Bk958Yr!$8J!o9v*ir8?fmm!vw z)Br_F)AE!w8SVLVHkv-^^HSe?oP0=O+h<#>2YREyP^q@GwFaIa<(Hvx0Di({J^!M4 z`=ElR=9$$jwKqNZQ}`20OXs-zzVVwAW@(R|e^R(At8ps-+*6>C{kMVh_iY7g%Bu$| z^yj=tQ;l8I``o#KTVmpiRGF)QT)Gu?*;|oeoxTQG&mF3 zDUF(b1GVQ84Hm7@N1_OUy`amo+mFVXW-&)zq52yb#+!e#T#n(-5V zp~nh67wi_6)7oYNz}@$>9KBisJfv7SnJiEQfxRAtjgLt3*#|u!bEcq>w^1wrgCIaI z=kVR+s~}#%${+Lr*{$FR4wmY~`nZy6s{$h#srP*t3|9B6-G`idZcI)D^g~7vM=DJ~ zWc&W$a|rD$XLr-LTo+oPA9qW-Dm@q+Kgc&N$}bqB{cr`y1!ZPnVEaGwpLKEA{mu)W zPmh$4LeC0DMZUzT1EFi3Mx7rF2HalaBUv>rr`5PR{PzIHBiC|3gl&qbnP?ioyTZ+JDAXlg`)t zQwtf2p8kGRz%>jT1Im7>WqbV1LFxt2G0Mw2^>pEuS2s#uhY^%`o_wu3&}2hFZXUe% zJylofb!ybK2&Go;6RC0QB`d&H7Q>`sIoRMO+SXa?}~Ca+gZo;AU#?Eqcye5)q7ZLx($zj zvI1t?N|tMYAi%WA=_Eei0^I$?G$AP|fYq)ELbHl%-)lpNvV6IUTqAKYFgo1*i~)BU zF+Fr7<>0^+bLK;mdVU5hGWHy0L^XVg5J?H^c@LxR zr?VA>RZokV`|9Ja_AMx?y#EwQWQ@sv0C6ozLs`H>+1lp3rICpCF6o2R!oI;r;QDb_ z+cn(R%<=J)x*ouJ$zPA|%$r+hhkp+f*{pGE^k$GaP_ws`+PtK5N&e_|);LZ$uewiI z*eVkg6a*5wLhaAudWvpUWX1i3`OYsiDc6$!HDY-MVl{Nro-ULcdpL%4a6EdFnIq3a z#-(JPK5a^3Qa;7~DfZrAt6h0pbg2kW8&~1${IV7?J|(EUx^>6kv@9~r`*(szrF{{J zP{DHli)8I9;GY6orKLo>mH|cd7(9*|)4mSoT3|Q3r##_LyL;FNMyoMkTY155S|3bl zsFII6hHM~=uvwr57t(^L_JOy(4kjoL#+}Y%BEX&K_%3wU}d0?I0IJ8k%k@VD4>Vj5i<&8eN7$#}DSAX~$8&PRAFd%dSu?X9D$^^@V!t!rkhi z6ta?XG|?hPTjaMP|NkTFEufly+y8L`L>MSJkXA&A4Wv^LC6tL03WL$3yHh|x5E!Av z5Red@h*Bdqx<^QdbT@)@*M4t4@qC}>|37DkGd+5Mz3=_tyLL+e?omL>#$aLOS$J>AC5R2A=6hEX zNiL<=I0GGXGAub^KCVUJPYw)H7D$2noJAVa``61LHT2iv{Qc*L-kU{TTmyCW+cVJ5 zMLdodS)&}<<>=LPgqs7`VXVz;re)LL71}`)LkHS6si0r1DA#%9vR&O8sbksZ@6Y>{ zsn8PmC#7G|9PKtpnRngZO?E5;bUm26pA;mf8#pGm_Zjba8Yba*=a#-+a}?Vn#}>8! zVHWF^B7|^&?t@?anL6bl4Kp^f+oPFF02?+=v;TcMmP;p-RbJQH7W?*W(_`@Sa%cUn z4W!A#HVn~N&+Uw6e3mN?K6@Jyo!Kwlbv^r7L<~2M{z%0l9@l0*cKc+gS?-SSO_El~ zP5tls?1|tAA+}U6Jg#D(l;b~-e>#4HBNsT%W3+A&8-4Ol6IG(w34Ato@(+%2D=HJ4 zuooX78c85G%83$>4#BdTe*S=8;U=kni@J z>B+-rl`ZVS;%S<+I|Zs{cul|-0**`(+~*vkpkn2*|G0q zTLgho*p>TNSRAjAk$LyL%6<_@+R$=&33&sNMiB0w9HF&}A|U9anM_-whw6gJPEQT> zo0x%G z9LdE3_P4>+?OyM$bhVA$sy;69u8Tl67Dylg{b^{R5`b=Ob#i>u{rQn5^;EbEwgT6T z)&2hAuqtibcQKNScyc{WL1zf^1}MCAJSS~UVjR=Du@E|7SqO>@0PEGQG3Ku;P(2~) zJ7aB$hkKab#zE0G-bg-Bxi?c||Lu32(JkQ@k18(zWU_zc@U4HtURsC67HXY4GsJ`8 z6Y%~0keiS#n40~57HE4)>E?az80SvLE2!Sko-&>=jeN+))Y&;=r~CcOK~d}0DhO5j zVg6W!GzY6Oo)H%uDqlm+^P}M!wl=WF+CO_Z5K#z4_8h|NSGTjWRU05Ak9!u#8ox06 zAzr-y9PB^xxukj~oIgScFfmwprdiL?Di2V?EXe<}%PdIA;{}#zn}R zqJj&UlxEw!uLN#eo&&d#0cFz@{*n zaCE>f|8f4qXKn zr13?+n_%^VIeJ-s$TV@A3s)m&I;1g$d_!M?FXc~sA%MPxV}h+QZ-ZAOHzyfaZ8p$@ z(je7|jPmLjBlq2I;s#8I6NM7`+A1s}qE%#Um}Gi04hR0#BRszWmN(5;hDb=l(qGZr zFA_A*Dkepbl|Uo@5}kkAAgt7Va$sEPaP#wiV$Edb(Fp$)W2u$@y}-?c?89ClgP6I) z?cRFWsc&zFf<}g6CpH4y!M@onAkUWd4&8&$$Wj4#X%!!AuE9AY&-BSt3ukxy4JjL} z7ie%SSL8@}JcjuZTaR8J{|yCk*wsMU9!06}Kfk#Cy`pjc1tnGoz~Av2yS_(`ylKKk z&f_P9q^0#o?#0AU*HLFPT{#Y{J1eM>SXu{NQTHig4vwB3-u8++J16-2LQ0hSfmX0YFm0-YF=FFo?}s`>5enWr|b1==qx4^5$t%&!m zNC-c7C0j<_*#-00DwN?Tp;&XPMDydXTcc}J-qum1Eb=Fzkx_B#oTi`!#ws!890_^T ziwG~nN>XxaL-&^!-byJFpnhK16^Hd&iR&uU;W* zF31lmQa*Ug@b$HOOJ4_|2{C+@^T^+t;h(!5>c%{ra9Eb%%I&12C9*FsSM)-RK_{az z<4Z_k%*d*7Ts+3+=OUzx>(}?}fvAcEbv_GhjDP^f71U~{-TO#oG0e)?_<`+xQPG{H zK35I9nA`kIHwYhdZWp9K(%AwR^T!w0r&P$75rZ*i{z55;c6unJtDO)wU61b9)czFQ zFwHEzJ};i|3Iakc%icPCp&1@Hq5NpDh?oL!5Hcu3X zX;By}h#xg`ZTE>1KCJ9t-x~f_3W}w}Cct`TSnRxs2ysAXnMg_jX)&}YD?Assm_qa~ zAkr_a`);E-T){w?NzNsSrm3s!j$Mweh^Mi^r9A`nT?<5@LrRz602-c9QnVgKmbdYK z5$W6)wIJnh3A*s@YP_9Psbej`e?-E8*deY-DaNl#$z+B-# zOy{`Bj&XoAx=+klq_JMT%>jyL;(uM^CiSfo``TQm&<1Y7c2Mor=3W4IY`v~C5##9k zvUuvaR~*ca{X|H`1B9&rdc_qh8Xb>qqwlYescD)Z4k$zHHg&eBbgqd_kfQqN7j7+H zD%-yC%zINrzC4JP?%Mxc`~|MD`+A(UEB4>4AyI7{rY-H@rMWfQ@@tA^4TJeEwKX$i zS>uKd1t6-HmaA(r_r2|=$NH1t5W|@i1|>iso7*|V><;U{gHF)Cfm%=V?c7~}>L0W> z4s{|(ml$4izTKgCE= ziM*cwB6{Ln=hWG&66YJ}a$S-6bmy(^yEk9&t$;}>Qt(zvs>2T~1!QB{ftw$bqa`q4 zX#;K0*_&1rmw?b~)coo8laOJo^|pBtfeO7;nGo75N|;%%G~d?-1b=~sJV{V}7p$4H zIhCylEDf)&J?XXEJ)H?E*r45e1qsclVGOS%#aQTyo33#pLUZz(19_-HO;o&)4K5DI zN5%=Ux+kaFqf6zP{NSZLL$ z09cU(_MAKzTHab8eg~xCV0fkBdJVEI?d;ULF>u)NzG)fUr;x_hk$3t6!bPVL^Z88( zDHj^QxY>QN)M33BOA+EULYTjc9D@>dET|WnT;spS82qG#Reo{28y> z_cx7m-bybKZpu&=zjBK?Eh?tbfBVC7PMV815CCHZ5fIS+@hd;Tk{NFq_U(o6nZ}mM zW6nQT8miVQDVN*oH7%rMZg6LxE_kwlZJ~(jqm7+BXd^1KDBZ61J0e) z_N-L~0XKC2rT(Y*6Tz*R2Q!#Edau}Wa;p2@hb=Iy13Q)QMO4idTR@sZ55-yO%1d8q ztF7gPq#)k}BX4RKJSUvlN zA>MUxBlZ6M`{sQUfw{uop#4c+aBLC$H}8JlXpyJa;F@N3GeX(`DQkLoa`Vv1t|Mk4 zkK|L|=%7U5diZooMSa1Gl^Uzo=6dv)*g&hPExP*b%?JK`)(I@2{s%hRdh7vzVmNjP zhpwyp{NYF5jS1ZS?nI10q1_>7f8DGNz@d$A{&(j(ed{%c^=9z#oo`f4LpdeLySP5BEUedu86aTJ^9VV=EwXTz=w`T8; z`oK(}!kfWhDvEYekqQcQj~ z+_~-Rin}e0dUZr;G$1_B7ikobrup^~=xCWglSBzrXg2k>mO(DS95mrXkQ><(DnBFp zSygqC2T@UcvTp%C&EsH2f>L*1MsUka5@ulh-6mmq(>g);5&hj$)PKA# z|2fI79gmS^r_|#|QL}28!?u}Y0u)aK-;G&+T0tgWIHY+uFMkf zcJEA)IK*?Sby0j7=%9}RpP#gNR5y9`B@p*J7QDRIPC&qs$45pUbENe*d0D#J9ZcJg z$}p#-qTYa$$y?`h8IpzI2M1?U5E`a z7fAi2mM$q1c9y9%+XJ)Y=P@dG+-e+7GCw`qeYI}Y5JE-OHl2hS2p~1rg#f+Y*hA@* zqKM~Q=plk;F2N-L3O0Mf#=@d?O_Ty0MXKTCj8(j12nUcgIZGdb#6a_(x_5-EUWTei zRTaaZW^DjL)c*SwlS(dO&;5RDMa!QZeBe^)6@{KzrnrB(7C`;}Tr>LL+w=Trh-uLC zJvngppCfjVg)sl9Dm$>FZF0Hno@7Cgn7NHdbHmEO|B-n)`NM4g4gbiMie74*!6~%p3 z)f?o~VR~5i47fv~^fQCG!|9}hAE+M{U+b$RrQU3cHieYjCYLqk*Zr>X)bd%O(sFtc zh6!fhYkwC6B&7B9!xSyE`+vkWZ7$IKK=g{bqc2`6118XRqHmYL;`ut{pSwl*_=M4S z8Os5H*<@*T)^JQ3qkwghxruWaUl&c}tnePNW)X%+mO*pyC_PLCmh|y3SV>p~h(TG! zevvf86@N;=?s|jBo*kZTg8_N_!s0?$>Yb#F^tTcM`1E4jdvlsDe-#w=i7DD*AvBdU z$pX|Vk=>!2RC7$WC*DzQ5APL6_bY0ND837|Xfa1m&7P1;)ivJrcdK|VaBeR8pYE@E zk`sD)-NtL-Uo;V@A2fMpark7T;crkA|rxG8yt($;TegEi9V)ps_&^k;D3m{*3g!4Iler^m;5dq!*kg^ zCRNJSL-eez0B`BExz%mK zh>p|5YyD$mw-8R%-Ss)oYPxo=qDGs0NqHT<@qcCVbD1#-y0nun0|=4ZAhOXfo47LSFm?7Ztxq@jBTE zp}HF*86u?C6U41T&10WEmYEEd7P-eX%~`^)R}fj}zu!Z(k`|p|Q^GuJAkBfQXsQfe zRH|^kfIhi$<>9h%VwzFm_4}3n<3+!IYKo~wU}fneN*d9xAQaTm-W{e?op$ybox&nA zX%n8r@(&F#6iVaMR%LgfmIv<$wgKM z*L4o|IS!t|WiQ$}o~S!YTzQ~5gT z@?}31XxrJ;i5jeqBIN?}+)g-{BpxXedUj+2Pn7>U59{|C=l@1d-op0$UD)G)JklZC z#qrI72<(@~+LDu#8??#dB3EF5C~9?REIEb4$}_5_0+u88)q_aqPM_SMvUr`tfU|jH z;~tIp*oslnx#Efhc>6L2OPwvotXJ2 zMF{a5URKS1)!|qO7cQpilpwv`AvoZ=_ zn52y9kN-08SmW5#hMV~K%!WRVB~8+GYiGtZIGRQ0SoZR3mjdqjiCzKd6?D;JQ`aZy zAkw3f&f)oylY7Sl;7&uz^y zMe1~4i@5Dg>e$Ii0<-J7OTvQ7!!c7^;2qQ{d%@GE&y<{dO${ka!h}NTO+)R>+Qu$H ziU4fxn@kkkKW;>KW~jZ+WnpY}?2-irgK>w9y(|hIst<-PiAVJf4|~5ddN0tRyR{v| zs~*nGsvl3vxZd7AHe57&(uE2r(biOTMWf8PGyd+C{{DLJ-o4k*i~cW90qy^f>(3|s zh;xZyq0)hs6g+8%GdF71I8y9Jaa3#`CSmV&rYoUCdEJwfH5v1(W;^kY&;2&f!UUiJ zXTc80I@lq6&ClvL%mD7?sw4*{dDuoCcp>|?+-~-BjTAy&(*Hul)_1mHwv{El{luFEkg^(YCO{s*(D-=F`Q4E&_VuEjE!ito%%y&QD5 zZ+mNdJI^Vzlt&h;@hPJ*dzwq!^}QHRF8ibTqWfN?s&-rG;$VUq`iqIsGZSGD10)XL z|FDIuw=>29E%_!x3GzmpQ^HiW?pIIDR|8$I=!=N-_6|^sZfWeptGo%~;9?Erdn(Eh zD64j}cWals3QQlLBPlr2g|cP_$GVNBe!y=C`$Q4?BW|=c!+yCkst0Z)L!PLhqA{6- z*spe*MMgsoaUvOwcCAW3W9yXOXmg=c5{F7PD9Pe+I40a&vxxk02YB4ZkXGKb2~k>H zyrF=5-=X#v-@j;HR?kT3Yl+I{xV_R8P8Ma)KQYbt7Y5bC{O@Dq)43#&XJF>!L=D>c zfc~s65Ifs$=C*%1HjQ{xM#i2t?LtKIl5!HD zn$%Fk{qjLlh3>Viw=;FJO$v;3&*cv1I8J*wPM6cpmN#dc=keCcSAjEYznwPibk#D5 z^Pn~Dq%~6|dJPEoD*yk;iSVVe*f%&Vj+szWa;JD))AC2Cy6ivwx6ojNTALVB{svMx?tCt~J+8;Y`7#us z!#cSZpb8nW5+{TVD)19 zd~828gbiRB#RuF$Vi21$(vkt5HPNY~ivSD!_`i!<>D3!-Y$XGEMm6j(X+SEFfJQqx zy^>b`9JRB%J8b|sF&|Y2J3s)JjHEn>eyFND(%jCDa<{(z61|p|)*>TH(}n<-`~;lw z+e|{0G%^C`vL3$Ixt#fae{5+8jg5_hC-s7_wt;!Wd-xi)1UW#w=Q-)OU+s5%cG5*W zi3hrg_rSH>rJFm-L!Bij^HJpiu}Ymo+HI-pY_)46np5guZubmd&e;+K0zlK-eK{RH z0xXyB3bj~14y9|b-_LSZIUt#I5{m-Dq&f=qNkZC%s;q9A58ooMW#H9)&_R z_WYJ5O{GAci?vedHK_A6^NOV4gsHa4^ac>=-5NNfoZb;i@J2Bnu4@QLC>i!WBah4M zHvCI^wDR6go)L=v=hvS0Eyw4mkFc(fAp!#A#V>G5UCuIJiqNF+W+*7R&~~(`jL2GM zz5c6Cn*_e0T*=m4Q9K3pLbj!rWbzU(Hy7%G_U<`B{wR+wOu?z;5al<7C?U;(DYX6U zJ05@sWx~0cZIsnb*J*E67ead$31p1(spo2UrN|`QezLDq&6&(iGOhU&;=D0ccb;{0 z(0tk$Mpyj5-V%i=^Wi*k9&)^vmQ1IL{&a}UT6Fry6BmyMxlZf3`-w(;DLHluqli+b zzNUK11!$`a?8pT^!vMjx(I8=d%H{Z}$3+A;-0c+TcofrZd#LqzOpZ9XC>-AV>Oh|Y z{cw7yqGThn%$Bp}@SXb~iYuQ-X=dqO;SCV4Ami|vj9{1!mVSXyoXl9{1B#BZtx(vW zBt)< zL!<_r9RhQ=A&Vx<7L6weAP2W9L&+A<;u?T&KiOK!j6U1sAPSXS8kVX)nHS``akc6e z%|luNBZ25YYE4X07^QJipc-Cl*a%^9VB+A|XPMG-1b`!bP@q#H;KKj6%EnB8&vpna zi40M*&xjcKqF`Er7ZoL_son+sh5C*#u{>|4_%OQbD(D1zw^U-x)+n#OAz=sJ-E>kdCmfjprA>Oe^N z&?jz>*ckk`c%Y2L>0V80FBvn{L7FImPy!L~zDD?H!EN2H)!!4QR5#Q#fP;m^I*zG7 zIC*Zuw7A!fyu4&1-tNbTO|*?2brhac0MU0yBjOxWB{7hw^viP6BZ{CYR`}LAw20m0 z$rhNAQi2Ebg&HOSZVXHUJm*4X-a?%j$q>m$o+dYOirDPPj{t-OcIby3FufVw=x(jQ zl^b#A(-n@Kf)^PJaDW#fJvakCsuRa&-b{=0;s1POwrcjtTp@aNBz3@)hmERwh;H?Bm01O?N(sW35KA zc%WcPG$*X9=IARzqVlw}CzYKFBz?W4mzk>Y3OcyvXluBV^v7?Lx^k@@?TA2~;#660 z+N|lhPB7*wRbi(~*Kk&}XE2tq;-04U;UB2Td=DqyKnj{#hZH z54Gb`szSXw9iF?&AQu)VmS5{DRk{mPcs46MPf8j0-H#GnEAxB;*Nl@6RD&#>W`- z$GDZE*~Jj>mT_A}`@6#<5&on?|}6xsjnr*qL5N}p`V_%*{x zrsVm;Y$l$xiv(pQ0QJ#I=qe^h>>HErS;Azx)l?DStFact%)>R}jx zLg73CGmYdm@1_CqUw(!2`1sRG<@=8Y3)=-$D}S)jIedwfu#aJgo;=YGwh78P(TIXiza{BRymCFwME zfjkfhC=jqN9~)-~xrv+H-Pv)Q;Qh>+0{zcMJb&ZlE!&q6E%Is-qSjYer$GFOIp#<{ z{G2?PX>uu;`DGj&LpiY+euvQIv-pDY;1LUq=W`t*XXfra;*)je5Vgi9`0KqQK>_dG z&zT_nq&>t~N(oV%YEQ z2LTSn3P z?D@a)g;>Z6-VgNGKeUH3ao_r`tP26bfY>aGV=Ax4I1V6I<7MR!FrZ!e+Qn|^BhyFoIF|WW@Z&<# zLmX&d(UJSyY$4z2d7ibXQ)p~=aHvullvEJ&M#W{1+Q*28Wxxb#eC@G70jryv8~vXX zgSD`*usdyl!J3V|9a43_ApL;`{~N%-wVquU7(rEVVicfNl+KS69XAgotUG!A+2yJ# z7!#6~odP_Rt7c_BU9|@I$U+P+Fsv1?K+Vb32;kIP00uRJDd+C~=B;z(x)=oP3tRKC zw>ZqKk#TnsZX^?UCTh&KhkWqvgyBW4w3nSALB{TJwuV50%$$a|(oL%ym;QUl0Pg{% zWdQN)nxGC65&2Y1T*EA5NSWLwD99?4W>!+w^q@<>gWH!&_%(+Nw*N3ed~NbqHJyV~ z1)#Mb2o5gCyRo&EEtg_2BTbrr1khOth^DM0sJNp7*S^PEL3YS|_5gSV zsu6phe=%f>tqg@r>$d1|)PDzzM65kOv2Y^6(Pj7()=H=iYS7-s2N4elo{E$mIiULJ z%g)X|0m#YEHPrukO*-<$Q^eeU@#AH2zyVeAn%A$ZIPTI{pfB{!xmVrus5vzBXjIdG z{m8#@w(h?f{+xIsck7`}*0Yp{7FT}0k#~L%UH3axmd#v@v{SIg-LuQ)9dhXtdqmt~ z%sbfW`UN={QbPk`7sta75)S3FP42)U1pSTxnH~btGzZJNG|3?#*=Oq!NvUW5@I~BI zank(cDeA|BKO%ekTB7|Z&Tob;jp@b>p{8#Bi|6Gy&_!QQio1L`|LaGAPP3enR~A~w zxBl<(6<(zPeznC@M?0Y`#p;P-YdZfB1^=*jsUNFOUvjPSYDaqV7XE6_ep><1vgD+04ght0yiE>%Ub8UriSVRFGnU|HG7Sf#hk9Ata>wEI<=l3T*#|U5 z`}9a>F7#L2Zs>4jFhh!|?)UnKc7U~0C5I*=SGNUGh}E+orvOJVJj;t5Iu!%4FTKpw zmgxd98^1&k2RGhAlYs_5;^~zs-RNL3g#@^*C8MU>*8H8eZ74)rgZp8o1#bz!&6cyb zy^=$dB|%VleVJa<##@=8%Re(rbe~Fr0WA%Hr`HCS6L8U_N_f0zbD+1iJGW;++?aVg z`hg|*?1`i*<+Iep=f;Pt#PCR%*lRr`jYv>g7HsWu`V=! zEuwmxv=YYygWz^rat{6Ky4Q5fHAhJ|bEZ^c-t~OYEK|8oMFIqr3>FE+J*4m0FI4AO zvU<;*8|I3Qq73oH?Xk&~Zww2j=)&Q(es;2uOgw&Yy}4GwQGtkD`GiSxl`FjAyHWx^#ZMc@nn>b{dbuiqGTK#KxB0;b561g=-6IoRDcy;}i=_FTIJBPHe(aG~7 z42IiFNM_I|;FRNRn!_enCg;l^bI zMU@W}teLe1R6CVFRD2A%MkBRx+sg*yoRZ&EPZ2j%U(dg_>2|mV{Z-EW`xd$qvjRWQ z&-o2lT`uXWYXe4>T!M#);8imK#I?1zp39VU#*K`J&Wp&qA%!La|B&1THr1m?j|||Y zqd2etpyCOfG_5FUWP|!Yc135U8R_%Gb}u2md&A6z3FYB32SXyRDn|OZZrQ~S0n=Ux z8_3-M+WmpG6(EQ6l$&QgWji!t5ZwoH48^w1tOGi`p4LaTqvxuQWG6Eh7usYBS|Agr z5AovKr2*YlIl(}nzk=x^OD!97(|V?dU%V_6j;5Nq6f zVnEMEa{_88@Hs5ETQ6YEHO+TSK`};mCjLB->V z8pl5IYfLZTDT9|6I^D1N*eO^>(`NcaE+Lr_cRtj3ElJl=FFZL=KL`&jgrG5b zP?2q21&C3p<1KkpjAm;zd`)$2pzsC0y*;aFyLIkq`#jKmuk@)tcyY2HSvIs~ch0f} za`FI_AhiIXczR#*b%3F1PE{WmL{et4UYjD3$HIPfkjmV=K>oopKbc>ZZYqiB`^cO8 z=KTjE{HIk40Y)Coy}S{W7C@|xb$@&sF^tWz0vQ(yn3}qzx;Zm`cCM!qVuUa+P6bh2p9zW|xE|a>FNBUyHF`DKiC=&W3D=?dJ$EPl z8y*L6Y{`=FT=o-#8IAX9{p^)1Ej6}QoXfCiD});AU$i4 zpRO}9P>zO_KF`CR$B9~SI#v<}&7hGO@hY*_^P4p~K?Q7nzV3I`UUvM>)xeo(Tz;`F zVvY6Z|DR#ovK%jWmn&;*c;2aL`-=T?KMuY9Ci;N(7sUv}elIq*q?i^M?cS{C9opi2 zuq0dZrear$g95xluU|xvn{0AfdQ1jegxj1hLXC)PqKNJQ39v1%O`#&cUc1C6KmgpZ z1>zc*0D^OzCuS^3sFHPWZSSr>^<>BXLgb)2!AOPkyd0$kAG<_&E;sQ1q+oW#TOBIe zQi6)RH?T|Ji%5gHP6skYqs-*i$LIUe6dB{SwB+kh77?$0UsKy5u2TGX@-4uBm^ znn22@*D|4x!EssCbR41n`?Tn)N>p{RqT7r_`+pa`g8ix5iHpyuOzgFv=E9Lz z2@)Hc*;!cu#syhfPru|~n-)_FN&;u~vOOyuR>Rr+E?>TU_t~e9sj14BlUeg7MA8|S zLkQ&$aV82kVHEq<$*x?1Vc3hEA5J{XbJ7dJPwE!^HMsT$uL(;~@37@J-KQOe5HKuG z*T;ms3UeN~q6TdQ6r{05@3+7l&n&R+f+p&1ReqhCh2lkU0lS&NBE2^XACr@1e0G*< zj&z8swrn9c4GjO1wY;PyQF$Ebv^*6s?KLcc{kH=$7MRRE2r;~PUT$1;I`rCFOQf>I z@yRw0K-f%-pAKLAyR=Ug%Sk4ztLr7-d{swwwO2%**r)SSK4toSPaUKF+2cM>sk(}@ zg@WltBsBF_7w9XNIT?u785ZqDsc5(zlm#bWGeg%_0h80Zp+e54LAB^h3>lK7;hKpA zCX}|=Pe{w&Ye1Ja*@&{V0iS$-tHT21>`2If0v@kG6eeO&+>Tf_!dfchc`pRMSK&`f(z_TU0fkoAkM7FMhCa;41=yJ^FI)Dl^nWu z*T_Wxhz7W6S7K*atquStfaKgTrHE;?zV{|tRg7DSuFt`6Ev@$9tJ`DETtCI_N9ai| z;-1RxkGURHeK!HZE4pZ`q)hcBy5tI-9{B7B#U8>p_?RQ%*W5z6-Lc;okU}AA&ftjy zKvv1*&u`uq3BYao5Ic=kcPY;&d~ablzcTzLEd=dR=+%Yx4I2Qjdws`DK>#qffg8V{VMRY;*hN1CQW) zFL?B{(jP-z%`td<<>`p6^@_XbcKb=}yG$EyC(lcpG1?^+_KypUbCfJXCXa`KL6WBp zUiKy?b$Z9u=XMG+4W4+nQ-KVM;@&(<^z>EL0HevhWQTODt<}uNn8(4X7}6fddMiGawB9mG2(HFlJgY-J{&;%BzdQe@3q zf-;{y>Rl(UR;Teb22TH8&TbC$+lBH&Ai<_H4M7s zP?DlOHr;5TFs9(QC^LCjLtG~wA9BOHKX#&GeAlZa)cQJ!=6vVW*}rYfbT8(iTgZ~A z##2U$9ocyZ<5d_vjT&uACM<%lM>iu@k=KC7B6LA;6rPHpN`$e)P0LY+=%YWtjd%Z@evnGE-&l`y9nUK%@4cmXN?yG63 z>*D7FV)XhPWSSi_aojz}^}Gv9dVD_|49Qv(NAsWpkN3qOK(rZPQF83jlhCa`D1@(7 z*RY^~@S0~DX$hE-O5;Xpf(!AtX*N*3XyC$wIvlA!?Sw5Z`7JJBz5*m()rzaEF}IZZs5bU;J>SmK93~b zrQdo_pqQ^8pf}Zu^j2u?$Dg>dM6N14yiys*yssP-Vje+C5@&)nDwDbQKIjwy&hTiG84*y0hLXt zzkkd=G!qVu|0#N*Em9QsB>Mtc6``M{nAS@bB<~d};9P(2WSZm5MAV^l`bxjo4kh~} zkbaQJ{TAlimGPghSKwm*J~Fux(sMK8T^MCg4QIG(+HHN5l;)dRQiC7O&MVH1Sr zLAOU|^gSp=qq`#tJFFR{UsA;nD0?0$KBukvU?tzfek-z2`4nM@Q+4C$v3Dq+R4ryZ z&3A_cEPD9uNYAc>dVH|_qdzdBKWl!DMs(|WdM!xHH?cp*GIMaqiy58*ly)P+fn!{F zL~Ct&o5h>2CFbtcxBy}Bwali8Mb3%W4&B{C5A0M zmkaovH>xZVz2}tr_MVlkg2tRHsQX0I1_}{*&SncQm`P);^ztz^4TJ{lcxF+4pQ1rboVWql2e2FOd27du?1$`H%+~J37P^4+u&NT zY&@~uY$tk>xn}vdNh2+x0~|p~v)_tM7loi0E_a+pcbu2sTv>Ma0co^jAw~%@F!U8( z%-7zQ+4uZ@&11zDuhg%+xSs{wlnn?VkA6FiC_9ok&$3IiLM7c*jdwyvkhY^*7cldo zCQhz^GX)+pCI&9mb@*8^13j~LDuH_$R_`vgYjsH|Q-Uw40ZUz?2rmB1QhrquNEw** zE?e(uTHTHx6F{@%8~R6z5lkzpnk2#Uf(28kXj@8jz-t1bcd~~zMD-Z>*Sf0PSinzS zNMM>hB6mU8iw*3q>U=Mt&YNqFZl|N^)m|OK1_AK}0Uft%02y+LV>> z+|yYTm{S=ysJ9hpue$eillW|hT!MxyRJ=MOnsc6sfjn^I^qex#MlP&$)=UojY<|gm zW|J@8;CZ6@`8WBBC+{2Qc#S5}J$8ry6zaD)U7eC;y)_2V>V}1twx6r5>vl75F0cIZ z5__KAn8tzeuPkIdgD~= zjoJkx7Z(-=<@a`b7qWVbve4-7iMKG~SQ5z^AXth5oC%5kchW1&*a>-0z#X5EfsbV42T#j*s}q)39M*r1Y;lC0$z%jP+7S#p`>-UVxVXd+ z0(`UAFGr5|*PDON-lIHxvX^!D*6+tQcAq|eJ1aO0hIqd5-f*&4lJkE%ROP!5XpoXM z;j6&l(CvkePo$Tk-^mxn5a8i-h)Ai13y>?j`0HI;&&c83Cb58LBwaa=lB4Y>7#Z8R z0C>pj9!0{972f?ZP5c(C-m0WV`~dt7dzL- z>#_8U!JeuY>|$$`l%xut63bWeX0wfcg<>({f@{nx_e?*Y&SRf?2${Z$99E6v5NhmY z5^@{z-s{S{gGLucqi{$F<8NjpXu*~NJEt76NI*y;lqzU~lx+Rj2bmDy9}90Dm88&e zad92o1qCVR-vhdcx5fUJUz*2-4r@ZID+l)Lzbg_S>{#Q~W{7UQ^k*!&Laq+UjXI(J z-R9y4_8Ib-un2Rz;> zTFa1D{`>LPGrw+jIyf%>`r*wReQZfghPtU8hPmcoCTx+z=O7p<2zmMaiOq&)OpHuj z6~6j;ZFy6&!}x=!o)5I<8{{u!Vr9Azls-kU_@#qQ#gs=I_dPqnVgk6%L#&+=U9;Ci`PLq{shF|3 z_55p<8gMpY$9VR0Up#RADXHkzeOi8Go#FI{9{BiDe2A|DIM1kasRmAKPrtwr(+XFY zh)1w#sY`?EL5MJq3L{4en#f#2%WJaGGrAu9iu|mwAnmEJhI}p+vF`LrM*-$yAxKXmz<)+hY^14b1JJyfOiK!KTf#Ppixdsi$D-6UrePUZ zf3(xIz45yYbpg%I{)`-|k~NirIj>Oz@(P;mZOu<036fxMXRZ)AzzFZDAUCV!-w5!Q zf1o^su}c#z1%R~xX<}Sgu>sB%t4W}{X58H?%1su{1Tp!hx0geK1p?&i3Thup4FzKB zVWHpTOeZu$F%M!&hr4t)P|VG}JBGM)Io~}<*O{0v87E(`fqrXiA>3=vgtt?!3*gfS znILSbCzg>Yf+&I-6%eQAyr;1UxVUpQnn%Io?I+J!8AsrXPFHV{G<%I1sJrs|-D>^Whr3W$a_EWSitK^j3qlu#w+!al#a*aJusT zd>~Bf8|Q-t7Y}V#Jo@PP(uvd%M}c`8{Q2|NM262~D;_epo38Le#EZVTqg>FT5!nbH z%jq~q)skYn(H3kvS@8Z1MiAmRjc)Ff%n(>25R}2u_Q2>p^Aa4^=E(<+!w*2!y6NbV^z}Lri37;~TRzkX zLjSk-p1-l5IdRiwgQUkqXMkk3{JW+I(f&`2e4}EJA}@4y6E^q8hxh?qS2Gtycfa!M z^A&#Khi*v%obS=z6GneEoF+`B9Xk_MzTUs&Txg7m4WGHTd7vEPjydBJ43u0!jj;LM%2DPdRFPe(kzmZo`t&nP9g^Nka8bzfaqI(c?Q)@!2KW&M!> zAyDKzivS+mkw$mlEs7M@u=%8*x2gg@q#2EI&=mqZN=18bay8v|!x^t>+j~1q=dZPz z>Yl2)v16ZsZL?eJxfbLt7ik*4p8_;JU&a{>=XT$8=t3>nOy;mW?KBGg6)uf9P~Ags zvkS3D3Lsk%<EP3TVSfh%C{YnrKvKXL2_#)cdmZ>c^4&iMj?o6Do8RRyf?tnD9% zvRk`9pX<^s2P-NPulJ-GChgasJ^JBmLVUcllr({Uc##j!J$vKnW^h=b`zL`}O27Pn zPEz>My5s8YunyG`{oaQScr6E}{xZ`X1*|A8FN-%IxMY`o=vREO3%LJ9K^%pyFudm* za?-NxLL{CZsi5%g^~a9PVEC(LW0Mbq-n`}F`Hhvs9K?fW`Jf&*UvU(4opR6>u+Y}d1@~o3)hBqWRq;ACAmXZ+j zbl|&HzqLY|1|9jh6~Z~eIT}5wuQspzfpEkNDvoEx*mAdTlQp%=iR`_eze>+*D#P#p1zSI z2nU|3?fj{jc02ofPpa$JT_KXar(z*zLh*KW<_~~qsWYjk5lqh-$b!tz)3SURuy&Kx zY}JRlJZ@7wE_hf##e2 z@;9UgiTf8|9xbqP?jHgNf&ff2V`cNEiW5Sb7UB0cMea2R2F_ZXos5`T9PvVB6%g6fXkDm!564irWA15(4Id+7e%{ zZS4h>)KUi%I06q_m}wR>3KY%DUo2w)QtPP&dAu!2vG`ch@f&#A4NG=&0zVi)1TG$v z6vWAgXWXOQmcP3(<6;OkIGHwac6J7g4PGF3GI}-$kFD`CQ=3^cyx>cPZ`)M;ys(^M0=B)QW7@2}%?5}x0B+E>lz@rKeIMKo z!c_yBp@`Zf_??0Nz$01HI%QD*cmRKo6a<<#x3?V_ds(s4--90mhF$SCOtp}z z1L_iuIUhZiqtG+9o_9+za|y1O85VFHpQ_*gKsd}tnAv&?=CpJOWF-8fn}fHVW@LYs z#O5(|o=|7;G>JVOYe_U#Kk%x*>ss;tVI6>c#lUK6{hG!C#%U#Vd*{KT<=BtgMMJM3 z)-yJ7*RZ#9A=Z9NHp*-7k1ee;O>(#uN+UjW&<46cj=;Uvw0U`IL@~?zPi?u_<6Z`E zMf_9b8T&N6I@Kyiqj#UY_Edwb6!Q+6hz-jBBy{DzK!y?Bf^aDV5k?tTGz>OX9KYdyp zjsY+^z@^hFDb3py^KKEd9a_bJPWhNH0A?2otwd3H!4`)dr33-JR&++_?*n*5P^4Ph zn2;ENKSq^*@~dQ9L>eA2^LK*gTcVjPYFb@LA)ao9oRg$oAgy9A8K00#|BtQn0BWk+ z-o7Fr5V{x;5Rf7ui4*~m-ccgb6a%66-m7$w-jotlq==%@6GCs14kEpGK@bG#(%ZLr z%l+Rw^UY+OjEqjmIcM*+*Lt4cLw|wR0s|=j>9CeD{s5zMr})Y)RS^Rq^*7b7h%Z4o z!jrIk@2!7H@*fx4GYTp%Y@9W+IRlc#3czt>6}rvC|CF3po;)gxKkSrbKSWX1G>%Tj zafX#ZshTR^?}RF74BO+H)oD*&37UP?mYg%AL&?o zVXsl_g%RhoS4%O9Ps{Pqf3M%>DY>o|O0jY?8s?026>Bqt^e69k(=KX|pZ?*>O*iiS zo}_IykUS@LbSK&&`4taVB!;M4R(DqFk~d^8syc~l=5t-=Pxw&fSmWE&7EG9WOt118 z4V`7KZTm|`Ssvzd>ey`Jgnt9HG)CFI?B-`?cbjaq!rz$wDBH3(oTUGBsv8%24710c ziIVoHQyU=cLT`?%{t?Muxs9}p66#A=ycA{>aW=%YC0vIhW8yAC4H!8E@_v%NM1+=7 zOymECrXs$xMVZa=OzFIK18B0AC4l^5*WrAB4o8WYu3z9-A3rQU8%x0-pQfMvR;Zai zQDBrPHw5qS37G_RwPq0pG1rg+ z(oJaj#&3L$&#sBhHQ+ZN6p5r?#4R*A&1`8;C#LzA&zm*WbW1?Xk0$~H7K;6h7iEq% ziuSw#`py6}Y^(@i0|NtmdZ1SC+74NfN%PN0wcqu!#GNUattuDzLc|x>At-^P17yH% zTRHxdnCVO!5zfcWzxkBn=fWk4&Fg`CD-!{HV<9fBOixQ?gPq7whHlRL+%r`>pJr;} zfY6kG?33HwFPU|=Dln5`h0;YzHu0=?@Ib};CN9lYqBf#;@S(l8Ki_K^_23T z{jDh))@sGIu&Yj-Cwq!@^jn6nT(xUchhrx`zYbLWLz5l%r|usi<6Gupt$0qsfQ08W zk}vp<7fWalQY*W;P_ko}Te`D`fwHmsOHb3&)t^Tx8^ zgkywTrgq({k3#bfd<;@CrJT~ud4zZB{L?mYN zS^|2pP2D8-&y$*?5sFmM4O*wr*h_Y2_#&Qc^q*JXyeDjO#>D$GF9+ zK!9&Xexc|b#%?h=>8_jo;=^%iKkp79evJN|;oz@nPj32)>J)%s8K|3Sm1x=$K^ZwF zG`@X^5@kbEZ~$lVpPLA-m=?;v;B0SzFD{@Nqg-nVfM}Osg~|_koo;A(KML#;l4Ll& z+BRp5xMDAt7ZH-94g0Dqz~9<$94N~FxXnsQ)(MahWUe8nNjleRmEJetSmm=wubNuF z0Z=kCGqV;ua;QE_BoWHX4@gO+DibF_Z*Yzf%E&_EvpXOh_Iaun6Lz=Scvog?&7n?8 z+)A@MJ2Xho(Cj=;A$qTFEHPo>{dxzCK@fT9I-?pNMkmrG4dlGQjNC)h5W;s2#3A_o zkwW=)HdMdsMG07A=FK{KI*kK&r>r2>^pHpGD2z&WMM1jK-j3~{$v|z^%@D3=lXov0 zHgHDbp$4pPUzmf5g4%)Gmh#76<6!5bzI~~P?G5*#T=vmq*7?Li2avQtF@4@l|p)TJ>q zGf1npjSVNesGpD9I9Uan0&eO4Frv06^q@IU`~JQU#I!>fX6S)tt7uYuw~f3DTe>2Z z)0$1Q^f37J4r{!)3~X2}?m^5IIDVS!9G!ZbpORHN*2->n?C~gXFzfEWhJf2{%9B*d zURA6V#fzCyBXkP^;Q>+sC+^WqBhNk&l1w@E%KZH5RFx@R{2meIRWn5-<;dN1mTDb2 zoDulokM!Qkszjvp!$E{yk6dBarmpe)%ij+^QHf`6D6uyq2SirQwIk0z zn_qnkD~X?HYgWE<(I*n;Gs&9XL&IebTh$bwKcwVl9|B>}(v*lHvi)rGRF# z5wNKDUA4qp%biJs>Zg3rbas`n3Q5;XbK#U}2+C)=yC=PYwd(NFe26DNUKtfsv_R`d4jOYzNqoZV#jua^y&DBea@ zZ=x5~pN#9luq__ejA%})2ffw~vyH#_<1>HTWAibU9GcQ(w{v}F|JcHdSO*_HpA+}8 z1&3zi5-5|Zt$8EiH@ccJE91mid8017`6%2^l3G=zJ%qv4RZh5 zF3BzXt1%rgTNB=sL2l|!A;_AzD@+LxZ!4H%+0ltCEY|Tkbf1Bd2msoCLa&q`cL#oh zjUs}$_AgU1Z>XQN^?SkutvZ2I8?f%M)h!7~C{RLTvj!KH;5z*?C$IgB?}=@71fCUC zut8;xB>9yP+OV7#a0e^a?X6|Ik}+;}a!S#Ba!N{97*N7Or=y!Ve!|3A5iZSQ)GNxc zM+NMSwO?Gfw`iI~ey%e#5%3oe;;%vP@>jM#(}$e{eL*R7;Bfay5&{OO-vE;uvk_Uh z+Wni62{jTLL*^q{f*eN?G;6V9XHG|_(9Pf#rAvAUf3*Js)9msM4WGB)fTsMI)?XWG%&#t!d{(tp4GcBc^cv0p4S$`F2QSI4(!h$ znq-jES^+OVNA_x(Xoy=4MOM$M;_#FspONieBdm{~cE=EN+K_g8wC>S*b%=Gvijh&s z%-<5<=i630UWmta-j#*9Lg*@4x7P@h%^x$XcfDhljj=pFG3@0Vkp{X9f{GVu*ylheTN4oH)~r~ij#mPo#$t$WAH6M|4uLyuStLE$wX&S{YL}T z*M^$xWc;=A1D*eX*^MUyqHOIo-YdS0>y4*a_Ty;G2k^PP78l31wYVuHyUvEMCcEQz zV-<*1_5F>-J=0l^a_d>yWhj$}L)0=fSy@JZSvm0S${+*n^G+6k%k(`poTcJsU|~5O zGCCR3${n1Ukr5TOjD7c%1v~Bqe>zzkaP!`R zn#z#?9V!@Q*H+YCgr;gYqMmg|-rw0JoTeqDBeq_-2{DZz!YoAMjFXj>m5t@zYs1KoqQpQxQ)nnT6!ji-n;bplT{~<&<0=@b;*ZD z5di}z=xS_%rW1;cW4MF1FTX=uAN3-B`tf*+e1z9rh8GYcm2VF3Scy2T38 z6QpXGkv8=L7GCda`0Te3zN$9VGhw<#lLis+fg8Ahes@??e|IH44CkEnG7fof$+%BC zf|RD71Qp=?yU*$;C9A>r6I#&fX{;!Dr7dsQrBaDLgWm#m!Mm3;xuC0g{>;yo9Ctmc zY9uTguJUXz{^|XF^Yv2$k;i0eyS7<=0iYl-|mT)~47tU<*evrP~*BCi-37DGAOsQqBr+#^x{bF;N{guq`OpXclR{{H^^9TX4d_tt0B zum3OR`bIQ+fvI{Tp@U?}lwOIou51x9bR3yfwolST5qSIiU0Myr^}x=bta!UCpXk1X z*#AjL834WU_MNAcw8&wqYmRjAhjnfL%W)(c<9HxVyifT-I$HzNbQClw9LHhF1+8lKFT&UB;`Q*>O z;T%vlasc*3*g$t9%TOedFQ;<_^guA4`Cf<}aFH`3-Yrr>Z8K7-YOi7etb^VZVC(6w zFn3ZMMJz-0p1?Yb&0DtR<8?vdIkuQU_^>EH9%_~SlLjF7%Yi(z&H7t_f3vJhvyM$} z3xSd#bnAzGYJ?d&LOH+88I-B^O>@El&Elv^%P{txDAuV*l+S~FKE+)6`|kMX9swff zo`;Ipw-Ebp$tUCIo)tyuFGuO$CaQTX;w{={Rqq`hIVVQhM7@^|5|^DFZHW-`O4ng8 z7gEuAzxqU z9y-);uW~OVu``+)bYOUUKllC2#?j7|V)V(JU5#}2c9sDlmnv3;ch8zV#AQ6#$bbLk zSxv>C>N|Icx`VUnmfvKT5iJrfWMJCTCnw(f8WdgNQFevGQZqd;764*ri2O={P$!|W zwd%9qR4;KtQcKVQuZaeS_}&JFE?9QnY^&5nIVf<|MbjZ?E9r0Al%S35$zRZ+=?PCm@|} zLzCZzLE8GwdHK(WT3AKRKgZiWtTF-2H8*Y1g>{m(e=+MU5$#aFeOlPt`!{6xog1`b zEfAKxH9bw)poawuuGr`E!N@Q$w-;eE{T9(^j&ff+Pc9By{X4xW_ed3{X<-$~&Xyd| zT9>S1QPY+1MgX$|fjv##ZzpRB_a!A0K5K4qgfq6FoUiRIzz%%mVD=9ZIh|(L5yOG6 zkNCSGjP^IUO%du<-0h&`Q#esW9|LXOp%}0th?-XCaQ$BCf;q+~LuPb|Lp(xf`H!0^ zPlK5|xC9)BOJVR z^B9v=lT(1U{{aBSiP6xn1v(18Mm=1FYFLp)e*7r}B%?a@zhFy#Gxh${TV?AH`E@AB zP}!r|m>75*547s#JP59Zwm(z>)iN;kK!wrzuoy%xysLbA<0Wp*aV@ri!|@T_oM(8tIAtXV3k6=apw}v+8~;7q{y$ zlA!SeyEe=~_YaA#GFbjYc!Wy$uF*X)aaGkHLHyq{Yu)k#zZ?U9ni%$i5azBHUzYil zp2k2~DNmW>RQNl-Vn#!}+{>?zEW^swp!Ub#OKI=w-)jzb?t%{VWtSStRJ$zY91au5HvkGxpZ9Q2V)IT>2jTG zK8Lp6ie@h#m50>}>+TyPm#>Z0G2vz=MiPF6`HT&-qw^z>4OSi|?=mvB+Uxx*6MZ}V zJ*!%7SIjTAq`zRoW&`jYy7!>{G(WtklHmL(a?ahyE*vOqB~4@YL&ZK7I~kv6P5ADm zs7kf=Agmyktoukmv3rQGP!#TaKclp_v-RGz0L-I&u-|{9R!pS=y4TaW;W0wBI(eP& z24zV*_nm{5z4bp5^~UdFF8ue>7o6%CFpIh}NNi?L$3)j%P3=NPVwCqW1P)EHU%W69 zczmFJ{|Qa_?9Z;Wk$b&gG8O;i96hyg3AAjPGv<;%v$5=m{i#0EI9DPC@(Re%_#Tk_ zV*}b#K+oTUs`oasLP$*z$DkJ%zC><1zvIkZ-EjNzBS9wM_o!edsm@=)4L!Fiz0EZ5 zRd=Xty2hpaQ?H$SDXfE!?~ZiFg1>PH?FfELi?n(eFEw!}R(Hu(iEP7llX6M+GOD8g zBh|o=Q`?-)p6IQxw|6dbd4uNpR?`+eJw0jV@zr1*MlLpDO0yM@G^3Hh`0J&cnY|4) zAUAPiS~ltEZJE_7{wTs09TrC9wE63LbwzJ|oiM=C?Op~dd9d(}x0Y1Jo*Ib#W=rFP zlOk>ycwCM1*Pn9sb*lOXd}zO=WCrcWuvM|wf{DVIJK^w$IT^I8G9-wNyfojhT=8K8 z)*F#!8L5qt?--nHws^uWpAJkv?HlE8Tq&k%d_l)a*GS9L9om2f2`^#4YF6eI$(1MMI3)w}8wrzFa2QRN$W9|@>UiZS9?nD^^Q;#1HPO`>WY8~d`BuZ%lRu&_r{kA;=Gr--wPny z4?G{~a5O2nI^GhOxH?-0vNE}QEQnAfhT_^v5uo&AWMWci(yK9P3I}o4*>Q1~XQU-V z12n|i8nw9i-exvf1RyP6zft@6V%FqV2+4Yv;$j}pDCK59K+pkn9Wx+`ImvPJ*vnM_ zE0TVB^nttOZDls?+vv?-Aq&A#SMEUwOu*5-LE%18S{AsHrEJX7R<@M0&alnb4y!nyhA8iTS z9A{3_FVqud50VM2KNQ7@tKsIDT;BFqk!HVFL{DD&IiRde#9UHq{Knuj)$i+B`g){q z-|DTsMfi69!gb5vB8jsp-=KAKsHZX<#7RkG3~xd}&3YcmVV@HhMSN267_vaj^i&yApfg1rb3tPz4q!8}0bTG2EH09qBGZx;3 zP1F);{SBTQgeA0KAkk#7goiR2Ad0R>2D*lh$R8GE?i^vsX#5y6?DUXUGI|L}0uKg1 zN$(Uo`NzlvvFR5*=hR=L`c+$dSKg-3|HI@Ov7N)yMdzNye}fm#TkA)uj^}*{%&@0e zcbQ=LgeG0rw{I`ZM$q-LNd$^KWjRB&e)lwT?Ka*YmX(Y>xBw7y(*B%Y@xqz^Lkf`_-aW9&`DpoOWZA_nIMp=3{+s6aRz%}Ma2Ksp=EqcS|pGx1-tBX#x zAcbv`DqiK}ELU-7=ml<>C*B<5dF1@))7TzJY90QNOiUDWBV`yi3NvB#^_yznc46iy z5)0;%FcSG0rl+SddDS*l822hj9Ql(T+SN33{aS!%v_4N2U|K^;BjyLc53Jt&U1aR2*yr2mN7>p0cnJcVaVFB{@h=$mza!L8J6;4@Q=9-HIrG3 z#q$>EE~c-?AqiX$o?@EKTe&|H;|~^2>s@n7k~xVlm$7H=U2=N9a7Cu%B=BtI%GJwO z-N6JN5l3eS<$v#S=9z!53v1k7315fChvf3FX0*Qz@)dD&b4!o{95@&Ma}FF}vfcEu z5~?^&l58DZyOte)#ciqm7{H(BLBpfN_+yd*B|h?%CBmNax2M*Cm_?1 zV$pj3`%A}Hdf@J_Oq)YY@N3m8l-I?Z2L=zk2oJcPf~4dBbXER-)0m@1rv#|GpZliE zbHCw3ICJ@;C`u{%3m$pX;7U}Jgmi{dh2DE|UP;o{8!6|?dZdjgGUyaA=A}Yu@sK|Y z53$p0pl$har4!Z)M7M3gHFDPwzqt0A<~=QMW*F&|D5@ z-LR>A7Nyo04|PSWx;y$2B!=XmN#7kI3DihYk8wmDT&758S*!IDz1PQ)uZPc7h)#X> z@4{PdKY1_Kujsua3CqP3k7gIDronhDO|V*VdDdo+ry|D|I4mdh67^w47$skb>Q^)! zFYMNkD#(c~EoY$Qq>oXa8ke_!ZBzh*^A35y>}^>1tOoOPxIVf&2DsQ%wG=SKaFuW1 z1>o>%6G6r2?#wYUF(hdGD`*(ojm$M-{l_ws=Vtr=yxNU19xDKVKoszyr7Cx6IwBhc z%NF5Xoh8a2mM#jWJ`LWM6wq5SsPWv{+p7S&%W{W+0BNT&(1>YDQJ5I+){0%or&38X zfThC|N)}#QK>du}N2ktX2#!8Jf_Cd{?!OEt^1Tm6@M?u(e)|G53P)cqOK-gH@e3zB zFWa{scdt9GMGC7)w0YOR{Lg2zrZv22ziD!AVQTCQFDrNJq6i-laE7iAj=mc4coRep+C-wp>A~Eh2$e3^}&w83auIHM4oJL!r60&`3uw0O{w!zo~AhXY2 zv)<`ios4vW1>m0N0g4F1n8}9c`1j>!RZ3TyqExA4`fE3vICHnqAD+OTn-L-2BwFaj zBWBbvfKnZ+9Wm{= z9sX9yqr7zN%NJ6i(f(1GW(6C2p?g!dxE`30ap(k9q-I%7HONmlvQFM&;&Diqzo^xm zE&&eM~9reP{&`=4lwPu{?i%Evp*PQ2no4fa1N-|qfT?i@UPr+=hK0q9EM769l|1#_PN1`6(|sBb0pDtxw$Vx8KZ zZ~!g~CCHu&?8MMR?Q_0dk@ACC-F$y1Kb8o})B8jM5~2jNcfn$~Vu+${MxUVK7Y@RS zG`}>~mCZXi`7&uCCjl30GzD~z1SR-bX$Z$)|8yY!b4%)%b2_SdW;qlTD!Vuok~-jZ zvwuZgLwum<)~t=YD7E1>Q;4#r{46`(Zgepn1W5GMh8e$GA4;Ty-GGr!Pmjs#Y4@3G z34!g#7oy3B=ml`FcrFvf3*A9gw5;|UTvquG{PHS{M8!@x_K|T1|6xV*xy~<{VM3C> zMeXK694m%%CZCAK3d^S#qR8zL<7oCSC>i%5|843`L~nXa*2GVweFP1H4CJ6pN*w`~ zk70FbGXpk+X!N$}EX|7jY?sm$Qo}B8?$IU3dAT?8iu5=B^SGVg&Pz+5%RGTj4~N5z zehY$Ah>1yGf3Kl}Sz=vp{CRO6g>+%sZH;3x8N--dqPvhrp<~go7UBp4+JM$q+mS>} zoIs}uW$pBdWdITaAXffNvEX{}GtCLa76xBt>D5bOYyWX4tdlh5ht}~o^14{$<$nc9 zd74G~u)n|PQBgX_wjqQg_oe6w36sjzQ{gp|%`EPy-(b3ci3XI9`nQ4qh zR}nc2JR*b6JVC|Slr*o!sX@jHlg8y?iw?5{F&(JU=ZU!HNri^Q(voJlX$Q=QqT*F6 zQ<5d(H=KtE@wJ6oRf^ec3p&x7=;_cw;S{Tt(D|wyu=iXXljlNmK6b}3#AG+u(Tf;$ z5PfgRXRfKJtS)THys`+JZ0&vBDAF3necQ%i){`5EdQNKTq6W506|qsKfz2ORi{}@x zuWrM6s`6V7-Ha~|()>+JeR27M#6Kl(!_P|DlQeN_v+FX@O^){jI?LMh08Vw(R(`SI zXgwgE`%x*Rqdqboc)O`DUfHSK;F4Btpi3Pe=vY1Q+r&9J_#%pu zKBN-?$w`ChILdXA{x-av4ua2LL2gNe9ZxU?vVV?;W(*wHx;s3m##DC4C4|Koq_=ot zHssE_8huZ^E@Jin8pr+TJ{+>$0Ww7(15}CgOmza8)_;I{sr&6c?cB$oAq~ z;jUUZPH_G^{^8H}oMmzZsT8Ggmul^%*cN{ECK6DNG7RLwH6Lf5NMX@p;acpN&b$w);D>9d1BTu|#pg z^f48mt6Pf9bCn$pvtiIdn`(Q*_8x@lTFs38yA+ts*X@1=tgU&X1vHH*9t}NJg~DL{ zU#)q*yV3CFDR$G|H3iWOmn*8!M`z$-@G}kTbm!Yw40LpK zG%>kxmPrhv+nZ4946D4q1T;)O6BPE65NLe>47OSRHR-(|%bPMZ51rN8I0BGnKkduKu}b#mNj6u4kNEhHrsH&5<^5M*lVNa8l( zZQTL_RhqCEC4~l>cd4H;jE*~fyXoLyFSv=BZ1gI<023?ha2;`ow1ANaK^`fdQCk<5 zW`9cH4_NE8(p*#_Kj5lwvkQ_@KXo(IX}>NH#$x|j(f@h#;Eivu?}SQcT5BdY>c>Ly zp*=Zz{N;5QqawJ?CW7u7S9=#FX5#~|HUps0#h3;j1C_;k1@ z5yCY98rlf`V^)phG(csep%Z-}t}N(E28e+*qF)fIQ(DGp&=aG}2ibFaKdSipWx~em zrC_Tw_VdHde_ohj_7uYY>-$pV#r2j;-Ap4V-Q2tN2W3p&Dn^WKBD_yF!aB_Qe~`0yr+Zm z$Tb!gLp?qAHegx(uv0e9!STLbKlyNzlV8t#{BwM+m71W?Pv}^b}uG@Nv$}kULtxX8qat6Y3+j~-) z3yRlHJ*@}(Xp7Bf@6P2|8QCMdODi^1=8AePZE#$U$XhRSb<}d+=;T=j@cLW&z|?RF zcT2*KdemH=LZ63%*cBC5EQ3N9*13J>o$NiTPSck8;(6gRpZmNl`6+N7pzhR*`W=)_ia?Zj;|yB8Q$5RC?Q@ba zRdxUdMj2X{LcTF*+^ z(QXcKNo#Ng#hvV;4CrddS?m@vWpshT-2!pb)+`Ezf<1Dy@!1-cmz#q#$5c@RVn~JJ zD$K>jaQ}D+bj3@X?QG-#4ATn@+yJ6Vo!TulpOg<^PI-XC zRCUU~kHGn}{e1myiYn0q+PtA#%*%ZIQ zCV!v_E6qE;c~9BDplEdqK>J2&!?#xLFt}4(Y8nltt5ww}D0Hm0AU=z&ms6lVyF})GoHNb~^*p%t*Ki7kY_Vz_`17VWkamb;O`T12Eesfm0 zv&u%Ye}GiYRZA0{wPN_N8?Y2LCSfQN^26k_hFuursBLoHfS$aAdK%T@2l!E3|i*09@>~!UaMtNGGYkse}zUgXw zT7{EPxJW&z_+WDr(`u7^OHWH7=Qb<`gRHJ$=q%%FGaYUZLF%CjaL+vumHm-$OEmwq z43-QM4A5wW@OHhRiXJ%U=XDb)Tf2Z!InzhGy^odB)(Z0LzXozye;507s*(S8Y0o(jp<4c6n84;6wa zVY#wFa!Jo{J$L-=;{$p-sAOUjYU5J{8_2%;>A-pW2hc9M{{EF+naR>l2Trv{o*spj2rgE<>_$T zlB?wWZ|nKrzjq@DD}!E3`Vrh_^*M+unmx()7_XEDiC6i2;62YYoNj+`O#kRmSo9L}f#4qn6R1aV>+ePePD@ zZ4`htir;f7S5?#i9O$DBXyb3i_%8zw8YZl! zP6LYY002e6yI;J=Z=k!+%<@Fr<#ONbxuV6|+1VL5)9IT&lKkH$O-&d)astYg??7*t z67kppkUb$JWqf`Z&sUPFRoTBzoTiR{csVq_%+1ZkS@qnc6yD&bG_|{!VUvAe?kOzjt)y;3l@k`IB63OFVFyapkV z6Dx$pPr!RdSzWs#1IL%tSkfmee#pC?WUczA2+m{!K48hFzYWd z?Wxj50QhLz&{_-c3z{3;&$$pUU*`DpfMj#q(iAFgAXip4amoIRgf=yXVPkgkS>4fv zDTL1U%C>{t5&K`keJw4vgVYq>BN~;CJk9wngVa;sdxR;|e#}+(+$1Rhit>%LmASdO z0d<+UvxE=Z%8}Vl&)=Dk3i7)q2z_n{<(^AkEyPDjRPL3;`5L9Y$-3zI&(C|qO&caF*0ee zfP&Gmr})$KU&oOy*|CqX$gkW5$PQDGI{I=0onjUR!8ZHEIFx*EzsuSITMF#SkV2K) zkJb5lJ;iRgZ`78SBiCfW7f}5sHN>I?xsh05Tu{v_xCW2b)6G_fO>f1mi<&m{2R4@| zL$yo4-#)x$IYaf-7a}biu{9I{boqTNROTU_fEBUzv_Rj>ue;W zSA)7}^?2zXv6^U*+s25`U=*dK7T(RibgfFguWJ_9LtTbv*kS>_} zxcAF$IKbI8VZWI=;J8-g-kn(@i1j;R>)unNS0xU?WcJZpF+p%TA{MnbW(p;kHhoL5 z`pxtJNaBtZSz(bNVt}X$h-9ZpJG-IK!V3$4?KK)Ax4N>z%EH2n4SR1)K?n<3yqW-_ zA64Zm>9n~R%%U^#N0C6#{1=!%iaX;=k7VE$cVPbsNx@Dr@BeL8%g31pr&(b0at;iQ+bD8-ot)~=VKn}Pa{Bv^$D&?bEl?Hv??+7;@tbkeUoN#11T!*AY#2I7dY zwTExQTQE5+h{p*;FRPL6(;?#YKuB#etIx`O9u2ynY}MDTwWb;1DNARyEAUMb4rd1V zMF&HY`JY7CL70k9bLFBuOb|$_fiQXV7enCm_7_58+kgNT8?JMj8Q@7jWV<22;&ut3 z$-E+Sl88KV^b%UeYgny8FuRdmTzJC5O%_3~gIzQeHmgR=M&c-p2InOs_Dh9)yAhXQ zBp3r_MRc2PSS{McnjQ3?bYb^>8i+&FimuH8szdhGwnmQf5~8Oif|!TprJN5Ey8>>Y zFM!yftJlqD$M&H5W|I8&yv zAER`$-{dURdLwcl=e4-b_$0i_O#PEjrG{OoTlZfV8PRXLVGoFrXQwBX4xQM7={d6p zV*s?EozT!9u!}E!hRA7&#I_`ijw36(+vXODd=bX8b=NR&XKEjlL7TURB0lK_7%}4T zTOw#rAcqy#T|=dFo$a(`LUduoO#x>=?i^oQ-Cdm+bKU&!LY2)~htNo?lcKY2KsdjQ z(%Sw?pWN~cBO%vbqFUUJ6~WV_z>f(Y!Z2d?r{sA0u%T(wGD;hBNZ&=qX~Oqdu}?12 z_^E6S-qK*~!TAR$>Tt3@<%02z8Z3*4ysvgy2fAVmgP2;o!*=o7dm>9fN z-)0F^jIv;ObiY1)FzcL+P?qA`(kd>KDdLp*ZyoE?wX)SijEj1WJIL% z*wl71QmRZ68W;x1Ee8=!Uxa>}_1%NqqC#bD;P6Pn1DbrD{LgotroW-tNF3{ShC$5b zwzV7VE<2h+3eZ(yCMM0JS3RXnr-9Qc@Jl4<#nQIqr_r-uk62NnM;N+dK^CkYY@xa( z@N%5Pfxq0{uLd1HkTw8%*$b*=_GY0*ot`o=LtyEq!P%C5BAs)t2q!0}Y1;5vA;`~# z<)27ddJZ((aBWzzpjqr${g*_84ve4wL8Q$Pr=|mdDI0<5azjJb&)aYBq#|*J za*T7oJxmsqPcI%y|DP0Q5~E*f(9Um?dyO+$)_}|dtsSx+ez7S<=p%N|*u=%=bb^Y) z(YNoBdUp>$!;gNE?~?54B2h=dgs)jQY+35P3O(uq*Is+kfA~sB(Rtk1IM+0@JacR> zbg%x^6pRBkQ>LLlEo*YY0ex_z#n*NJIRDhr9ugBg-re0r<-cg>&qSs40|+K>y=Lcf zauK8HJT}kD9O`vwrIAA{Fh4qv~b4ed}wm1H2v9&=iJTlY=GAtVEh*zr=;O8c!r7 zSeP<$cxK=dXjTOH4`@(NK-G?rG$rcXV}yWkZ9&u z(r07ptlqWd+5|=vl47K@y-K0~y~to}6sYdm>eAchGPGYs@$r&zwd%Z|Z|=};WAQ%@ zqgRJL$>tRC=6yiwp+mmeO*S|zGVQ)X>>3-Ny!D#PHCuU>#W?rz4|*eUkKb4Yz=|z; zJXboFc(sX$9pMz<&|r!}J?sjZhDpn0i|y{uYJci^oKNbN@yY@u*k>aFx@s4y03;1L z&yM#IJ<^-=V{Shfq?k8Pjs|+G&Zh~9+S&0Qy*aXbE;l3&`uqDArT3~hA8c%=34&?y zf1d%?n9K8CAG#H)BDo=JZEHb9Rq)5pIwbIO+ zSdYo{M>=mvn)1dojkuU<22!BM!gHEZVk4d74v-qET;=ZU58f;ijUX41wF`{pgn7TB z*@q7lguhTyT0xst@>99wD@oblEOGQoZoZJ?7GIK=DXW__|h;xE>2$^3EfY za|bS9FG5d$h5hfnvh+rP9Q(#+eY(z@os>oj;3jpr0XsgywS36zdt6yWLihXcQCopK z3pgYk&$Bp*`6%mRkhNKMRY3r<*p&m9s75 zpXaRjG&~}1?q2|maM_nrz|99wkT;us#A!}A;HQA4_Q9boNTTUEtuXh*BeVyqvK zSRChN(*Fta`E?WO)WCiG%nMMMNUa+1n!dZgXV*KG!v5z`cPRKxpUa)AMmyNW1sC>{ zSO~XK?F^D{9gkb_ZO8g3BvgFhjnNox6)LYE9B(}FvU~TI>#0~+m{R6rTrAX-7b%X= z{$VE{NBvpKg}JAv=jpAhw1i-=qo0kmGrFOU?_}l8W(YiO`8Pm_B;nslxifHftZ}Ek z9kfpX2ov`$JuP}0P0=khHXWkU`M&S=dQs0^2;`AM`Evl^Zw>Jn-M9a|jb;Z=0f?nl zCVyX%hkU_7Z`ZcXF?@sl8wB)4tS;V*;p(n>dHLjr+$qv19!dQ;z_8M?wxy?2sM8Gy z3_W)D?cW|{duI+OTs{1TA3uj6fs1V4O@XsU5-39quoVZY8P~_Hje^&+Vw(HvDJtv#J!aa}^jD~^!%jT~qu?*+&ZpMHU zFsj9jy$O*TS^aH>P!>d^pPruPtADApU+5eH8)5X1N(C0;y}G@XrPRqU*(4^G zr1B&;o>Tw($5fC%0rG1?*gBx%pT)^R&EJ1scy3}H`#LQRRpSZ2tvS_a74@Uixr&^l`YLfUdTu;*Xy)Zd01Xg2me8T8`_c6+a1#HYS_&I#ePrh=Gc9MoQ$OT_me$; zfp{)kc5~p?gE+XJkPPQFvT>hu*uukJo&y&z*J(%9yethn2R+^Y$JA9oHQl#u0a0Km zAr1rqDXEQ8=@4bqlokggM|UV7{g48qV~BK%h%mZKMvWE`kP<<UteiCd(N@tyVpJA(4;l>-6dbENVk{`-nzaHk+iWQ zhoB_P^jiFUL3n21RoZqy51)#~e-Wc6r7tVbhZngT_;yVUDSBYg^hYS@trUV9RQ)X2 zborh~HIKul*==cP_C+yK~z!U2}saIwnnu&S!{&8HA*U~Fd7F{Ezp;tQsMqdg~d zYUZw4+emorTjMKfQ*g{WEZv>4oIM{EDVNMTIKkhp$$?XRIk^xeq$fN;)?o7~Vvikk zWYH1JlRLrgv77osUq}!|E-l#+*ouwGUo6~Z!M={fZOy(BPws0*2-z{C>QHC#q%sYN z_nZ8HfXn^4FoX~awX=z>-eU*;v{l`HCYur&+qv;O7}-zm_VL}*kUu8IS(eWgpF_k& z=<2TbH#FXNS{oJB_$6+nx)Y6;_lS;52B9aOe4emD!<3Z2Hmfw7pt z3%2-tX`a#w#W4xjYWU#$q){|@KA}!d6|FE*j8KHo!Nzag+(sQja<+#-INV|)y|KcW z*aciUoi6==8_Pgh)sWCondSSdnP|!|Z1JPv#fQbsc<*~;7)$>FG;9+KsE(1=zoV~o znxulup(L)r=@!_-iHY+&=DX%0{Lu`u@nmK%vjgNL0MwnWZieZjZY1#JokPBz)9Z!a{$z?;V$RPe&yw z+wTnpP;A`SDtX4k#II4Q$#zN2_fJAX-&NIYUBwaAtg&8KTlSe|Y_)mMvqUGp$KOrq z&LhnC4Bi1WF#N5Qr`P`||sy7!N%XMJBrc1-BuGHJ|H# zGfE4ueJuVw+3b7fxy~n5I?VCc#5%U?yn-u(GKrs%c|N~PLfX^Y0piRnD>jh0E-lNu zvz4DuqmiLI=f_nf`K}V{B_Y59Ug^8!#a+ca(r$iiW6L&KrTbmRvX34-2vVCD@3j4W zkE~VwbBklelI3^KR;yY2I$@Gy(6f(-E@WV5sJbbJAC z1}2B%9_BtiT@0Nc%)0s8dGLN?ZfB4Pm=mE z$=UovB(>K^IEOCZBUF!*$cfHxpe?0zlmYZ-4C3diI4HUq1Ir(NiaAxh_6z@0{`kt18hq7_PJGu9{b_-QMkC66Ig186fOAEJ^k>@w`m> z11b09*4pT(eL)ofxVVFzGf5jSZVIMU;rl_^L5fxsGt^&@`Z;l;V|TDz@wGQF2nOn< zvQA0CLt~iJT)>U5CdhuezvI;VXCPtd>J8ATf_hXxtq`eZSgt1%yM*=n)jK5--5wQx zXghZ{rmST5QmFj4gYvb)<$lNG-)Yde>IK@KoU};#h zO0e6=@ii&|M5iJjtIv;m!&Gl}#A;La6&g}&dT3_7_m{32!y1zqBGCt*+5-_CBg-x6 ziwPbvzWau7a0hLd%Wz;K>A2xN%#k3Pt2Fi01Iz=Uf`=2y(RKa{fh z5dTm-xjp{N2$GGq@bfc5t=QLH_6ATjH90`8D5d2yp#Pz~g7BX;Z~N+C;N^j!hVu?` zniS@S;F!ehc)cqGv2!O@P&1dkc;w7a$a3Y0+D-jId}vH#g=5=|P#WY!AR^}q3>9}1 zjX?qB17McBY*MH(b_#m<9FpDX&=)i#bgjg?Ej?1~3jO4F!(l>OjhNm)C8QGU{(K#O z*d9DPFc2rZNW=%mCMaOXYBNCqMrq~-tN-9T#2+bF4yEXBD*~|j|9_s)I^8L=4A)Vl zqLn_*s6;CfzW}@ByY2vR*XRk_81XX4_|*b{gtt;@z%J)@O(H2F z1t!>wyc-R4Hu#-Tu?LD(MB(p&(!QDPyeRXu==++H$CFyUz^g2)BJFP;GHY&}1j!u- z0jvwg(|~MThHk#D%91eW-|v56gkbzGc>Ak78C%C|1!Nvj+3B*dO246=sB!tZ@tyLb zy$je@(D_kMlpjHNEA{(Jv68_xD394Ax^r@iAEAsar_tpeNGey2do*pOgoOdZMzVWu z0t8>SMcg1bpT7Y?7H7?j#L+inQw@GccUL^9s-!gJqIRDuWF}t8vJI7 zjCb|Hll?WhroF9;@80WAtF?gP=$3(4t2|`X$npf4TC;Sq!0c$m4c@1+xowM8{!+7E zg&|zDOmh5D3gD#3ww|afa*PXzM|7av+(0ZRF@cw*<7^z);A=peVBByHQe*Jw_!aA` zJz{vjUf!Nh*6z=b*(Sv#5q;>6U4H<8?)zseY!m+iQMTBs=O`-_mQMQviDNgb`f?}; zSjW#@Ga|%n%muB>-9qr)08%1$fpF5b%U5XMy%U+xd0c!0C%e=c0}{JFF}7zXmxMF` z=*1q2p!?9Q__wA#Bs-8bO?`y>B+V^+5`!@I4afZplDe)ktyxy#NJ@p}ulhpPwD6}` zX>eWFF2c`sqR~V!08M(`!pM9uyd!?_5^)KTNW>xL+T~}@|O42S5LN9`y*Yjnd0$gg*`F8-L75ydD4u*<+9Ipa6c zM-znp%!w0qLLvVUxg(TENRXCvh^3%4KVc{4kD)%RvbFzPS9tnfJfR<__2MeeFG6!u z^>>8J$K5{f{)J>15dVTpi`L2>-<(Ve<3IS*R~bjo|~GK(2D|a9BQRXU!aI zquBoT5h1n7yXGK*bZs}C6jbgDqRZz(YcWe_z;-F`VF!#$xM2`x%K~2TCyUvJavY9WzXMet zP3r9g(58KYXh@%Le<2|u@q_T>@aj|GyBGQ^Gw3<_ojpVpL-})cFE!Ud|M5|i`osSnw&u0F&a0A}Bt}nyvW7VOZ#HQ`1G)x-p z8{G>-kH~%9+@FsYGi=9^=#PukQL0=Dxdu0T^Rw=Tz#0hjT$ym<7bE)LZvb*^QgJQ)XU(G7o!-daTy5YK&`$vk_ z!2#_LwpcwaDb#5a+)n;5!_4XNQHL)YmW}2NKPs*{#(pYpbzRP{w{UhYGY}ZOLXUUw zgfx@>(p>?V7E_Viv{c^-GY`JLZ3GxoZi2CqH(t*8{vd;VISC61^5sJ8dh&XtC6m$8 zgBVZFWxbsB6)Dl*Er5u^;okA_BrJRH(g;D^QJ#Z)=OcNJVDS|Nc3rQtP61eS3=|27 zNW~(qpeN&EJ_-&!ZbuetG3EVOXMzLaOmeg4j}AT9gm$U~l_XS`3KF5bSe0BEWz~Er6-}zi$fT6F=`=d+?Pv#JcJXM?A5`pgWd;CS^ zH$|8qYleP~A|>ZCNqMhgEH3Kr2j&@}1ZzhJ^3-IB!(+Fi$wv3>KSsTO-~S#GBO}!$ zS7QyRUqM8lzeWhi2VeedfAbMSFzUYQ}Z z{Q3MA5U2d{&>98J(H}pG1^oXt>N_u2BkQe|m*_LUipG9t?n?5~GBk*ukbFU(ToFP2 zq?;*5JQ^DTG$$%|y4}qZdA4%DHiaiSB5=MCUV>wldblQ{E z)LVqSPwl19uerc2>Q+uxDRNZsb-*EUVJ_1@$C0A^G+F&@HusFB!&$c9#C?W*CUjIW zO$bSo=CP|j$QAG=`)Nszf+Q=^!4kQwvnb{yUI5xN1c2S_co#3|G+Ai_tOl;`zWwV) zW4$*}r=H`$q2puw8mNyoA8rSZQO~bj024KQ)1wUDpKym zG*TyW8IBeOe`E4T(P5-9*teu>6>AtQ<4k15!pjp(nF%kOxgD<{E|7bc1H&c=)~rQT zJM@{Ygy1l%yNE37^2B81_KdSc&SU*+k%({lLQ)A}DW*=lpViaEiITC)#GSw9FG2w` z<}7RMoelBTDB3DUzC;6>@vkX8xSz(*+YBon5odpP@%&#ey>)g%`Uu8Q`^4(E#&^T#=l)#31H!B(yp}W z;_%1p*~}5U@d?x1?7+Wus&xKnORL(oMD!uarbPbb<0896kyX@A;55}X5z@%RAR7?7 zI)JM_H?DlUEMt8p_e$8GS+S@assQwRqn^fdD)R?0ZXiop^i^ZBBFEyjiE&v2_9anw z6GJuS%Pjky36~@nYn_4j^u2T%d*g7k@q9!`5zasKHfZ83(Q1yNHemVxecbRR$;*S7 z$dC6P>i(o9I`2Lct5@3nMYI>+IA7mHa&XB6jv6UjcE=o;UA#1$mXrRZGfs!Mnytyf zErY>d?a6Z=F^L@+`??X{KT;(X0Ar7VJPo6#BZaoDw!Wp9pAAKt-no0X9GrVWbN09x z@tHvghCYN8Ola}F2(8}gQ~KoJ%0G*~gji;^OS^`$w5K z6Kr6sI0Pk+ex%hf985Xd`tAF^F}75z2yEs84u{!6!6~$Yk5ntTZlP)5LPA2~&KCzH z-laUr{F8u;=ORaS4?x~r0SCNR#JS_9}DAMT+sPE=$74&s2Mr1vP{Ecam z@rLgXULJR@=Jk*&kI`bA+OxeGr$Fr$AxN0Lqjvp9GP>voE{?{&nTW ziS>+l8izARH_dVTHSTSa$`ZkAQc3T1t^_n**1jkjvcw3{?^!MXNc2)J;&szJrfFd1 z(6&`8B6V|_^LLM_DIw^FnQgz- zXok1f_0t_biWm8GS>u$qhp*2_^2J~?Q&Y7uP_u9Gz7akQeA&&{CdZ&{6SjEENBbPB z5l4W`-Gmr7RYs{*>+#T!@8K5i?z(!SF)wJsoP;y-^9$)YA*5Y;KT@BS+1-50M57~ zS6#&X@;AoL@v{yeEfDU_xsSKg*B06cjvc$6MKOpuMM^+-+9v+$vYtbo{*6oXH`7%@ zl5h!%b5A`3gART7hl<}ZaZOhva&XE_%lB3OStqsq5@oy0{l)hzhi7+*l$_$!HVzF_ zw0|9iSWt7k4H9||{-(XAx#p;C=hs;2tM%?LqmHKW29Y;~j3>|BzFOW6riEMKfx7 zR&D;0S?e;{-on0T#uj+$)l{2k@*|vW$-N^!9(};Z97aZm65U+L*P_sjJtbMRk}cPx zeRr=;A)a${)(t038(41uB(<*Xej#y2eOv8D)y4rbj%(-u>}*JSiU0JWO)+dr;Rjgb>8UYLI*v;R1);Kb}JEX0>d=&<9L<7)9 z3r27;H9n<>f!%-~EQbLa`caXQ-8Cpi9^@W+d^6UfM?Y0HEF7Kv zq85riWZM6wDr0e`qZ%nsd02J>_Kh;pD{A3`73g zmeYE>m>aqSP8OP|I4>7r%|TWy2KKcVMPKfXS>z~S!Xn}x0^YTZx;XdkF3kh1W&py( z8N=$;>)M#kduZqLC|etq2M-=d zl@3U!Am?>br{+;Tu-=Ebaz`j+S4%BHe$Px8hTre|^u8lcI-3@eSW%gptVxd!>&Qt) zmM>y-GE?8{R#5RDB&rI*pMygJH@I+~nloXGIKA>QOi|A(+Z{i^qZT<pk+`&$= zrt}k;XA*1K$*pq=&Chtjd-Fqqr{+l`q~h-QH}im;Tv#e+&u_I%&DAwknd|a?ewM30 z#c1^aoK=-ae;H=Msii*o(9 z&k?B&))a{`ya)36@#uobWY;&KI@*8jU?EWW;ltqcE7o_VC6A8VY`(=kd;k)zCbFLR z`H$CtrT4opy1}rEekJZq@rOZQhuB1fl>e~*jL4d#%1`eadP%6o`4f>hxEk%5eWL2w9XwPdVGqC#*e6Sma%2y$q- zeV;QgubYY7tZz-=R>)ZW-dXZ5SIY(#1M3eBcerHd_YeNe0iKXed>Fl-I`$Yy(K3A4 z5+%Ka{hMU6MyphrJ$+@B<{b0c-CR6lw9W)}{bJ-^tbQq%)-e~g2sfAhqKUffa>lFuUMGUrxLzvHz%$e*-3HTCTMZ-3e+ zX|~VQ9|44WnSKYAO(1)^M#@H%tY1vsrU&w(t-G; z@@?qLt<4JV?gK+){CWqzE3}}QI)o@AB(ubR#fgCtOp^HG4Q41fMZdgbr6*VLX8J`S zMc?^UBf{D5bNiWQf!57ry~71eR&;M8LJ|Q6CnOBE2)+LOaKNY)t@A_T1ue}-SKe0r zL%EX(C!${V^i)guhbPlzS>|4TY_bP^ZEa>LQKB#MQ`#;2>f&vLJrLt}fuqkL2BO^TIFRn5#u7<|W zeGRyv^*^ktU;H@jtCme%^ZZHn>oOC#;^{WWh3{ZT4=UdLa{VpaN1u+eFAFUX747Zw z81+Fyy$(=Bo2#Skeb2e<<{9qTuN=>P(H$f0>=o>0zyU8~?Wsu6M$cZVIXOAFn6lwt z$G;a6LJ=`+XwjYSmHX8)D#KC2h6o)|VcELvD5p`|B+db-IKvoeHO)1ETRHhyu4TJ7 z5clypo>5q2`VL#L!S-le=})Tu3wQ1>`>-FpM3q`x4g6+jFvh1y!Y3_bUtd}Ag~Vw= z8iNJs9pj1>M?8?nrm8lXKX~~`vy`uMn&j`PNFI4Vvf1(=+@9IXArpXRoytX<`J9{| zzk0y)rkR{2Kj7|1)x|p+8xn`l_(wa(>YHx?TvMxsHwUHN-stLGyMBGxG^64>Ns%LV z@p1Ef=QR>KtoI*0x;c>5>iW$QVe7eWdJoKM z)njksG9n2+N>4(VcN7#BVkNGU+UPq#9*LnY7Z^CIb`<-<^3PTTTqW`?7oEOx>Lfo3 zo}_vcgMEH8aZV)=O7jSwda+#RVR1Z>*kZ5Q+*qf#2AFgN(m32 z{(76Z3Rc|PXMVjs2eJEWAU}#v-vDBWe0`VOYA_@9op=ocHw<2#!{uPn^B%ekylw%2 zQIdVc(|qlu%9g^Tq=kjUivn;gFHtTsmoa>^O{4%f-Wd!W1aQD8$2jjky?s?|9+1e4 z1m01y1s3mkr%2$!_1=A|QJ%jX1AwdOM}IhmZu~q?F~RE+=b7qd=z4@BPzb(Q-B3LM zE-XvFsBv)mzY#UBv~*BC!}-)cGV(f50J^xc>oUtnlO@WX&#TmIvZe!o{oBmdl_uOz zD;6)q6MjwWHIJ59d@Xq14A2v0UW{D);z!<8%YBFo{M=CvjE0TRHqAY-eObrg{ahoZ zzk!d5Z?MYIq#f~6 zkxn)p?BKfIX8uLN_fA$SP5DcxIOnN<$eqbj8pf!ygSfs9jEI0)m8H>A2)Ghq%Ka_1`d81s;%qLURa!)j!zZ=Yh|eLV&q|I8mVl z=+JD+4oVe~Uo>aJj|X-r018@PxHS!EL>|zzHcPRP?(_>E08exd(ZT)wTd-GIdPRT; zeCwPh0daZ0RyfV$X%^B+7r_d;M$w=&dNQy00{M(-bSj|6n- zFy?h!HdefitUOwXx#gMoj8ZObLxj+yN$-iaz!7_wJJ%v=k080wsJtL9H_VHecT68T z#s=mmwS3?huoWvzUQ6L~{J={yUi)I}$njqAvxwO}K8Oea7FaP+NrUx%glb97n2~}S zn}u!6dVJt-C)87+J+=@Ws`CGhzLW0(S!^n>@+zX1r|pcS8F+SouueehL$U@O?4J4o7aMsy194}CMz81#gmzTYla zKR%N;x%MGhGuIwuMFbwdEIuqQr>4pD&_s9xGI64}aCbTp{n*3F#jxZq+9`mz^8Gst z@N^Z7-Ym{DpvVm3IFkyskwQn7q); zuYSp0(CLmMuZ@{X8m=K>T9l+B5GRf+ej|EQ>aWu7=iQ#ri+ z@T|BdYs~Sz!79^9_c5U!De?8@A6L)3V`>q zkxI9hsc{jLV}8Rx3AsrQODpG zKiafC)Xy2NQ_N2Z*Q$L+_nuR~C&w2Z2qX0*C_>nG6tq%vxR!h4E&9P%11FV?&|E#w zmi5}NJ-@F9~rsM$3(RFwo zor38V6JbWogrLs}9Yo&_n+Cul3Jb4;(|*MOiL`@sHIq|8&+g_AlRMBPVg!34bpZdU z_~Hadh5vbyCAveal8gbMs>W#vZ~!m~G(`zn)*msHq9CPY$gNwqE-o(UEt?#_d*Gy? z)>FPm(;qqHb~)tOz4`uvi2a5fY~@aK<-AV!Z5EQ98+hygom2e#fl--fMuOzF1fs){ zGKV7(wb$_wLNUJ6L`O;_d5P`YK>X)+c8Vy*_aF-uMog{A3Ojg3b=46%9fSCo^gVS+ zzeg*LK357CZ@B>txA9xiTX^H=DFgo6qs1Ux^s-WUWrp1_zXa;#X+6`}y^}9ZzS^!I z!GT#xGE*7+%Fc2B=j+qPJXBpbHY~>*?Q{OC(Sb_U!Fwp||3PXDP-gmtbLYJY}YuvoyC*LqqV!cD&yO7dP~ZGk=uQJW|AX)Zg*$LCGYv; zhI~^0_G=_obuNU~)KcTU8h^_|Cmkor=D`eG}PBdoZ{n z1SV7SPUdL7ksi(uqMNrJW#0e@IQxFni(vZ%%>5t?t?rodidv?I2~?MAbr+fpwr@?~;RN8qFt{V?0bvZ|Iqj$qC3rZfN=O)zxvzln*)g9kqUzt=S@G&O!cS1D~rvYV`13vkx#x(L;Nd zV#hnh$gJ`5X2*%De5<41^^3Ef;0cd_N=j=xs>Xc}@hO*$At^_Bh*@SccZ|i?)79Sx zzyjm7?}t%U%&A`Pjw=&Y<`dWPFG3KNI7GY9YwR({VTv@SkpK-t$u5rx5 z_6ctYKgKRnjeiiR2n|i&*Ea-{RJ$vNH;?pG;sTr((%7@P%G0_$>{^;=y^l714=zE8 z1YGZbn{R)^Uu__eKRPg9HohBwH0A!~aoXtj4S7`Z8& z`a3{X+U7^mySss%<%lp`dU)T;U`wO9gs-Sg2H1{w06ujP_LI*%!2dES34#T+OaOtq zR&qy?(wiarF0wo=#hw*it7|GOkn^<8LjKX4-ysv9A&$!P%EA60iR~rHU+z|>7%WBx7v)KY#OFlbh7NB-S80q zg{vVCoTkK%J^WpcoG#7mod^)y=m|loB9AH%k1L%60P24g2yF<06Kp}}L(5@u%RFWKoXa^@iydofv=>SS|_MF)|Uz zky2%TeEj2QFVOz}The0Zj4hOtI3%g{-|4mg84EESkjTF)eE0XbkLQ56D!P1Qt4!S8 z!BI>{R3@Z^&^QVaWho$A?FJsm}@@~aj5R>-Ykv*<<%dEAdG|Yaw z@U&Hw((~HT`T03OAG(V1t+TMti$7{nlYC1m>GEPoq8FTqwM6Gt9JeBqAtm_ zYzVDxFDXAEkrP7k9{@8y9Vp5bAm zClY`{t3FB;y#Wa)Fl6%-j6a`U21%Tk{|0W z)vHj{W04ati7>baYS+Yc>FY=88#wN;3>uepWZ*LPw7vvdjh9-7zch7eYY#!_I>`eP z==RmtRz=@zm#o625RD&{U7ur(m9&Pj1k&7^Bvm~ZA9rv0+*q-~J z{2!hwQx^cak>Br=iDdQ9z3kJU$I4d`^Las}`F_zY&&ilss)1F}Uv~EP>ssS9|4#P) zej4*>LY4QKlZ4PRx1uvc!pmwdf|9KVWjB{R!$yvriVZ z%X@T?U4JH3V>+H>YvPL!y1}N$quS~+rvH`=$&8)3D`Ef1jR%SU!vAexb2R!94rPFz z!OVJL38|#$O!(yje_;}7 zalVqGB4<7uP65D#k=)QlAelV!~hXge@li02&|k_#Eiiyn!m+K;S1D82;0r z@f|PlIIkZBhUS^nTks?-S&pO*|SVg(6_2_KWCGCFN2>(foCjG@oE*qx#zLdv`9R%_si2omq?3HKME zP>&2nY}UF*8HB_my>c3#GQl5FU41ke5F9#U7Ikt`M)@1_lPytXQtk-bkGfOS8d&dG z=Xk@5g&M9d(0jH6{V=R(5SG7+%<)OPu4-rB#>8WZiR}c)y#oe)em}5wny!Bl?V(=; zCliDJZ`}H~_Uns>`y8$Ce!F&rI1*QEf-D9ewfb?W`zS>vw45}l7=*cvAcUfnT5@$U zK-c$m^?3b^{}HCj?)xc*o660C_x0yr0uYAE0qi?nOs#Ne^QeAg+WCRfeJ)=j$hct{ z3ex%EO$v?<3L2Zop_)z2;$E}T;(IaXA&3sGyTS?pyf7MImU0BlBneCcurD_D?UpF5 zVedsa{?0dvQ#3V_2F-*6&0*?cK1GO)mGCCZ(;uC#L=cx@Af;E~E7wQwgS+^VoLb5C z=5Ane1<1w{ER$J9<~LBZ4)bfA`OF? zpETS?19V?yLz6jCh<#VkwW`umxf&h2PW?zansCrCU94bDVPPQ^tL*vF<;*PTOPLNI z@87unJz^+FIzoag@EQPd`0KuOqjVQuup>?=(SYl4l_!UcY{qI6cax7p0xbI7D?0Z3 z3_?X(V(IltGV%`M<))bZ)4RxRjD|A$S@&fhrK-phNv|=hFsMa#ad*)ZeoOu84a^^j zuOr46EE4UhGiShF^6Xll<2tg!*!%mYh!q&YbUZ$IiPZAP5N_^y?O!|eTdW>bzq(3Q z!#<>2WH%%3=F`Ass0T$-bDl-u(2M9dFUI6T)Qd13IZNEAD^&wTfaAJ0JA^XN=H zX&1|3nMh+uc}%{603f~;Gg7v|g_*|%0xl1J`~ z426T8JV4hupac}JOI!pWA`GNUWhX4|;wA+3IrkKW!PqoOrp)(YTi(v?tits0r3t|f zc8YM^OwR$09fF0ysoaDgT~UeVQrTD^tg7H-c!+&$s`M!Vm+2c0ET`SazitaeG|G1k0gB1oZc}H|fKB|!uLGxy_D`h%q>H*uj$gazRBh3k{f&S!WUOX(DZL6yyQ{>9 z#GqD3lI^&D@?$NpFE_;Yr*|i^Q=K-y)Vz?O;G!U*GYA{8dcbWW)i!%lXNXvfv9q$W z8h-P=H)T_C;JtI7G{L98b;}X@vr*99rF<5djA&y)1C^%iq+SBGU{E$0%(E@^BKbU zNRmebt0WYhdHxA? z9lKScSUM~J18jHLBczZZ&fER~t894O__{V>(Ax;bgb&0(sf~T#4 z2Fn%(&?a`TrW+0{fmM|5WH%7PU+vzK1#qIE|6ZCp^Vnx(AJ({vYoefh6;%{Z9@Q!q zm3$Pr8yqKkAHTX}e&|XUG!H!$0}lqi>abv>=Swzb$7`fcjezjrZ&Gwu$8w|)I#QsB z233dvm~Q`*YMH&(1&LxvilddV161*+G}e58JsHms0c#T}@H(Y_=gz$VqkHUjP2DE0 zYxx77{)y^mn6gQo`7BZ!%3${1_Fv-_;EH4q-o6F+)8xY=dp~HfX&9?=EaH5B`;lcaAyv%4KkVOQ?b?!h8;)EB4Mvlex*7_a^q zf_RY5+0)U{(X(^xL6|=_tci(?(y{$E75F&~hVFcbbiVQ&;Y=Q z=tAy)fZ4%ugVP?w4`LhMt)JB@w_FIUA`+gu02;gqzb!$NJE2@^>??NXbyzXmVY2Zsir zv(m4csz&*;_s4orO3xf&h)OVg&2ysM0>G|R-NVSIT)e==152~mu0aX(R8KQ0$9+u8 zKQL60BK!z3G!{5HAd4ElY@Cz#;^5$j*HQS5(>wR1f%mj@Roa+hu~$Pp1M-DX1MGWR z3|Qha1tNu$N=bAzrjQAIN4UgoM=f-*^CHOca7TABVZ^kfqnz6A;imt2+PZN&A{%** zgo(nB4~kE|{P9UODDp>a9YVu@?mscAVK9?iNTjYTc~EMYR|w7#NN(3s5n<;csniJ& zrFcF;D8Ty+GNnL$}{+cfJ$S!_a zCWwj~WH2daO}*5AxrldyH^6OV`T1C{)EEHQ1KJfgm_)-!2k~-s6rc!%2qMETJHg`Y zaAUxAi)30Ke2b@i6Y44y!ETp=m_X^or-;W{Eq%#h;t&Pa^wJh(5%&S9i|5Z95V77w zU`jP9{IU7SbBG?A<|~yfZv)6R3(?}&wA=dojyWdw@xUiwX*86_6(3l!fSq$FrNbY4 zcJ7WQBFezVj)et>fU+ss>^19U1 zd@fV0)YGJ^YTr%%B1O~jdmTBDqI=K^Kv7gpo|0hJr7lfaZ__U9`c-SvgQ2x!ptGWp zMsM2dg&9k@&(FPjI~bW6l>iCJp(&ElRv`5#~s6ql~+ zT{W9Tut-WdF2Vl69SBOQ4FBU?4$%ft7LlZflEQrA!ffHNOf+A;t5^uks)yV6K zusZL)mbcSkY$X8z!-`{vYPQS+d*+bXJdrazBz`0NxTqsNa#Am%!Z=S{5XI}q7ZQkz z8vh6drjTXIkgP9ZrY#)-?N-J)0y9qf-$uR}Mf_)p7wjpBRS@|Pak z5zelT-?JlJi5T6r<*ztLuNEolGnxBQ<2&8HMI=Ybk4WWBD%^qGuQ9&?q6@&RgP9?0 z(M;cvpa&(VzySFj(!MQ4yrzl^VJS=szofSa(u{8*c4I=rAmuH@pN0Cm_$VV~prCfI zdA(Z`vd?4Tl?$b0m36T#yw)YtVot$A05!+|HRt{eHO0!iOqK@H0R^5n;f2Hg8x2;O zlF~uIvj3rWEJ&QkANO^KaEvc3+mwr7hnRL1fNJhHkPWoC+Dcm*jY-NKoI}PQ%eh!z zvmnLqRT$T9jds*c1>zPF(54)iu1*6YL;7LRNE0c!m}D3Gmcqcw2)jQn%vWBqPal}( z0#AJRyNLUYYCAjO2+v0Y>``VN^)mAj}`uhm%&! zx*E}0v*KCZd}DfK!4icG@at&*nE&DGyyL0-|NmcBWn`p72pJ*g5GrMKQXS$Hk~qh9 zkUb;WA@dkn2g%5a$~g9xag2`ay)&{Yd!OG+@6YG^dEb8jbgMtya;|e-*XubRkNZOr zG*q2K-8OpBo%VW%UGv|kK;eRG$G6lP9=gmM!EzVvP_q~CJ!b8WbPRs#9%+q#tNdTuY_kZJYyfBr8WvJOV>ShH?8 zs2K=r{Za!Co;Z^hID`MsKhuDuDC_ZRadU{Z8C?D)0WRk|6o-$=GStr91omF}t|fSo zl7rCX4U~Z+P9VkslGgjsjW|Cq$kr6s4xWIySvSZ+J|{6hG{dY;YPr1p&ezM$M(fgz zJg>^~OZkF%WJI~FO&O)a2M-Trps#1(BF=kajZ-_K)>Xn)myD5iVA|J?Px0cze%p6w z1K0D5i5_qoCEk(t$dsnpZ+;$mQ2*q#;JEIw?9j*v&1LcU5AlvTW#H=Omi7igtn%qp zdeFEdb4g4hAOqNi*MVMagQqb3PxO#J8-DJHap@NB{KVU7jmE^$E07-h?GXac(?_s7 zhNH42!;CK>l4~ogVxzx_bNm|hO1Pd+Dn{CjB}ccho9H)tC#5k7PkJvG`1J3M8@oX& ziIphQWY^{}G%mdHhWp*kBSs~Qdewkaq2DOHsjU((q$FHld?|jU7ueTMV_{nU@E=9k-|OgY z@g(zkB%8M5d)FbR?kZ)Sb_$M&*i~aUWic*9rnXkdk`kMu06383x~!pSK-d;3NxUUU<<|_A^-@a32{1yGW+EC^&aK?o3*}dxi|ISi=8hM<% zGQ+fI^W^MsT5;2b(LY(Q{~`YT{7d`+$+G_={^+oIt7Z50^lW?=&MPzNPib(DLF433 zcMT54*$(w3QfgnVr}`|L17jj49apZEodR7(BB)lSv~ve*+SI=Ez0*96Y%)9tLumF? z6&2}JeK-Km@cY6*dM`YPJ@#7=>`o(CI<1k$C=M=CylotY{S@CqKL( zCIIX6@yX0-h@P#evV$Meb{7K@t{#*Y>gVrnboavF)inkhzK#$~JJ|yJuPvHIxY!@j z5KyOF<)JVbs03Jf`$J6#ra7&1l->_0t5&uiUz5mZnNEBrz$XumUxAh77qe2z1_|**`;#co&rbHFrY-MMS^PG0TPO z&is~bT4sBve7+LzL5W_qB8kPKuIu{+`nGL>8vfDDS7N1K7ih8i$0#BGhl>J@`QF$t zn7-#n-+9s#3zSBgN93BT^TH=6o)eBwtnUfOri9$4EbeG&u@2B4NgElfCKd7gafoJ9P4vb5|)a^l%K<`RP&==&Eiu|W1WP`3=}0^ z{+=Igb1yV8Gs`MOXv~cDF$n7XYhH-I5|0D#tusXAhW=suu0`pemf;<+6f)TE zB0aA>KstmEF{mOR#<#-?H}cy&7Ce3Bz8yrnEZoHQ$BoDO;L&!e{ehAS1 zmXx{C;w#D4Su?WDh^Lwsuccq+p{OP_!cJo`cNZ`WKu| zLI0Z3g(d5aRu&Jqkp-TYv#9^}_KL-2Dno|(dw$mxgfFl?pAbk11z+Yr*q&FS-r@ym z-)5|d*+H)ln%>tw;B9lJNm;rcobsmoHg=&t@-^1_G!Ayv z7SQbi|I`&anPv!)rB4gs9ujME+=G4Sz0c|oUPCC2u-TS*L$KMEwz*W};I`IzFI$J& z)sk^h>5e1K4-+AY$I`b3rudxCZ^zcyO=N>msIPBSA|Gl{l zSNO74Wdd7=eZ35gB^uhops}iCrgaF_OD3YvE%_x2gAuiG=sd zeOj-qEUeL`Hi?_i6xdB@pa}*;hNDZn7&3TqYWb z-}^Abd#jWEsLSJ1w1WLMG9$8zSqjzZb&kxo(V(k5gOg^R)u0h<5k?3;P9zb)=}{e1 zt4pK>ZLq059@+c!3LKZ`;coJ%ts3bdY3zd$_oE5k5o z8iipz1XF-jWBjD@@gI8Yug}wNl4q3QXL>|=`>p=083Ud0r*#n4v&DEYnQ6h#!MSd9 z4vVv9w?xpq$+&&Mgar+iJ4*g5pR@R)0~pVV>y%SgSEBl9qv52CC~(|7;GRD%S;$2r zSR%UXeEh$<@i7h8>tYS!Bee?xdw2`}hq}T4Mem?KnIEQwQiq%?I;ZrPy>q=Cxk5$0 zw`%Wtt4|ALMHHbxM&ELu{JF>~vH>YwVeG}?0`Q?tUWk;+xaL>$_bEb9*oPDV$pa{S z>SwMo5dT7ZmM0%KfPDs%FE>4g(j)cLq3eak7HizSIcg?``<4QPd7607I@Xuy@t+PK zbei6t(8)mFyak9FgU1+tqVS}C{_kn`S+T2L*AD?QI=@k;UyPLFoI6pS(F{YkFP#!( z9+7_#cIIhZtQxcX;wl}N+m5Tt>q8<$#{4gA2b>yyG&nlm82Yhto7m#plok`1l`QgJ z%!zB7%VXd>Bs~&UP~}k+#ji8uv&NnPokyR5bd11H)L4(@{va?e8Sgdfvfo{AHvw}J zX;f}yDjaN+=A}0=5loOde&`8*r+AlDY{I8hGlT$<4iVvzJXnhv%6qx*SaUAD)d46- zp~PrP5T{g~11>%*zCcoRV`Jm8JnhJRK8UFt-h)aUK%%f2%LFnS|BSJ~)~XxY^`ih0 z`DSz~6g7`t)hpm;pjDo80Suqh?s`fY`9@F;KJWk-ptvnew z%bu@}vFNFQ{IEm5=ha~s>rsA%Fwvq?LHx|+l9E6(1on>W*J?u6Z5vc%A4*0umZ zm_n~}rsE=0UjIqGGTz2I?({aA`DfIOi1m!nGc?ZW0*fl;T_Aqd_t@&I-L|aVh98HM z(*9Wx&UAZS{X4d4K^$mw<`wsQu7m{`23j+rCPE0CuU!sqK3H=jnyJ7VUygo>NvZv$ zE;OeSn-}flAoQ+ySft_9y$6=QO`AIVmhj>YFfgh;9tkLbHt@~}2ngg=EMCK(g7!91 zQK2W?H@xfI46^-sALPGnL8{8N2P7%uZulYq$gcLdN7`1Z(~6O@eG_(j#lw~}`*~W| z&2p1`TOr82l3gq2==vMVxq}mEj_0&K3=QPL0eB`FTuB3uaJ}s?{0*b82?b6Z%7hfa zHi}Ec9=YDdkk{_z(MuDLj}8EhL`#04UM++&F;50#{(c_-jI9z)_a~DW_QLM=AFMpMEXqT8Gg&G12+{1P@UNqYEz6#U9Ub+wR-!{%z00GD(at zxGs*AVWl%*jzaPbQ-4(?~nRNu^n|j&SA2rDqpQQKse+aG3A$dH3Bnk z1F`SZxXUpv$t+gv-jKWu(_IG{&%#($bOS{}XC{DI20rz7D1-kAz!Hs4wbv)IS)7P!Crw3ry3 z_2ui5V;H2Z-jn<=oE57K03DNE<)CPI)S(=D6yo~qPZtOHPrs8Bs<$cv@QN0bhEMP#^S*yqWPyAf--2KEnoYQF zO={bqc!gUU?oob@P`NkD+UN64Ba1)bG{lQkO>*r>vaW7og~l~eo1Y+bvZ;*e$vuzD zkA^?08PUjbzrP4oBbz8FO{0Xz8BQzAXr~JXtck;n_TUV}{!yPlbr1e{09W}a71oUj zPK|2i!MD(B7usv5jm?oB`w;Dkqe3B5F)fwsK zM4do>GjnjX8E-q=u0$~UW|>6{#me$AVYhB{_$`>(C$k6|H-6w(WHOcG4je;EO&H|H zYp1@T5!A97E!`YCW5|w;0D;`YKag*#A*A)#yebRl?nD4=1FF;>jSxy#j(+!k=Wx6nWBub16nAd#K_L>_X)wUbADyz^5x63vi}+{ z?$Uj<@x>d=7C|k?i*j9eF7v(~J!pAfMN1bA&fa~u)Z=kATiD`C(7vig)`obeHru=~ z-Il_Gql}1;Ou20AxnLP^D=%;A=O&6N2Z|ykW}375qX=P$z1u!L<4#Mze;eeo`endN zCtVJGJ%mvyZyrIln=RJdmIQI1rIC?*doRI@sX!0pa| zeOxlU<=J;*SS3`i`MYfp0?J#S>SOl~YqY{WZg-<|pdVP{rBFCje}lNrn7Bse91IC* z^J|<6j|1DEAViaCIsZd@UjKy$lY#^n?^zJvdQuFp)n3QE5^=pkJytb{;&~W6LoSY4 z8qnzUwRM^Q7!bxO8_XyiOMC=JMmp&tT#Wh5^UQK)yGu>DGS#y-UyrPy+o+2nico> zCx=e08D+f}F~zT@m@T% zTs*R6CwQ{&-K@*l6+EtNe|S|5jWeH6y(t!Q_W+=JgTwX{p!On9O!pu+k773AwfkL5{6o7Nk_ zn|Y!4y(y27@%o%$mdwzsE8jCsdp_|)h-%OwHAWV;ZENHlru8e&OFZ<~v{3is#T&X~ zRnB_0Ix_Ggo%b$$Qd|Nj=9Ae6Dk>eINj|J4t&tAE3Q!$zYX4Us+H)k|wg(052{k7T zDjzT3B{*zm6oUH;%?XaI_`|oWGJbRW&rXP<(rI*TIP4Op9H@sJu&o!n=gsQixu?1J zd&fYPp=nch&Be4!3ybhJISNF~UxVPeapBc&)r~y#EzOIEFR)sE1WqTOX>C5>Do5ou z1r8O)YKH_i@_1>92dDQ{0SoPb6i)VN6}FHubmj@9GiMgqZ+1%{#6J-jo+r*sfcs(V}3$6vqQCWZKp=1xqgp)CWvT+or`+jx)Ch`0wJU5|neaN<8x0rc?Cjx+S z?zILWFsJi(cjDZPZ1ku>K2#Bh82&N(kg;+Y{k{T`6RT|(d{zhKiF)nC*_s2i)bJWw zG&YzLp{0iAn10d@t)e8J`N99^PhWRtySRol5i zPP^TV@(!;*e6Eio)77v2q$&EOA1CWk5=zLbGR5-=qcKt1%l-ikq9El1`RN0tzO@Hw zZyN&BRU~D8v{R7MTD^!=oUse~6DOFuKBS|YmL+EFl7SIhf?DNhYAm`;ckHU`sgt#c~z7y~p zR9&izFQ+^Tm=%9$*m_M%TZs+{^C7d%`vm#bQ5BGtrw*ILL5V59VIzjE9U%;iIv4SQ zWc*f!+0Vb{s|zy%`mTXK1tpII-k@B@lkX+yZY<_yG}U=N^t7vqTxsJDFXDK9EyLnD z)G+*s)D;NrdlUl^jpafnrEt@8W!MPCs$vn;P{FelH(hgY5O_9xw7O|p0`CB1;AK60 zi|i?y@8Z~prZ7h4@(hmhp;%_RcBbY(pyYk0KehX3+NSZhr)xDzHNB%B=b+wT_c1!b zsIF`ee`;Am2vt9e%O6tv4pva5pN5|aV>2xB>fh`Psq;zJPyHZ9n()4W`?M6c1O_2e zf5TeNsQFTUdd^;$+}s`e$$l3U*^N9qai}UcXtc8*P1kQ&$u?lQ>Whj95l8nnd>9XY z?%0~$IT(@bx4Ij^!1$3FCN3w!;m+rlgTVZOvEl(LhY&eU0A{?(;EgHhXPa!Ct9`(8 z2dulE-CoL*4+WXEn>1V#Jn(D0=8Eq#n^I|5=}+AJsrKb}Yoi!EssBFEWO;8(qN~(O z6yEOwYhvMsP_S|6J8OENv+Io0?R?q7X82O!k=zs|^GFM5)TC}kg(f3`f$P&%OtkG? zsURE6;^9{`Y_Io16|T-fZU)bw9;r>QOMDX-fC#no&}qNRAv3{T^L_-K*w>>W4%E2a z>R6nFo^1pfhi|8a)_G3vgPcEQhc08inpr}D^~fz2EXsJ!my5=6qXyyM-Y*4L9Qf@CDO@Voo-@e-y|htZvT+BdDA=3RMf2R@r2>-Nr$!qarAfAuP7 z6(cFk`Bl?Amiiuy8;!9G5pD*{B@St^-w~us^D+4G+ib#VV8?ot^=(9*+?wKV`1)~Z z7XS151@P9ypD0aV)8_{?rMx*05_Sf@axGOJ`yb=!+BE-K7Q z&CtoET^&ydAMAW*&P5}RJh5Wgb0DGL>8y}g^MWj;3@N+W8u#rp*UuABw~9H$D7Ca7 zMEOJaIzx8Eq6yoEtDtCF&f_{K*gF<2A>Yc}tbQDu5geww7ZTu6Up7 z@6ur9SAFT`4*lkY-7`|(fclr>t5_g6hcu?z$D^!R0gB$ZwMzQ*1+m*jnIxR{0lkjj zxkXm2Y3rJp>C;5$E14K-|AF&6W1eoLm;NP@sb1Um{aV zv8&nv!}5B_t&7EjeP+wJ_tN-0{-zujK&#Hx|I#r zH(@TRK@Qqj=8Sax4zkA^fxuRqRipiU!u0z{slro1UJW5i!ARRW4?TApvIq%S5~B3j zrmBD7(`V-_ZxwY(TmOb+mR9y@Or1))xMO*1GxkA!F6&O;~D;Noy(UZeyb|J!UEiPHr#VP;8v@w{|r-BaX-*#s{Z|A z^QeD`>z4nW$udELiBQHY6Wa6VspRZ1GBrT36!lCfct$o(y9GOAifY?H4vwA|>^b)x zo$&J~SnW{`aKbOtI#`^Z#qOw7Ian}W&egB=G&XKToyeyfn|y&jAs~cWFw)4-^E8N3 zwYVjUiEopTNp~W~pKxLLJ5JoMP&42iZxHWm$7~?)MUb2vq!K?U(%@5|sRlg+A|>(n z@81yjwR9}tmUa(54)NoKxpnKX6m z3ATq#wlaG&Q33Q^I03=EuW`@nQ6jTHm|i<#E#4&XnSE=s1$E!QYrGk{ii9Zwi+;4i z@kE*J!s%_#s}zZ_VhL-U(h2sZTQf{}%Q{0@_@Wty{&%N$&f6cQ2kx*edPpCPTG%pw z_;87L&h!bcEu9X@@oAqB8?%p7o4#5qXxjR8F<=}&Ub<|HiZ+cnK0>9x96*I!aM}%2 zn^0f;suRP~!Go<$fXPFze$k%_;Dzu*vRNP(wnks}JG7S;T@o{mz>MxW1X(k~Ts=LX zR{wUi3HtOBX{h%eGgO+UqIXIf;9f4n;*$~+G(}}2v|qd^J|7H`6piFF9DD!0VD^~J zgcA8aK7Qzq(_w`Bw&|Rs7_L4rM_U*tze?GF-DBE&=%FN=3b|k_-$Lybk2(`@)8c`gRr!cy)D zhh3J=)U*88H*pKuqWlKf8f9PEX*u!zXuBWsgG#U^^xc3N??rNI2XXgvgI?L=-+)vl zR=QxXm34Yp`2KB;|MUe8jMqO)u#jr?Kpn|ylrF*u$awC=9e0qvv*$g zQ#{_Q{#?^9Nrr-+Pt6Bwq$Q>DqWtUOFMkU>{pkH!jruq10sLsu+@##qS${tFCMMzs zy*#eO)EX+FlEfKz@I{Ro25sAesIRB*0q9Q!d{3#N;FCUdU2`H;8||Pfun=U_eDLWQ zO8o#OZYg*Ait^3RTH7E`mRq3q76Udyko&$l>i&fn7OhO51oYfp45n%)Tc)ObP$7&o zY%WaXK_>jz=n`C%D8~xiL+cWsp?(|nhML}8QO%Xr!aC|}8}eU$DcRx5cb&^fyY^`k zqex8Mo?HVkUdD1fKqLEyd?FVBedSpP$Fkc3e`1E>hoXWTgvgE>r#Jrm&(JgI`xh-P zSX?xAA_8=U`{IFzg5DcG#cn==bRG9Sd;wulUofrhTPkl~ow$TV?A`s>wrg?^BQxVq z5HE3=E|=J|zn>Gw*jzZTbOtbrtkzq0T-|EI9~C^7#*$qAz}O9*u2SGr9E;M~I?AwI z?qwQZ`0T$*gnnW04neUh;euvyT^54ALy7z?u%X7Gmm3o`wHi6;3p`M{tn{dF^4>I- zF~2{N`hSs@!u9Js!V<1C$c@*o{;s`q^vd*q_hi`%aWiIaC*!5gFO*&aog&{?`Oogf1Fe09EayDKkYk3|X~?oM1JUS=scJv{91eyF3Qikf zrqOYMwx946&L==Yme~LW6t%S0%!3ouVH3;F@LIUiBd?>v$%K@+O;;GQUzmKfoOisK zx8I|Fc>YP)qYgq}iyBMbea*$E?KIue#4@p&xv~qQYSbyL}W)!wfmdQkNWyHmfuqtv~!Bw4? z@Y4cUl}xuN{q?q&G|gfO7@jPi$34znFm5fnrUi&9ky5dycx0a}*8kUNucM7zN0U~O z99^1>J*gfw#V0+d9m0j}rNjyz+CTep;;PnaE}+Jexf+To_Y_rU^vPyo@f0qXKdVE% ziv=elZ`0(88`|kXrnT#R2+&5wNT5DHy5A1e*=<|NsU&}b4bdVb9L4sc8ap+{~2!lEz|(x4pY3}))oRa zhI`xsD&;?ecC+uR$+eq4f0hN`f2fxD^)kQRN4}i{0|VU!_R~!-KrjY?HYSLEpgbdK zJv;+g8<^-(2g0{sTVG0mLx#>4ID+v8IbP481FM$@i*gH1GFyEjfLQHe4=zr!df^Ft z^8q{^stI-hQ7U&YAtEZOZiAgf`OCRGuu@}6Y=ZcvsC4W)N%I>@iVNJy^|lRh`%!1F*W>1G@)?V)K8x=T4m>qG-hbevriC*}w|7!tJ83CbW?QQa zy5PYDllOJP#wdYwxJk`@4!GNI8v?e;@zl|@*Y;M=4&3v6YE?>?85Up2&mcn+sSHN? z9po>qYts`9P~5Yqm-v1v&fxr5~cidE98g;AcHo3{rKGH$Zbj> zZNiUK;D-%xs5JlhI3>jlIiYQrp^oPU4`#P??yc}daq?><+mhAwQs;~Uy z$N%5Zb0r7pC2mxyjdpjsEBmKzq!#`Pml5t_m1BWw*Xt8Ugl^nz|&ecddL0C60GwL{6c*pKEo;+!Y01*a;eCfdi}A;P7uB zp?^R?M3fKr?YCnp^%khy`0Cmf#E`3Ku$P?6U*) z*gt~5G(Jy2|8B}Ho1zYRm94Hung3-5r1aDt?=QiBd($5#cx~9)4V#p>oRYqmY}geE-Rh6wZ^fY>OC$Sp_*<7l_>8>K+|-dXCRB7>mAJ#+;JT{;mJL;2~aF+g?u ziKzIgh7iLkE3a1QuZH)$L!6GCtUoV-%2wZAn+S(p0M@UE@3FX6F7fc*$YME`dG{K8 zI%fr4rlk&52uL~xq_6pz)~N3Qi*V_2?jqa9=ad%yg8vNc{@Xf7JU>wM*Gl^dF%}T{ zblO5Y{bwvQB6pqTap@DopZis2ILC7S4VWOnWVK>Kv=aGO+NW$O7t9nBDXq;vock{a|PD;dQ2;Y5iKde;EM(+#~P&{QLk^w}BR!P}m08@m@MWA_}h7PLl>Z&A4$aK5!OH-Cjq1<~3xMf0`~LT64UW=QSri z@suv#i6Z+>FFU)M+KfXpYr~_zRHuJl^*=AvS9FMaXI9;~dXM)BNSI(qze@Y$9otB} z#?PVpAB_6@c)^?5&!bZ}@Gbp5nUp(yh_I_?eQ}VYVwPamDn{f+5`QWV@)R5hB8_BNI8e^vEJD0dseR}W)D&tdl~S;; zj;W=}(GVT7aksHsMs)aK*)pb{siY)M19CYv>(rHi?XTRml_6pvudMG_S~bj>{(mKn zrY@VNvz$R4_3_KO_8&if>@_)0+&Zi&4bk{+$V{2>2ytbRJA^E)5A+G7jcS2p*~nx# z2+(poUB=OR2}ti5{SAAhV|leKml?j9-yR|@{fEUe>k!y}#fQH@#KeKfvMRl`+{I6v znMp_ePD(@!+cX-~nYV*ClkF#FD!F-djk^*U>m~Wm1L+FJoK3J6=o#H6WO&G*Uz^2G zZg%!}aK<0?|e*Bml>!&3vQb@t37@0L2t;FA3K&(%uAsrn!vbJuJoYFcA zdsTpUJGN$%zb&kQ+qMbp+h?ET9v4nleVJ2pIL&nJ{~qI$hbCQi3raCgKFw|&D)q{m zc_i#YBA-JeSm1SK6+c~RVY|fI>D3kawH>2T1YS$Jp$I0ZBMTO2G`BGk7{^#hwx(ql z(|LKT=aAkNXb`HZhp$wg3fYY6-Y95%0vQv6v^J^cm)(ukj@$sm9f!>Jy~ImSve zNWAM!Yh|#OX&mTs;dO5?-#-k3Qdz- znkEpwKbV4bnm{(>IhkIQV7>EE|25mTEQJj$)@p+XmV$VRmDR2zu!8jGrPi0KxT-fO z-0+A~tBbTPEAt)Jw20xzL3r!AlF$o~l{@PLAk^j=UDE9vyhoK)kb)#_9c*hPf2=Dm z-2jLK?n6b$2R_FBN}L6)1yyhu?)6QG<^f)2XgE>dHcE=E!rhZ`iGjsE^xa}b27UhJZf)uY0qvnm`IqwyK7I0Do zR}_U%hR`qz7H-6Q34DqlH6R+*aT~W|q|i*JLXA^saqD1w3*Ar*f_YoTiRhE0-S)S| z8MQr=#fvm^*&@XXfM@o&6n^D2obu$2>XK*xiZ`_2(0X?-AlbZbBZ2vJ25BVsQpLuv zVlKCV{S(K230?7zrOyci$kq|~#oVmd*dt zu~PZ%7P+~!5BI%XszdYm*)cjIs(K{HNVT`Kscwbcva)1zd3^LGVY>zZI*uof!B1{Z ztW|$6OnKmF2_5!{ZRrDnPx=y@7r4gxa5+RHIc~c<#M~cSsN*BsRgwT{+C}TGFX~o5 zcLDzz2ZVx>u>FKJcR1{cY-Q=T=cM)0@sGT<2cYg>2~Ry+E)*S5oBG<*^Z3L%Nlq^V zSX-jsMjYXXKe>*7ijvkvr(bh4o4;?uA?WW!G6(wA?-6PtiZW`*Zhs7EV!yu>1ax=E z?oRrCK3!m;<8`zpUWIT}sDPUmXWe4%I3eo&uYCnuko%aBp$aF<0QelX+^Eu6MqW&e z%|))E*ojBMs(SwD`J!ofd(H3fRf~a}^bwWRCS9dv)~Aw)Nz>4mEC8fei&%V)8YK>f z4(@3)bzrbXP5~%om8&oqmJ(T|20h1?mBYAn9L}L##*HKRP{yKSJy!*xNc;yOR7l}H z?;Y1U>0x8yv z=EzQF@T;TC|A)G=2ysLe-Gkw3x7xRCD?I6L-M@j6Qy`#Zkg^b`G_b$`1XC;!ymcLa zbpBd9U2z3ZA&%MVHa^XCR*4&bI8FK)tbY_?*hlqnN4j=HIvjqytA9w)HxNdOmA~z0 zLkqq8@-sq#Q>;m6YG+WNw59L$lScpb?$3ZRZ4jx}^FwkXMB(AbCy%nuCXd*cubJK8 z9NR%#UHJQIFK{K(7O@Z1ussQ(efNz?iw9c;VB8*FUU22ty9dt-u1Wo%4R-6U;(LDY zKO`6Xj-2Gu4%g)Pj$iAkYt>%&(MlPS&^X*NKh_Tw{WMi?xn0~A_L9cc=CqSY#g4ZR z|4l)(|5TD`o}Kj$WPuAmlMyo;KZ`TLJIZ1-R{u=Bq$>X z@e2V&pDnV#&P+M4N~XhrKp?rjE#q0?P_Nbg>@3cdI+;bNyIfNW^&TT9gbHg3biof6 z)CW{oBQWK*v#8N!7J=$42BiN8;LXq*pG=UI?~*c}Vd`qX&p3Cce4}3%{#W^=84p|n zAJa?t{MwjWtgcH-W1B!4tIa69%)Y3?zUUo|u_`0u4aO2O;@&7jnP?*6DJk|H z2?`O=R3S*!TN@YX(Yy}uzlu2R5Qhd419*+&~UyFS3S_T=m`7Nkn`nxW8w%3N4vWoPtPnIx?8s%p)P1+@mSy2jkXg#+tF8df}HpzcpudtMqN$wjtEvH&yYRVXK zW06&JmRj-jp9QyD?o+ZxPjH|kaLO0N3r>)wZ@afMQ6yKnH7HCx52s8l4FxOzr{fH* zG_%;{-C#=IJZfM=_FS>le?TtHudZ;s4vv6QuY=MEykW(+Udz+l;|5>ze@u5Na1p42 zPBbc{{AW`M6NkURbjm{YTFi`FixEy!Mo;8-_hLjZ&q*h{@u=#S7=$+_@zr4e)yguF z#LJrh{kUa5D>nflnJm1MH=ot0KSz6DWW-Vu`MCAI=}E2&C{?WDs~Ty}&!F5%`PuF70Tq|RA6lre%QLv4Q@$mzRp3>t{n1*w>G_@+GF`XUw>tzB&jjneW!UO-K;~Tae$;A&uh6-M zyQ}TLj}%O^{GMh>%wiHg{_eR^2LB@9|E4UMqpk;B30rmNLgg+14{DbW9TjwEO z$twVy5=?5B=AU_da-Qwg!bo-NYf#eg`UuX;e2<0GA^r7XGK<;HfY%G5BoGa`0QcLO zI3DpjVDb9H^4e%n?jtTLa{)+DYKA7+ae3$(i@o4kBIl0NkLsOq>>Y8+iVpNgnK*qP za8H+CH^8zMtZo47ANWpNaiFZ5$=dUlRcFBD@;xF08 zvj1ycxL8)qZ0iGwIcxhPWS#lM?sz06eVj9(-6VfP1Q$XFqiTopzv@;(Ahg5uX7*e6 zuRxad?lF&{+8nTM*S$O`M5_;(U@#CG%&PH$#Ynws)Q3kQeT4whB;A*~MtzQ*mj}H$ z<^c)`P+T1g8vPifTtE;y{_qVr7eU}Bg;2iZP0^q~=ipMij&i1n4Kla=D5o7X8cbZag+DehUd~ zg5)M4-D)>1q6UU1xh;xfsNLKSHx=Rs5;|}KE-9Y zCx=RpJoyNF?%+84+dchIdmi6mGZoYI^ZWZ${h?Fwa`_bP80O$O=6mopFXH@aPC4b! zxqK?8RYx3ePw7>;76M`2XxYgFZh4-IyNL;A-<$MU!(QSFI2dtR!mZ| zIg}#ZO=&Uo45*K&=()C*rfL%}4@&x5N$>W6u&&*MTGGK-vxun@>A&wZa4YC22YCRx z;lvxnQ$B^6yw^con!k<6J>y(v78XGLH&xb8->D zRlb_l@0M zn=pW#0Cz+n!odTIPD-veB&k7*KcgPoH>O@sF1|{v$KbRxpS|7AI1m^G7?b0`F=No5 zNmN@kPR-(@kwkeYtzoOt9f?aujeuIik;wb=ZZ{}6PqmNKcu1>dOrObd-_Ak27-cPQ z4jDC4v|zX&z_{^?5+70;0wl)J@3kQGO!B~{QNy}?0QkJ@IN9P@K$kdGc&ey&{QbgXc=zS*M?c z;Tj(vLHpP5y#%kv8h+Xt$JmKej0?_4-Tr`D6I5c zwuSq78k-+CkB{XK<~?|7cTop(?yGtjE$wD_%~p<*u5QB7ug&Rj{y${*&(Bf>5yH+v z2Ooo9p?c$!=hDFsoCPWdWkuTV{-CP0-ExogZC-m#-NJcoAurK=J^O}k^h>*%(2119 zGu0e|se=1^$t0H|6zDXNaI4a|p)-25_2_(Zh;K+H9 z4ki?)$+>n<-D=2=`FDlZ%KzK!l{twZ+0Fqk96a8MJVftqV26BQ8!i#CKzLpH?gwl> z@9vF1AQODu3H}NL43t(cSUEX0AVZ#=VMW!HAbfBC3%zLJTSGy}S8+|8XwEp#&4>Mw z17J-)1kU(fh+-V5Hlk<8xo!i>PC3c|{T!ObGUbE7pj#M#Q_#wO!7AdOai9!x{2p|R z(M^O4Pw%zc0A~MD?UFX5Wq=y`C9g&*`6w4=1`bz1*XaxBxZ7{2C*ot`=vZ_c6L+*x z!VJa=1k~{_GJ=nExfxJ0tv)MvrLn-zqfP%{B<%&npPR*B{-ND?~WxZ9vw(KWW`rdzK2KV(O$WC;O z#c8|h`BPB?y6o(<|DbpVh5oQipsK*glwJN>Oo2Pgob0()jr&I~x*zZJtHdTJc69Ex zPtVnm4x!3f8ef2*K4w2=fLe@Hx)w(Okj*}b15h!UzrZ$kylDc2ocEW7e$ zUac;$EJA=k@mb<%Ph9@7v?3G!aNGgO4B_;J2nLB+$jl-w%X-^5Fi&^jclX*N?wHE$ zlSwA+x|qAW%alHDtR=-ZPdJVI-v6nja+4*x{+_D{m;^o68$lV^<7WW01o%jSDfE3@ zoLR7m7y#b<_}DTz)SMs`_+EZ_Bs|frsnDP?82@cu+RO7$wlw@(cT42Qx91DU?308j6*^R1VdF zdhPv?Xfb-HeGOyIjujjYyyAQsS{B6*aqn23FuM1P^3J8}2VO@x5-pf6M*$kohnR)y z2l?EJK5f_$s#7%i_;2E6>s8S{XPHES?`N-S7hhD>e7vZ=#fbgV&$H2e6(Wh5H&%Wz zQMl_|&^XmW++xN5RLUD|Jq|SIWx^jgI~cr7XO+gNaJ;WO7f99<+Tm8|RjBynq=;eo zkFzIOrDiSoRK~k!^?e_Yz62OwDBiP0${lH?WKbK+)h?foOHAPMnyicHdO%ayBOy^p zMS-z*xyW~bUswvgA+quA@QY#A{X6s?7D88vWS3zpc5(5E(g!QHIl2eE%WdUDLoRL> zb!z7)<$ndVmA)=FPE&2o&Vj{)jO$#FIZMlaciR^h4xXM@*6u!-g{~((;F#C7k&~jq zb2Bi1G>eFhn#;U4ap<5wan#e352f;c`tI#jT5?+5OtE2?6{G9D^ZaLjKY1_HPoaJF zqywF94!3k1=5!|ne1ca0nkc*?XT#C#0jZ*^`XU&tMOwt~e-%ocR_fXO)6CUe`u=+) zU+d3?0L?xDc~5(LMwQR^&w@(INI8gx3K&vA$kCQ|?UuIJ&f2l=^80Vo-+Pt*yA%Rf z@V+tOj;HzUSIemPnO++!f0lCRYqu7!^l|PnJ~A=u=jyy!o5kg2!zRsdtWQys*pMgm z-RQ^ro43O#R|jKG6RYVT>l8ZkV{Zv|``2rU%T#b$77z+RbBqHWgpY!35TzS!iR~hK z2qTNO5u?Gf(G=jHrTS9BJ8ly_=pR?n;6jTrt1dshHBZ@JHA289pkaIDhxe$hg znld0IH&SCXsBZkIv6UNJ<@6=|Abys&s`K1V%y=Ds1>)5>vr+Ie#@XS+eDitbX-BoZ=fTmyN)0cm zHP8&muR7X;MY3^F}4lWi{p|KhfozH26{mya!184|_M4q_03(#clc$A64rT}9oL#^}Y zp1Zu8^SW~a%)t}zXHbVOLQ`&0>UTvcu^B=TkaR09y1RUU!$9x9zZK59YK$6H$tSol zf(&K?N=wODPdPahfM29-V1ogLPD>g?TUQb#5*k1MuUgTJPhDN#+i$|%8}^e@BMypd zSR1?0rRE=>4S`Ca&AJ~WK3Y@kemPf6t*RE9q(mifX8YR6m0ar35^Xv=j>N$a^q*@> zZAQv+wTf}v_q-`n1TL85$BlxZhj>|qS;z&-h}H*vN&N6!ABI<%P_F z$&F#C!7o0qZz<8KS!(5g)A@f~od-};ZMU}RsDMZ@R6&6tNJ0}S(nJM>AV?8HhtQ-~ z>Agq^MG!&<1woM-dant^&_Q~y(woxDzj@#9JLk+lvxiY8VUoS~v!1ory4Q7cC~%;( z-z-)`IR!amRc~#4`tY+kq{>(%2QQsrIlv-O;&9BwE@HV(do!?Kr|D^aY|ZmY_(zwc z08$pjhVdIq?0EH6`bwZw1_nVDvCxU6B){B_-oczsNtl>Bv(&3f^> z@4UP3eDfONcQMs>;T>dn9AbEk1q$<5M^_hqs#nrieOCv5SF^x>|N31RicGuE@U|qG zEdB%@I==%Tq&rS53=bnZh%Jlz+d}?xje)CO%nF=|*>5NEhL z_3v63tzDu$O-+fS7HF0S%F6KI4vZP5G4S5Bbg7{VGhbg8>yAA)M!3% zJtcZa3i#+0JMT{{>Axi5dtRvYHB#01J4ZHwRSw5&Afvwe-V87;HXXqer9_*=Wdo1@ zoNx;ZJVTd~lWN3ORtEE;x;YrK;8ECT18g86g6xkDe^r`1b<`Y=LGk>5A;vQw9SG|; zxNdxTu~W$!QlxSJvA?ol)MMvt6`QpcU-z@g*~@6R`WG4QgYg1meVWsfbdM~a@9C;H zZ8g1+-#h1prq8aj$4EF`T^zCViA)^F(J%=E+M|dPnc%fO_tCl;p!Z$4Q-7emsc|xT zb!uqB3k-+W`kcAWE^h`Wga5mN{s|ZLiU3sxwQn--b*&i9O_c4%J{dQrw<=s+St-$B zOmwlwhe8)^A?-;AC4e}w-Ld`=pmZ)JMpU5Z;ugZb=y8!DEUlBRjDdXa=?=U$(+B?f zx33yeH#-XkjIxsh)SHZ|M$WB25HeA(xuC1J8FISw)UNgh;4j1wAq+)~^Y zrVltY>b}AGlKJp;k76s1&-Ckh!4WxiR?RO;UD@3r>QyS+Z#fVn9;o}u17__@N; zwyTdSkqf2!Whc$9$-6tmp!*4T9P`ZT*h2x@TQrV z)6$J1HM%>k{~!MG+?#BWS1Msv^4=p{sX7Xc7LW%20k}*Tk^{N#f8EyzHB8Y$0iE_w z88B3$p)Z3py%D&)dO{oT+RnyZLn4FbY7oYEf|AtrYQ6KYvf@4+{tOeu*9BWymL}$$ zn+_%){-O!$Dx8O;XC4sY00ja>wCSA;*B0h}ACWWib`gj8|nk(#f zlLRYK`igA8;gNqCpk;|B)?${ZHEkh8FNpHG!n*|)p4s8o=L@~|Aw$FhUfWO$R`w71 zC1kC#1KVB3VZ?1A(@&14Z=+r8TfmJu$9e!NYo0pIdwWXkmk}LgYexVLj0vLP-T;LE@5TA5Kkc1yZ7=bYC#wen+6(Ta zga4TF5Nw(g5=W{wo4@LR@bR4byX_;AyF&Z?aEDUipD!N`%Z2VgsZg|)3*o?t>qI_L zPBI*Rj~p3nvV1kvAI1|Nc)wqjzLi>(>}eHfXaX^zU2cH}$nPIUs6A1id5}o#JCivp zc%;3;et=c!Gn1)j53-(-zWe+F{wzNAu7=Z{^kU)pAbAY7ukeDoW`SsQ6r8TZQ#rNpVcHIg%2^7 z_SiQ~$sOZ%1n3q#RYxermP>tr^7M@TRuI>7{XWW~3eUseo15Mrp7a3V;OG0ECJACJ zKZfV)eA9w@=;0^|GEMYswV%;d@1>K%$+ZE}(o+=x=!C6FuG!p$IRk9!2Rk$%3G+rK z7|N{1Y__>E-6w}jv_!lr9>(sCjQW~?Ag;Y28t?fe zMFZ(23}?a07cfFn7UR((c){mu;avfH^ob)chCVBdA3+VHm%YW7OcxGdal&#ABtJMi zFqx=IA@(3)#8e^fR{&NvPB(gj%Il_EX-mlT6p#}Fy8e@}aq$y?l_|Ds%+Aa+dQ z=Ig)<^&meaI}iNfrUsaW72+o(J=#m`pUedLpa|_ffSE@N-DWwEK5HblSCLBKX$R=X zmlP(_e7CMhJ~9eOj%226W;Uyp;XE1>;o=3zk&BY$SUNvibBz zS`_H2z1mxQ^Ulz~@#OEx5oi6atJ8l)q8K>sgY&+(z*j1Mn%?yAPZKLog5rN6QKHf0 z)Bxe>IO1M|^(k!GX-t<4m(y>U$cNmI5}XtsS$LWKEnsGluF>1d+?*u;WKq;LKe=M$ z^3(U-Y-B;#2eU;kh;{MUOr2}VCM2O0a%yPaqP~hYnn;QbXdGnqJE48r@@aEO2-~)a z6l0j9CL2_oJN^*+QylOOL!?&32VTy6&mk7DnbpvZd;)oK0Yh^r5FiPN$&}%xk(&I7 zFteU#c555qZ?t}XVM1q_mGGS|0&28}d9rc^WyI`;Q(ZOE1ZZtY>qa@DHK;aL;vAe{W+M9x)Qb<|g>G<*U)5F}H8v zRQ(*?OZ541Xc~A^+xMXf<~bA9(-Jp9h#X)f8WR;AU0L684w$b?@6EriumS*dz*vY= zjHNij&m|KHu6orMXur3EW(@^rCJydX(U4i)Jq5yG4cxTWICk6(J(q*T>O2=Rb&jpz z66fZs2B9)ID#~UJPtOyT*%*jve>0>i?e?BXO98d&t9g}9FwE#b+(vqtI|Wt=mi=7! z|5%B|Jz6#dedAPk!uU(^JH*oJd7V02$t3xCFl9~uyKDjz0^7j2+q*|x-DhncaZxgj z#i=Ph<-##i;`&t_oXQ+!j>9FtIVg-ApN6Yl0%ns>bvUkG7^)1gg$wHF6uep#ikE}9 zmIZqwr6fs_`w&L9Dk_3|3rif2aZtv8=uymM#?NmAQ$AS=lK45)bg3&azOF) zF2$Ej@R)raqn=tS_-RuW+24%ip#at==RMTNU}ACBDf64vZ|Vv;FU`Y+US|Sw=p(FP z(Ym0T(@gMxod^C6s(bv`j49_n$IC;EobtH8yb=K`SFy$bX z8Og%|x5C8GjwS?<)TX|KYy1BBty*nL*%mq@Rcj4X8SbU7ES;(_^%!RZGJkZZZzMYQ zC+SS3-Ke>B?97DjX9u*4iOfC)`dT6pI@5R?9fl1V8sFcm6E;dqCuScRce+R*WNmcT z_mO`Y7KaSMPheSk|5M!= zaW9q)B`5mEzup!7^4<;_0f8fT`T(Q5ICu&G`}``@cL_j6ug9J$;8MrJ7O@OK1J5A# z6tzp^7UhE}GjfOky`1mEQ8u*cwBA05TZEW(yC*~tyD$#d7gwBEKKUKf$GwgIT`+XxCAFQC1w$8!# zZtk=7687?LMJ3;Ka`mkW+JlAgkV;TCrqtzuCoFxG0|)J*w32xUg|fv}OTgGbK~G=5 zPFc_H5Z77AlAVECc`;+(TgOyiJ}%UZnuMs%9fSMO1R+fZcwa@%i{^!4914Ma&ohA< zT^s5}=xqg`-MN-k$UD*Px}8S9!@kR8o8an;!^ykGfSag*L!W&ed4>#|YV|3bBsQ4g z;Xijo=gGC#!POZO$RQeRsIlyq>e;RQn8f2_b3;v*S>K+1NqdI1Jh{$CZwiSnBy$wS z{A#^rGkEPsMe5SX51kUsId2Si>m6Q`sXqAp!-LB9lX%YJ@tu-c^u8RtB}W%$pk{g5sGMrz$)3j#qQ`=lL&6I>9`%Ryi$LI4(Z@T!n8 zstDR9*gt8*Jqg9HrUlK#j1^zeBGBwBz(5Q94w>t{uw`@jOsx>&Lb8UKf&5WUKP&o1 z4jTWyvOWZMz{b9U2!Q#nXqVPwqsLO5%H!IlGHXx05PEHfnc8f7o0iBT&ezMvApH}}AONrg&_qMd+>q+?Q9tpjx%9Lc)df%;9aV84ZYfo3@Xg@Apd3X-K2JS*W)D3t(tKML}V zOj^3Tw}SO~Bt!eimez#~d1`+Jz^U{_{>)xv2mQXK%V$)x{v%&8N3E`4_}nn{`cZhk zs_maAV!9=ULzyr4CMLd{0d9dLhJ4u%PQX8NUg6tvybo&0`5yJtZK{V&-cG6zfV~;IqcPAdV-)#{79z|Rq=n%2LJh7%MK)=W zmS#66wH0k4!fr(^Zmq}Cd`~J(nI$F?z)^vvTdc(QvMRZqqrAOxHD>rp;#Mk3k2Me0 z^NSCgcs>;qv3hL+xViJiBW>EX+unQ^bxmh=KiG9EZDgVh4KxTj1ZIHly})A<;MQ+l z`u4wdoZyeh8zAPzRG`#j~d!R@%Vj7-)Lk9Pm7i>8S(3+rM55+6iG zRVl_%LR_3j99;5@xhc7Z{ASkgLAGQDqZ8@N4Zw->7j(bc6Mg>+zE$}i`w+nLlHF!F zp^k)4Eb8{R&0g6bZtHhBoyB1pzuMhu9uPvrM#49)m4`s}@XD^q^?SzK`+uMTk7WOTvsd_MsgB^}bq zEdRf;u4^?BuJi|yHp=CwXWs#h=ps{oW*akC&hg~CRwca|^rWIV7rYHq;?= zSkNTD@0C;khM`6EAR%SS$sX&~UgmLl=CJ}9E%g&X(tPP2cQMK|W#EP)uNH+)X5vysaVC+5Yah!p0}yzh9$ z=cGuU;PvCgc_V-MPLv|}Wwze!efcK&*9znsv?Ra5KN)I$wYK9NEw zC@9`Ox?6y1Cn03kme%uFEo^(m7C?Tp!s?Ra(hBVFA`3I}GK^%`#x!{N{2j3PM%e(b z0>_j#?gt11^D6_40%StY!~!bv=x$)auaw0xG5xg})DO_l-iAA&)@%ydoG zH?kBnm;eA+5di?G&IFNn%5J`D28P{vX@_}cVz6TNkPx!$#K8XHHRSa{U@xf+dS>_X56|&aY|v`1rVMGEl$%+zYJ&G*^J{jw08s*}(C4DHl7E zWkQIt4*@_@MGbIcmU!VgvMqt)hLF_#@l4cshs8_aQCE;}2L;zOmMJvFe7yToIN3%g z6uwX8e3aCUo0`&-1X;`ECh|f>sXyQg@q$W>%OgBu0i9;{JR(-yLo|~vm9?$M_ep8Q z2)djZ{el8`?xk`Du*U!yj|4#KG_kvD1=Tes9dT4$#Wq9}sa=lXHd9um7tHP%PBHGT&4K&Vz$UwViOnGd`( zA;^BKbL(evmrIhF@ZA?HIo%Y?lVwIyy##l=$80Ev%GP4FRt9c1TE@$MjbTj#i2Z!8 zD|)ihblEge#OVxwj9Y~s!4);BhM_Va?Y;cXJa2=7luG2Ip=A<#Q`h!l3RVSJTF7sV zxmW*>uY~Zd?^Lkg9a*3PfP5ee0o1HyKq;Rau9o8>g^=60v!i#a!me($l=zX9<;w#V zCYjamL)}6bQb@kvZ*V^+SAoqLs9icU_>1=s4F&NX860GK$}+;wgSM3G{C7Yvg5_l% zFqObE>i}Ep?K71)BIi&>_HaIv;`;rcuTzB^tV~`#mwmNptn7E*;dkD5IWFzBmXr9A zTEAiMf6MR>f-#QX3z(Z-)lu@5Oxff*BwV_Y!iv_z@4Bdv)?8xJ#nV?5@uwI-()ee3 zW1!v1&*Qs9rD+&2277VK{o-9=EjsME%Nzgy;;$A6ECzlTy>sLp-KHl4uwCV)M$_J9 zvQX{o>5s5w6MA$dI_#Tj`I-%PG~ChPDJDxFa{2oUS05K>$m(!s!of(3bpmiN_5&Po zOPE=?IR}OABGa~Xl>|_MIm??!vx!m&fWNXM;{7Ze$6xJH<7wYi_Z5bWQ-rdj@3RUB z=|M^$*itK`yAIX~zzyAbHLx&)vP*HB{>i3V4%ojcgVNTDei`&N%GUmcs*%O*FIY&G z%4+l9i);Mwzx4yXTSh@GU3=B~zTsob-p|;JpI9lx`G0^8Hj9ah*#lTzK#O&C-tf&7 z|7mlgvPu)b*QpH?QWd@R5`r#UvbBh1ZQLx*OtKFdHxg z&KbIy^t# z%j-vlRoBYr=86F$!(h^O%D;(L32#`MfhFtjMaFVq; zq6$r(xMc7=Qmr5$JEhF&t3>J8<^5u_=#noe4wlLHWG4aep-YSr68?V4#MrVWV+7le zO8|nEnh3%5YNwcV&C=gOI0mg~KeuRUpppqtE0nw3L@ona=zh>F6117}y@L%zw4lAz zQ&oOHxN!#f>o1dt!_As+(?!7bARcVD!?C@-#rI4tV!7X$aQ{6zTmtZ>Jx57pX%(Wl z!>A|ZTJ}%k!=7p@dgN&;`uLP+IOq(86*6%79QptltV}w;!<;LtI(QZ*tfsh%l$9a5 z&YOszR#H`3(O#EK4zlA{gFT$n&H|H3?O$9-Rww%)Bk5cBphlLMeK=brR9TK2(1OF` z!|q`5I613`5P6yfIed)kNZuoUF2!C**6|>*R11{S3iyy`hiikllm+9_kks`iwiwx`-NFV z+4~-(?$>oP5&dr^>iMfUj?U^R#x31q7PX&}Bh&A;2BkiK?;a7&rI;Ax54aUNQn=Hw zJaSp68^r%()wYD#8@Qs=ZTovnA0&RP*Yc1=I_BNA;o~ZVOlSu>ylcyynY3daD;K-L zwr2PgAAoIv$yj)Qnc^b`0Mt);@W33Zu%T*tpvssqvX`yp7__ujsC#((Gbk1xu=dhv z{Vq}M^AK{eF~WlewvOl|H8m%Nfxrdba_)qmgkFcug8UK)jX7;oAds?Q|L#D30BR{7 zfM?&gYSyCzUn-Wx0meDI`EgSwCBV4k&`8#!UpiNBwT@<7b+6{`K&HEK6(w^qg(i-l z7W$B_ZP?SIIsleN>R>xb)n>-Oz9#)JX zR6jcd^UY>P4tLsqc`Zg&WEji>V~?4Mm7ptS8l;H4BJm6Bk;9o&5V=l;&V~_SEC7Jx~&(7#) z4^e#YE1ywS#ehc+$ZDSd+_}O!>b>Pn6tNk@!vg%QFS-L+ShkCYjo%IUUfn12P*Bgl zWrS-1yzE15sSPr9pz@_$AK6Cr-KK%#??_eSTPk2MB2j9LDqvccsCdvtp#P zFq;?uIr7mR_h5>D9iwZ4Pp-<`Kt^iJ8#7mKN1NTHf#Mv`?z4pPELATpc_}-cr**!+ zn3|rx@cL7G)*xSu`Q*GHN3`&Y-~pthq;W{???v5g`b^4J@_0ZQ4cy%?@0;4>kb09x zKI2B-`cWDNhO@j+@L_O}o1A~|iv)C=h+l#-GtZ64o%Dvdm|*dIn-Oiv8(LY_-Y8(w zWzJ;(K(?J})OD0)W7}i*mF*~@%_kw9j2+`OwPV9(kIb#Dog*LV-4>Qw0+oyqzYcjV zypOBW_#e;jZq6P_N+;>)*xKmW=!jI7=t3-{4cpsQoGLsH=RdB5{mu#m-vKzR6p%{| z@)0y#=>9HYfdPg0-Bi1+ZG-zDh2b~c-FOl~WqrT50eU zosnV$1hMBthV1WLAkM+#5&4RO70shaM&tUB*4mBLNc2+Pqi5e86bWNi-zU_TxHwzY zY(}W%#ha;q2Rvzw>Gv6(p-#C>NK2b9M9W2jr+oO^t+I5aGIPC1allGx743lGU?Nem zwn6^|eb(bPX<6PCJEJ=e-~-jf@t75-9_+_1KbE&K3wfxBZ_}a{*1pIWVHaQYe2piE zg2^3xJjBjv`65tUTKF!R^MZ=*zF`6jCSEsU_v?Njar1jFzr1=^D0uBb|3U&RL!3_* z=7_OzhV>7TP5BdN78mGXpH0D2w3ig^a0r<(?$cBMt>1MGr8W#XjfoMZks=26Zq55c zhI%}sNj9gYBb*Fa2+j3%d)jO1&bv}~uYpdJE8U1dR7!d$`Ve$dAJJdk}*TBzD zU&{PcN76+|LX^MDX;wXml=R1@12*C=E|E{3glWp;KFY$CLg8UtmyDBk7&wxAa#I4z zPK67Pedi!5MV@uyr4#Spit-}SqRN1%UH;rUqVeUgW#Cf zBQ*}xS*C>R{j!ot0PCP_4Mthw@?Y#*reX!-d`QGriEyvHmtMLr1&iDL(wbom2!gvG zDcRXnKI^6Rp5;pyNIQJrIyGKu-ot1>X~1;9O@DRj>9^pOl>Q#-d-5W?>25O~Q`sLP zXU}_PO=}strGZoN&v7%L$VT9T&E?~*-D3ag-?VMdh#(}ljV{sT?sr6QV1Cn{1qMmXOD-Zw3ewx0!1wD@{nmeOhO$AMgY=?DnrmtX^}Dk_sD zURJRPWN6!?A4Ab%zK9!yF?caXrb4U&>PX_(MW$n($h<0!_oy&bb`ZTco;$h8VlOc_ z`c85p3IwXUB0-tHo4cWWF19P${xDa*JGV#^-FmD# zYL{TTQZM7TT)^vr!-sHTe?EH5C5fE48U}v>3Gm?Cz=kv1~z3rVH!{IcnG;`dkiSL(q2i`B`?nY`k zYA2f((q|0-*R%i23(-&f?d8$0dMzEzFFU`VpO-QI=MLr`&B#64@!vs2qbr<^ZW+sV&Gt3M9 z95s67c7@ZpxdRQd!>-U}zl~V-&T52nac0wK;4~+`>}Oe2vxa;4Fi~ z<@de>g?h$Zi5cEfN6x2OqrVmw4R*upY5iGDL9l(Dp|r%bukoavKOqn*o{w$Q>Sjzw;4ZS963O!?&s-RYd^~L9)MU|Zq*Alk3MdCyS!^6u|@7Bk=98SZXkdbnYIhdps z)EIe8q^9B2xIVYD8YD$lv8kh@6Bd$6=Ldd6h$?GUFLQ)-<^ zKyVVGN}oC+eSv-7bo`JMFmp(5Z8iOUL;x(2Z#>^Hp(ovXh8lusTpzg ze`4uqqOjN31}z?pykb`#p{S@h15nDgmufm6;lf3LmvJITMY`iqxA&#a7_Llw4E;w@ zfr9)m(+w6bM;U1EBjPHWUG&`cDkMQsg8qYXi&_`N*KQ9RXsJc3J7R3=+VHq`BmF57 zptD0F&3^8$aN&ODyhg}GpdUjDEOe5x{n2o1ec<^Ba4?nxm zvPP(#RdmcUde3%@%U0<40D=U7>^A2APf&`;N~2*WF~Ik|7aSFRUnO!TMA;aR^4Rv| z{282S235NEzcGyBkVdlaOL9BF)`E!!k5WjHP)MjJX(`=Hz+oXy+U;5P$z*vL(SA+^HRp>LA9uN-R-xCk+wEn#YNSYV2d$0^3DHKA;V( z7zObVSFYAIx3S4$Y(Keaw{TmBKFW9cJ6D9$ZR#%lujSjc)&Wg;)JAl>Rvja@f6P^% z(H?|ul<8``HDc-yRo)Z2gVz*ud!KgqaWm!Te|Lgz0q=8Z5tb!u^%!PKR*&stLX~^s z-jJ6t)BI*uDF@M6?iS_h+Zp$S%YkveN+X7}>HU=(xSd%yxGP=Q^7%oZ{kyfTt@lvE zp!v2wmZqjcxEy?<%7G??376eh^#oB||K#WX*^!EF^$r1X63cub8Si(EM{ct|B6z;! zLIGmT+w}*%O!oCu7W7lbt;qEW>*9v%`wb}BrP|eYUAUU`WdMx0%j2;zdRp1XFs=ia zRRr?e>|GC_@t0&9+Ek;J|Mv1^fQ_(sywnf&Z`z`&X|@cSJ80JI7BJBC^tXL=LNfO& zy6-^_PcVQRqm8=4>`UDHEr_V%lkOJYueCqN^U<{=Bzz&uXF}DY=YqG~U|Lx1m3wuaSa4w|ogs5AU<6 zk8BOv`*_tFkAEG@dMnbXTT?c92mRKSo|8~=clh%J{CYK>!kVc*L&}Q>DPgE4NXMqu zDSy4>dF8=WjlcWUIXmK9v$@3y+KouJJiLgz+`F z4CTHC=5zf7L`B2MS5n3R0wF+ZWi*(CN-2;jAD&02=e;w(Da*Y}>bFaJU6yH+CYG0% zzYc5HhlMnW=q>Mizh%C`i6EqQc!yc)-i+`R?(O#TMU!Sf;%$7-0q)BO4(uiP@UZCS zUOy%{sS+MOaFODjlSFl~EFIbkUxjUk>5c$5cd?A?+zyV?M~^mVKB4rrV}+{}N~*cp ztEB_%O&@N--34a{$M%(VFxVhSjjR;QW36s0fF&j7Cb-Kz69WHwl?-YeF3Pz>M%M^3 ziOtxMvze`iOZ3r@NwY|QwK3;vT};$->gtd>L<19dDG>{nTKeyQUF)BBofYjO9;fBN z5-)SerL^unxqa_xxz~{$*H7;$$QQ0kyotGM^gxZuZPx2Za(y6%_Kg<_aRC(R=T^n! z1th}ex1^!YD#UP78+>XP=EvWH`bzKeSGa~&-{3~}%QTX|d}eRKs^LtM4ZPjmK+_*H z&PUaCy0eCu`a7g5nEl}4>c#*CQ#+f*BU=KpxouvfI$+qo5)%!MP)cghk}4F4#tJAm zSOYS`im*;JNA4P{nd9JKoKTsm>dRbT6Owhg?w?^)yA9Ot@xCR)Y8yX{!hsqAsvRAc zLk~Lxxg8!LB5frR19{qUDji-F>UdVM%*ORU?TGSpZ)e>Txcu4A;@NdZJ=o-tyso8_qwd zr+GXKI5pIG;)At8@%WU#*LUw_ZunO`i#!R=OnCh)AxgQoRro$WC|kW#`EJlqWFl(l zKlwt>F7wK+z2K&pJwGMhXvJeO!pE|oDIO)!oN`{S zxBKdo$meeMFTVllH0p4_;eE5&BUzSz^KR%i`N~4|L9e*Df#Wdv3S%o6nv0Vo|HYiqo^JQLNrE=*jn0_vy8QIC*2zmG+- z2nHQx>8^hb4CPteD;qLTzx#=$OR-HZt;Eixrv6VR9}WaV2x^(YhB0yd2wm+gF?4wt zxTuQbFUma{!L4Ier_HDvrydE;U?(GcVQCw#($jiWY2Q^m9|%^QhyZu3=6phplo@8S zW`9C=_J-D4S3qG)y-2tY(B}3kY;)Iy&9g60%2E?vf3~$dGoel$-{ffzqNI%QpDOeB z-Tn7I{<*ZY1PquRZBOG;Y|CXTbe6k-$yD6zVB>NSrPRACsDuZwYZpA^VE zVcSVA;YP|#%*at8-Q=Ib41Di9)({D6AM5e`$ej~QbbIrWO&VN5#TdFyr-Wpy^0y#C zM?IG1{;vI|y!nlWeK-P{f~DQ(7^^`)gLv~9OS1dP4#aiVUTHW|qZruDDVS~A-~_XB z0e^LMmDGV6)f^BVPyd3N^pOQlAq;;((Fr?n35MZHNaYu7S^-wLgySZ( z(?kGdY!jJ>lznHrcVDQIeo<#|J9{{ggx%ciu!TXPI3T!a95Qmykc<+wqa|}R2_M3# zv)y9EvPH;&bSVxzj33N<-FXzN*-KxL8tJt`Da>JVvRJ_AGbYk|0BlYta*gR?48nF(oimI@yMKH# z#fdnQpAD#O@2kuD->+~Fi0Kx*l&55Ig?fuayQ|(XM@>z3@7HYM>Ui>Uc*r^k&zm2I zzc%r3n2Wl23?P9Trx-Lkb9m@i(=nEBzh)gU9}*NyvM_OXci&sU7B$F9 zb}Y3IMJ&8fwL0qpT6a6wggXm59?gPdH0v2UTRz6X_hh+oXOZLIjpe^T!Lh6T;*^ek zld7g|I&~u@#+b$JviU-Z8<`bPDr>-g=H936Phk?a#>s@R!7=IzGXd2{S*F5Ba-AOP z%rx-b3NwX$k&Fm%O6g}G*l?w6G@V?5KG}v?W@5Du8LWqTrK8M4;hlh}2jFI1PAlJC z%8~mPlE)U~qX`=x9#n=5`q3bhdk}1BxVQy~3hR-c$qD-R%KiIuxqHH=<0)7ns3VuGT7u2eck~)zh1Pl&K^_x+O(k#av_a7&c(zj&FS=0 zvJP|20c8+;EZ{!?upkGfr=ubPGOb|Gjj*g_FfEq8Ey}Iah~)!MaeZ9ZyWaBY2#;ys z%TQpw17o93HG1A}|9egT`Q}bSO+>5$cV(#rGdw+hn~Xy7jSAC(_$xCk#&#uVgAyzn z+FD0gPVC7QK?P+UeO}>xT5~7Dk>q$I?YVz-cV2&PFLIN!pQwCy8lAcNZR0Cpgw5R0 z@~F0rIojyvEfkkBv>+>s8OWT-e9 zHF~rJD$uMz2BOMHY$E1?#Kc9nPwqr#w>KMAG*vyUdhM-!+=)XpZYzk z{gJvMw6{Y68Y>OFez4!E+GxHj2LTbkdL-i=*J{1`X=L7AL)qW>T{6}9E03Di5M!4Nq5O&<<|$ zT3VyzWHAn*ZR9vClP5hHR5HPm>@GFTE}X_|{zHb!Ovz@Bh`jIL$(@~<$9DnON9{@* z?R_0%AC}3B?l0G58%u3;NzYsNV5FXA;qfO4g=ZwPj?>?NMKX7e7 z{k!3|Gt*<_LG*X&XyhyJO1y(%f*rBgU`kfBPo-4ZYt#Pg=_IIbW&P=TzSB#BB~oi~ zvMT1}E3Opn=ko?(Ta#6Eei!z*YCztXv`o56@}Cs&Kf4y(x=;G*9K@%^u1oRyiJ-BL zO_IphdrTv$m((h*1_>z)%||S0?;31irz#sIvEY>HeK{u7#{gQ$uOZ``i>xDT7nwi6 zwvVOHSUQ}R+=B@oTE{-6)*tb;zB+C^`UaIxh5zV*sFJHN2|o}b{kB!xydO*(*t zE(((MUAx-`^iB25ov%rZP4e-iR8wvHn%w_gnZ_f5fCLuspvN;j$Nb#V;=LS>!g*6# z?n(B&(78{6&obDmxh16M+|}xLq*ZmE+EmJbSBDrO&VA`m=(i+;_U10*4-NXNw_6s? zs4anBN@ggkahY$rvevz{g^`&!Lg~JO_{y3qUO7TBeR^7kgMH7E-oAirmKXz#D}v+J z4y_sQiZ62y&GecIS#=1yx52Q={|y5mlyI~7US3{(V}L1K zq|UC@D<+HoX7#`&O%;0soQgFU;hT9rvwem-HBR8BRAZ9eRaZ*;CMyAdH6v}WoXvBW zCL%n-S5`MY#+nqEIC;Q)dkxKB@13#4z$@Dy(vT@>(wOWu4+VKhjfqCr6r9xJ=m_{p zxJS$@w4%m{)gn;kyzp~w9LChjqhzKPJ3C4T0U6LU#@^AjnnVZ)@3rX^SS!@u|6Zn~ zVL2bhU=@L4(ussKfi%NuuHRJCG*jvoLxX(rTW4@BV_FcU{h?#Q1(T6n3XJ|(Rh%-K z)I5g_eQ9Qk!rEJLKPgw@0MRek)1STRp(c`v<8X?quoQqo1^KcU$2aL9kw9?y)$gz0 z++1lLOU0xBr9jj;=6}+{jCajd*oM>S@Y@O`8GHB`4gt6ucJnBEMRn9y4g0-ul(mhg zfq5hx$uoWglqU}Lyh=aI9_DjKMiPIJQ^&DR`O!0+7Zx-%HEnmfs%1)D2c%T||HLEJ zm4TG*75KO4ScFxD>^&fF0a9+fqMGun6xeAU&*flJzhLMuEse1!cxOtAp0Kth)N*!r>KR?Dp-Xha8zf1cUU}^ zw^ZG93M+~Mvbs70okyX*7QdG z+jlE;R4n;DcW`dDz z?{r^J_yRfs?|0Oe>Ekk+7lpeGdKlMa@;qM7{M{z~RH~W5X3D?n&Q7*;ZZ$wHTpIih zf$oGtib5(VQnkm793kExF1obgI=X{wS+3BM9!OSFrN#y#Py2Qb$d@TGW~^6aB02}q z9>O%;(~yglw>6d-7fl*cbU0AE9MD*J_l8#oWq(}9pcCe6sCu+4BrS1-y&XuHLeQHG z&L)<&u~N=3Q6x4Zq;~Y^F2d3m3_GrYL5zXVl0=8z-RK$tjg6otVCw0*s!EzeDfb$k zjR>9@8qWTBo8KGE_vGJx?)9w$9OL>WTdj>7e7Z|#1|;y@k`khVvcq8ku}I7MJlZ>M z)0L!hkqt$U!6%e5)8 zNtgXe*tm>G>~o7uRfVTNziATCGc$KXr?^$=kgslml&<{NNl8<6y`{IlRST>XR?W1I z_m-OBGz;LdJLz*bUJUe5{}c=9NkWrFh~?SWuH}kvSDT#dFYkx^WFz&IADi2P5;6?^S|3J3P-_#r>(La;;tG7`MJIaEykmYoKR0t*Vk@dr2pb*|-*a?j;#*Afhv>3#5W=Oq0KJ zYDB&+5h{Tg)K@29ONA_CW`^_MtTT&M|W zOth!85XP>=oJgY!t;WjBN?jB_fK#E@3TBaT|44yHmoe*nP$}y}7I>La{)g9y8xAjZ zwTktWNjF=|Dl$XXq9B{6C&kLTzJbQwhKFc%sm8-0;${V-)plbxAR%l_p}y z=VUq2zULW9rrnT3dxNm3N%1-uhU)b3YOUJ<5I_YNbop7SVA|IV&Op*G&*~GOy2awL z6blUVUs7JZ5omw*KeylYKjH~ae%hEyR9VwgpoI-1?kQ>p*GAC{nF&Jo<9z;{EXK{F zX4QaFsd_NE0>R9Lnyq;_qi%KSIW1(nY+W11-QGHAj7&&m@v-|^>awP$^ZR)_&K}rh zD48>}3QQqPmQ?4##-yRPSYU8UX$3^}7T9Sa zkL5O(HBqMxVB>}mvk5lavtBP6yy{Wwzw5th?=6ta{Gab@hK(!2@%~N_B5$9_L)@>J z^k4n^7phm``TD9gBxC2>sx~k~Bk}e1Sl^a7%HE*KUnCGfy>fDLj?HnB+VSs(?YwT_ zfx6~m)fURGe&vrI{yi$2?q3M__MoaBC%($eylbShecS+-#Kns0K*tyDk`jVB5z9EDMrYP zb*rM??%_|pAJs3YvY%xk!tdo>vf~g;Dt_Vmg{xNkx!A*Z4T(7O?qVBif)ta;@e1ov z9tJ?n%68>apqbCAne?AcV&b@Kj#FU5JD(W)VD+2qh`1Bwm&46Nwpw@6l>q7f; zGMtYJ#R?OQ1LTXwyuOc!#ZL7=D}gy5B@pBe!LVc$%e9O9UMe3>RO?h zS;M2hp=v$m!yFISoGc7EJu5(6Mo5${2Emd|1#YhF!V+b|U^y=eyW>4H# z5Ci%YZt50r?)gR5Jd;iuW{kna?R0QO(?ffUf5!f9vB(9eY-tyo=yHJaFN-5o`F~Vh z1z6NwvtLk@6a@to1f^qX=@ccG5D?g<8|jdSrKCHT29c8P?(Xi8?(UBJ$M^g0eeeI_ zVfTUEbLPyjyRC|*45gEx5#>r$I~9I7NH zw^>Qs=1WOP1IgU1!2bBWTg`B@uUL?YwWZ;r3PVIhq@8v0qV*KwR6X+H*=jicW8(Q{ z4#zZUq&py)ZOI8jy--tg(LjuPY_i;K4w!ITZwz8WgtaZfC-z|2H|xWD z419WJs~)NzrQ6Bj9>$!n-K-*IoX9Nw;c+%V#wq~1&%Zx$dwzd6UnTwsWz8vg{2eNA z-BKIvBz;q(F!buZzt#C4yL$lpB2CosE%?7i`>*1DvqIyKd;1yyF)SFaf@i5Fc0X!8xGmIag8X#SHl1 zPjyc4S$-%eb#JD26`w|!dh43{IN|m zTFrV$_~CLvTqQeLPY%p-oe+&jHlEQ|C|TSOF`d;_Cw6u`aA*ha1&5Aq87|CteXH_al0Np&3TJ5|)e%=Ya= zRg6S~LcEnFg2&{J?VujL@8nlx5-fFaf3|24vhS?(d04#wRwBZpf#DnoC+ZLdPBZ`% z-^mZ1^hS-EUmlpYjnm)1YMIEgeZAoSeaPplr_0O!B!rjaVmLmv%8L&I_7nlma6a6u zn%6(TJ690-a`G50?mCNcCdNB015$0xJ_(irXigczBH>)PzdN^J#<(NMEb<|HwAeifHTT+ z9_`-&!eFvx8!|lM7xK;)?`xPv@~cB!Z8V<>+z zjJIHl4N+)I-)0OZVcw&$qG!=gz|Y_Wpi8720O%|PFBzeDj66J8Y%?u~&db#idwV}H z2V<%V){%vlldxhQ_oixPXhSdjFkCfbt2AR`W2<7Bi_-aWA}Y@mu$<~ovx!89 zIFziax46R1+P3voaUeJt?OuHBe0*3v8c8wE-xi?Xiss?7U8*6L8-wqaIj_dU+vP6j ziY9ruTA_u|=8mCt?$;(9_P3`KIwzMCf!oXr68B4E>wn?oD$*AJyh@@r1)&RU>cEOu zgj<>(aV3LywWQI$f|7*SegugAc80=WiT0c6BUA#aYHI50$|7x{L(Qv?FTm4XLKdAj zZdd(oyqJUoS)l0?-a#vG+yIjm4pLWFj`SCj%fX?5kIB=FbU&8zck z2=z%J8YA-Cl(Z}@4fjW6hy|`_t%P&)^YvoOK1=OHEHn?b0CfYw3Tqfj1-C#^;Q8Yf zou}A*4aJXpxTpJc9>0H_5XryriuRmv?-%t!XD}5*6Tb|^6*iet;mCa+qqI}?MIY_G zEisVS=Gi!8G=M@m56_hhC_VSTd9O|$)rkMG>Y;zgphS{!dpG2VKc8e5^mVSRyKwHA zB#YbS>ZHvf{iTtbBLUO3smDUh2sXrZ)%QZBDFn2E4^H z@rY8kcrkL~Q(XG3sHnF51qR`c;o|3A0Y3iA-Ic2aJjrWyZLk`KepfP&U4J_=L)8k7 zI#K(Q@@_DStR~ivw?LZP$M}A$ev8^EZD#}=v@I-83>v5XuJ>v}&~;v0s=jf=ENYY< zN)|1ibizcqq{{TPN*W&wX&9%}gj@PesSR6x1Xn^;M2PW~-)LviF9+(SS-PXpQ4l}| zEK|~{(c4+36K{@P11-}ZkBc74AZFPAj~%`}(!0yzRNF!ux?;Yf8$_?3`4o@Q8tAX_ z-!J84Wlfzb`q5DYU*J7cJaf^3H)9j?D=;z@a*pY^UMa^ea-=ywlS<&6F|-#KX`3r;NqQ1NZGlGE?32YM+l;L z2ih)=!Cb|{M3aCR8&gnz4yj2?r$K}l@lN}#7WXjJ>{V|w^~^e%C)bY`X*yj44j(dJ zFN^5AouX+Rp$M;{!Dgrssv&rX*;p%t4J!BsgWg6OE#PgmD=cYJx69Ddnhj=x2V@x! zUO<$j4v>TNVAZJLbK#!3fM6FK48-|K01CDz7enCcfFYO$zQ+t@x`NV2xWt=;8Kv$5wYX3FT(|ghBbe*L!RLq{+Wnsd9Yj!N+qM(fYU~rPF_~ zYf&(0K!?R2le5-60ekLgWT~pdrpuahCkxRRx7^RHufRxn1lLd^`Zj$?Sn4ag4MBAW zyOq$gl}E5_Xoo43CE+y&c_lJrL)o!)DGvN>*C26El#No?8)GO%TJQ^h4lno_qX=0* z^qf65n93GTGGYIB2&l;ndHWyxvzHY_>pj z5P~TYc6csF+tOeYq>{;adS5#zhS6OqA%@DgU=)l;?64#P2E1N*0}S8vDY^6PGH1RR zik@OE136MiV{*KxYZ?@q$%R;R!lc(!4SkPvd`AersK?ZESj=-EVyr7U(80ynFVe@@ z#vIm}KdE?!K%%dWh!+*uWiEBIG%TOAkJl*zQWSS|P!-7`=ZF?cB6CqpuFw1vL;Tm& zxo6$;qP@@Xqn2ITfU8GQ!{J5EP2cCqE`MMz4o6(8t{jcA7OGll zn|D|lwaBqS?ZZ_|@rcKl+=9}lnp@cSESD~DsLJ8&44y0ypj-v2mXb*1S|n=NNe8mck6+T)rb zz8=x|-p3Y$V;Tf@XM2D1*pED*MWm$nx!Fc65$Bc{OT>*9o-Ps z*TC^)stS%~k$NjKhPF7pVF;Uw$xFlw`mRb<>!;to66SRjwyzxz2#A)4D*K}y+UWab zXIG9$(YLAO9_+51EZ})I5`Vfj@t@3WvOSs70YFZ5I$g7qUo|keiSV9Y&394D2Jwy0 zSfOce8aEXqDaUo7;CUt}?^LkpgaqkofkAlAbn%WRAjp7vv3fglPit%I7gw!sO{92G zrls2E_@MMY%9PuFujks3FZ?9$pA7JaaXpB{cQ@*-*+DN(YdkueL$AHy$F5maz0U7M z{7*Rtkb8@C%O*j0N{?$h>*&z&k*EEp0$G(V-J&lV&i95RoOlpmpk{P7i}F!$4)`ak zz28~M9b&Mo6q0O1pDWMURp^J;%~F~ZN(j-SCsYehMN#rBobr%Kp_K5EU95Q5fXrZ~d9Bi>Vbw(;Hs4Ltna~=TdRK)S5fwtr=h*g2Nz>{w=!L4~5BIvo{mSLw z(Pp$M&Rmq4F`ZXWGbFH$KZ5TGdlvXaFq|+?MN1O+;oL7G!!^0(#tMD;X6w%4y5Aq_M#?= z9-?mv4ZH)+K(5#L>7tE%$_Q4fC9--FKRu(xcZ zesbu`D2o&Y1FE%?Ll5}q6S=M1;*#(p@yiw@w9&BeB1?ak;?)a7c*@9MQ#q9Fe3D`AHa~XIYn=@GUyj{SbtXIr{G_xnDOgowu~cVV3x=SW zr}tk1@|d)D0g$|{t*xb{rQuKIjggV#RpL{II0~ny_!6ei6mSgbtMPGsg61M=a}6 z?N;TT#02FxR{Tu)AMl=`H==<>jRV`?1a4GqB?Ma5u4 zB+ep4H9TI*Lu;v;K1%+|6_8U*!*R`v_a|V<2Z51Ry8m`QNFqU{*7km!{Aev&@U=X1 zWp5RDO>1NPw8^V^^}@biR4^a>$f&&AEqXg|;S*HFVC36)D!<@I4CRcRx5@8cIcz{@ zg~19O>yP4$${tM%Z<6wZCftjd8a{U{1@QV%etIB}GU!>(}Tl;~BoS`%Xh6KP%FQ5ETp|R2@m0S3TlM4!doZGMoy8F7>s$oq=eE?bWL_IJEZ&rxnqFq{50$( zwb6c1nnnM|%gLIa+s+{CkYx{B?19HmqGMw>x$(@%9HMFm;6xdEYd?B;Ulz8!&WQO# z|C>AHYq{!XG08+_V*lhNTtGQbnSQJxXSAP6G1oDT^T)|5hQ@`*OPLr+4RUF@l`R=c z;d&jOBvLPV{_Cj$+xen*t4U8l506_8hmT*Ta?ZQ=kg41tm73`ET5G~RkSonW2G1Io z3oPqOLiz$j?iCF$4{v02y@Xtb&?VojP^I(Q*`>`{SzrSF7W%9|`yp;Iu)x6riXpFC z`^5RlRc(Syf#!%eI_rE@CSA1u$iOxvS!Yh>&=^_F_~?A($Y4amc+n-fbgg33{Mta= z|K_9ZWZXPidbZ$XYCfZc{|=gbvpO{yUcQ>YD!v2FjH5=gGST5gn;P8C%>MM2K~hSp zsvE~obn8*zSHyFMw)rVFc=CL7P4*?zFj>cau-E*(MXS)_dAIreZWyYaT4dxxO{Rj* z7Z>%L?Ozj6UjSeroFAZCAM@h7ams|#p?vk}9pc&{%r^4nCGR2pF-Wq}?1qZzfvXp; zJ_ECdbJfu%KXXlF-%L$T48-XiW&9RGOoLesqjWbNX`aNFD&XXrq>X2^XYfUIUpwf> zSAK}fSn1R<%#~V;HqzOdPg1s~5w42UHm$$=DngMtGiNmG*z}YzjD=cNLQnFjA`=hb z_T#F7txU1yF*>>2>*R1b6gU@8-CT6B@_qo__xH)&>7Crh17+o#kfa&w-LrURzYkOf zF=slR=_cx>*A-G(_6a-ec;^nR)-7Fp!qA8pXzChD8O8C^mRL>><^=!qKYmD6Qm~dGDCFa)MS)u&qB~}Pw8;b>3A{ep-8JfYkSqmr0$fY~Emc2wAeB-nSJ`uhs6DmGtdL z(JaSHM;-Hatz}?ix}0(~aYHAq5$n{KHF^@JfxB`U8XI!qSn}at&tCIUn2w9f=4OJ+ zX`*ZEotJJUG+3hLY7jx-*bm0jXHs*e$s9DlxRl1N_F@8=Yx4bnno=}w?=lLx6~K3m z(f%dphqvlvdk%hDhW^cXUNjPPGsTsru((?@nd9NNvpbd$7+Z&VqIN{aly*dFLR*z)!qxy5Mua7 zickGvka=gV9*~KHquqpTC}@%R=|5DgJ;B&w^&F$p4N-@YTJ2Ua($l@dY(8t*y@)+J zE&H-1w!ud7*?ASc&fjY;+G4gGuC_!6X`Ns|rGr%V&?=CL&_YhGZ^LxbDnCoMVXtll zn4XAv(tG+z^hlgyuf`LF;pk=w_(}Z1W?mapqJ>by7$|<~2AxVN*1y+5`b&b~7Z|De z1fMw%HoC#>V)Lx%99(z)E9J~B4c&GY@98#VlALvXH2>#k#+;xmr>xrE?TnY75b5L7 zxp^(2898IbYk1k~1-YG7KsncNyJKDfj*^SJ3KCkn?J->_geD$W&3}rwjUZYs)37?O zxH4(Uj5{&jmL?;wH-Qa4pd+WM=QmW}%UD$(IiT@YjO^%XJ`O#NL1x7s#5CM&Fm0;Z z;7C#~4izozNBn)nclpbNuI(?=!+Q*S6hDg}zl)k>)TqCi)CsBER@;vgB>IP||NFat z0Ic4iMtw>#D;KG6Q)6vhv52?*%%UR~v#%stvHr4$a99Y2P*9);gLyA!hx4LOUlvTg zYr7^Whd8VacXPNb%Do9cYW)u3sEC#`nTziEVO|Cg3$BcutgpPnF_kY~G?EBRgV<$H zQ#ug}>Y;70GWqFp3>y3%<~wM7q;WMI9ms4Z!VS=)SuAHx=oWNShYezaDMvlg3A{JE zsolSlJXqYh))K~m2Rn;S;if&F`KaLm)~lnbTk@>U8AX3C3tQ~GfVp4PQ=if`%MQyo z7kn(3_|9Qi!@ipC>Q)=66Pc457*f0&(vX}VqPyZtlgvs`=bK!)q5jyEHrXIB4tp-f zvx9CoAn`sU%e1?y+u$GOH1;bZI>WtHGL7`m4g==rU0VF=O(ajJInMQ5;C{bU>D#`X zvrJ{{wJ7Lx#y!$iP-O3ki^DlOx=Q?&zgsZS-(CK-7(Nm|M^4BRf2PTF(a_LezuN1r z?>hg-R60KLgBWvcSA|#@6>0Xg%e8=c=h@xuwOTg-l5dXWo##zomy3&@QuhBqH-iC* zs;y<4NpoIrP?Vp$Xy>SoT(tOol5Un9{VlF6d>C9;>(@C`Kgr%UIR@r(fyU9_Csb1V zlRtOBm!10~RYrM64lKc)#gf_Y4$~h0ujK!}X>6?&_;a&qZcY`?)E*oebrAhgOA)<< zmx*qdg&@xLwyTWL&R@O2?r5b;hkhz1F3u>a`{Iuxjh?E6*4=8y#0uDOTqbO=@+Hsk zg=6;@IU`ulQf30D<I?Bi#YpaBx^YO4c;217p}eA| zacWlIZvOmYKJ_5R^nNtp!d%(;G@Kc?1F$k}7Qj4rD^)X4m-3^jur+sBdF@tJRkd9a zFrNqjMtnlpoSvQQ)-}v0{OOTb;!0sJ&)q7Xh!hP?G(=QSqZ-D6u>*-tj)Z7{DvIZJ z4D$pThO{#H4}~w=38oN1#oz+98cG|gJA2E$5>x*&KhDDaC>k$%d3wF^^cyX@>(q!!2mYWJKcj|tgTfuSeDXsP}AVem3c{sKn=Oi!z4W_{CxiOs`x$1Yu)u{ zX)mR^+YA)t)26WG_0?zf{d1LcUynCj&E)dZ6g{FTdy83vI-)0j(%pD-PNJc%n$K}* zKbG>zC#|^kA-z6OLDD<(Eno+B%oYb5bQR>nmBK14K%W=&KNp{bVZG{B)#0 zAcdvbzE}BL$ApS$t!BeXyIGm8W}QPG^t1l+ff@N~ZsG00#X;xcXMLIu^YxMH-EX+Y z8Ul28Tdf^jj;CmK+Km_UMS~YK+6g(VYj!O4v|=}7qjbrw<-8)@kMoyTkU%DMYwFM& zK8(}`o+cg|{RqB@$Ul9klQmVxdXz34-L1(v6--&Sk>5=({ub;i4EOs?P;!OomiturSlciiafG_Ak5`k) zD4obXwts$GBT}a>BbS{WPK&pmfj>|cX-DF49Um8YJ0lVHgrbeHYC*2MII_MotXQmD zlzcVldZruu5>Pw&w2<(--qmWn5o&NCM3;H|8~o2|_J7Kt8IqHoJ+Uob=J}ARNqqZicgdik z?zZl}%3*blN%nU0&;fS0>7!I*K#=yrAyn`U7`a%!TdEcaBv+BS{Ik1n&anz?=Oz5- zqmv=s_jCS|m!jga!4hFFBI++_4&j&A`x=``k)bm2Cfc^PisQf#lp3zaiov*U-8hpN z$Blk!oaXLMN4fdiW+BY_x^>64`t=VhLE~22d~J&)lL{=mGz(Sv_YXeydZ|;e@MOTD z%9qK7PHsnj&h57vqGcp$8)WS57a=l0az23{L7iCbTo+{@pvN@?pjnkDwO8ZHbzaQV zN^6_Rp_azTl6Ueb3aBf37JHtKFWAG&No9tv*<6I5@#!U0MHreMMR7MDP8ipM zKzn+N=2zWyOv2go1&8C@*R-<+Sw9d`7QN(S@h8(Jqi{l(yGnLD+k{;L`aoCRE86oR z&s}+gS0K<%cmrcl^i!v+Cd|EP<;Ay<%Nkb)^`+iJcxK4?u}Ph@hf@Rl*>v9Gm`Yox zXku)vxb?^GD9Uu#tBZOp`TV&z>V!P2TYZbzX3x^eh7-Hag=HQ>|5gNS{)``XF2 z&U`>p=k?=1YL_ox%f6Tw7MUntMbI1GHC&LAC8|Zi)anLL%d+buqdIVBPQT7D5q>&T zm;=8T4+riZ|Ml}Hq(!}6NsEg>s+&MTRnL%1(J5**o&llrwk~>ea}&7BOrPI(-S|Y3 zy&Y$HJw$RV%MD*ua#<~#Q196atA#Zi*hk8hBkl)S(!Z9|@nRbU1C2+b%7JvTPS8a1 z!C~AL1w!#c0usW63PlaS-n>+BC?zX+rC|NK&bvjka{=Ub=Wj&$*~Z{i0C!;KtGpg-@Yn0jic0iTUGdbtN--nRDQN`{HxJfRfqO8-tZCGAw$m{m4@BVSeT%Vs1h54 zVv$hkWmO6hg~YS!B7r-9JUs@?IB@#s(4{aS6;0mQ{#m+_7~IeB_h7X+p|q|bjb5g_ z{L-$uD^Ft5dF^^)Y&=EUoBzj3fUVqEeAW%+uJ?B{EI(%e@LP55RK8jbRBxDEE~k6E z%@XI@RAs_uFX1!}2l%vHHxgzy`lHp7lb`PDlPp1ZkL#8c{9lU{bPYz9V8v1e6-rzh zq31+qPukWi8=-QCWIkPOf3#uKuj<2YBzKrvNNGft%C4Cv%AI zKG=dB4ni#1OXykpJ$^)DSFJA=zQS=ir10rVzAZYP=C?a5)QSE@kZa!QsrnU@Z-C;M zZ?cU9jp~REExN=F0Ac8-&bj$`_6xsm!_?e~kgQ}aFZUlUHCmuH@iEOsAc1N$d2-U9 zQZ1AeCfckK%wpIz$}0AlO(Ll*qUNkNEHLeOp!}oJ~pN?Kao`LHedd|u6QGhJR@-Z~T*V|t|G za(#YLKMkNn>4VSSwH4$1XnLooyJ+ZWBf9H5)Y~FGiBTcs5#1=22|avgqlEZo{)7`$ zvDy^fbgBiYHs8-leY;@nW}CuC^=9^_KBKoQmA@JuV}0b|#1?EQ`6YY_zTY_9%c;dzfr;zLvUh8W`>m$FmDg+cx6$EtmSPXdgVuT{~oX@jd~ zb7(}ee-*dlz`Elyx|Gzxc5bs&{O-m1#sx!vnXN3^FoTGqc=7|Oik=R#B8^ZW({=6+ zOfTRq1`d z>iDZ&`~b?0Cb?d|padm}FITu1&u5YMJ?=5EJ^Yq11F4BG-N4uK8%-L`GD0XEp4KxP zWACeTvdp~Zy-0k_eK?xNz91z=QCF{n=^&WOkAE!Q(}$9aD_;*xGd37Yz4D^0e@;wf zJXmr2af73cHzI{Zlu}3~YW_(}@9ku}X?K~w?XP3}rL~tzvDErW=(n5#ZM2qaA7%Rl zfC`ZQB`1cJuYS=Iu39nPIjWSWO0uxB9{Y;&0;?cG)6(*AndJTghzf+UDYSPk@q|ZF z{AG_Z47E$lCtFQftq<^XlcV}=|UR^s1* z?pQjoTjrUhsTSm!u#-LWEU0eY&9-p9bx-!z@D%7eo=0-6owL#+>D$b%Sv+6Z4OM)P ze^z6GdxPUlINK2er@t}ZSXYp4?nu$bd}!FbDmEb@fj026{Bc(|js%Tqs}r71eAxgI zeL9|j2k?o}6#`I-)FFmZ!@SJv&{HjbMZ|^)-A2BB!z)|RfgR}P)s6X2r}=&b?R$26 z##yYH&f=NH>V5~20>+`njs@Jp#9XxvnMGkH+1~Nzm@o<(MTD5c0XZn*Q?~f%TNx@e zvWjMNq$#TDvn&e+)zQmI5AWP#`MpO6;upleBpodatQK6VsH^IJ^0rRuD8;k)=$xq6 zn#YBXWa&#pXP}J^gU!?HTMITN)%m=!b%(#~N{f_(N&U*D8Ipx*6T6|IXU4q9S$I}# zqLOqI`#eb9I7&NDrm4oihU~6bszS=9zYDcP!0o*0nLWq^yQ)y&2mVJs-8D{i{$+MA zTcjtSvUBkUR(HE|qn=n0I)l?f-Igt$mp7k2ELkhfaF8F2rZZ}w7EgP??AXo(gLg~!JlsmKRyt;r^8iDWeOFpL3dKCc(% zSml`P*D#_IQjw>og+!W?(ycKn(zL5c!7jDL^3b@~lLL*Tj_vBBt^Vw3tZolscw3vk zHj+r7_^$?{;c3xD#{PEI=5-uo+!kB8ybn8sx}i-9OLfP>EX1P{5s^*fwjG0*wD4p zxVuW1$IRkwpRp!)yT-@HnuZ6ceft zdv2!}R*z(qLlJ39F_syq_%lMZydAUcAYrrOFK3 z1?5TMTUs$-LPoz&9uw&mi6Udx8H>W$E-UcXp*y2rV_e3yAPns*ttw0i2=vS5bv>t& z3$D1H6GupuR~0&NzAQ1M^C#na_US9qpif9+zim9r1fJ+KAK#hMeFh90#qUv3k71qf z&cA;!O?U-RtH6}+kIN?6m_ao1Uf;^(SrLUOQP+%T-Lyl7)rt#O_&Kf8YkGa5*4Um` z-+{m0nfO}uZ$6h7Zatrbx0icThY0k`7YU8IiiRThb9Vvm58#dh_fHLX+YNIKuCD#{ zrkX%6!{p9yI&r=V62FfAsJN|&Yqe`s}Gn5Koi-TxRLyP^`8|yvUnE_{Dty4n251>DZu#OwKz(~`2xWz zM&GsUn#fYLXN4F{p3Zh=i-AmjBwBD0x<7p1Fx*CLu3@sg&0fpQY)|I?L}t5s4hX`u zbMCOSr;7(ZqNwtl=HoZqyhu4`sLObx_F;tao8fSUHZhOXgVD36vq+(8*aar*A+*K) zTs>H4YiM@JT4)Q|g`a8H3N~;w61^kZ#6f1B+dq~1RZV6+b&UOOk*=OoKs}eW%F#fS zpHzT2+ctl+Cts$KqZ@_Rr=-c8x%ogzPkA(*pxa0m{0UDn4moQEWO5ip-0+(P1WVbH zZ|HYxVm7!5y{t|zz;%0Du9mg=+e}ur|FK{=Mf2rSBcTQ7?!`eGh&`H^4;QzbGC@Z#jdz4|J@KdJH>WTzDH_`6iLxu;kI$;7LRfn{JAx@{uZyDw>N*f+>6_` z^|AzO+NI;>M?YPdON^^twQGyoyiysVAK)(mnbdZH3^|UIEyT7XQXKU2j7@Le0pezR z4J$|e&Xl~Y``bofzPbq=VB}UX|i5VPio?QzgRq;F$3--ae5?#Cqtz>K+S#)^L2g?6}afC@1Z2wiJ z3pe}^NahE6zE7W4yv`zd?gE)T_bg_kl<9S2?c+?&fx|PVwdpW23tz>ESpRAgK$FAC zW3f~`by}>n-pcBhWh|gry!v>zzS@RJ?R72&t|!oVIoBuhDSHwN$OZ(0RiPx53%I&X zs}{LI{i@J8N^^^)!1ZSSf=;hLs1t!~_-9`$lN9^Cq?(9MI-)RozR!Km+1+=?UGDUH zi&CQX(4Vdzngjmm=3I^91luRxize)P01glx0I9uMWlWBZ{W!b@6v^G6LF?|ufxmME zN`WWKDMO*4V(b-85;vrT$C}9H7Ts~YEt2Zi9KFo~MM52JJG0t;=@wjEFmMqnM2FT< zqbyOt?G5d_na3l#Ua5lYiK)B-9q*Mr=1HuwLqJn&M1q_3oDQ5O#ZHUz2Nekj4F61b z6K`VYH)kI`9vztLP9cNK4K%%@Hd@G?DJzoua!g3Kay4F1av`mV>m$Yd;D67a6ct{nBqvwsKUjwFmj&A`WAMF-IpB~3iHnf^PIVIJYaxvc8E^%W}|N+on92hnr31Q;IiGKrEjj-+Sxg8G#GZ0Q@mXX>=<@bW1cQx zYdyJpY*cJg-{;l0@{^NR*-xl*PP+N!j{Bnn7Xmdq2C#n1R(1VaoH6Q?LAos`@_tHS z=MdbDGlss_^^u)xWk&i_GAoK^5}=$U3E&`j1Tou3|_qpYYi2&DJ@c4-XF;tvBN-ap9LwCR(xJkH5*)XULU_ z#^qAXO(r9>W5AS?ppr>?Tn=QO;NtQFjQXv}qeo)8bk#7@Am<++tCY4>DH50ZaAdjL z;wj`DZc=lHxm-=+->+j;X-Xu05)+a z$!X7FG?n;Ofv%1df)4W6=IgTgDZ=DQ6%m{+Hy25KPQa+I686kkI~9I24n^LNMF6J_ zKU|HKCr%3)-%~B(e)|EO)3?^culbL{LQWj(u+9=$^~Cbx#wZ?0=Weewbadoi-;|KI zz~JTXz+b!YAW9Y>Kg!Wtfgh7Af%JY^7#aB&0h%%Vgc=RtC_pJN5;=*DK;0Jhru7zl zZvw>b)lD#JRbda!ipk{43i)z|KburI`Q}j%qpOHFd&1Pz6p+F4)Ui(BZdqV1M#&h_&)Y>t^HrhD8KgTU>HLCH{|=D80SJE3h`=hQgiI+{dPf0-0u6pE zo+Qz&Q-4T`xz?=s#%pIOfH5gHHl+|n{dI|E)rd%^Z`ti$7)K+S&y88VGibTjD;A?C zSWuutE?7O7RURf3PM+1R-SB~j#|bDNz%b9^&Yl1Sv%Ahzz-NvUaZIxsg%k~R72G{m z`X0`1!qf0uqE{}^b;O(J$TDiU%?u<-*vcqkQNgm{Ll=!DVWiNv0tm-I5KcDpj#DM?sUG_q&b*~LCD8_ zq>Vcmh1Em3IBk1s&|zah?@l%4&)1!abf700h>Dj&@R=wezmB) zg4Ce={s*;{7~DRcyF058Aguw+*H*R2bR{J$Iqm2WO`-fvP9Sd{&`vI6*w3yo(6{NP zjUpzD#t&+vAPZD}PzO>ao^6u>PjVJQ6OFP3^T(h$w`)Kk85<~Glc{-~AEUs1A7$Zq z(Rdo}j#j<#n8@93M18!?Nz+Qeb+AZH=V55#ECP7>OEWG9l|xoqMj%eiee>^H6JDxN zQSG#+3d}N71xR8k^sL%wPZD8+=s3O2#)~yb7alPfKhT2`fL~8ceabZy5eEhMz|4G| z&-pQ*O7PB1W=~*KT&DZ>g-b&Kna;&CTzx`#5_7J?mU>-+)=hE``gk=Eei2P4_64}$ za$F{yw+HGO@UOhbb{Gm!|G>xB_k5L#I1k7ed4r)fmW%z55Io`(FTr&t&w^Q{?LtCV zvb9*3ss7FZ^6y$|Q-!G(9+uTULSa}rS{U0gz}V6<3=tS^JJV%=w+`R6N-mQwF7~XA zX09+^AZ7u+NVED4wDE}P-7hWb^!KJBxc6Ml%(8bvnCne=Q1olWDTUnOb9dTOOJ`(a z5Ra(6QK#-?5yPCU@JAS_7!6hySQbjCWbl_Xn)I)ukx&PQUR9`k?Q|j*4+;AxVu~mQ zMV_skXI;L3FnL5fTSm3AA2-S!8mWz{DbU_cF>bpgG&LvymOnc?`=ntX@a&v$ZvCA(Vz9kx zoiW%XEi>Gc=gs#T#RscaRQ&nV=k63#0zvF&jZuxEw9gGo9nLKA$kAaajnb8vJT|V@_UmR;F*}zee8%eT)YU5|C|~67I7$jU&RblY1PX_4 zUIN+4{|=5^yqng3{z;$LEvYlfjy~I8;RD`OdgS=R``te^c3N8Qs6eJOYl(>5t82AO zxH-_2TsJdln*9~wZ{GJ#iv-S?(>1XjOrjFo7w;2@VbF1Yo0W?sfxtZI=zk+d;3B{O>f76>VL&hA&@ z5!A7KO2~7Hx5{I_%ZB!I)nC>aJOj2(c6kk87j?SG^PpYoT*mi+OCcvw!}`EFnk7=s z$2F5~_0RZ0@`IlqMolh0Jy=yZ(d@LCqlv~29DV|SZn*y^pj>P1nsJKhD* zdTh^M2*82myVUu(J}G(QP%Xq|BGn|SbbMSu(_k2 z{nBaVk&C{|e?c+XF2PIL!Cv{F1ALkpObrlLE+-*-(Jxh~REoU~;|=L-i-faFaH0jp zU+w{&?a4f3g$35@z(sungV!I`CQ_C@SK861hCT%ZoK`}eGLZM=-7C{5otLjvQ70;H znd96HrF(va$xw$q2*5B^z0FSIi&;u`r>{cF+aY0NGJHiJTXZ)c?-w@r6Ys|-rGPn- z7j=b`I^h&jfVkyk$>+v&D4z|kzpczc4?KUHxATWh3bz7SM``Kg^j3eeQH+y~i5YZH zxa>~cS!LqaA9w}M0Dx5={*#p3>vKjh_+f)&_+xGJq5oUgvprBrEM@ScgT0C=qZI0F zVH%+#t3V=BLFwqwmX()Ck6#G+>eg=+Dv*(0nU%!zhA6v6*iOH0lCEYI$VUS?Uwqgh z0B-a`!5@n&c8-7|YfWJ0~jihQYc#(sm#{k)F*DIBK~6_`m)REXJ5Q72$VVD^*pXd&G6k~N*Hn6 z{(b9!_w%hx1D#!V9CC=oh4*iHPFs~pKywNPh6gG#MirYm1TdY<@#d^ zoRE-^?bEB07)i>O#e>;-t2<8syhYsLlISCN5zBipZ`Q7^4Kuqe|LqfaHKT$dH%I5{X&be= zG~5?W(AN@+k`Lqm&|sA*t-6}Q zVjF@Ca{C}pIxf{3*>)FE4bL?S10xL#3@jhoSE&NKo^!Q-_4f{jT=R1}isgmS?*iFr zIXeF(AUJw&k0H43?v8RDxNqNL^1KhObwsB0$K9^qd*~_DRHCvq6$1pa;3UEe5H6Td z$y3}E(9-EqmzYL zq+35uJcPtgt~>W0d!gL=UOwbep&4jnM$t8ved|O-P{xn_wU?I$tn3Uv_W%(KFJj<( zk1cH~rx@oYE))!uwav^n=}9ri6u6{dRQD^@ee(zpn;!zq245@d^>K6Ih7Fv`nfwQ zJV;JOB}!>Pl|0pmcqyfSWy*I_(v?#J&Zv~}XF&ZXA7aOiIOF`wsR5VrvN9krJs)5nX5OPu zxA)$E{IjNef&s-J9F^5SkEWhN8W7u)HcN66jp~~fUkZs3pwf^`!t5E)eHgrVvX@Os zoBB$8z#ED_Y1m{mqO1Aac)U9@sBuV?mn9eK1F`QgoK*Hp02u6op^Vcs0O927%|j71Kyz9$ z$-cY?`bFH=t8M+34;>e_e~`p`fHl_)n-7-ndidm% zfIyM7tZY*syCfsCxJPtZHn+n!%f~I(&oksJijmJkhRJ}BYbx>!(9>uwf^(l5LbG)4 zmYrPgOiz+u=2{;Yj2UPpp|LQ7K#EmqPAsv!urgDgbwF&R=4tR+n|}yUQBhGGe^5)! zi!`kVBm?iwL5o3>!y0hq)1hKscUrxj--Gm+8`22qq9xU9w%{xuTi1QzNI;-^^Zhuf zDAQ7dX-+OggrsgAf_$dBS zGie$1=!BRQu99H+2Lk}Qw^Z(HmJavIdjS{$U{`Zz4Dlns&t-Jzf|#5K2T>5jWpsOg z%h8v}l8d^J`A&KI1(?OL8DuhO>A{eQoQQq$UDx(f%3B*3J99@HURcL^1S5rjL{b!Q zTqHPf(?P@Wp_kqfm^hxT)X^VlL}`kMc$Q8=AP;P^1iz>Gn=QdLV1M)tOlSBn7Jh6_ z0>u^OqKCigSHj(cC^UJAlb!aesFIzJU zUS776UY=S`)@Q5+jqiEB`M!-9-5*uR%1KmFgsBsGJWt%5}m;Ey`uCH;_xor40Dx^g@pwvjz1?w zA@ChQ33%XF)+#D9;S><_Pd}UC zUgBOO=TK1P2FiV&Fa|ygh$k_Lq_tU2PQs&8%P9;BwHb#J@cv17p+^c2nZj@YIMB!z z$DC1Bb$Jgw4FH6MZ@k$H13=$Jbm?A3g**pPIKO}Y=5#vCg?8x{*VL$V_qPS$&tLZ2 zZ9T2_{T9~>lybVdzD_52un*sGU{rb=J)}{jeGldd;A^o6c&A(voGa`P=nBZ~@_0Q{ zE^B&vdb^;(<@V|nc+w&xUwwgjDC24oK6YmoIi@Jh_4LKW#@48`NSWk+(Hw_!)<|ml z)p~YlW`=H@BhU3R+O=!l_`%H87GdO|;Dp&cZ=VyE65g^(lh_({kZx!$N1K_$4JO+* zax@G2yzW>?^gtU3q^+es*^c+}Be+-hm!>xqD!tUOKN=1ELy+OS_uKk?0D)JYl_fqw zn#^XbXl%Rc7{9Km>0=^B9_ue3Z|?+Mzs++c4l#tFfDqsQ(t_ZJFb2>O;xn^BKT%&~C`-6RdLT15 z*%cYdrLQk0CT6Ggqi~9a{J~f;@(*?r$1THc6ep}g#}p?$7BV`$ljztm;d47Kf%h&+ ziWif*EU(Kq!#3lytG*5W`o7-Z#tr2513E;VWejtId*iH( zM*e;-X&;133z2-l$Adu6F)-3j2xhKYnGg7dzDT{pf(CojTJ?*_X z8s@prOMrFDXlT$l!v2a79MU7}OX8b3htp@ICZhl)KjXkD=>)WNbV1CE9in>$3={C# z+f+6R5m8arJbAt5p~1nQu{c1G0WbWj6t8cP7B^f2=tMAd?svXG?E3dO_nIW1-M^Lz z6#2?%loVB^xkLUz=0IhUi4V&Y$F+rQ?Joy%E|!54r2hW?gLkP<3lf1tm1$VV2=;HV zJ1`r$zORY30|%4cxs{%jE~RBMen za??I&tI)(gu5D1)twCl6)*4Xj3d~Y}AVV&z#RnTmVn9MdK(MjBJ;M0sEixpxQ33{# zl(X6s&B4LJ%E5`{E$^0*LD~27f9QG(u&COuZFn$2L|{M~Q5vPYLAtx8K|;Daq&o$q z1?g_2djOFx>5`J}hW{G9@8^yG{r2Gjdt_$z-dC(R*IMU#Qb@Z!Q@aN=?yxNX-#zkQ zPbo(WM3RMt#p}4s*2ld2ASV~kz|a5c@!Jfn;>bSFa}VBJU2I|ZyFo`$FxBE zyOHROpe4lG0pA8=N5Pe#+v|fkOG7k&ny!o%E`g8UrH@Ew! z@vP$+c$T@`&kaUuQ37R z_~zy&fllW|8EvEiePN%<^`3SFPFaO&CcFKH94Jn0cDJ#2aPT;cO}~cIl>;qg3y7UB zzry7e<%2=X=k==^^dBqN4@dQH-E&I^G zXU-Hs6@0gxq(7HXfo)-swCkB5lGdy{ywAk}^lvfi;Dxtlku z8l1KwEPJLANUROgkc5aCtmYf1r!~;?^Ye#Q>?qP)f9He7ub`J``c<#2=OIY$71?6i zNOOJKU5pVwvlkQ;@y$)dL2c@c+cdS}Skl8mFGt7`ge&+wE{``hC=27k2)#^y!|WX0 z|Fa*X^RTf8FPeyBo$2L!sK1dVoiEf;Du5J)ZsGq1k+f`f#F zM8O_@bplKd@fmnRMbiMtd8`iD@%i~xS>9{u+Lat8yex?QL;zW*B^S0y}ESv-`doFq{BIwFW zI6GM5B>c}DbK_}mZ`)8k%bJ=zYRL?gm6eM%>nbWLY+Y4^`~Wk#=SM~PS2xH-RYw5B z-hCG{0Rc_uyFjlQ>!}_ z*as666Em~q8YC$FV0$_6cMKV+CN?%UIzY#9)CkZND63v4hYC8baL6@H#D&|T5t5((5(G?!ObkI&J-rdz>1@=K)!1)FOd z2@*&XW*`*8H4M)#pKtD=C5L2XoY zq2yHYzK>1B5^c2Al$u)MOBIu%c1!XK_`ADamc^)`q2E}R6Yhg&;^gE^N=gDc2)meM z>BUi165rFi0xRyzV*PjRZ8(+YQx!nJtepm<)#xFFAB)9%#PnuO3<2)Mu{QhU-1ee_ z!QvMIDlU&rC|ygk?9dVENjp@-tozwt9VmSZo_bF zJ|7tH?58xZd-eqfJWs<%L3XormT~d<_T2o9d9rn8uOi%0M5K1QI9X0tE_}>txAx=7 z8_vAI;$kUDdgMhDQ&XfZROd7{K<@T1qQ0K9cPRM$s1%sBb@lZcLfiK#r0JW)pYrhV zBq>*bSdybzWj5HYBnr#$N4D(=C1w5NHUq(d0$=Xl`W-Ru`*$F`s7$Zo#io`zMuoj9Os-CXbgCO&&CJZ8+X=&Xr$M=lV>*$Mt@QWjH;@%OOy8~aj;0c=@LYh zO1*Bj77pWUO?Y9zRDMlO2zns`6$X43E7x)q3kO3$%?11yEVKS37FV3uTl}qGo~sqI zVS8&^pHF5*1}_FZPnkTfNa4jY8dBZi#9GnROYfx==JCOeQra64Tll|o6)3?K5q?x1 z7X}#e_V@0%u@m-ZbwiF&b$hgEhCPb>Usi1EE~d>;pOEFSetrmlXvpjvdxNkUC~~rM z*El-9m4t-Y2QxD|t$I?>K=g1RIKb43QicFUhFWSycY9MJ2+B8txBd&eaqTtu?4nXE zrTVoNiWe|>e98yX`AUV=+I1pyGSnS=OG<(ewffgO`L>z0AlN^ zisbeJvhUx&H!~~Dkpj9M*d!E10Fk(C*3mOHc6Mf$iXXDNx!t?-M&`mwY`oqmPV2o&7PmmqE$#t!LBZ<4YdZ?P6i4k}v}LpjFn zrX?zaF!Aj6{VXp-kG4=?|MMoDD6fUfiCQqMLWY2!FX<)lLJH->UYm)C5O#eLWfG zqQy9}6caUtEH6fVJ)C}_C}YE7>Q~_X{OFX!uQ9yQe??Zd`jSfqRj{A|ssUOf69zx~ zLRVMUk>Zi>(3p&y7syQ!ypmkQ#L!J$P2%X!dKb-f5x{`Z@wzzy_TFg&{JYYAK=b3o zz4=4NzUb<&4Wx1z52OHQOR?a;mM9AgOQA~f$QuuYa(csRDG7j^Kp>!g>}Y+^sgER2 z-b`1w^~|HT!f(V%n28oF5Ua3PbTmaI=rz5DjH$9QyMBO*Wdby+DhH@;eZA}6eAB|s zuG3r!>ztlXVJy)2-qpu2M#n-lGA71i3V&}UPfKDqA8szUQ*&^S05)xSmc8zx_s%@@ z_g^`(5$EQtRSIsDqNnnuj!1q#5gUGHm!W6E7&r7v>`}|M5@WFuOQD^i*`}_MDvq2Ht zpZ~dTZsu)MOQ6+yvOfFxt@XjOaB9-tE(tCWM6P(@43-+o^+Rofs61I$=0M&GHJ=n) z&AF_nB4bgD8Iz~7+X!sQn7kq8{JblqI`QeLbSBVwg}hnpM!r$(j+3@e;9zL?6~@P75f0DnW~=GkOPiB}D6={iL8C9B1;L(BJ6akA=qh&0xiAt(>|w3>6i6U&?>yo@t9?T- zY#suGiS#!N*#`kqUMUKnprBK-8f@xBC7`e_paS-X4ij2S@898h49jG`6dY)Obly4Fw;zRqsfubDJDIR!euGA zulap+f$u;D?2DC?bAl3q`hZt_oIn6IdVbZRhQZLyB+f3zt>meP&K=p7Q^)HFU_5aW zPh<**V$o?6lHC`Y7sA!K-K)&nhR+1x@M`h>nAA{_;Vg~FtGD2khk zRl03H!0httg+AA_SpJdl9j;lUuHrO)6p}WfjV2D(t2N#_{N|;1FLLXiC}vReN#WXi zkJ9{w8P`DL-8&W>^t%Ms+Xo41ku>+3nwmg5&lp;m+U7K&Esgms-1w%f0&qQ_2irji zE22+X|0#CEOeBK~PavtD6VX|&Dc_oW7oSD~ucR}R^2~nNCQ8rg>FK@F&YYvG$r3I6 z7s~b;Ub}2-b7ylm90xIE%bL|)UP{+1VMlxYX=J%HPVfnXECQ6d@71$-o`J;>uH6Xs z3L)-g*c1WBY`@b=ARfx-Lk46b6wuj5ni&tPX2~oPSN%KBi|2d+SXag}mo@?2vDxEi z^08!w1@Nr_WLXkJGq4H(+Z!nq30UF$=xa=-JNSb~ITyG=0i=Lry4>Yx&E)2LO-&78 zU1Vlsb8>P5s!~bS3@sXv^b_)Va(hDhaN&?{#dYyUFir#6h)#VRe1Ei?E)`d7*DlQF zuTNQx!dgrd1O*&^82{i|C4t$6^TeiE`n!ytxQy<+;w8? z%}p*(ga)Zg6BAHnnlZy49kQs|Vw^a(OUr~V{bzPXjG2E&aE4V$3AOsSQ}g)C~HB?AH8Ok=%!30As4b zXEhJg+sq#>EjJ=cDf@ z<3;b@3siJkvrDo3)Gy!{4zCY!b$b~6V3lR*_tuWEOL1Fcy!Ldu#5bW0)`=1186-xu zb}^N_ymZye1m%2^i*vslhSGX7pf9~WjU;~Mqnpl?_d8{)8te-Fhz_DDzbn&;!b4XY zuo-`|Nn>RB>*_*mK$n&}p?RwDgWdc!1h4*v=T^zd$^By3vo?SW z9qu&#bKFXpDxdboQt-K-TZ2-;Zvr@2y|x|pzl}TNM?#7pj$=j;@x4&Af=$k-=>qPB z@UO!cVA3ZhRE~5&H)@aT^82$R|n7(%k+*KwV_Vqtj#h=kCyCfu)l%r9J3)(rk6NsCn z|Gd>1e3;bW+xF!h;lZ!oSb&H&0WfC;X<&{T`b zEr=fs=vpaNo$~UC`TcppQ!47bp82x0vS=2-J5BO;nhjnO7)w#q2u;{I=DYJvGhGsz zz@q64#*hZy{0(q2{@XHv^g@+Xton6mN*UyIE_CDLgtoR^{Gy+(U`-o1c7isw^*h$= zn54{t5J;7}X<3zp0d3o-4{0=NG$Crq^n*!3zygx$Gz|VmGbo8GnpTpZQ zSnMY3{P$SgB-3Y+yAuys2=eO5tM5D8+ns3$kS`keH4N(dQqmP;3T5d+&mE@8dvXf- zVkl*!#7HKpJ7)uUXK%vA6F(pDEIu$6^NM*imjI@umEetYO>!>AF$D$FDTeXy9O7dl z;|_fV(WdV!1Wfo?cR6>znUs+IQpTlbs>ekA!6%-2O(oYHTw+njd#8cz`xmYHdy`m_ zawWW|8CF!dO?Vxb2FbVISwTdluhiKjcw68OT!G)fupH2UKCsEGTf`nsw2e5$ND=*afrj(>iQyu0ef z&xx$E#LsbzKZdiX!zvX2c0jHgqaEchQ0 zLA+hC_sD;DJ-ceZ!^HY)5C3zGr+DCGqgIDRuLZmNuX_Q3gl6^sn5;Z>_A7rF3a0nJ zjy`$u#%n(wy#K@fnyjm2vQ{>RqqL2vNn$G_R?FIW+J;hy1tjuEG+s% z5J@G+N@W!ue!R^V_nS|N{pX!xv3br4sNniH8Xm^R>mV?IkB`5#wT1eE+r&qQgvwk0 znF4v%#j8J2`+q*uS`h*m0vx%3gr0Mx$6I zbsyL)cJbGatKZ{3;n`dsZ_1|gX5Zk{(XV}PsV$_QMmL3u{r5>b4}~N907Wg;ZmI`( z4d_yNa$hX|{3{1U&q2nWrCL>zCy-Z>>!|UOOg8X`qZrZ61mHK;Dlp)kZDAD&u;&fs zW}(K&ATNOI*`97s0frcRbPQA?-Y_fKeDw14pCj12mOzmF^EmL&0+bK1IN(K5%eP2S zfhgbadzyd|z9sCshSL}f3rH3R@sjOKZSt#Q5H={)X?cN@xXs@1qNcX?v2PooK{aZD zy&(#p^5T-eRA~0P1OINBv;3E%o&|R7CZ|%1W{#c=S%6!ZeE|H?M2{ih+_mac;KC)z z%Qdin)xjcct0I|`Nuy&3{Owg4-UWRQlAI?}wE-wSH8Uf*j;l2N^QSfKf4l24?v-)Y z{MAXZ5Ihrp6jiWL_+IZi!r!2KkkhW81FkV7x->a`_l8kFEQ*>fXT6m!Jev9dSUW&r z$ZjhAyJq17p_aD$A$jN)c$1Mte5~{sEh5u3G(~>@Uala0KypV7T*6|8&#kMOjd8Mt zfc9Dv*VW7SEz>&{3CQuF*Utvugo$W+$fAwhPFrYqfqq8jZkzA<9i1}<_s?Xfw{$8Y zK@(ZhvqRnAx3`i5uSWV+7WSMFN9lmwCzNN=d;!0YzXyMXkgrr~Wo0FGMNN&0XvFO% zXrHsNx3|4L*0++#2aOnghKkxSXIVPQb?Mzf#KF$~bAG-g&}OW@!%z66v89C$y+BVz z9c-EXU=Okwk5}-o-N!nZx!eOMclVT-R)4%By)xHjF`Kkzzb=vM+uhv-R)QuXx!?YL z#7eI~Y_M~q)K1(qxyNjk^OaFHJvK|4(jb5oK`3g^BP}Hbq?Dg$W(CeQM`~{+BqW4} zhGtS$82!EdKR=_Wqh52g5Xml`?FG%0flWjDlE*8(2Ck<^6+A!kWM3iTzz4I?Di{?#^I z&nA*0i|g#Qq7&^KlEl-2DBE{f8)O2hJP^pVag7F$mrl2&M11Nu(ui$WzTcsJnU~QO z)VZUk*A7lKjc^0v;a%+x72y|rUG^Uzys&T z@^TwbPhNs&EnE}!oHTv50Bn0Uu~WZ(x%yp7GvQ?j^9gIE`BB;}N9;|h0HXA1@nEL* z1UAFf8F_4PZQ<;qCs?pQTG6}sDByQFM#qBs1_*h^uhSqcjrU_g0cYv}2y*T0SQH%c zr>$?g2T-wd%6_ z(ODs%PFWe{kuRD+%fiC!><@6cN-p?CTW!Y^)UIm{fpMJVAS{3Vi|rDv-ObH&)ARwU zBWhtN>hhlJ zESX%U7m<}>go&kZ(Tz#6-9o2>Ex?L2lyHBbtlZ^fbXgKB2+W($#($Q=0vFhpeOg?^ z83nf^ErqJ3z=Y=H=DzMrpo5(5wDIe|eA2p~=&MGS)rt8zKBDd2%=}HuPgq_-fkO?k zMZ0DKBC1pO$?-8W%i6)g!LIJ@?QM>wnOX5xy@uH)1B^0zmVuEnHcK?*gVc^8LAQDW z^~RMarm$&}5i-b|q^WjSpQ(1oU^H!z?m3T)MCEuMTido`&cki0hhtffYWvJ>{lnH# znQei&z(AbB>zyY)ix(Fz3GL8@g@wOvFnlEc9<6Z&1rk(o>n`$`@6|2iqw&9#35~MM zFI3)MH&{9qnFvWv;+jYx3(GruyZAALwP9vz6Gw?rA`u56ZUjmM$9P9kD#c33^l?r-Tgb!}lpQWsjMwiX_O8CD#Xn>jNkHDJuPyFqh;YMrO&*JF@b1M-x2prO-4z< zlg(~LL-l7qiwDk#KK!HhY3pL5vd_4*COIPDEp{gf(aQLW=o1v%hwiQTe!&U&7^GdQ z8vlNj`KH3@aXCws8$mabwBqZJpI%07XrVoLLVVVKPo=)x=RtjWdnVT#$N2VvfEoWX zEG*((9&2H_CldEfUz*AXu?|ct2+s+-T|nfg`61uf8Zz`5#a%RL^~Zx0+i&-XtXx8DSO0tqC_s;cSSE-_s1 zB`21FZ?n0Om4fC+#x4kmCP4l-_k&E#l&s21J2@0K%h@m9UZUsZG5xxzS9O*>|0IV0 zX9Pxoo+RRN1r3L5ir>}VN}a#0sC*!IeZ61%@|1t&a})^4Jky7MRXBXkVLC!u^9uuu zRudPNQ$#r6_sA5U2=CuHHx;^etB2431RrRF^M1KAnELoVp~KQi z)f6oTKh7HC8F2@cr2S-TvX{xP2Uv@A+Ko7DJR6&vNDrGluHwVmfImva?TkiTCH?Ys z6w2!|GSPCI6&UED=^vKlc^#6$Bq-)`aY&YcNY#n-P5<;MfC9lsjOAr)1GXR3_@O;w z$@vm{|G7*$Z>q}Ed^w?Yop3Y)4qHReSUQ>2VtEr?6_Lu`Z4s)O%D@o_fG+}0dlR`c zBs5VHp|(X}3UA6_2iGIs$FoN(5t}?(?m~XVTx}8p3R6N&B>qy#tGfsnhy z!$TmT%~y4$el4b>8!@IoydM+U~j77w*cSwrI6m|s{;B$U)Q<{Xa0nZiVTo}@>uxXy7g%dusv6EFBY zrTQK|TIr6=4LJ6Y-v?>z`A3_hxv$#M69=FRj~(JS!qH5{cB`_p{pr;m99T+Wkr91l zR6(P;vWl-xhPqe2$Gri@YnH$>(b;65-s5AC61NS)4J#EcR4+)ewd(DuGLS2<8prU( zccXcsz&y?9daMHgLq=Zrb9#)t;^SJ&gFPPj`Vjp26ZC)lvr@bi;pIS^>nej46}6d} znV;5G1ql-2PzZdx%8Uxa`f@4&Q@Rw>6vV(yjt72knZ>}NX^jXnb3tqKz_UjB?xd{;QjX+^IsXAXpb4>>JbUIL9 zn5wc;%ioFk_oxg|!1PW6(hOOAG2MD{SimEq) z-KD)!g@ok zCf!+tI2&J}cae7A&N5b8+?_eRfk@lr1yUD9cOXoBeUL*qVJPTYpi6-Bf{CuU?(Sf< zu4&TsLh^BGhT8can+~(-Y-{PwN^GI_3=;oc$k;{4LL^b+<@UkXN6(+spsms6yrcP9 zmLh%?EwAVB6#>KF_oaof?o&|k+eyrJH<%vCcMOtFw~~wY=)F<3JWjt2Z$df6+cM?$ ztpq*|7$^pfm{rxP-u_NcbM}zMx9xPBF=Z9{bMWN(^l&=-Jr@${48izwYTtN6u$1zy z&UO`8LG58>gB<_Kx`Y`a0$c~G9T%IFzu=>u7gmP(rb9$>$_UZ8@9W(1*v4#oj|_pCD7%0 z)S(;Y=I7%z%pw{rDa;JCsh&(Zv6(0%xgaUA`(+|r)lZ)o)?w6SlrKUPNRc4x`wM&y z@?!Br$6)|azW?pmhblqKU4@~--)C6)iRW}cCarNoOa1dXBN|x5w%6~@R|~h(qHA;e z77&n%nsfz1to5C4Mp7de_#0AA$h(?*FvSW9p;7Ec z@^N0Brqfvum^w;0OWtha%CDb801$MN z2<3U(X^3PXHCat~SU)h?JBV>Pr^%xe+0NmVW$J6a9_={ZMU_c8^81MaEUXR`$X2O! zPFI_ql!mG5cqqpb16)Mlo}gS`L;X(8%0}2yJb9W_XMQlA=U>j#=oiBCGQ2@C-x&N z${$#J=cg2PS&56v(;db@3_q5wPDuWo5EEw_{J`lp~vd`xvy{(z#y7ZaL1TyXn%o?()ahX8$loS*-t&K$`yB zYW%yZiU;0(bZG?_P`Q|Zpl=$52<+IGPo7OX&^2WCN@1ktb(8q{pxP<&st|ANrk&J^e z0(nU;WzqzT`1NuA7|G1`FQ_dk}MAcp18t}O2CfR zio!MvSp?;-L79j`MbyLh=Sl|A)b_+KL^$XBKR{1NCIlmTf0+sST{Xo@xZ$ z>@b?Xp3scH3jHgUgoFeGo+dIF1bFtkfSg#b6IHL1F-6&o+#oe|A3S_~S+1R`yPKA~ zGi6mRWooSGQ8{X6R!j)Hyfxmm-7?qE1gcR2?Xj>sh0T)ZPEVV!1(%LilhXq4`pX!R z`H#Lk!FJV$$fjfQN2$B9zl}(XM(XvEA>s)ekO~wtk_$2czsDU%jPPI^SQy zAeW+tc?ZRj)zj%XWHjRm@~jXRKi?AlZ8eaPjCgbT1X>UpeQA6|GEi40mm&8Jbc|YN z_xu$tTIH`=(s_3M`vRZWe!gev2IY%h@i3)f7ZEWE{%Z;)uIN%;y-Iz|j34*D6#JsT zqbC;emM|YoV|}9i?j5ieP`Zv`$LOK<1@@0N{OFxYuCU_B%2ELa~Aqus?=pYkU2iP63I7Ts>3&CYG&2|w(|h*)%K_iS1~XK z*yf#AfLn=8t>*n>t+-+Dvg?S=-HYf>`#=;cz*9(5?N(6RVro`wvZ^)i|E~3fB8qm{=Q!CFCzO#`u_8a zQ{-^Lhqu1|ob@DF!O3TVfIQTo@axyFvC$ZTyDD}sKtaOZ9B6T#M1`QMV+@w$VJ}6? zQR<#MVDAA1k?Vb{hj5(^a%D)2JJz(EZV&4S8&FA~i4)rt!vyXvh%V2t=f^AVpS|oI zPZDdFtZw$YmVU75OuP*BO7>EDz!PJ*_2FGh00wC_6xZ~;&%DmPGguOuzr#(~TOez= z?l6tM>3(0KNxhwPDx{jN4Z(-xU;Xhv9wgJYt`Wc;r>BmM(n3=4^e-9%0v;Lu7X2L@ z_=1rmwRx;7^}hEjo?hr=}Fe@#+CVX?S;8`cAH=&J1FU@fZ5o}2z1e#&J!g>^Gwgi> zAjHB+5Pa(12Mj^?d-4-GuTs@|nSLKhPp$p6Yqu`7iM$9*ZD0bndz{VX5<+g?J%N2O>aQo{yG<~5 z+Ov?=R7rXDHjiZq`b|h+LA2UOC`H79-ZALr+fjmX8YjX0&tc!tF3?GKVe#Dp_FGxQ zhXl+cyp8fCkAx;(Di&i#pC@NJ~IBDm_4U-JVitG7*FztJH56=o|J=yto@ z6{_R5!*WxIFfY1>(sWju9-GjHb(~-@L zt31Xh4~KRUaM&_UkIQndV+toMuMP&&=bHB9K!5YMDc?xZ*99ygG1S7ZhQ&r?f}$90 zzU|EjOV%1v>169?=!PF4#37~>8qo!P5ry*Ap{^77*mBScMYGgHm`Sg7VDFGX*ByiTi!uOPs#dU)BpFSM7Dyc zXm>8(%_fMSKnChcT4c?*4-QFQaw5f$i3zO@rh|MS+13Wf-9;kL_uq*$xf<1&C-BUw z{8^rCW(ym7bk|0+tjq4*jh4#Z%wrFvco^w8OKS7vxnO<`U|EfCePdQ*Ion7fu1V0) zk%(k79f0XWAH%*bDo5xvts$Qt{a^^ZU zPl+v(luLm1{)g`TxVRz71<`LAF{=h@X1^1}mZ!OCQ<>s_lge=YqaFU2%#~j+ss`{> z`tNXDCK0+}7GiQqu~ZU}uVNe?Xduvd*$hvpBywIvC}z38xS+{*dD$1p!Xnh=V?p^- zpbZl_2hBfX+*5G)12fCd99UjmFDsjHQ}U=S#?ji-#;asS_~QS;`SoFI0ZJh3sTCee z6*}(vuj=rI35#jP;B3ukiJ~RZK8@U%EV^-Rl$+!HZDr@CWPB2{Fkw8AuklBV zp&UV9C}PUwgau`i*`IntL~?6+pE8H(bYCzBM74fNrREYKD&4IqN-aC;yr}fE##@!Z z%MPi!bbsp6_*IFO|1)2T@VL>0%LnvBhL`LiV6O-Knc6Vbg}WPQX|wFVYu&zT%xmNC z3sUVfFCR**&;%{VDWaQUBG6YwXXcxYL2fT}nIm$cEIXD}-KWNK4o-=0)DeIJS?kBO zhIR7N(^vCX$3la?q_uRbrUd<{Q@rxnJ2JjU88;VF{Ww?ZH&dAvdg20ah2hC%YBRZS z;hM0aGG_CW}0ZW^Z4N^#^n0K0n{CPx@og zEgZ(RxIyMi<{ry+2QL_lg%7dz1+i<&wMPc>1m+n=pN}>*>h~Qg&n&W>eGnqF$y13B z5}t8Kde-*8X8)g;(Lql^4t-xdjn@ITSB6KU2ax90^D`H0-<`X+oxB|F?YTiQFUWR< z&^ro^R@(()l3CR4#V$VoLn=Wlqnm`Lz=!*Nkd*pR7^SrQzg^djq z;jUwscshHUHLu;jCV$9V+PW0}Al14@>G~Sa>DKm@H^_j6$hPc<(0;T>`YPXtZv$0e zAF&9WyDUJ@M0eEAKi~K8LL>4F_V254zp#3Nc<}<_X}uo15f)30LGmp11G3B3EQ^;* z`yaKoY}HQxA_9N!c>X`zKaAn8_I91ACJbW$h$In%ey2CW{i;ZkvKJsIeIly{L|_uY zLJcB$)>4k%lRd%<{d9hJUx>ML^5EOSo{BApUJk=2F4=B=?L)v)mQm8-OByh5@2$bXt{`k2zOfZUlF33fP{N zVijvP5%L2kpC$1X^+y?`Wt?Uq5lTvg1tVe7m?2J!qYSp$i%{YHN2o6dZe4G3iTE7- zo};}O&Qs1t`@c=)&ymuG3!9wKCut}3clc~w9SpA=SS@Gs-jf0E2BN$B<2JVYxB`ab z_RZM`)lVgbJpm=4SrAP)CqF;KYGFPcMPBi%#fLCF{Ox`s!c~g4TVHX>J;cPOt7jH& z9#+emWTz*@-%GFvFDS)Dd#e+w6baS8+4u3ZsAG=c%-`Lf={Srl`wJkn7T5BH;E4-r zvedV|QheQ)`968iLl?;#Br9lx`W|deYlOzYbaNEN5dMk_3<|te_D_vH!mHM~9Ykd$ zT*7Wt7n^hi7cXMTr7zFB`9LMC6vS+D&v_$wV)}=S`?nA0KF>>H#uw!N&gX4f*uvx3 z`~R_GR2cr4W|>Z(e-T_c*!TeH7iG75lzw-e#9{_X;cHr$Rlon>6+UDjJNnyD^bmP- zKkbn^2C+Wg<*8MQhs(mj3d&O<$n5p-u$T1?B7}~12KB9UK0!;(l7q91oOl-AI25Bq z#Y8}muJ3s`v(55)ixws?aUHO@*ZY&50Do7C-2lfv^C-kBvUKT-B=sXXYAm{j?TS#q z#sr8VIF5cW3EBkH##_rcMSN2cA|`m1A||`^HRZkB?0PK2<>`*w$+&7dFbeBCL4Ftl zH@8=Qj^QF=%!6AC@pq7a#oGV+?QbBLC@gfiqBTpjYd_#GfjJfAbwaqbURnvPIgsiB za?kL+jU*uSVjTGsQr6@2v`x&>R>hJ!ERV87X|P{^kygu5W2LMeYvcXA&Y+@dkt;lrcLrfBrduh9Uv^4gcwWS@ z%pgdmaw?liFuP4^yX}BNK9Fa8H54m}plQ>qbnN{yZmi^m7ijA=nIoA3nhk?w*8E+Q zc0Z*0PMN(7iujPl?~t(07@5*D2bUL+OyGeE>K)uP1g|0N=W5&z1A-wro~ z+h6-RCc8o?>aU%~g5${MwU`lf0o)CNJ+tyzCw)VqAhTnuHufY>Q^%71Sj%l7y&+o3TEf*QVbd+(cI2`^;fyWFcb^7GE}`fjf<0J+l+( zSnbD;$^XAr#y>BW*fluBdGg4IW4BYLdl(8CGj`sTHdX-B9fCcuZ8h@TBgxN?8HqGF zlG0EJ$E@0)MgM7gKl$62{D#tG5obkOGi9a*qWOj>ArDs`pgjEQ@xHjY^I4+D)lBW~ zPcFS}G{}U%lk%6R3ed}>l%awPq#n%BE>Ln}13=@8+8cn-3@t+eZ!}=ss-3^x=(G`} zYcctqbs*TFrA{m&@P?;*d;`18yG-M4rubWMXS|HIx+W>M5OAr7A8M;7ToS&i==6>Fg)tmpe z(s`h2`NuttMnG@s`yY;Kd5+(y+im~Ou4iSvXIJdn90|E(BmVOz57!B7kH4#i@Rxk? z3oce8nILAB2+Myjfs;iFwRq{n9=yVyuSDS8`Bo@JcRHU2*nXdNC_mY#wV3A0#&3L* zjqM@BIo_SSqLzI_AB1RI#oKWOO0v>#wvChg( z#J8AQG;jZ3v;L?~Ld*DN@Olbz*OT_j?k_$<*dzeV)id1QCx<+;CJq)%5hIW^CzI&F zH4v=uV=(30p3HiM_<*?VUb>{bR_B+?!!X6G>mG{xm{0ss@L9)B_ZL^_RA2W-&wrGj zdDgx)nmY)hw=98r(^aN`W5RA=e4%v3X~E+xR+jey)Ung*G;0n%Kg50XY{R#fya#lr z5q-nG0X=EJW4B&hxZPRc1p*Nc0Td_~exSm@fIVw6-&Hqb+on(bL77}r-G&cBdLVcX zs1Q>WWqFjh41y4UHv)Hh+&l_IIL%aGpm0+tD?aXEzRtL*M(;7V$LRD-AA91TX_oik z=~#IrIrFcPG+chid;iaiaRce#AwCU<=N}ff1_p_KiMI1hOk=DQg87%DRo6fC)5}9w z(#KZsjLs*8lIa`ZkW2(H2UnF^eCJ<$AmT<`hPNb;F8x64T^wn}M%;Y}a4Ox$l~v&^ zb0BBChx_!Hkswhec8C}?i5vjufa^mzf%*R1Sd=Qu4p4u>oUI3z>Z+~FS(@(#QtAWI zoC~N%yFNVgujx3(=sl=szxnCzUYWHP4ZjQHA(Wr`n2JCE9bfl*h)sPbleYw z`@av(#zZleJKiKG{MCp5QH1}VRIs~-O^z=3EOP()OmNL>K2w9ju}mUPDw73mV0Sbv zOeoh5X#3#ThISDxv0Shs&H|+%4vZzLYJOk~izHg;N-jczf*KYACL<|HNo3n!hyuY# zO*)Ft?2DZ?20@J>CSewiRgvPk^r=177JN39K*SqS<#Cxs}2`qqOs*5JU7}Q8!r6)wz+LJaT!7*?b!Tj_#&Q3v`G$dQU3-9B{ zw-Y%jtwCz&ChX|O;dU?$#A8nkihEzaZa+|X-7pGc>v-4fevw=={8R4y?soKffA~W) zdCHBaFuc#0p4MlQ3oTb<>$AY@nE*N%Y{fKSm|$z!M^7Z>@yQc(C#f8Ood>Gl@>y@A z3yq7kYri_IVxikp2^e*SJO|*&$TWKOML0t>a{yq)3I)1xrp}Ink*LWChC-AwuEs2H zh>TuTOo%W+d3`l_XFFU$0~i~COQBX{KDC*f?g?PqG+@VojDozcXC@Wh0LF8OyM}u0 zM^B+V)M^**kglfr!-??vg^s5&x`b&r>pD#6yz50#3`* z>x%GZ?~u6tY~8Q>JCxb|d_Su3U@WuA`Kv@%+#A|YVL^5l&7XvVtkq9RnlWA+%cF-k zyqJB)j}1kK^h;wU_RpN|&MfFrhp~LWB=BV}y7+}+XL<4cv2iL3)H?`N=`?`4?Uw6= zJ2-bj&h5enn(6&Mom*Q_xSz^b_tf%ws0de4B!i;rNvGF2>fKx8LN~V8ppRCm zJ!-X7Fsc^IO@!Aq1_<~F!K_|*-rXWjj0r^UN9x=z{-D~V0#)Yrw{U1|;d+ftkW*+L zq}#yB96*9fAV@fKnm^2C^Dt3q3+UCOHlLRD{cE!P@1J@51Mg?-y*iz(T#Uc1?~JU@KhY@JMA*h}!*4T?JI8d!S-zWN)7(^6m&0Gv>hZK%mop2uDurwi=eyO>%pUja8>Y~Q?}EZuHe%j> zCuRZ(6U7%_#F0TzkC5BhdPjC0lnQzQV1AkX(SF;TT%Eh-L}`>7Ir@4(+Vx2RLkr9d z*9Tt-KV#A+F^R0ybtPL~^@bvAux+7NwZnk6usNXMjSeIkUKsn97c31HQ9B8-JX~7 zUFPGjL!8$VjbC_OAIO;q*gXZ(1fqL*omwb{2d%(CwO>#AjGznldcB{K2jrXU{8)Z&IHkzuwO(+5 z0A82A!>~Y>o?iX=(GJ7GU-?b}^)(RtN4bIJM5qkw;QG5|)pXi9a&<=MK;f__(YIUH z*fu2a#`n|_#lX66lou4dAHme6fAIZHDFL$ynm5<(LXDo;^$}L~JlbhIID}w^ak@E=xssNa}tuY##*q z;7Uq7#;*c8fzwF%=n?rZgN=n?jh5v&Rc#lr<}gT@g2r_h#lWL7(^2yNXf=>4c^{Q~XnOjI?#Ow@UV}U52dOzI9@YP_p#SV4@IxN^ z_^K5iga`a0Cue=3h%(wj{!YxO`CQ_{u)_3LRq~iism5XX)ot$+v}!=glG|Prpq5R) zcHFu9d)%-DlMgCVu4tfm2F)M`d{o}W8RCRj?g!`~?bG)&Z z3^ZI64+0KW!t!Y0R|V3DW?|(pJf$<_VFZNRj`WnT*tNIk4~sjjC$*faYisuwT8LVo zCrI&FjO<$%ieEg_b&VH`P1{*b(pZgg21q0x{QNcj2x(e)NkQFmS3_7GB%1Hw=O zLn>WLNjHdvf~1s`?w?7)lu+`fQWj`sB8+|-l-nI9NQFfTjeqG)*w|tDGkeARfO_u)rPejk@pJZ;d zUUwqS@Dhum+azeVUA5-JjX6ONSa+fvoA93N&`J z+jC?G4{W?j+xl#Iu_sPS?1Z_6g>qcwQeh`)AOm;B zQ=$32b?S51%7>5Adq+o&L*-Zoixs1dfqS2@g*N?5BFRbF8du^o-l~5+oh-8ZpB?Z& z?@>r_yEUMJ&GR)0+t37+8TrmQ^h*>^FgnEQb_o(VJxMX`dZPqs8kzSj?bq7^cgX96#gIu4 zRnXFj{eAj#9G`QLeIM<-COKT6fve}5OY-yREz#L(&zT`O&XBfH8UeeX52MEIq>Xxo z2VTR&ib)KvN4am2BI*%~A)=0Jm)M1lXWyWfqd!7iwh*R1BB-F#*$C5K8o-w6Hv8GY zGFh$LLdM9+Wv9j*yFPW=58z-(t<#@3N^^m@-a7pOq;tn(^y;y}eVmuxO3PFMtL~X5 zlkOBZoOQtF_}_|K^i9uP(1Z`Z)O6Zlr@p1nVj(;)zr#**N)d$j7L$xVTr2t1g8B{I zv%v;JkP^B+{f_zgj`eCI2@}fUO@9-~czK+z+b#1E6*{Zms5Yr7@spoikl_S=);&tm zT3j4+tXU?4d4D^*q40jS$}VB1ZZr~}g3)5H4w{FbyQy|fM^XuF<~Pt1IM5^o#1`qP zGK$Q8@IP;AWwnXlZl_Bou<1yPedQ_isKe@U`nc0r<&^iphMVnpfx5TBlAC<`!$K2@ zlS9^DC!MdCp#%g0+lxsFMeB4VNcngL_sW$TvS&eQPyU}FsX7NaXww=6y;wHxbJUN> zD2+C{8G!cBppWT2Fkn z#FoQPN`+{Lk@M6bWN&NML0>Hr2meo~(CJkO6=JT>DJzu)9G@ z7n_x~6OH%ztZo5N`vH1RsrTIOcz1~^OL#f7_t1^io4a9G&(qv4$$HA7{AXFt?R=&? z45TO{z8CUqB_zTZr)8jYvzWpRN{!~VB{{O3Pp7ASWM~UCDt=Ea_OIF!S?pOdUthEs zy4lk6@VBUBFC%;-CYzl52fE}56hcEk%lJc&ycb8bCmbdFI6afmE~(UN>XBB(2lWp^ zdFVVwUlpCP$3=*LIT_px)9E4z`)Iw_ul>Ki!{47WK$9*={AVU2<2ek(=8;bDv%Rj9 z=YjZ?_IqQd`zu52gK?wtPgwrAI3HVTizwf?6_+f3i-MNQoYiG-p{`=$^K$mWakIZx zIm?^3u%8WR-lRUJ?us6s(y``|m4&-;;-%}i-)frcM+O#iL}gRbtg&fCpL|Xi3xLwy zV}K7mGjfgX{CF+2>t5arK`=^3QOVHU| zWeR1+-$9}=ueRI+1E=S&HgDUidlvg+3YY#coUHaTyoh`MeAEm^jmV|tg3I4>$l$q& z^fXnCO;h2jn%4#jHoGJG66XC`ATBpCUDkN;XRx>1_r|dd$M^QH7$MJY;&@?)0X+QA z&x;|l*Ld7*8TlB{=+$Hyl`w_TE9Y%<{1HR-MCy!rd%A+geV+iKv2R(9h2A-2ydjJ= z6rOgRRqeVf6_n zNXWl-(TjhwCq@6~1NsS9Z@ucysvF_sKlH%fCiz@1CNy_-~ych!?4468BAtJ z9@N#pX!QwTc$QPb781!~*CjY|GM0KeCP$%*X)~IJMFPu;V#;{L-s(*gb(i(#ftuOd z1MjS9cSS06o7KI0v}P)^9W&k6_Lm>Pbw3hcgjGCTwmP&W z=vzP%jv(~ko3@tGYkbH>5LK=5!1eMuwTMu&fHFT|M&hOXu)=QM)B17Yh`lu|83ih8 zk22-WGvq+KMU{?xGE3p5kNO)}elWCh7H!Nv)BuuPoSGjcxo7ImGrpLrF44|@N13a>8>CKo zslcIMe*&iLpv23JLECp6|8F`<OJ5Y^0dWW%q@)_79-HDrgC(T~SR^oae`jWP~fB zH&SX!LU2Ow81{#g@Ip%0`|qe5^&aOY0i0sBhA7MJD^pnl^cgfQR}S`xiV$iKoxTwg zCHNj%$>G%;Z(&J8_?cLdNgfkEJH=)s_u_?j%hS8JqOI*$mKh|r!qiek~9Xev&D z#R$O^(K9(qubVpXpkZEatpEEZAoH!n;4%_9I8MK_T^Q$;Uw`U>TL6lnK(50D1O$fy zsMTWF@ZbyT;Bw-3hF{FI*Y*p_C59|yMV2D|1?AM#jA& zc%(mZH1k8px1$X0xKLIcptu*sh8%d;iW*((!d*9IR{LSUc45nlvz>|!(<3LaQk5Cn zaw#FRG}Tg(O6~;My3FdYy)|yPJ~B?nSBD$YBn3t}a5h-qE{$e(gTUqOb3YEZcxt~5 z#>tBA0A;)8Wu0i)lVmB;1*!*JDxkf2X3vMqFcFF1@?9fBYanR+xYFc-;&rO z49~S82|hSH_wrlV;3vXYE)KZ*Jl9i0mCO*S0ZON@(z`s!V;kCEAL44BxzS%P-HtUQ zTnKH`t;twQ7a9eUx)Pf$q#GZ^Y3x(#`y_$iwn>}a7M@!#Y>-D9dxt+dTM{V3B?a{Wh0 zp?RKmlLYLST{=OG|I@!ueD@9n>j1uiI~`bE+1Gx*QNz0!tp|hmpKBhern(9~?t~`A zUE@uYX`6_H=di!tF}up()5wm9!F{=`#Lwn#h4xM>7W#ulKgP$88Zn4~6fWAq;Ok7& z)V}@#UW->e1ahm*WY^0z-m z63Ee*eOSQ#=!4Ka6QSMgKJ#oL3a;75Rp?`980v^m6P=~?1U-YFMlIIN+WI4ToAh$> zSQ4~7vZHwP#uw_=8@Hb7WY0o_23QEMJHd>az7I=M!cw`>FetQFZET6JBk!mYn_DuM z1OI%e(ku zW&2`)`;mAQ`-JEPy)Ch>3sxnWGtTHWookvjFaJ%IIwYO4Xl$nI440z^d7qDk^)#hm z$)g?ncr=PN(lb}ZUM}##KoH_jR&jG=ah5_M$L5F6pxZ$I{OA(Tw(T6lP@|iAh40P= zYrN}&l*FCA(LDxIW4O^SI?hWM@@WVFXzxNBhV|>BS_}-QTBBx7b>Vqr;T&`yK`L7@iFU{LR2`~ zwB2Z&F*UK)u>Xmh`f%mE#laMZJyU~39|do@MsbHLs09h6J!WUD`1L&R#P}IW+e1n# zDkLuO4GJzy9!KYaG73U96(zEM3n<8{n3diSE7!=hvJQ3?lVRpzu*| zd3IHAboryH$pB9eJb*{0Eh-bZz=hH+t~rA&PX;BdXQ>%(uWL{pNHQ9 zAb>Q7h@GCW6ZP0!d+~kd;W8AZ-cz`%W;Pw6&l`w+$u*@Es;bADXdFy(xCpJdDhb_&}+N3|%3Zr~7SV$*y? zbJh|SM@Rd24L6Huol6%}1B&)F$vj|`P-4uI_U#8UL`!nVwOt6{)US}umbY5cW zkyQ@e5Ti6%8A7KdHX+todZ;}85V1eu8y{1A@x!RTjbUqxsk&lcMq)dq4$O^gSpPFd z+@g@ruQ07-7IPakD-D4u0NT0BKPtE(_hUf{#-UBBmlUP`?OEYpzN5@pP7^&DkC~&X zJVs!4C52g>W++N)X+gI^2h*lEO=?&R5+Po;gWTo%wBO#-{1tk6Uewo%z3I~1$uTN0 z*#C1pW)B(~R!t2gAkY3mKsuqi(Bk8{_6Ipp^Nl}B%?E&{ox^k^8U$gwmnxPc9IVQ~ z7bW+UedtdP$0^Z?~=cBc8Z7vO+*=ZU2 z_e#(=7p%uZmduan?V^M5Hz$g2ot!%5ho%kBY5wvacC9xqcn>QHclF5ZSD0h3?+O_! zn>;Ulwe3N~fyM)>LO@yHh(gbq;R5*R`UIGCnwC_#Od6HES>WIAynNoY z=Pdly&NXL* zDFF`_m9hYn)izVf( z)Dd}%0zmQPi~wO7Yf!&hw0vh-Sq+9&r;kkM7nx4o2Cbd13BMsAG3E*i`*-f%1$l!5 zk9D_H&y|@N=2-C!=K_Q+yv#cd=(OkQ-aGqVQ2gP3TrUmQ{kD(8Kv7FChO+c4rgu<^ z&e8N-krJHBPWO$`h~8G;Oiu>(X5Vm%wWpV>zfcmocX#3T>TL*^Ynk($REwQ)UZq7% z0J`aBjMB+{ za`Z(*h4xgk@ND4YN!eAkIr)8yOvPK}Z0l~yX(mY!DuQ+f>#2I$#?hJk8}4}if&PkH zQR<>4>z4EFb1lDr)DW$%%eG5PU?j2O^j5FXdlP7j>gklzDg0teu8LNyn*C~W%VdbD zv<`44Uc0}8Jdc;YK>`V=9e@9JMj%rA09jkfBhpmSz5$h3gt$pxn(19I(JNGd5y<%n4?ICor9o)-|VnT(QIr{%KctlNt8PMQi(OP}LIownveMae16BURZsTmo9p-YR&{g z|L&kV(YN0gfcRn&XqN}#I^DuawMe{n78P8Dm$g%FH=ovffJY5#;26_Q?@kF`gg%Ig zjAZd)+9U}G#W5->=aCPUsvKj&!9*6K*gOC1u2Pr3%2WUP$Y0txNsc%F=D61J%8?9J zjQqZIIB5&-WBKXaUChbm2jv!cn0z4B-bQVcbkEK4Ocs=$&VbDGI;izADOn%SWJ0)V zmI~RqQi3a36su0K*??BL^97p!^;RxDsazju%X2`1`-0|zZ4c*{lP4^-ZaOO@L|UrpKT)n}*FF29dxr_Kysqm<@?q!$(`ghpEF ztSewfTM-8;muFLC#*;nJ*vclYNK}GRXtB2n=V}dg56{PHh-~xn5nd-#WqaRmHKya- z4EA<-C=zT44JNq3@xCNy%Fwgo9I=Y%;;h=Ox?9x{{c`1gRf&S3q2U)_JWa`Lr#GHv z%8RA%>PC*eOn-lF_ehxuU1XDLTwioaed~0G-}1L$hYR2F_ZofBNk$X{A;IJ5#eI)0 z-ZAu%L!=SrM?`&j^eK%XNF0$S;R@H?6(D~%30fK2!)Ze@-aBXo@Y6PMem6u#d{AYX zOOgpjY$U@YE!YgC*@uy3IAPF4GL*1wKv+2y-Y8|4Uf`^}#7@ zgfV_Fc|Lcpc^}rdVA^F#vmA-51oYJ!ZE=m$czI z#XK{4HBmhztg*&t*E-0XSh4OG*Ao;LCj1O_xnn%$amO8(debYWJhf$a_&YA-hk=?Q z$h@F}=6JmCM>_&KpW~k;mW4)G=@YntA)iSI*SV$xi&4-*v73%86}&O3Kf808Vqk)2 zySUiB_CIUWS$}y3f~BmQp0}w}FhpRjQHvpNa0qiC!Jn`OlUBhgHJ-g!W31yiW&)aZb;@78ixn`NqOt0;ou1}(@ITX({ZXoS0q%@b zNf#HHJq?Uim3>rda$HaMQzjfiuzQ#+tPJ+3Wx#B12pn}+$az?Mw)fD z>{oPMMF5X#tj0bqoE@)^h#J#~Ie)CL*Ynb@wO>%S%3+27C!6wl={F8AT;g?9Ij78^ z;hvCAyl^U@f1UM>9s%iPdZkZ65%kM>?PStT074R;QDK7J_wL)QEKdrj57{E^BBK-T z+!s=!hHECjraqfK_{2@eCQGKI$LL_Nz5~HAHZaBqq|N!IIR@| zz^1!xrHe(w=(t4!y|H9kf@nR?*)CD#DZPuS9(!X)0|czn%eOD&Ere`e0420i6H~W* zZlH61yuV&dJ)(?q{O~@82*xvA__;g({rdxY)2lj|$P-xc=_xaqGA(9RvwuPAcCw~k z2&yqgh-Hj;l+M?HVFwP@VOy)Qo&RR{#CP-xv{*`jYgUH?&?~Vz%R&}cyH}voFan$9Wig%ZJ~0bAtrznSSn53}?hQz0z29aYdMt zIG2xN8_$l5xh&VM_iRi`Hz`zbAiwSMJfNOn#0bZ8;J`*Mjb&~xk$AL)t`+b)sx!2O ztz4Is-T8VkI4S&@oe$mh^ta}~P%=?4?+MX!uL4YVc$1Cb(yKkVXbl51ZSGk` z_5J*bzaBeAs{M;@Z2x4Yj{OtbRnB1?SU{Vq1#*bigAWa?VCX`F`)X0e2mJ=UZzKQ0 zfetUtt*zDc2@=8WuSf6$)H^|icZ1}LmA!G}1}H^T0&B4Q=l8G{adH)3!|w!YrtzZ+ zCcTsIv(Ek9x4Y$-JhFhufBV6U1VnTM6ArUYD-|ymmaj91Ejpv2T-uCml3+KbB?Gag zDh$^j`Zw(jJ7QcOzf zx&E(}gZHOc8e*9oc0)IZcuuu^$rUexmZAKoz)HF;4}I)EgIX2-QMmF7XvL-8m=+C1 zqsqlyTc(bH5EK3yh142{lmV>myn}*E)PH!(CGK1MJ-ALh)vh8`jWLd<^N>*-rN6|e z?|jfZ;5L^k2uBCN0M~F@hnXgUk*Z3ze~wS9u9Is0qP|VMKn@**q>r6S;{0;7)cFY* zNOym^r~V=X2M7W%XFfEp((~6r;)i#(?Yl87NmE3$>0LBuYdvSGrtEdB1>MDh)UC=W zVT~}a=^v@!gsZ-ojk$Z~HOEOd_v75Yx#IjV5S4k1*2~Sx3G&qnV1k1Nz@)&~q|CBR zg^2pSam#V{OwC)oiz}N%liL9gy84)3;D>T@rQ=@h>aR;9#Z#B{htDs&`sKZVe0Rl! zV`8ioP$ZsJy=s~Ti#t!PyfnlEaTR>EGML9YZSha8O;qL0o&_6X>i%kL`)jeWeI~Z& z04$^C2O`wtUm@syjWzg@-$Kf|8}X8m0d&km&!j(x`XQjDgIH#SMmqt7k{(9$G*pQ? z^O)WU>$Q(u_i9WP2v=&YRqC!^(<6@0$15v38z20TSxgK zBz?p0Kzat0dFD4}n&mK4CW&VOsMPz10P>;6KB?PwwTzUXGLci&WW4VQ+|R$BAz9>g ze?|aMS|1!9hF?%2Vu0CuM21#5lfNnAWfIVJfY>wrAdGG~*G=RTRsnh9oku~?>-_q# zdwpVmoVsAezAC9a-uYlAXuWp3+rbM3;%);_O4x8f{U}a-4@R%bYv2~rc^KkQkLuS%i+;fuPYgSmLKd@$9F1Z7!=BX zM0aL*R)5z?0J7xqtaT|pnV<5>JFC|>DJ}DFTRoLy5XdX+#S!Rx{{b(b-LLzp)Z)sE z@p+&9v#G>C)d)UskU=m%J2^CfS=>eCrno8tnOS`5LAUOqIS*1SWBxnVtuG#?Y?3q% zjCdYKiZPHmF$}rgMBjJV2$1jX2T7UjFUFQJ_8XkUFiaGhz??Tl$Y^%1^S$zK~}Du$KpfC zOFouWj9+!K(=G$L0%weY9I ztI2Q2X!vVS1ntzr%CMN3Ze}wFw__H;G7V;N6A}{vPLMkRE0yqjCfHKM{!*WJn97f+ zsj<<$Z^Q^_aVgd)73w#f0a`VrfF&?V`#8JigKUD7&l>?OPHR~d-Q&cM80T9PO zKl4;xP1ZhNy;qui%{$%CqPWgptY6jQjEVIBw-!X1Bn0;j=SK;(2Qk#S)`ooJZg4+8 zI|a;|8JXPvy^`Z%2??A#E-&G}{!zyKB3b|kCKM>dMW-t#MlWew8h{8a(0I4yENS#K z5ZF9y$WNJI=R4~ZfivT{_xMA;)Q~nEHQ`vk5O@LU!$3djT+A`sN_LAgqYDh8^VAeo zp}FTu*7%gaEgaV04%4(0BeTbd55LjBRDU+VP0>*P$$EK37l@SgGnd;;-Ml+hdDLIh zc4R)s%ag!lgYIzMM{aZCBl)v-PebIVNiKo=r*zLI=Ksf{$^%DN+w?{`*W z%u0`sVZ&N)Ox)R;_47zCHbF9Z|CGCUUlOA8`|@TfQwr}dq4h}xN>P=MRV|=_fV=*{ z(3zW4!hep0oE0fnxSrR$xw<5$5B(*wR6_z7h5DisYM3>22zXqok`uc#=xfNk8aCSAGKD`ke zf9K`s^yC?tidqeG-KElkc}F zXWHTaPe6`@gu#zgO7<(=t!8JoU4#8NAz=X^TrvR&jN$=p8Q zT;%Ew+R6;N$aU~|e-r0*T}m4_tOEQ~l8`CA_nVX&VV{cpd)fKzmk;_qV{0EYf;FQe zy^oD0x7QT&ALBXunx`j?CWh@)PZnE5fBW(+gcpCF?D`0Ip07i%vM za~iW76(gM{=vBLb`*ra#P7qrt1Wn$w+L4rvmWf57HH=r`tKgu z{MTOzVIF_*xL1nhT7!vI5gbl;Jlf7xx6@CL12OYLb%|0VTu_<9ivkJJX0N!^Wohz= zh-h&4>AKe?)R9gCgci|mD+{ORyAnV2p1Z&#*HdmZ_xvU+HWPp^~9hG(-yJhfUY11rF66wo>{JTxS{XiI~Yd;7n3h2OsI zbfXW@d|3r<9hgC(3GxjfV5vgnA_#LOE`Je9WHsm3w2m7i_gww?bI>*S{W@1Aq_Nwh z3z7Qc?*3Sv=>DB_j>SkKW@~|TX7YWp+U?ykg~)gZz5B1T!?fjF1hJ@QF>giFI2E}m zwNb_`0!mcvx!{kSzhzUB*oO+ z!CO~`FP2k#?_$hZal_dWkXa}yyXb#<0LDUtJ{vPaxQNWba;E)YprfV)&+wXcCiwRbH!qy?1i~Y&CG+dIw2b@}2)&AV9xA?8Dp}k6Et^6vk zH&|OgTcJ9nqVrLPP?T)cH;VG-WlvFGN>>^BAJS;#fCvvPv;E+&drk zT47c*A$(UMu1Er}5q6Qs&wG*!bnR|{L-W=w%6(lTx&!+$rd^o-!RCYoCLJ;}zD7tk z_QM!KvBHR2o1{{{8AHlL85$AE>EK0r^q|p5gk?5FEt(1yJD?KF9_ym`t$9!?Y@T^p zSCN6z%TvPn)ODX&GMJUP;SOqtdKUBdt=OxCPX7Z(2sjHAm|sBRbG>pd9Q&p-MAkw6 z?=zkq`l!mn-!@QS&<6W!FG@6LF&)j3>HcpHKIXf8b!uJ$(<;kAM(G08vj4^j4q5qd z8#8Ic^Mh{c)o`vbBM*jHW|BCi?E^t}2_g zQy7Iresh$97H^Oz-x^L-QpG*2>knU^PJEnHSqEvLK{fB(16t9mvjSc<8vBWiW*MKI zS&V}A$gB!NG#=}pLUmMa1$vj;!c>gJ;2aNr-Qq52hgH2OrUCIvFh{%5t#9=@xXFPs ze{ns~_PibUEnOC-#2`%}oF(kTeH&?sKPxE~m>}C}M>}9eBioxmKk*E`)tZPF9?jLs zcKSpjS0bi2JyLcPmKrV5lcfg_o%|h5LSE79O2M3{xFQhD9T9z>xm{Pi;}QAgk?jM5 z0zj~;Z*BjW__GVk0VIMG6B4F%@79gD_=!>& zDlTq&gx(ylIzSi$dB*)Iuk*V7$%5h`S6qnOWG5O{3aNk8{1z95G8sc%T4m*9_^sPW z2L}-T-u+-*yKu*`6gvPCb!gr@};u3{{8%3HH>~zuHUygHIPW(I0F?j>mp5} zh`lneMtAw7m~M{CMGJ+4*q@L}zzpblfpJd#I$qlD8`DyC#h{l5BPGIF=-(tCGBlzb zM9^6~7MjGEaC_z@d{G}eaz@rari zKZ*Uw)tI0X4Sk1bNFQF}16+vL!-rR&un&x){9GBXOKB7d##eHSQ~l>WG=o;WpolAj z2a2%gVASQ-;R$Hfi0pbP)nbU+<8LEt-ytD!>7imFx%F;lo+N7SkDT^nkPh@*9WDZ= z^2di2-FIa-o+sjh1#$Rp94g3y!3ML9$#1Lgu9_+`G7(1(OT>R3U!o7}zK{ zZ~ga1m>r>sl3l1=eUMB^6=tmt;>~6a4;xZ8v^cI;5Z>Tr@VX` z7YRT-Hi0~vji3AI<$Ar}aT{L{bOQ~^cgJ5AafY|W8;ku$;fNb{WN<*EfY4Jt2>3TX zRA(*jpZ%%TE=!kvF-HiMZ>AzJ;dF=5;S^SxIgG4(9@ZA0?{;i5T1INtEo;JXA4}_p zd6PxO9swK473%&c$qRYl469-jPm#47Pe@p)yqU@704-O&1_XjT%2ZP#jDed33FYd` z#w%*gB|93}_F+?1``)S$+!NKY7Gn6;?5$YluP-iw zLvN)_0`fY>zh0!RjBfMYQ9M#HYcYYg?Z@HB_aF3kh-cGZ^YOIY=wSlF_ ze!^NW+E91;s6IT-NfDK_UP|wc{LJ$4{#tF0zPxHU*Zf14 zr{5#*+Ro}QE#XWAa7FdhbQsJ>PC_twZa&m$Jz#z@Ep2&9N+U~3a-9{&p%nT&rbJ#A z&Pd)ideEXZi5AsVY0+$baG035jpa$QpkSW&)7JYMUM5?ED;v77fzz~5tL60NIyiIR zBl&V`Zr&^9U&4b=GLq@i&dB~gx$k->u?{4&LEEaR#o&8T<@xaG6VwFE)pL5cG0T`M zXlRN%4g}sWk{}?N0paIbd+ zqF=qh>UJxMFK46~O|rVSu!`@aZua5Gv~m5fLJm+pXuhWPHL)A`jgP^UfA5xw9{>f`* zWg&|7ro#Z8lctUvP^rZKe)9i*uP9rpX$bT+8ur~9a)pta9DSa%W#^Tf8w^oo&aGf_ z#UnRmAP$J%*eL$=bMD@4hnU{?Y_f0Vvx!pGHLfM+JCr61=KFCa3-F0J{!UsR79J>5 z$rLg$J&d58ho&CdF-*mL)Vl;)!z#*vP)-lDeoZy_J5RnG`-K5pgltblO;HIXPI38LiYQ&p+aM z^9Cp$FlWRDBX!t1$AaZ&6zAsTWp#XVqLfCw znHU?v&MUBKM23e+ckAzs65foC#mu4#GK(#PZ@{4XG{(>%qN}_UxGAExAKms4d}Vb38lo!7|1@t3;fTQPIjz`-kC}J0W$k)sbNIbk)oY8@ zYtPgx$EYXe-hUN(s({?>j>YIjpL^TLmmObNap2{>`G_P06Sx<@nVH9rp1iS5ab6bt zJ-;6Zyw7$&B5~)nQC>)D{HVv0x0=)oJ|En|67pfQ_$IUTc8^90h8vWLo$+7sew5`r zSs%YCn9MHnl)UeVF?13ddO_c zm76Z^E;?+L)92&KHbQv-By!0CUct`2A`Gwv?{KUg7I zq*1$jWk0~{tjya6svIRC^A4P?xdH?D7D?^Y?JMVlh?eP=P??>6c1H%L@Z#BW>X|u^ z+JcDRssAyEnqYVcw}p2z*xP=HtQ=O#stT+<#w1a9_#OMs)?;J_>^=BHr-`5E1D}u4 zH9sA7jCbt{-6WZ3G)Gki_^#7OJ%G|8T*9QYzi_8$-aN-i1OieZn0X0i=g zk1iB)_|XI;8-js`%i|vodWbGTKp=>FFOq-oJPNo2yf$}jT(4hw~coJv! zlX#HvVbkHl=NGgCnC6O&51X#|SpA(V1E;>hpXG0b`L-#TkX;PGfr8@t>X%(qw7ZC@ z3nf7J%~rPH|8R&eFBBHoCjs3PqR|X`bQ=o{E*Fk$YT~A>Y4vy9^=3GH`J~b)!8w~> zXc3}m8L}Os7@f+KZCU^d);|I2kAY1Hi5JNW;%(Dn^WhGTj3@CyR!V1tk}9f9VU%Eb zZ<=18Pw=UKpFCW)N?vDYZZiB5{jiDPG%4md^(SK5RdEozFM#fj7E52}fU6$}1sZmTwYAJ4(_fd3ihQ6rlZk2c zx5Zu07Q!~6TFtg&CUMuKY=LaS3e=|IbPu%mrFhzv;e4om#R1_(Iwiw#V&rL*^aHbvlenqeD5;+8u7=nd`>my5;UowVzv)0mV z9)4-LWieTsfM$l<&Qgi%uEl9@?%n@++efBt_eOfXI2w6tJJ(jcr zz>?aP`~onh`ML@RTaE0e5S{m|+*DP@*Sor^LvDDTEF7mKHQ+U7DaDi`~>3E_TNI29O3=Ixq!bK2&*99a+K*LeX-wpSs zXORv_bb|bkx`u|t(NgBCdkSkDeFnqhhNqE8hf?`PromOD;^7f%T~!kpB8KK}Xy}9i z164aFt{6$OL!8-QK$e9AvdjlX9Knl*ZYhl-Tr2$cXDsGhz%YFxuUaH-=&#KmWp>(r zZM|nhigvy{{(SOjp{YIFyF>-Eu_Pt0?p$yy7TIWz#rH}ghK7btLG?W}W6AA&o5q_x zC+wZD$14R1h)s)+ zMN1Q0oEDX%A9~p2|E!S2l7uQ-c=jtEEd-5tiJtg6>dkc->?JW`o1YsAH>e|o7pLpW zK9iV~K4R(1R*B~lBKS$ZiYYsu*`x)8iC;VHl-*WuCyPIe|1Mv0q|bNV9tyd zx6d%JIXQAvK#iq)!T!*_Ub82SnN+5y$m*P{l(X#`5S9Zs3z)(ajPoz<1^9=G=_GcJ z&Ci2S+N%W;0Gc!)82~0(KdKo`2FZfm-Q6Pt1qlI8tir)SXb-#$FPND zEP*QG1?L6g@PVhpuehW*VuijW)AXytyTAQ>*9b${ci$IPYiq~e%ky2l&O|H^4TNgp z;?0DX*p>M62Kvfqyc8`L5ec z_;{G3Rg19NgoFfeJL>^jSY!pieL@kOK{~*9UBoU|e3$vFSD4d@!lerSEnq+@7>45V zli77=Y4d{My?|BFjj#cH})B_?#WdM@%0M=ON*oejn#r~mE zdjCCzW$A4r5F>V189tSFMY)Sxy!!5QX}7wCOvH(TgPt)_Mm&&^e{MM!!GC0+T(FRg zkRnc_xivt$$@Fh^RF8BOp*77V%lp12~rln9^u`Z2ODW4-mHMgPx6} zI-TF#K6jAVjlyvW!p~O+Uy7B#O#=aZm?6r*&yA6puDTJ99~q%ai~8fgVx&;s~>kr`l3Cl-x$tEmN}Vl~YO(;pA!ki^698?Cc@yKZe{C+k3{*Vn zTMv-%PD_7iAc(l9OyHg{I;VtoY>%ZV^_x|(Vivf`T~$shB&D!4Fc_jOelMw(Tybgp z7>LMJAxujnCh4TLHIo3A1+ao9J0bTM5 z*Xg?+ca{%tU;tYyBWDhE8b6KIS?4(K0z?$h*zXf<$mBc;Z8pROqF?mhcPrN9ER`1g zKuT&3iZl*o)TfI2R&f#qiVHHyUxd-pBuqdt@+_0?RMCwEi37do=5Uk$)B5P60GN}W zO6Umeo~EVnO^=NmBA_1!gl33YwaDbyH9nkx z?D-auYBB{t1UT;-)+vGpJ4kV(Q?531vI?G;isGpwaVJ1-ayU*5h|2(ig79msU--Q1D9>;^p6t& zT3;5mF0X@hHZZOPzSDW2P!IToy+0En{s=-kgEzu6R?4$|!W!SdAwaRS^7G*wt2SU= zey%mavV>Uy%lL2$m{y|~^vHH}Rv!2>Oe(dO=W|IV7frWQ2%+B;P((B-f8^xd)NVYT96!aE46%yL8xh&oa~d2?0=yk++VcKtp&-eq5G z-Pvy8nA@LNa8%n88mY8#U>KHUXY+J)+T|}bo;-BkHJes$_a3fB2%Z-=xH;@kG9D;iCBXg4QKq5hQ^^dnb4(R$ z|H3GIZD}5=?KMgVSv1SNE-BWR_US#47GjhS1%n_YfheS?7qxY$QrnX#&#>nW{g-mz zY*F79Cc&-vxm$!irW1*SOlD>a&ZtzinE51Q#+m9=RlBXrsI%1W&c`w%VBZ-foe?#{ zU~GB^n5UsH zc6KnAEsHK zI+Z+bN)U3mK6SQ8%@WSFCjCRUP_sn3M%5k6 z6yk!Wk6FBxCYh>P4Z?(09PDpizZr406JP{s%2e9?5A7KD;#%2!!T_~lIr3#Ejyu94$< z$drbzfno1;3;%=Bdr<+U3MK63_lLfo`@NjvSxgYU*xaA z%M|C-EZ%|Pc2i>!+-T0vHF|0>A9*Ndi_^o}yxy%1ScZwN7Xar$i2NosG zb5Jb=NcQH=zyr&t7-G7Q;)I+x=)K3{B5KTsF%y&Q_!69Y#)vrG26@Li~Td$mn?{+kY{vY?+=!oIu|-J~Iw6 zV(2tZ%PcdS&_S2SNMN*wHx71UhQ`7NdqN8H z^X2vCX&Zpv?}r~qeHU|;|PiT-+ph?{TUzI{ZN?w9mS*stup?O3jC$i@%8@hw%#Psix;W+sKp`7;WPp`=M1j$ z|H4-wN09cEpj#O7xfpgVbxwKAT<^SS3_0T81hDsDG3hd5lX5FUqzzsoejZC33gB%@oeR!u!c z?@!+YRlr^jk|%+rjP~c3VUCkY5?=M5Dd;50|J0V81z&+}42aRgt%Zv)sledqwQt11 z-zsu{1Qtk7T#QJ1e{Bek4tI=o_R^&aHaaAP=9eb6bgpwpiJyZVq?5=h24YSF*yMi8 zpN6v&dQGyH9$6nhS+xwsrjD2V(OoUS$yAAh)~}%<1zAEdC7*OlIfQy1o`^e-f6g$i z2$s}ez_>NMLPD*X#p1skK=LeRULceN?d<not5+WL3_QAAL>OOTfC4(X7P?ov9W zLAtw3aA**vJET)k>27I|27v*Iw@1A9`n~sNtvjB(Kxg(o`|SOXU#vQ+M6xb6xb^|f zM6x%V*+5+rG|hnMugOj*xmWmIoS^cwPN(u%$-yN>A)iC5r`yS;3;FYu-q**OcC)pN zwk`H2`6hQ}*&OHiJ2bmI(AcO=61cl?JA^-DceLSanhEh3O%nO=HkdSP@)Ytp_};!Z-*^W)GuaZ1 z2~g43IACc^XhWjGp**E)44g3l?1aiPC70HXtFwE(#g zI9IRr%B4fhoX3nqY!rQdJfWdqV6n=A9P{-_`L&RyILtN=9%iETvzFkt$q#@r_E_GX~4(kOBCE#oe99QLTmKeMMJ<9r3pi%-~Y=IP+C8JSj01)kSm?tNWbM6CqMRa-R{SpwZYLNME-t zJ=+n6WVWsX%V&jl0D_}`TFhy_MF=EX@B@+`p$cgPwF|3?QU`cH*=<-Uy2Q4hJ1*ny zGPr_2sOWnFFpy6XXdc7`&~DxrrBgX=eYiN%{#M@5`{uL{4unuPaHGt;`(G?f;^|4h-Q2sE zNIcSpf?49OAzoG93AF97o(Dd>R*bUvo|L~&2xYE!C1qv%Bl%x_EG zJ!J?Y=2vlV;w?%K^itx)#bYay;Bq@C3fGyCDWLCNy z(wCs}nbV@!u5Fe%+lc+~;bPDLnP#zO9g*+4v&W;0<_I)wjWE~MWp{1$F~g6yNm(jo zwBmjy_dFKHm6|=+q?`buh+z2PZe;`(&4lJ4;+3(FSV0@k2^LJe}e*%|6|AW?+MrOf= z31goXb3A@CjwSL38nJotY|_^tg~z16$TEUG!xz+9Q_r7;^N%ZE;#28Fq}(nLS>8}g zVE#F1T6H1H+~Tee>#PC$>J8%PCn2N%i6@X}l@u8PBGA4&r@YXc$&TB^3KSSXRg>rH z6nluY>V5($W{MudUeAe5EPdUL8oGl3q3Y-MmiWz2*l5S+7jf|QS!=|AQ?B9l=I z5Z0IXTtPwZ?Bz|-r+ELlnp6xiE@7zqIQOK{&*?Mr!}c(hf~%yjkO%hYCtp3dqk~=_XmAer_ck3 zKqI3kDxgM8VJ<8zQ_&>aPUK)~M|V&}qZqmz3#A0)8*YC$d4)Sd+WWnO>`Rv|0N}bu z?u(7WIHD7}&GAA4t4sN<@! zQQKw#0*wg|A+}zZoW4c<4tjOw<1Ksg!|>1&?bgooh7RcE6FiC6X>|+*VU8FbZWdv6 z$QvA@t9g0YlU1Z& zvl=LjpaAXAKrAaB7brv#!hr$J@pt09yUgk&{fOG6a0IR-EHC0gJmDQtDas_GKFWMK zY(-|L*L`%|8~c=f5|^eC8!N8!Zvqrn+#XUupecFutRov(gF|ojfA4DIxxSXwFv)Xf zn!VHOQ@fkfOwgi?cIA9Y8{5A1PXrw5#wcH+*Lb?um4bD1#C$_R(S&<@ugyrWI!<9! zRkH!&=4nBJ98?7k3>ghPY$=Q_sDO8*8MGWI`)xZ1f-;gbkO~KfiRAL9t>%Tf1#{F$ z85@G~=`@^emu)%l9rzqprEMg$PcT6`GJmX4syHYs>KC0|MgU~wDMGV)c>@*T?)dP) ziBqCKxu^bk0$;RZgf1M8QtwHVx7VAgwhj>qh2j%N5_xiNlAFf+Bpn~7z9Ll2=<7vQ z__9ie6UVDT*fG$jp4sNSEMh6AP?8h}=;eF9tjmb#!U2mB$Af=xY0&eBz8ya%#N#wu zQJ~y&SZ#y`E)?hxmaUsp*=R`4?~Se(j!Whm7a#Q!y_X#0jho$yUn~5ltVosjuW0^R z8i(3bDSqUAHRXUm`R;pJ&^Vm`=&ibR7|@@3&$|Beim|~h-|Xu?99RKgh6#T+HKMuz z5B)a=t%Tjf3?ZRk(<&Po#2SxTCNvN($8Q8b8Lw0ToqQOnVq9FO*|b9%;b|Ne@Ggs> z^k+kWe{8=LNJrTd#(IGCz+_cdmyPv}I2nMG@L=X8NAR=ojItGAiAwR%#DzvHCuSUwAK)w=Il5h5a9%sOGo#1d-7_}u_UBPNny8cp+)`)mtPFU7BZ zjlL1NuVO@jB!U_lc7}!o4M6z47vv-oDIJiA48h|eWZt=0xn*L*R+-ZiLthU#Q6%|$ zLMV{ieIth*9fgwCafCi$M2~u;>nX4IrCBnu@Sz#$#?})+xdd$mP$Sd%B)?o+^hU$f zMq)zSik^)c>+NF`1QUek3_r72q5D3>&2A@4WJ20?)>q0l^6+-uJ-N9dF3~77x|DE7 z*`f8Go3YD?*;w!#2>7A?JSHWY7_&#F9mtWH@FGl3Unh6`HAWlwayJ5#3&I|UcfCz! zyR)H`jQv>?8_@0XyCv`tm?w!}ArK9gLE0#(2xR&Y4Lxc7+BVUF{#kMTOT6o1%7vh; z@}Z*|=RqueIK4%tUBAr3c|Ojb11~3jq-@3%5E!ScfmsO6M5cP7W5oW9bx0nipu1e0{`!4RCNdPx?`hyg4*3upoSo(6-dNJ zR7#8Ex*e2WXb$e*T)EfjPxBLLT19aVv8d-#RRpofe9vLkYrS#Z@H)1WRKV8?=qlun z35t76^>h5bG)CAq7A1Wk%9Bj~4KfNL?>P+p=P5rPmrEn3LuDY*3Pa>^#|a?{iWV>& zn!HgMeKoGc!SOb2(CbjJopQzuqIWwE35*O|@Z2DhdEeW}D(3uzQjHtrZAy~EGfkcQwGH* zw0!@9>H_gC-eTPbhlM70P=$wUf%aYFK{QnK2vpVIh8Le0RT8{ANvB$7y?<#Q#adpQ zZ`Sb&FP+omNDF0w2j4Yys=lVhfxz19dK*a zngjh%N^odt{4hj{O#vp&c%_*K*nQyRZz_2rb?qCEU(6pIb8~M*`S`Q3c+b~6bi(7l z21WSg8;+l;w`{f@28^sW_+~$b1FG+w-&uXSmU$32x2@>!!QX*b;rn;{816HQbSKkO zXBnGvTvxe~)UdSDz+f!vOEqXn9;C%&47MpmHXh5UVDLku1oNyLdC zpD1W0elLl!&d(y>-@9BsJLmWpqUn?z(OtR<>uEL^jG;ecrf5i(LS>UWTjte-s`?ClRQNOV#xMo7j~^cK{ra$# z_;Cx{X_we(KfYuOvNb~mo#(xRBNoCfoqe$g!P|&HT~X+2>+q55aD12 z$zZO@CKH~+(9!&_hq&hwo^uzW z-3|XmD&(0n`rx)6{QtZg3U?Le zzKHin8;AJ?4T+(F!YFDR4YdmySC$Gos5u~56^~$le(FHI{h`c3+I@p$P#G=VLFk>*fJhqr~5<^_apbkovMa@W&1 zxEgP9XuQ4vDyR$W=rr`4)wtf>JxI?KqVeaj4|+{uF7d@Rd8o!IOe&L}VHlLrVNor> zsvIsJu``#-7D{Ac43h1C;4M=YFe`9BQi}P!QAWe;jS|;$)oT6m44=z-3cxS8EJi5d zX0(>KIxu~)pS@TjUM?j(=Xpj$K~v5j2yXnJ`iHFJ$`X&f3?h{g=ZtsKIJEp?_@7t< zgP@FZzpaL)X!w+~@AqITp^s-v8VNj9CY3h`OvJPHJ~iAFn4Q3vdnt|r z1lj=w&F5_h++v6*7V-);s!Wav6P+-$8|&*z#FNqHRCY6kRJOYr>V)3|FdmbAYViI8 zKKm_L0eE?mF{C8iDR0l7y^|Azya)r3lIzj*fT0n z&?03q^ey|WdG#&gRkClU3f8}i{oldgUc|QdQBVLMiFa~eX^LxX1Q+oG66C~T2r@w0 z0aTZZT1>%6)VsEOoos9iezix1PiQoGBE>#j-{p%-6k;Loq{2(d@)I?F`Rm5!J-DM`!$i<-0uEzUf?w1WoaQ=^n&Yf}KfO*33 z?wrrf6*wC|MLaF|d@N_5M6vOh)@cg8JuKmZ`C#leZ=>)(GxU5+K$Voc>h|ri`UOPg zmO%pMEY5GTy~r>h_4k9eDQ^-f>VA0kX_gvj=fpWa@~t_IbXNp5Rt0bf$mX4!-sS1u zIfg^sRJl7SGa}j{g&kur{xR>QbBH{0Zb?k4{1AS}hxdV=5vDS_;rM$Kd&e+P%z%Fl z)ui>GN+#I{#S0p_ZGre0T_)xR2nWqPC5QL<>XGo}tVia-t9zjAJMkk3psqTJ0E`} zB|G|BpniFnvhU$=O%DfLA?XJ!B2&3+W&kLX1O8w>Q%J)Uc^Liwzk+HQQ@%2S0^@#P z3&=$_hyh4GCzq4^kd|Ugz?Q^!f-P14GLQm;cL_&eZ5uL@YYBuuTYZFmKVmiN+%fS? z4eYv$8A?GWs*7P%oW$bKYK$r$=%$(q_nL(zTO7${zpts8nM~48g3AOV#$`U8TH~@( zdoM~s4L3|-9LLMjBal3i72y@!eE|bVx$HJpY_Dlm=EYb6wE{$Q&YyZFGaD54hNZ}& zayI#ey&kpUjP`sRyGGrAuJkFuaO$7!c>U15Cj(K+?aP zG}`myegK7uEX^4RQ`&zxk@qv!&Argk(V3HQc0K{^n|wyLpEO4RKizUB97N@WCpNfy zwfF6i_VuF|>t(<0T&8%=OeFk%)Z#2wj-$7rR{y4l3YZw~i)SK?yY=)m*K@b)De)Rn zIm6NRf*FmTvjVixA z<0}H^rx_|V-@pO{z~KH904x4%Y3?BXb7wf;<2g+tJzc^ks8RwnGDsH%oqwoeh;Ap7 z%;+x1Ns$gy1lG$9RH3L_>GImha}i}d0a9Q&`FJazW2CI~8ePUIqPipStb(+JGMUHN zFTbV8%b!tU>3g^g1G528nEDRPCZ21^cKuNTvsy~CZRahJ^Sm)TUMY+OT>gKtF8>C! zu#4T?v&6+l*D~)jC_ukO?@#SP#N5Rhl4(bucf_nEwG?s)AI|V~g2NKp+u&6Mhu;<^ z{>X?j=ss0B;Q&4no*cePZ$#81RLoo4m##qmI=Zj|vDR_b;*QV;#1V#RDPrvFvu5B&TIYy`7$?$`vds`U`P(YejT9_ z&jXJU5JkRf)o2E7V9P%7IRv2QHS_d+^e~nrvR4PLV8+-p`7{ohujBx2`d-*3rV(Y= zAlpN?{`C^znF80YWyn+YSGq#Z^7e&)BfoTe-X@G#<@^l&)4~DM;v~C3QtRmx<}ld` zWa1Jc3s`>#B0uIDjzPs5kSpD8Q}3FK;&vfDSP~CJLVS71-~%|Zdu$^g;nc4S*m$T@a*8H z$e2f0vZa0lTL3`*ms?L)0%2{fU+YjNERx)WEE`aGsRz=T)tp@bCR?gTpv{IM5jVkd z`Mu@b{M~izI3X%y0tjW+HZ*4Jmw_rE@M=d{p{lh3`{cVii>+SIe;ccRpGV5SU~(>C zDK-Glba8RJuYmWGa#b=h2lT7X;FGXD-C)v%ih1Z2wDC=nv__jp*%3PO(2zs>0u#@2 zj-xoMzFgPNFzm$yAW=mAsw))Z)q*8s?9ehiBiGOfQ?=sr=TSnffCvk!tu)tm0$aw} zdTaxH+o0oHc&ci!$zD?um=V8j9*~D`0)r7S59{NCVl9-BC2Yj8E#%f@B2ptQ^L~$1 z8n1q}Ow$PDpMdK_ZdWI=@ryXqFH+}@zk|-4(bX!kR2nda>$mDy8mg)<*;3ih)9D1C zfjTA-#6$R78;i~_^fS*P3fH0N;0BS9|ZDxloyxC^lAf8!=0P(3#KvDb!#IdYEHrPVHf{4=j z8WfX+&-)Z%#&IxZ)Rq>~1sb#G_<}iuQzLqj1UbwAqt_qfb7|t$$37@<47j3M4C%+? z8U|PGXx;}``#wIPo!h;RU-vBozg3P82zC9ZkoC_@{Q2|4L+vN5-j`7D^-uQZXYudk zuxs3-@eg&{bW5X*Z^818>^`?MXp%i7uDuXu9j17-5JfzO+y+|D%Qdn1ta+zZ+y>}~?u04a@hg{1*ojg*V?>GM%Q&3mH?m#;8f(Z<&iPCQB!OT+SAU?&eAY6*1&kG2bq^1 z;;XyT=0=?~LWjsUX37`bvqM7%NoAgE;DOun4*@!2^((Mwpg*JVURHsM zOdIa9rq}4r#ZhkKDQWw!@c}}9liQf$ziCw9FhNxyqwpX7t=WNbS2SyJMxrrHnk_>C zdLG0etArm6q>WKhNS;}pH+@}8-+!dcCmY|W>yQ^~z8WF(7p{u3GWGj=s~#PzV!sN) z9{j0i_)%@&OZll6K~GYia1_lq)EdB5fnSEtd5X_DbR{O26T=-W5>kNt2H2+)_RouF z{ez3VW-p9Rqle;ynZ35;_;mUj<8H>wyz^h(YE;GirBOAh+^KDD>y@)oce8dcN+uVj zafk~8zy!ybux`#XZ?tBh&rm3n8MJa{$MWjC0?s@|T`>^72Rbl?P;Wh6{@xaTUn}3E z`G)*~jNT=gCsmM2_Lm%hE$4wl;h@{g&pfLwOM;1cg741L*Rd}X^GX5(96?fTvGu|5 zGLv9c41Q<`n^yz>2@M>?F$t#@K%||wwK+YN%EF8L5r7*j3>cpWYJv!qn+V-)CcQQPwMe1nAPuo3Y(7XhkpFRMteUNU^8DAD5O`L8-07r zx^;~?gYoPsZ4NEM>&|b7b-LUYg&n4syua8diT%d)+O)Bz+)!BPr@NQeoEIDH`hdJt z^`0@H7NZIN90F1t)A@3EZUYS<&s+l9Z1lJubM~EG@;&M=J;lOAJ|}k(CiH6`x7#+g zCu98UeRI2VrVRXDO>S}i7#5rvk0L`5<0Oy^PvHK>KSg%OPDqL89XTUlkLX z>&iG5z<&T0YOMfA2EfS2O1^5-m3#FWJn zuAK?KF+j1hKLkLlpW{TWzw8{VHG)GKw5vC}@eIZg^_z@URIq%R=biIU=U5(y{O}U_ zCan5DF~ooWlbYay=U4m1sS9Y?_3bk#zZn3el)*KJgW6pS!nra+-@KNeWD@ZKSQQkE zxe=cu`*>C$VUUWr!*nXcC?V`S99;Y`w9`=E+{UTR%mQ3iWk+CKfEnrl*+SzdHWe+S zfcmOHP8=<)x>pA#BdPE}XYYJuU)R`ofBq)z)EziXw*iUTG8$nZnOMRB$6~Ft3n}XP zMU8s#k|Zkn{gZSmr>({t^NWpZV_R$qK!k%y6#;W%d!Q&@((iWM&kc`CHutN?iW(Y> zX+Mbcu7o8hMAQiHVrZs=k}(%>rSGJ5BEzNfxwn00-V{FlVaEyRRnCEX#&h-dpqDaf z90`&Fg!=W$ij~3bqGPiwTzZ6}#-aPgF>pQD6G6PJHz$N9+H1GuzOKg2^gzY3f2Xep z-^KYhZ$3?VVr&+M#Q+4N0M8p>*$@ue5DTg*)>; z5=*(F8g)5Ew==so135ZqI(1+rvY69l!et4PRgZ{RQQ|V`^7vePZs^XbcWA@Zp$LzG zPSb;3-9uog2h>XTQq3~7n%r1@$u}k}2a)np)oGr-_@*RJ-Yt3_k7?z-e~JP>Ha>1a z&;w)WttKdz0#)R;AyI%<}VP&fFTV-B%YQthvs@Hak^f?vpJ;I z-%bbP2H$OG3n^ryDh6)?*#v^RD0zySZ^w@g2M1?(IghdxP_c3cT>p7hUwzq)6?R*; z9N-mBmZh@5^O-+!dEk^RqMcq6#7*Z=AIAgMM6GnC<=qMy+KLMp4c|F zH2wb!@!vnQN zC6~|Pq|l3N;bPdk@WmB{xw-U3%C~uqJPxCC&KhmOhk}Iq=a5|eoV>jw8@Qw-jfygR3wJUYi>{3(pvY1?vn zM!hbBwfmP+cwjz!NrDP{?1|2`NQ@9~r)Trk18`v&a&>dm&4kt6f@P6rYj^g=Zvb-& zZ~;A=yFj4qxwlQVr>B?nC~{o3-&DC~t*~fJmnw2Rjih7>gKUlA{7P+GqLL!K8SlA% z!~0rOF)@FyGst}1*Hy2SZ{dPi5S0SV&u`txCmA3Bx zAU#f8{7)tZXXlz3g{B=Xsb(mFQH0Xb@QgucT{fZJu=Z$3ZSviJ*TA2P??&{=LxxT1 zRHO=o)tORiF~ZkS_5q$JxX-TE(w?6c7vmSP7AL6Jqn`w;TiWJXbH$`(W3Y2rbJ=nc z1rvH-_9tx%ozAam1V6%Yym&*e=Am=*!SVckeAC85xifvXr?U+;ja{Gon?@c7Ukn9T zxSY?ky$Mn+#Qb=ptIkZ`z8cnC5!^n*!Y3T=oObpSpZnoTpc)7f2Fcra3t0GnggxIaVY_oIwOcnG`QZPCxv&NqCN7%G66@~$38d_fIn z_ZTN&{MZM0*({a}=*T;*LbxK;w@Y$$5aKuv%Z6MxA}4TZXeI+ICJ=OK@|awDfz}2jWjRP3yS1 z2x+K9edW%Bs)&J3HzySh>t0EtV-~S)T<8tEsL!^=Td z;d9~MGlXu;9{dJjs}k#D1^(S?nCCm}KbY>Q5*x-R`AhGikh1jpqfgJf>wjD@FkP$| z7Rdu?{JS9P1Ewvb5_!56J%y_mrV8#0D$!b%uj{77JGA@bH6gKUmH8tgCZ&XnQ3>RI zlKuMn9>>0j?C%v75=^&(_$tV?pT?A_cZ949QgA$Jj}NNid~MY4X&*%sMl(obGLkk( zbF3ox_>rJtDdMr&KBmjy;)5_7N&6IajL_Q={q-LErL#!8q;^msRPDL;(3W3`@Zwfg zZ$px2(`*@DM@(^qkIHv91tu`}jm{3H8CL&oQ$fCnhFMyKcwSUK(^ zGBj%RI2iWyjE&#kUVft?ZXP79QWKjN+3YlgXy^9unN$sH_c`QF^qeykJHAhClsx^G z?2dfz9=Ezx&&S};9Y|5^6_}kd^efA%E4WMenDb8C53rKis39y(v!PdHkx-TMu8{tX zPWJ2<6p_@#eZimQBdzr#$9?AOW&QboA*pp25)x@VikO|)d~#C?sgmu+2jeVPk$$l1 zmw1hNJLWbq(L2{Ze6Sx>$)Lm|z|$t1PmYd`8kzoLv0G@O5!{k#dAZCx=pN0SD$O?w zs_B`Bk!DT6U)}qMO6Di?;T(X6U55{%7%h1IX2v9D&MJm?BCIAYNTq1G7{6fpCB9gY zn0{&bD>lkQ#>p?UMUTZLY`Dq}EAR{1m=0M=JI&NqELNC;2Jp$lmaIK{x~+Ox^(lpF zPkQhaBCL91Havpn)BADpl($g-x=FB0k!F1|LPDS;btH^Hn=I|GkdHAxKOa8|g2;%| zjalK+hEsyUyCz#atRR#$U^`5%Yg*d^!ftXX`tiTofT?2IWK)l84q&|ag~B=^KG06G z;+pt(T+Yi0WL{m@9)pugk1+TdIU*;BN^NyJW866+i#T;l_7+E2undCD&GD~ZLap(s z-m-h7P(C-I3p%t5>OMAua0h2LTT+>6XWD$Im^Q=P6|$;pu_%-&Za=W%l3xluVGJpr ztiff*v5k}P2BxhYFXw|+K87+ZcujoUQW=x+j<8PIp;+QaUJST6APX}{vj{D`Wd7g) z+i7aGWXgAcIu03vKEdyoNZZXA?4dk(Eaz{3mAMxe7nk%@!+V`QbGqCpps<#C$|A*_ z|3?^7p8w5h83PC}20ho=$w(NUY64YVAa5@WdR5Sr005uA1RON_+N8H^?j2akq%K3= zG4XA@ef*5(-<})w&V?1kL(=4Fuw}n`r{>4=VYR~2<#Fz6P!caPCw zB~U7>ZFhwja0$GhUMiY4GVVIATQnXcYZ+-WoZdLkFLd_U?Z0z~hH8?oVlkg%w0z#_ ziu1`*mFW6hfUuB$w}auok->d0sD|yT{AH9M?zYIo%APxyC?&3!K6pb2@ZFgBWwQAW zz#=2lW3QpJv-5>vI{$KPw}TIpU9F*U%>7@!Js8F%RntxQv!0I?A%{z8>;tm;eJtcI z$>zu?;r7!HG9pvMUm~$!y0#vkD)pg|Vfv75;VymLMb#6&Y_3gWa}KBh)1nAVHr zDWHgd-#6BWHB*bevRr8&Q6B;AnvSmfz3cz=m1EyqXlQ5@C&C^WIBdDdh#@Sa-{_YQvQu8Wy&~Y z6SiTNg4=Y;A5E1@KMjYIeAE;UrWBuk6k=aZ+#^ez9^(L&&R@5D__VzXSukg0uKSfy z@x+f(+)sk|xemfER_Ro#g`E7_H5GB)84;#I4f48+yeCH1wGx~h^|Tr`_5Nr?lI$<) zCGf92o20$_@vkX39aV}yOUKLBlolFYHTeV`YTP%76PBN%_0;Phz$vU0gAF;Wed753 z?Xa^v?g;zgfNPNggGjKqG`k%x!;Dy4FV~ngiZ$cjf2_9mdsrQ1tr5?K5KhIy)Z*IJ z3S2zMt`9;0Qx!@0XEvJGS>s|eaD+m-cMrC?@YpY7WgG-<0GW57F8E#WE7Jb?8KH&B z4k5;@EVd~SLRc@Ui~QP=HkHtR_0x4SLfX!5zb9MSBA0^N#X~9S@O9em6w8}Ynj@0Hh|8H@2#$T(+}!|Qq-@Ei)Xy4=Ymz2-cB{g~Y+#Xe--?Fthd>9NRGl+dKy z2cYen=)Z32@5^sMaK+H@J5HI~U8*5|E~mZ#QMDDG>x;bQMzjus@P>OP!tPc(V@~hg zW+Zc$iavUxr2(fAZdTY7{fz59E;(w&bOX=>Kxl{hkg1QKCe>-l z3@zc>xK6kG4qz5qM$&P4eu#L*}27uZqQ19GGRkcI&$j$Ku{ zxc6JY4dm=%vh^Aub{z%;cP$k8*Ai94R~3C)w$4%(4I`~$wC5)*Yqjgf(-d{3b$g@8 zy!4OR)l@!CJM^nRgPuotJKI?IvH%AYp!IaITKUwrrO2n;>q@ed!0MHN<%xAlgpb!Q z$=ORCXe-;rGJ2-2_gcSE|0!dK-}VyjA>ZLDCzeA>lv*Y}SrW?y(Rkr$L2I*uKR_4s z{7955tN+-EyA)B_v;PG;7g8AcfA7sAUUx;z!njsS8jz25@G_XASL#j%Fk1{F_ji@b zCZkv}o33{47T;Wr_V$LBB}$KuY4ayPtzNu>vA3~#HYn?VhQBLosAw%{l&cwiV1(K# zA!D>f;gfyxPLfKq)w_As`*r(T<1XLxwCWnkh8N7Xgw(SJ$&??scen@7BR)VGm)8M; zarE*y^L%EIM)Ak)Pm(U3t_mKUcqBs7lIX~ZW!!*(0Q(4^#k$i`gZ{dyAKWE{@3>NK zVwyc9WAQcZ(13C`F0D>6H5C-A)+7=ui82hO*@ zWn(e&mrunFHoF?tt9VKhy-|*bPoUS=89bdmzD9QY8J)$>@_Wlayf1LvoR7z5rnEUf zAAkL|$p3BZk_MLh{CW9)!yKJtW4)TXm{b`)&#b_CgVU`IOLb+Pe*eajVaF!Od!L8D z-G^qZ540-LTDPgRDF&IPe)|#z27!t}-_db>wobK^(d}j1rfu=TFv7_9Rd_olv`CNP!k+O)K z>dW5Tx)_?(VN%y;4JbliOv7VJ@;|BCS(v zt<~ar4rGdW4Xu+fTz017oS2ecHy#<>O{sOoBaaexF$>dVs0AwcZw`V|ihjP{0uR6Gq6Fyo zwIaWOd$D}bd z!8;4h@8U5)vC$N?(e(86y4ZV7yGS^)D5XRjfCW2Hb+Ft~vnC=O(!sBjc6*yJH>Yb- z44;5$giIZEjrHiB){7S%@Q!Pb(6Vkom9w_G8XFtCyaDO6eTa?BjGrwsFC_)AR7ktG zN@4w6pd2`y0EY_n^WK30Q__oHzuZLxM4vHSNJso#&;0jVdPj;f;WEwVwXGX*PyBrW z@l#wcrdM`$WjeynKgK}61-P+IAofI)0K|fhh6XnaOKe8Qo~`%+=x70jsF^gN5EEb4 z`{hec9U!aFPY)SRSH9Za-R&ZZ%>DQ=%uz9&PeR|nEg*`j9!M>SRe?Svu;L684=k~> zu}SB!z+?tQsFZlQCeQODpi`vsUY_+4CN{7mqIm=h(3w~PBNwZ@PDGsCT4dAT2&nV4 z4Uo(WKjr_|u2hbO2Cx6G?)+WAEz9 z4S#3hEOEUIsGh|Q@@`*0{|>mKd3WREF%4e{AHsck$8C2ZgZvto7oHG^HpC`M%Ze%; z{Q%R-^VmW}zr&zqkz*C$9*tg56vF2|Ou(G*zl%c4&&LOv%{!kL-xjwvJ_@6}vqJf` z{jtppgva|B(S9DQRB5bo*UaKS;NyWF6{oUcVM33{3;%&Ie+K=gw;LV!(z0)tj8FrO zB5&=X|E=8rbAg?VkHg}}5fjFO-=4?uHvTZsA_M{<#sce!iJ93J(dU7cm28CNNI~{6dU+L{fm-dkuge-lTVE>FFs- z4Zm|5>LAPRCH8|ph2?{TCt8obw83$wEH}63ojW?5{7_>${4xHtgJvgYiTY{1@!Q0# zm!n}op4W5>5Tx!sQb0lq3JMA&i==4^YHAW7j3u?tgsy!}*@9Sif|vz7WSs)KpPVe9 z`?JHjQU%^+7q?^c4)PKGcj2S*eG9!6!wK*sJ3Bk&7*u2-YNZ|?zy!K93pG}FL?j2I zjC6F_!6%2s@rr19Q$p{nsuD<0W#!}|?x?;vda@0@%IfG#pwZFRp29E&s%<@D0YFq_ z?vr!GHZC?c{$~K#n6jckMg9)(FQB^%A_SHUHv!U!?kRN&Vc|tLQUNy+jhBp@QRRO2 zfsKOlnL^DqHREu>M1vgfzuqJO^-G5*V`O|zq4)ufT1Y@{J1H(s)Hj<)$-tl$fP21u zlNUy5N2SCJJ3V!oAwqiy6j@p>Lk|oPH;(IuF<#Em73-??;Nv zt*D55j`{&?4P2Sr%ZLvjKHS+bEbE|Q7mWR>OnLKqrRO2jb8)|ZVxIKw3u3Hr7K}N) zCpm<=O>Vw5C@CriTI*CB=zA{8t7 z;2U{)Ujlxw3yyZw6<$whd8R*Hz{U^VAfhFvXkuPWoF^-InM5jwW}U5GEDkT203L}V zdSrN5lxb~qIM=7#6{$j5&FiL(dDOyUc4WgH@vgCz1dF%{Cv9nD*twm2VplyItNqfK zAS(@OTl?1Gt|$yOOp`Hu=`MU6V}IXpcywq4E4G-ZXhaYa-|kPrRIJ{I8_jlheDbr8 zG6$E}U+ZU#9ch}==kidhSFBf? zLG{(kVBlYKz;*d7FzTByuW?J6?eNh2l|lsU(igwF5EY9Yh4%I z&F(R(+bFLoX`5l41$G5jJACk57Wek?eut~qbp>944=ChuYJD%iHOd48xtd)glwyDW z%`7#a+)U1pr5nz`9)SBzU84exNlDOqI= zDl#3No=$CV`cV6Um||TZ?;I`L*2vhH;ww1o-31b5rD%U7)aJ%ARKP@@JkEN=BP3AJ z-h&eO<>n*UKULxlm%sQG#7Lm#1Uljma8Ll|()A+O8{PH&Y}1?O3?WJ3H$cC;5~2#u zszJ_gF|rdApBfuGZ&qnC+>C*7X;SbjUM;bfs73VuA}x_dLNYQkQc`aqB?4IZH`O`b zhK5|@mYf0Z$~N9XZ;GqvtW(fE)(vz#tGn(u2v+D*Si_|2K7Ra2L=T~+p#kk^!V#Kh z{KO^WmgFZnRZDM{R5#HpnSrtDQPr2a(O*g&nLLI(7PvSD7H_KO=A}*JcVcG2rbPxM zfG@6r33`cE6*UUxlDd<#bN}wI?55Wqzb-Bwv|u^xB8*$sy!aScHUA`0#{epMUVaF6lQ~K;5q=fS3NyFmNnW- ze5>_(m09sM{I_50_d6dyKeOJavBkw3pxw9Vbv7^Kbyqr>Hr)jMY=a#MLD@xU)4P4F!K70(4UB=e12(n>#ZENf9$oMb)BG+B*m5b_fd!nV*-dh`ng@(T zfN6m1;c|Bf=^JwZjnSge@|b&n_OKh1TQAg#fP^IKhTO#dg=Rg7(Y-s3FW!jpBr-)P z-mn))ndGV$sTGZ1-Z%QjkyrWQ+mmSYue|F@3~`au))nGo;4T(N_nu7yc{Tt5JM!?S zA{N&Es|<>dkKZeZNQN!PaaPf9+?PV*H@E>N2s_14Mwy+`8Sq=oZz z)`Pj5u~yra7c(E*K7kHix>)EvQLVh|0PZFLSqTCS51{%r*opPlab9`PIr{`TV#K3p`>~ zFJ;B6R@w6&3}jfPKy;K(pV|7*_mxQ}Ld0g6gcaN^nl(VLRrP%PxeD`xfux@@21K)r z2@o(jZ8SmWuuuB#s&ov7WcZ$(<9$IvXKilo6D^YFpLxeIHZ%GlFa7To%b;A$a+hLn z&`cKFW)x#YAS94Ef{o#vMwxF+Rb1=6gGV% z<`6&pU_foEV5%}0tSxgC;94~%KVh7~0vnj`qG)~*_!3!BQ2DrGdHu?lXUcv5eJ~sx zSPSa0(n@m$eGdxWG%s9i5acyHq{3v3&wV~-m_)>$D%K|y)Q5j}@HJylO$`kI4RuJBuL zl_?$eE1tx-7OrNr^QH(-52jR{?la2foSZW4!fzVcT^ck5*~sTc39NWeVDl%M_VO-*55Q!cCE#KXSWKd%qtmY^rK1#pd{v$MZo7O2xz zW^dl`Surn#Q&UqL6BSN(&}AYkCHBRV?rv^|4zoD+CWd|~AQpdhO!Z(u=X%GHl*aa* za$+z>orSl=IWKm;WuC{EmysNxZ}$5|d;L`i^jvuItgPgCKoKYIi4;Jn!2mP|gW1{H zLjw-WY&$&K-bCG}6nLcoQSfRKM%L333;v&JnqhWW0((3#necJx-`q4eGc%jee^xBs zqG{~lz-C1SZcndH{j_n5xDmBjp}3^Ddw)g+G#clWA#S()VEQq)hpojIM7Z7CsTZm3 z^p6A0Jvg{nQC1$FdT@+^jsgJ4>Xl_l3;QBg#KpV|eUkU9tjs8Sw*g$4;Pz%d^*QCK zV+Tr?AojnYLPJB_*cUmxFr$?FXEMQ`<%khfZ#+D>ZDs($9MnDiYKw89K%e*X=g(!r zK8tszspJ^K3m#D}hW1A%@7P%iSqz$PEM5eL-_0ECc$vgec6kOS?mMgZVJ6D&dwGtz zu0je2$HKyL03bm@Y++;|hys}^ICnu9=|sqcp+dNPtzClab3JHhLh{U;#BOfDsM~ob zb%4B;Ch0WtiK4tbuw&!cLk8y!sM-4DANLIkEGCcDbx9}x_06-Ys@N%EK6B@wjp+q2 zSFjI~&5y5%1F=5P0HOT4_2b7E5Z_22!Q*;YI|UwH;Z3vSj65i*^?cUTpOJAJClku6H|_?X=ROp z=jlUixi-(d@&D$}_ikNHFayQ|^2+>m5UP^_p-AxM2xmY%`e?Saw3L6Zz7sFaa^lUz zc7fEWV1GQT@1|l{m zX@B!@Wze0|neSR2{LbY8fDZydIi=NoEd2`O?%rPMVXbE&PSv#23DOsdn*@XJcI-&w zslEdtiAVcefI0p3zcGHtbph?`{nndnm?ABZhCw6YTIkCnPJ=J5A9+&ekdF%Nm$?}=z%9Y~u zEn544f&s)dL5uFls;v1GxRD0hfUdxEZx`!rF#e!SenJ7gKl_TWj?|~T!JlFf6BjfQV#vvgRC_; z7Ex7|!5&CS9jJQ)+&5^DGdD4M1E$tr0m5ATK&G%T8yhAY)iZvEcE&H!&?Y0GXpQ#( z!n`zyupuWM@*owT9Nh#&Q2@6$(YW8z2#Q>>UKmfQazIQxJxx&fNP+8e*`Zlm2M}Ogl7d`9N@#IFEg$c4JM!b^4{&Uwd z2;YGdwpd@`80$gc+Gmh^fZOMt+>7Sy1yO>qaB-=RFqE% z`}6yKzu*7u`|I3tb8ww=UFUj@=e$4KM|5r**bx#EB9Tae_sxeaZ)tv#5-$uKA>2SY z`Rl0fp_%wTXi-RPgO@4EulLCzL< z!6G1@fTRLlJ!?tXfPXshm~ipI)>Tjz?FDWnf0$^=qag-`avUb9zxEx+79TT=v`+<> zh+f^czGty(D5dtWDGCO<<3P0hY8rrlz$$jznLe0vguni;OL5}ZL?B?`WkDW`Nbolh z4KT2H$Mw7P`6EPjs2>DN0v!-g zncEHek;mp#)-U?jNtqrz&{n=5i1Q4Wlvw8D2DEtx|0B*L+uC@;uR$t8Z}euryV}7o zraL$W91um_XM?qp($r%%R)hWG{O>cmJl4_YL19~_I=yR$-J;S00^?wx=7-P51OjK` zj4Ik^yWsgFCV{Qva}36p6kcC{kYvwchS;j_fr`7r68g77rDqQi9_O&A3s{(<>+%J zs(hWyjBTA8Jfr`~05g1DX)w-^;CCv=8rN28?$dJkgV8Sh0&GdMM!%~Ki=VNbc{PpX z85S>3yFGEjk&uua7DwAMuX4t4fxiLEHW3jKkMfyp#EkYE3q2&?8fcP)VP4=d1rp2s zuU}%$R5`i0fV0z74X>^~h9jiGzwHmN!$EBQuXDX4ne)4M*H$_dUpqNDIXhPr6F#uU z_j_$&X?fi|KJ4NBX?|pJ)Ov2%sQaP|M&gdp?IjlF$wcX?N7^X#o26};S)umA{V3~} ziAes{&~rwO@$|xkfN7TL=}1E&BPrSQ^(6YS-3Ns&=dlUGw-1oz0_MNasGDdyc(V#4 zrK3j)=8RnWw(1<=WwBED!k@lX!2;1wwNm&U70KUL#=c7}y|KA|$$g3V#d0~c4ci0{ zdf%ta^p?9SvL+`;#TEqNp~0_3jxIH(jLqFrXjhN?H&Cy}&40tcg7k&Lttk12_2orDk-70qwU}B!&Tcx4tL69cp;^N}=@p*x8h_#i~jT<*&&$_p5E~J8`=}nl} z6I9aD(zv;~L&1~;?|h0x0%b-V9UUDf_41zCSsIfM3-j|pHf(79h(~s|P2L#*OS5=C2=N1+)8=ME4cc<^VdU<fQ>#Bc1c#FlD=3_|#-w3EMnf zKXxAu7UD%)r|_ISFzPLJXVOcvyH`>Q@x@tVGJfzQaQ8GF`GZcs*K#b1 ze~1;8A0H)t{2~77k2sB*A~SC9q8&qn>uN&tv*3vUFqESF7WT+wjW{y zyyvL3T5Drkv#>D2LxyH6iQ!`D6D7JnG@KvYjY{y)3g*-i12L2Ug4y7!hH)9cKWV5pXZS*t++ybw;{xMk zuU@~f%9s8BEq;IECE~A~yK+*+TahS{SxVYXs_81uL_!f!EvJeS{?Vhi?cxIOwWg7oInb%R_t47ns zQ12`j$@vJ`%87Le9(iHQWRxTZr5{j>ZM|T7KXZQJ)U9u`bZVG1nkb2B_$YasCSszzX;xy-xq?>Qob;A8h>xMTEX0x;4`(^LwdITWX{2ZP9nhA zqQRRD5`Kyq`lAqaD7^+7svDj-gkuDn1rDn=kR!U8+hPHll51u<9&29P?^vdLep5vM(ZP9MZuQ zU@{M-kD++z;u%J`%KV&mbu#GNWFGSm!&#nQs5b#Y?ab%WePE=0sPz1v2G%h&e;+D< zTMmjGQD<~h-(;6g(fhEbV=Y+P#u-&Q+Q5BG2|GQ>aM%^Sb|^8!l5`+f^GQU}{XQ zC7IHb0kYiX>O*N1-QoeAG`d3?eO-G0y3^T$1?Pco*mc|sW&Gr)t%tG^S6;diU#koY zy&tB*-adoJT#hkwt74+)!**HFN3bfDVTIM~TCze~NGx#k+5O}kBetPx$1kb=7gS@l9h zHlM&qgk12)xOc~OF{jeS2M+{KIbW|HoTXQ8JDeLmnCv1#E?GIa_4Lz3%x9qD$8_@Z zgiSD0F)V*X*@UkB!oMRMtH|LVQ=f4N3qpCR6lJ3kNtZhrGo`!P{|-ZXHb@83L@mNu ziTqRsgY3U#{npEPlA|07Gx%jGgOXNh!p4YF8;X8y!7hYK>(Nn1L<&_sM;BY#yA%@6 z?w2guMY^l9)&5|J|F^+?9(f+hLC7FQTMkor6SXx1N-6Fmaa^bGOYWH`Znp|p03TK? zKd|ZB`TPalbUNo6ei)rme7P1X9UGsEH%mrE?Y^o6a#%haYfTy`A`N4`;gsb9`iw7% zbb(#~-Z}(`!$e+Tpdc%R6r?;_Ny0>IY*d|F+z<bm3(-05IxwG&w-^c`7}99TW)9TlOkVA++_j9EubEu!Dujtm?`$I?;XC+*wz!)2T#&nyMgcPJH=_cIA?;}|l<}zQSC)5yTf!q! zXTD=-qU*B%5YB}{TP9uxqAtC|8D7I8lHSHZx0Shv-sdaI9&CE2mO@D`TaX>sKa(Ky z9A=i+gT@Xx1O+!^h>NRO$19*mpqSyl9A@V4vjVUzex^*yDPkW0-Qc~vWmY+k>=(>c zH8<$;YuBPUC*h5IL-DU051NF6R-C=$IGl%7J zP8Xo=)aErg=LnZ{UhM(>qj!Kp(r}jSrVx^+O6H}r%_9*0p%-_x?@+;K-=x@L`wa5G zJ#e-O03mEIXa`^A2zonp+Hb7YsJrPS&zlYA+*~|oUG+bRZ^d?4EC7)Z>4MAW^qSY% zhY(e@CH5nGhoOJVCe>lijZ)Jex?1?oZBdCB!I9lFNokZ(++y6PMK}Mx%5VqN7pc9x zi^Q?@PoE^UJx$}E<))JK55AF|@RcRGB4ZL%Yb* zOu6&Ytl#zKz83{dg!WoeflgWJ485Vfn*Ikrb?!cjkIfVDc~G!uJauy}H^VzOZUNac zLYiE%_U+a0r1u_;C5d21oI6{LzgjqvQWDJ=X6vM0=+Nj@=+S03H#Fz)sF_vC(-tL; zq<7|q^jE&Pi9BdUt`AM7O(dHv?Pp-!lrDeeWFN+Ut@!z0wj!B54$u0;9@29kcF1mZiqmwpo>-UNGHih# zrfY9WCE{d8w+hW}L4qi7Zn_^`);YPGpI7J4o``;t(os4cb@(y-g3-u37+Kp#yfm;< z+akAHvEqv~x`cbzW}L(R&kDQftMNE!mXNy@zeY^;n4Z_769}mhr?sK2cs?fM9As0AU=< z6n1dH!h#8H_vd?4qYG{nR5P}b@W>gJ2~cB|Yr@nN582W{uYQ?YM-=Z~DO&Z#PL;-$ z2j)(Q$h?+GAhr?b1I1UO4+8-=>c(T-hZcg5EI;XxCtQOQO!$f$=^peF;tvth$r87h z6Hof+gj|azKo2qI&_qv_>fSw6O7LZ=lj`1QIw75DeG3PK=7H?8!bWuIIyQ(~bx^6J zq+is%a8yB=mJq&pN;}vU#jvOeBHZELe3Q9Z5AM9Qx?(g@JwXcGmB;#SdbtLJ|6Wdi zrzAU}BX-D{hRRf|a$sZIJZVgge48j{!qddqLHm1;cZ;>&Mi#rz#_8UJu;I2GmYj-& zOjLO{{n%j>l%z6b3KKO5))KsHpM^%iooSzH<(7HR*;|H5tT3;^$l~c4me6;M4Ky{Q zc)fDarKS0RrmT+9bX?guITp|{O*xcKEr^JkXGzi(Qs24jFbyiXM%;IGhp|x7L$+4G z8OihP!=)RA-7k-)%4PX$(WNE~r@f_6=}1pue*epXapL>mRjW+DHtc9z!ftkvktxAr zq2p~Gh}*JvAG@BYi!9Gl?<4O(9y(KuG7Dq+n8}>fsgqiEq`;Qk7AN!ptEe^-MWi-F1I?f=6w*&nlbp#oH z5Y@#Cj8?hAR$08{xEEt?O*&8cnMRO+kIgDrgh7|sdz$|81A%?en)3Hzww3KVr7EE= zg;~iVkl-B4G}Y`Q@xY%d{p%r@A-g`cdGJBvlOul0R|E_BACQnO{!1sDBy{-vc;{=& z+Wv`_ub>2zRY8RZ-oxn$KV&itWWa%3`*pdVR^k?pz$nGtCn9M(L`&;(?##q;N{iQS z@&g@+myNEEtx~h?fZ^)$dSm!XKV8^`KakiN(R?bWRr%^ytPCEL&lb&*xOncZxfdJl ziMT=dOfLsIGvo~9J9~*J@|>0p23+3Sbwxg1x6S|Y>X%%`Nk*jbPuqOMQnmS5j%|w< zle}Ziu}OOTbXml+DW5hc)S%h&^6>shw%C@=0_BP>_ADy zRxI&h>-9T3i*SZUY&l^WJU{YYMd@>`jtB`Blfc1TgKArH&tMUgp>)wBVc3x{s2&}& z7`xDsKGp%)j@!7D#x5fuIY8e)`81I+)Z)nRjyKjrAbBwdB)u4a5-!DoE^k0wV`kTs zJRZNRDWSC|JIv7*`Yg~(t^#%M>CZT2W~Mys(w1}E-<*-VD}4JuF)xj9KcXo*u8Hhn zK4Yueun0Rxe{)*>Ksy~|wtkT0>WeJ;RgZoJvU6WV-dPZK-Bis6pIunG-Ect7G;hV0Rgd2sSHR=&)fr>Aq6M!U z-Z!CqB~ETRXaBNRuvKyDNq34uKzk$f^3n3-6~5T3Mn#3!jt5h8*5D3O$Ra!LM< z|_~Z(ROvw-Gl+RfTEBfNU`R>VTrC`j&t zUWXjBC%ElBqz@)ClndNTA}pmJ34f3PDIL&j@F9JLZ8KExU^$$7c@=c`1K~fIlI5RP zzcR0YY=!XZNq|7N>}~^F4&FU6m@p>t#7opNR;0vCs(3}r)o60@u!-6E{3tIeqGSkj zZuWZ~#w{GV$jfA%u}Jh~0lHj-fXrK2x(7%}^V~bGYAY&fum#DWuF}ojo3swzAk6`I zeO6eXfO`xiIPNmb6?R^UO@aKBlH2|3KD7ZJtbxSyVy(c==UsA%9YdhBtYa_b>_oldZfq>=j zK-x`6eoZ2hLW^>MYHu&;(QeBi#Nk$rj!KVwSa4-J8|is@d1V4iR>U+Es3eo6Lhn|( zSfrS)LJ{Af0<`H(6wE`GjTc0WKwk8^*v($(a}uO*kF~o(Xa|5^+77_3&)tmFR`V0u z5|=;I$1?+KY?Hy0L>UFOkzi%9cqV5J)S~QNB!uNZ1Hun-VOI&miaxHR9*rwL_|8K+ zHt1ea$}>}tQ(OW1l-Z>EVr~9bj4uav>>O*R1@8$|q|Q7+F>Hc+5GtJJZNS$OAaqC;cjG$uX0HWUssQQJ_tK|FEWR2C z_uvQjAUp!h*FUCn`;MPrjsb(zVN<9AfA?+}8;Oof1A~vxJr6n2sraMm(@_r>o1{KP z?Tj0r3Sv<}Dd(gSe$faw-Z%Ocf7B;x_Fk&L-=X{sbW+}Z z5PAq241BW~r8*uGNEz)1VgEBc%}@;QH6MSRPPUz5T+pHa%%+e*<<9tF2KhhZsd zEvc2jF`m}-#zxOHQP4x*<%h3u`41oB>TkE%u7H+qc|JfTGWR%MO*DGTtIH3gAT#sX z%_K0KoO+a{$GrP5qo^d66=&)Hwf#`KHbcIiWt&SWIHhVl8U7LFy2G{h#qt zOw~-mw{623Z)N--Nc-QY=^8B5eEFV9e#*u`mRc@)(d=rplvO>RqEsLEnkw3v0 zv(ajsuQm2SD(|;(B&NN}^3Sy1`=?z;r$f|vtaMu47yaLB>vwDB_R}$oBpC&xeGFH@ zDW_+TsTn_o=6)VjP!xa(D#nQADH8UMo8yC4$r`>!1z4_*Z5R#Hqcfp9Gz=Ym<^t#zDoVNeNj z(H%i;iN`T*_aUeAogB?gJNLMcB1MncGz21LTVI*^DT+D+0PmG@35Jm8+x~uFy8U&j zPj<%GnB7{1JOw@??I(SYTrb-3l3|kcb{z<^s;alccUZXmRSNC!9$~G)MitJsf8i@k zHH#Z%f*YtdU>X}p94R|k^e$DI2K*kI_lLsNHLcrldno40A)n>Z; zA4MoVbD$mTfBR_ty;>P9byR|bGgtj8>62uX0FP*5zt*3prp0e*f3+`F_GXjfr--Ze zAqn6gN~3CNX$yOO8F*f_&l}JEroZvd#I&9W* zN~qRc$4e;H{>{+2z$E)*O+kUA-E3KdWYKI{#cht+vZg>Z2d7TcNbr>3a5 z&proz0y5Q)7QD|mu|Flv9$AD@eq8p*a@RQEd?u00bDzY=kFv2P09c|?Ud;kzKS z`Rng5&OL&OEd{oG$%WYH0wWa}DFv-R#gdkG&--jm74zCc(TpFyz2}vzy4_s0e0cqd zCI0GWNb`(WO>d%s*jMfvUA(RGw>`YN^kLjFKNA){Cf<}+a5y-5NWzm>azAbBrjokX zqo`WT=UT=ewD@E8_5%{g&XLfy9RyV`>Ms zzt0vTW_djw4+o6X zQrZ8QYVhMT8Q+|&{wmBI7{ju4tJwd|0jmiPShkh93-E$JR7b`JW7(c3jZTf!yz`aj zIyVyhrs__Lp!+PW!X~-y^Ipm!Zn^f&mhM>ITdMW?gDI1VxvFiCg~xc-*dr7pR5~i! zYnv*joXc(4e%vFF7v~x=!(H8xK}@M+?(=Eas#rC-1Nt0Um07rbMmF& zRu83~+V@b&uFja%_^m`U$y+qMy@-eGIH24i<&=X>i3+ZqTFP8YML{;0UM9#;p);jx zWR6Cvi&SAgAJ#hSGe*)9c>R^)+dO%&k#oKr9JOm!D-6`z+|YW+A?#=kc5D-5LPz84 zt)R)z^mUH^ZF8^8Rpgc~=ql57B7*%TV1YHFkxSXT_)e*kk>eNdo_eu?ot13u- zc<`$-<>t3VDIcqiRqokEvTw%HfFNW z7ozUjti69c9WLAvJhvqH!14CMh5a@&x>}f}0;hp_XJp(&8T6^Kpe&_RmctdCfhIM1 z_l9tl6zFZ6e>25K@PhzgLXDBdp0KFfFQq`&s$q$ZJ8?)CL+u>U#NObk`w1cjk&2#+ z7Yh$d+Rw@LUBVu%5PrP`5nq{~g!j^bXVk{oV)zQ*D`G5$B^u5Wi9_b_1`guD3_M*O z_dNO=i{gcxlQc#aNAEgURf9@p;GL@+ic5N)vwTMT3S6<2+m5_!QGIqiJ$WzV(O3|op6!LS8>?u)j=Uo(C(e=g&9+p$;pLJA?BL9dujt}A zs5tek;&95_lEQ`=^%JQ&3WzCT>|uN4W2KI;K2uNQ=W(A;2NkYEzD zYw&T&QUAJNOh3^Rohsi;&;CXSWwkw)Sb8ue9Z3GQycb(&geu;c?j&2ylEgY(!Y;GX z+=88YcxGQIF?z);}IB z&!X1jXPM{zD&CzB{4ASY(|U5tuG>Bp{f$4J?vwn`vVEQF`^bf)C(JTJY0PHXmUVIp z5T|uvHr)nBF1|n1E$>MB{sv{1K}1KOcC}*|&-e=Y8*V1GDX5!SP-=z!d^XWD^n@eR z^&6Ty4?)m@7iu*zItiffWcMn{Ge2L&`8EDoY-+gV*5g|w3Gfl94|K9}k-YOFt_G41 z1i=0QoMHz0AGT9(aLeG=Ef4=pACs4B=R_oY6!bu;AUGj0j9R!EA!rX zc2FnmxnZYEiKCs|D*;G}e$lg)xs1d)#2g|xa00N&to68rf!&RA$NZoD1*@zyNEIt^ zmS+@ek}Oat`ai*kcY=4hCUQ`;oN7X3$n^;|?U0FnbzDC(A=G|1CHkL$N*8J1w2)J< zF#GPNjyC9k7QgDGX%B#X1M#$hD>U@1LHHoElyL*)*-$c%IW{fMGP-8&?Og??Cc8fq z`|NTzekK{$IWc(~{{~?$P;2U2_33G+_M4N}J4ym83w7@-HzYuTyqd?OFK>-L--?WC zno`pYnM*r6`VbFlYjH;h=xDHCbY!ct`$eaoFR}z)k~8I9yVOUr_U%Oyk7Ci}^D=`7 z&xh%cGO74$Tn3CA6lJow7urZ$*2s4Q+gnAYT|cOqSS`jG(*>Q;ix?~zY z0X#dFqQl2k#6Tf_=`!a3cpOJdb<@(8pyP5Ql%|67udnN~%F26GgJ)c$By;b8$Us8JYu#Jo zq3>a3S`J8U(O1cr#hs(WnX@dV@E{qM!bi#ErXX4%DJi*ce$|w3KUkAFb4D(a{os5!jT-^i=83!mmAdbriU9#_TQb(6Xq}P% z5k=X)8rNOJUyRpG%tU=Vw3+XeU(cj6ke8-nnR>LuBIaMl=Y|Wb3pV0eQ+h zTkW9ZBe!&tNj8L#+JBF3y%ylIg$a5+R>>`b_5W(Aqd=?LmRV=R<2ROJEwl}El$BYC_rwb9l}h&C63@w#V!w;XLMqup~5IqZ$6w&&g4a{TsHc)^`{^n<(ZtB#NUQBHK@CWLJ7(r8LP3Te0f9&d#vsdjj_ zWc6*680N{u7@Aa@C>P}T`of1m@x{h)_CcfmgV3Piy&1;XD}jP5i1o*m5{`YA1{btG ze)a_2VFH4(HnZUFpK}d-S-HeoT3&s#dNxh7181X_or=EIZ_iLV&lNIwP9wL+4KX2R zx*^9J9vaC0jntgqLBX8Y1D&d{+VMRtUxkiNfq)m&tC}B?GA`85KEmG7A@N67Hu-?! zqFR&JVh^+%Hr5YvfxAc-)FO%t!?Qsp!;56DgTPizNEzXonj%$jGM-5AI@|>|hm4BC zq*~@>-Te5+Fq4;3ZUq$0j|eW&`jBjesqwGvMR(^l%IgKcCD=^1`b5aB)5n&({Mac{ zqw(dofWEG*uZ!DETo>|1@=q0f%oo_%)39>>(AZT(48-Fgt(@_|5H=;?T4ae^s zO6`H7^%*lJowr~lXJTfIjXv5Iug8D{Jd*U)R*$+JPTB0 zlMkOq8Bsi<-!l5GPy51T*r$4xQ+)X{;~GntIGm2A#ag*eZWDxdC?1cD??EEoCNlBHN{_T2U7SIx1?9OHU{>|bBDSohO;NsA%=pK z57EGm92bQG5xW9p^@=T&KD`3zha7RE%1mhquwtXx%_lJN@dn`wzbmx z^^g|t9NB!11gUO9)@&-lEEl z6)P>hiu#=z>krB*=2-_hW494fKk*BtDg4Z`{OQ|#fEETJeF!(rIWes#s{R>e%11`a zk2H*`cjk_W67f5h6E!}yTKi&K)b3mLi$Ts^D1~1q7Hn{M`1$t&$4e_yt(OO-gwJ+x`NoS%3S5Wk(gK( z8njPKla_Bv_Zsi&^0UbI2TZ6vsG(AAb^k$q4*N2;cwKzu;VNQ6vY5LPnE*2u9C~UF z^WDi0YE}$4)~Q;0G89Gf&=9dP(a#mTwQEAO9?TnI&pj!Gvb9Ue>Qelt4gl01z^@nI zpsO1pQTTQHuJUGWxesoJcee5^-02GJJC&QfEE0kPciP@sQ}uVJ3IS@&B6?skaK?n~ z+Sd)u%W=)Na%Z;IryEzbBgprlyy^{SIe^5ls3ziEWx=93&7ussxJ|(~z&`n}#LxIg z`+uI-{*5C7X+{m;Yl!d_}!;ij%aEX1QL*~;u z<6A{<&;Of9vk|zyY}#F-_Fri=rOzAbToM1i&L~ew^U3Vt!ffLE)@0Hvhr~u?zdG zAn{dfAaG1g&Osj@=p+~yZN;CJWm;^d&BGkH#hQM56sCk=7dSw%Sfg8_YzUG;)Z+~rek$2n36obvkxElSRP5d@VxT} zA&>S6_uhhhF7?J1KYYd}KNR1)FF0H%4RSGESxwGsy+G;>0A}7@bxfIh9}H*9gQm+c zA-nOf1jpHOzSh!V8aoMkCV>1XFH+Q>D!BcKwl2>z$<9HwfsB=* zrlzJy5pX3h0T_|&vq8gpQ_BcQ!4+WO7guY@@J%Vu9R=7y(v5dqK^+EQ4^_`xmFF}_ zQ%WWm-|qOz&jUW23ZecIKM~iItJO_%4(K|YcpoTyv$Dqh5p~tU1SHG4JUWoj30sPZ zy!HdyJeP7bV&n6rLoatJ@O2zZgBgGV!DG6j6cLNB*Nam0$I=1D$W_z)Zp^`hr$!s^ zQSfwYppxR==%g!4GLR_^mmunTZ~27{?yY*2EbE1WM>qY6eR%>8mIzOR_5rbu2pU?b zuhKoR*FqDPEG?vkj8KsUgl5HdzKJ;dTizCKisVJ+%@(pJ(r%GoO}lN`2n%_E9kDGDyJ^}7~j0cmnBvb z?tcYQ{eDV}^TAb1w7IOzX_c}No|kyu>USN<_jxONsuRzDn6|RA5@c2v0Eo)KAY0u6 zP`lo}i}{`NK?Oy&owFG zgNJwd_nzSDT%H|RuF72Y0)`PllcjJgUyOAhgJ$NNcj(7yrRjvU4BEnjOgE_pwG##< zjeYtErn+jFttKsm+Q(aZ=M1`S z$74}E+!YNCy*T)ZTdslPZhK}0dcUl~p!Wqs=!G&jW$2D3)GfK&1#mBjG1E)aNwc;_ zGNd6ihiM6-&(!dI@GLtprQZQUqvF~?QEt1{A{@praqR}bL!$JGGx^9%=;EMmx%iZi za7*)^V-^%(EA&w$P8GVN2F-aL@xUKKM1=p$M!dz@9ezHURz8$ zL4oF!HPGVZl?;X0)&!=E(=C5>-kIhtBy3mq_5$l2Pz{?jo&IwKI#+@OSw>A$*3C}R zHi1SXx@^r}KjUXH#GwQ^uA`-mFh6`#V|1%2FdVo*?+^_8*gZlzC z*ZU#sjhEuQd_8Cwk_LNWzhe@@P3)VvwV4b4Y+_L%OJvjpn#;)OZT`eg^(skz^I`2u+bgKVu-zzY^jz- zDoTcUoRbL;%$asTm{TN5rnrJeh0f*&Dr+1pp0n7oyT)jIk-(8XJ6sFr?#ZP=0GR`u zQLfkY9_m(Qd|E|?jpR78S%8?dVhs2Fk}7fIZdAey`zb;7qg7=&VjRC&GHFwP>II;) z@?$gH<4dPjt{CHP^m~V(6h=IiR1ysUdWz*4J8zrLKj2MGe+U)^9Md?(&82F)sW&~R zD9F&2FC->Ro*2hmH8Pw&3~6)G819!>e#mh6qqdi+9PLP4`54}mU zS-e_+go3%bUqu2KfAViIp8c(LJMAr&$FSd@lXq(-Axn4R8|iM_QG_>g!H|?}N>veY z-~R*lZ=c+x)19jC;_Yg6d%&aqwR;AB_$&vv*rdTrs=wL*cqvHuA#{BL>V@LAPN@mc zTlB-peL3n7xxfFeuN&M1>o_i`zw|;Kz7}K5{#tFaQ+RaVw2h2oYCcN1yZG6=ktf=}0(2}p+tcV<3C6Evz#gTnOkT37;Nn)4_ znLo$L*8zkF>(_ID2nqV&`7{Y{*4%Ewl_gHDW}!kBeNLjrA8z_|K{mT{xYh^IRXI{o zwF0M)DR5-%|8}VL>R@>LfiN!*M?jk;TNQw3$-ZTlB@W!JTBU5a2mNKwaW0;{P}`)p z51!x+eEMfbqMr;$woirFICUeZJ$bhfuk)Tnm!X(_3a(6n!{*`D$qA+zFj!Uaul=;M zv)iZANzp5LncXveS{DhXBaIEew2lEAA%9l~vyG+Y3h=MhuKoD&gXh|;)YU74Da!#S zY_r}o1Gwi=0PE%Zm+zarxQEjD%GT0M^bIVU?Dkr?g?!V`jyt1f@D4O4F}ZEl>`odp z;ji~7&#<*!?OWKJ77i8u!aH}tywnqaSleldTk4;qxv&psCee({^71LNR!sN%dHprT zXK9ACm!busmDJvcyK}<#UK$$m-8e$WRZ@rb93Ou$fuYad#kawyF5*yA?}Yjm#g(KY zjsm7aXp6&yZeUsthjgHb>+0_LqryEWcQ&9Kgwpnxj_V2r2I?6GPuCW@Zlo=~ZV+}; zd-Xu?jc6q*=Gs+T?mcR$S!o0);poU54@nuPu=KRH|4aV7rRP!KCXY#$TeLKSfcLM= zF)U#Hx!0xiHx34Q_S=FhsQr+iCa_N8kga{XlH(liej4cwDoN!SmO0C zrsptX6s%p%_Anw`DYd-1X>u_#QLIz{5ELR5i1Q%9w1AyZA62s+7A(EV=|OaqSmJC# zU}LKhP%W!IwDA6|X38Se7tS%w^x-dMNg&;haW8apa8w2YMB4XSHr6-W-9@X|3VU9V zJ(C%nJNqP+gsuDY7TY7?;x+m~Ga`n*znU5%*ZTm>Et+_2z;$kZ(3d|=Ez9oGw1j&p z!ozSz0lnB8lV)?*ASCtsO9QdmG$CDqJG#$sA|o5tX;KUmH)&tN#i5Gj?Rfra4N zl)kRTO7@Buf2c23S;ZApMI&f5v{xAmYlHG9?KLbhg*Zz}fR|_;z`+8jTN8j^vBJi} z>DhVvHNO%YYhU0lI3(W`FroyQhpRs+`1G9^jPEx0J`Oj5U83(Pc)U)N7#wJW@zdq{tOv+hBrI>`C@ z^*pOcRNk?t6Plt*y?C#~F=kw9pjxliQsaUVU2|V9krkSkbuSTvKV(C>qotpoL@Ul|uIR~cbZ`eUU!Ot;v|)SctJ%`0)k&`lm7|Wejn0qZIz?HK z0?P~Q@E~RO8PyKXo?y;7Hlu_>BYq_0I07Y@_!jNey+1AmO$$oQyvOjxN%ltT8leh9 z*iQ0XaV&dx1zWX=D!uH4bv|TFz!Qi$^~#U*`ow%;1)VcoE}D5&BR{`*B+D=VfiB?1 zs#T)O56+ctXawp6{|{E657w23m-?zisV_Ry>Qg3thz?*#m}CW+gQRdZ8A+5cQu^Ff zfU10C7M=@qFC=yKE1QUt1qbhA5N50gFvwt^VJ`g`4%(=xCl*xEi_${!s!cU#vA$m- zFs1V7%rp3Q%Ml`z4Re{jav=SK?po_B{Eu*0S?}7~*Mx@;A5v0M-opCWYLE+vy;9QB zm4WK)x8sy%`08~39^a?*yM|TfzUc zy!&jD5bMwGuKM-Rfo*{mp_e-M8&eK4a{=t_F94*@+l>~S!hoR}7j$yRa2^b!uj}hcniX6 zM$aL?LVXRHf6f=93jL&-8(Yw0gthAC@ay%I}Av4b3Pzyu)uJ z(6wWjal+^ORy17cI*bNyV|HB|O-i8+tNi#?E8Rni3qegfr1Sx78H}>m15ZaP0XFQ` zmlU49j_`po+WHh4lOKvV_`@JzD;#d!epk^-rn9MJfz|Y6fz0{xW`Qz8f-1H z?)C6nOrakGEAUTAC~zhuI!g>xa@dhgW@ z_aaBl7q_t<t$MUL z%r%sBs$oS<);LTL5XZRptAQmfi}RYd#QW{OqV4m)xBaetgd|EU7Ns)YYrMEAH?6u zT5VLU?}b1~ydSZmXDhdj$UD!`>Ttd5 z2=YW_`C8fli#4_av}6UImOePAQ%@v`H3J_B42}UcQDoP-N2aJ9d4Sj92eiaDYR%2f z%*@PS^o56q``v#M4y+E~L3AF5%opk^D=Vkf z{Me_ES65dD5D}C$@n&Z!t`sVTLh0(#(Thew{?XCVpFdx3ZvD{Wn(6K5=jY-gD2{;S z<>i&M4V5x7Gg{`U-YP08`VMO9P*O|b{o?$5?M0Ymm)>;=EG=oNJ$L1$&rzB}hbh-s z1-=(9NyDokT|oN7*H;`I2UG;qv;oU3bG8g0jgLtuBqR)tjsg=jMilbbPw>((V6WlG zBtEw(@%!?kgnh@|!s1l6VPwa&yIeDi&8d{{1}8)yen#ycpPg!)UHCQXqqKtJ;+XL_ z;h`exlkD@M=qrj!e)^nCn!FVz`#vgD=BW2kXta}44A+Y#8Y=jC*5z}gT&RXiw6*?B zN~XHHx~Y|%*@yD-*CE6lmDK&_cUHnM+*TpPb5*YolYhHrC4&s@V1<-xWWZNMT!vNZ#=2w+_;W>%dAGyX#UkIM6FvSwDgWIqHD4 zmmwiC6Z;|otPxeE)PdtS+r9jR8(XZb;iKb2=ivr5!*b-3I$sJ2f_4< z!XT$E2=*Z zd&ALY3?m#jnSg79H{Rj5(OJJ|X~xeR)#iMt$f{`DmAvitQ1%Kd0wVmK8wk}S5<_z) zAX3n^jAQEArY5-#cDH0@Sy!G9eefd3Ff4RO8QIk`emVM*0#3;>ddAgA(AYPF3f8%% zh>Eq+FxLo5goqzm{XzYr4b1H1pl27l561BcUJ?^9iVOmavu$Y!F@vG$Wy)6RM>PH1 zcw1LY0IaoXYh- z03B`mZA&Jrp(A2~JHy!~Sjp9{LZe;seXhRS5?K837~UF{gq<9TZq63r5eMhKeHz>< zNLav!VlNp}W=5ma8^C1q6sbu2Q6~*oGmLbLd5Jw6+{H8n!tcgbv!gTJvsC34uT`JPT1YYOJ<4!DemCbjmCf-Q`#%O`bg%9<RwyQA!6B0LcuI7hYN%xdvNxO+?~l1;tlB-^ z&`?51+?bDEoo;SKD{mWffF$V-5vCDoYw;SwR5p2nW*6s)1=d z=F}OTdbV*HQ$1yrp%X>U z1hKds?uu|P!v8tFLz@q@scg%PPX@u^r8lgOi7|I8lQN4Aa62l+(5Mj(9Hi_zhT9WbVYZIL<0g(* zJl^~JEtC(npBi}4e^!JXG#oVg!qcqwSx~juGh!GBO@g#4P3;$B1xHRkx->3Gm2ZA@ zSo%jx&(CzDtLX}9MT9En(DiL)w_{IwRPu!F+-3{IN2K6oySv#u+-~t>c zy@CT&Yp0B-`_f>5(2E&s3`hxwQm)m@ue-`yK-U%g|%!rhoST13o zp1r&F#{@Qm;Bju8#O@)GbHnGXW%`Fn0(-9Vw(k}pmk%bPDO%PW(5iSJVxb4AdE~PX z)Qbk|TzdzwIgNv?{B_CQBI!IXGDoWXW!vBMK+%tH+1Q+hwSF+fx>yoS`cF@OnnI~- z^-yxBKjkR-9)ZI0+|{Ooy@@qOD&#f0VFx2TCwN5QGNr>&M2IJ> zr303vcEoV3Aj%h6=d&|A}$ZPSfm2t3vhwtKh+O2!P!LaY)n5y?uuu}gfnR&qJt z!Em?zYa;RE$vv`ZZc}!IODk|qd2VaxO}MS1fcN6BI|+s%WpsBP+@0Hnwm*ClyT(;; zUu+&f{zc3-7bja>Iurw|-q+8KI0(8Ky-jLf%rW%{*34u)bzj>^uGiXVD z^g_P(_H&_3lS{e02EKH{Ch7o1)%^Q$^3eKvlalxkY-e1xjb*MqA#B z0WHeEvt>c8$skg=htVZJFq2cO%Q&ik5AoeVSpMhZI%(&kx*?t9QA~0!dT!9F+M9@x z^MOh;5RjO5wPy7;eBx_v1)u{CvcuQfQ-59|NE~TMup%^hH4sxlUst%~zm1c$ z+i#y~azSn&@AAl2%*00A#mZMOvjgvzcy*j0G-mO4>M{Mw{6)pWbrIjMc90ldpF++; zySj^L)uOdoF9mF=I<_Gq+fS)augG*AVXCzFG?~7nV!S zWi`YUU>Sc^;I~ofyXAgz57(=~hGI7W>4&&>?<@eB7KGGA+juWePcDdY6kD}EXpfNk zMucXGU}-3e{}cLD z4ymYWbf=6S0a4}qU_tN8u>*f8aHT--G%m!m95NYQ3LbUQ%k_)#bARdWdH z$TD?5jE*r!vC+E_zm{1zLjcWixqcYge6Lnyw#VK=W*c@|@A z%+jU~DF%5a+DMuKl>m1SkByCu>jqc`MKd$vF!)bqix|fNHt3VP;ioFGQ-JwMB9SZ- zELi;)zZv2)kmi}v9`5e06A-_HEp`L276Et>Za)vw8#hdt0X5lBOdoAB3kD4clpj2h zh*kqaF0vteW!C}XGc&|Vx;`m;lpDH_KdqJmG;w;Fqeh~JMn-_{%=fZsFIY1#aIUK> zk}ag@3u&=k8VYKd0I5Kfh?AEW<{4T!;MF@lRqr=@kCFs@7)4F%dxhFfD zn$#4C#Ds)-lI;lGN1dHjGXUv^@(R>eWtvfTId^u`F-}epoC6eO*Gyqk%hV1In3N>= zP*S>bbz?_IM5n3~(k&>ts-HwI?uN#dM8$zJKmkoZvf zK4`Z68#A-c1r&Q>xHv7-C?ng-1Ff0jGfoMD06%*JyMzKw#scIvuDBAplBW~WavlESM1o4J%eoJ8*e%DJN;`=?A54zmmj3w7uO2;~WEHYwoYV>-`k zioxKiAF~9C{Mov)M3I8EMltwP2-hfV$2og5tow)%WB=$VP6BC_Lmjrpmh9jZ8-Pj> z_VQ~b{PDUe`D8Ia_kNf;1*3<3;OGeYRo&(O$4xD2pG9P#nnsXg6Krm5RP|oo+~k_R zJTf|J&>&l7{j=negNHUphKqk4abR=+gyr|n<2ADv(=a@glewWf9#B(3f`Y$%V(ZGY z0agKMVn7Tbrhz{mZWy6XPQz@geh}A$SWK`e_Tv|M*pAeEio!>zPb_<;?czK=J#P{i z-bf%tFj06U6@J$e^7-zO8p|mBDQAb*l>}^)1|$WZ4u$=uOLmQw<>lOHtCQ-_`cB_M zR|8j_`AeZFfe9mXApV3QYO+|5!chKfoEFFhpVHG zDs_zRqLZwS`F%-lnRkQvUSX9`b2|8W27l8Nr~m8nfDa;IP%U_Hb(e6g;rMv@TSr<7 zOUYFYN=*pDQr6xt(vU3^-G0D_-pj;K>uncbJ1M9wglj zun#CdufcqZpkCV|9U$RIujQ|D5oAB^SLq3%j;*())}, m_height{storage.GetFloat("height", kDefaultHeight.to())}, From 812a1b8e1aedf1c21fc2dfc52759279bb0236e77 Mon Sep 17 00:00:00 2001 From: Dave Oleksy Date: Wed, 14 Jan 2026 22:14:20 -0600 Subject: [PATCH 15/27] [hal] Add 2026 REV products for usage reporting (#8567) Adding REV Easy Swerve and MAXSpline Encoder to usage reporting. Co-authored-by: Dave Oleksy --- hal/src/generate/Instances.txt | 1 + hal/src/generate/ResourceType.txt | 1 + hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java | 4 ++++ hal/src/generated/main/native/include/hal/FRCUsageReporting.h | 2 ++ hal/src/generated/main/native/include/hal/UsageReporting.h | 2 ++ 5 files changed, 10 insertions(+) diff --git a/hal/src/generate/Instances.txt b/hal/src/generate/Instances.txt index bbb9dadb43..93b09f78e4 100644 --- a/hal/src/generate/Instances.txt +++ b/hal/src/generate/Instances.txt @@ -36,6 +36,7 @@ kRobotDriveSwerve_YAGSL = 15 kRobotDriveSwerve_CTRE = 16 kRobotDriveSwerve_MaxSwerve = 17 kRobotDriveSwerve_AdvantageKit = 18 +kRobotDriveSwerve_EasySwerve = 19 kDriverStationCIO_Analog = 1 kDriverStationCIO_DigitalIn = 2 kDriverStationCIO_DigitalOut = 3 diff --git a/hal/src/generate/ResourceType.txt b/hal/src/generate/ResourceType.txt index f572a44eb8..7e6d58631e 100644 --- a/hal/src/generate/ResourceType.txt +++ b/hal/src/generate/ResourceType.txt @@ -134,3 +134,4 @@ kResourceType_PoseEstimator3d = 132 kResourceType_LinearSystemLoop = 133 kResourceType_LumynLabs_ConnectorX = 134 kResourceType_LumynLabs_ConnectorXAnimate = 135 +kResourceType_RevMAXSplineEncoder = 136 diff --git a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java b/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java index fdb51a83d2..d2b5ebd93a 100644 --- a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java +++ b/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java @@ -291,6 +291,8 @@ public final class FRCNetComm { public static final int kResourceType_LumynLabs_ConnectorX = 134; /** kResourceType_LumynLabs_ConnectorXAnimate = 135. */ public static final int kResourceType_LumynLabs_ConnectorXAnimate = 135; + /** kResourceType_RevMAXSplineEncoder = 136. */ + public static final int kResourceType_RevMAXSplineEncoder = 136; } /** @@ -377,6 +379,8 @@ public final class FRCNetComm { public static final int kRobotDriveSwerve_MaxSwerve = 17; /** kRobotDriveSwerve_AdvantageKit = 18. */ public static final int kRobotDriveSwerve_AdvantageKit = 18; + /** kRobotDriveSwerve_EasySwerve = 19. */ + public static final int kRobotDriveSwerve_EasySwerve = 19; /** kDriverStationCIO_Analog = 1. */ public static final int kDriverStationCIO_Analog = 1; /** kDriverStationCIO_DigitalIn = 2. */ diff --git a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h b/hal/src/generated/main/native/include/hal/FRCUsageReporting.h index 309dbc49d3..6d6c2b01b3 100644 --- a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h +++ b/hal/src/generated/main/native/include/hal/FRCUsageReporting.h @@ -187,6 +187,7 @@ namespace HALUsageReporting { kResourceType_LinearSystemLoop = 133, kResourceType_LumynLabs_ConnectorX = 134, kResourceType_LumynLabs_ConnectorXAnimate = 135, + kResourceType_RevMAXSplineEncoder = 136, }; enum tInstances : int32_t { kLanguage_LabVIEW = 1, @@ -227,6 +228,7 @@ namespace HALUsageReporting { kRobotDriveSwerve_CTRE = 16, kRobotDriveSwerve_MaxSwerve = 17, kRobotDriveSwerve_AdvantageKit = 18, + kRobotDriveSwerve_EasySwerve = 19, kDriverStationCIO_Analog = 1, kDriverStationCIO_DigitalIn = 2, kDriverStationCIO_DigitalOut = 3, diff --git a/hal/src/generated/main/native/include/hal/UsageReporting.h b/hal/src/generated/main/native/include/hal/UsageReporting.h index b0d5295577..1230e187f6 100644 --- a/hal/src/generated/main/native/include/hal/UsageReporting.h +++ b/hal/src/generated/main/native/include/hal/UsageReporting.h @@ -156,6 +156,7 @@ typedef enum kResourceType_LinearSystemLoop = 133, kResourceType_LumynLabs_ConnectorX = 134, kResourceType_LumynLabs_ConnectorXAnimate = 135, + kResourceType_RevMAXSplineEncoder = 136, // kResourceType_MaximumID = 255, } tResourceType; @@ -200,6 +201,7 @@ typedef enum kRobotDriveSwerve_CTRE = 16, kRobotDriveSwerve_MaxSwerve = 17, kRobotDriveSwerve_AdvantageKit = 18, + kRobotDriveSwerve_EasySwerve = 19, kDriverStationCIO_Analog = 1, kDriverStationCIO_DigitalIn = 2, kDriverStationCIO_DigitalOut = 3, From 9e1258440b7953af31fe53d6081112c033a9869b Mon Sep 17 00:00:00 2001 From: Joseph Eng <91924258+KangarooKoala@users.noreply.github.com> Date: Wed, 14 Jan 2026 20:16:24 -0800 Subject: [PATCH 16/27] [wpimath] Fix Rotation3d interpolation and document extrinsic vs intrinsic (#8544) Documents the extrinsic vs intrinsic semantics of `plus()` and `minus()`. (`rotateBy()` was documented in [a previous PR](https://github.com/wpilibsuite/allwpilib/pull/5508)) Fixes usage of `plus()` and `minus()` in `Rotation3d.interpolate()`. (Fixes #8523) Fixes incorrect usages of `plus()`, `minus()`, and `rotateBy()` throughout `Odometry3d`. Adds explanatory comments for some `plus()`, `minus()`, and `rotateBy()` operations. Fixes `TimeInterpolatableBuffer` not using twists for `Pose3d` (this was just because I happened to notice it, it isn't really related to the PR) To check all of our usages of `plus()`, `minus()`, and `rotateBy()`, I marked them as deprecated, checked compile errors from `./gradlew compileJava`, and then undeprecated them. You can see all of the spots that showed up (at least on the Java side) by viewing the diff for 241109c. I wanted to present this alternative to #8526 because the change has its own quirks, there's little time before kickoff, and there would be no code-side warning to teams (and mentors) already used to the current behavior. --- .../first/math/geometry/CoordinateSystem.java | 26 ++++- .../edu/wpi/first/math/geometry/Pose2d.java | 2 +- .../edu/wpi/first/math/geometry/Pose3d.java | 5 +- .../wpi/first/math/geometry/Rotation2d.java | 11 +++ .../wpi/first/math/geometry/Rotation3d.java | 89 +++++++++++++++-- .../wpi/first/math/geometry/Transform2d.java | 7 +- .../wpi/first/math/geometry/Transform3d.java | 12 ++- .../wpi/first/math/kinematics/Odometry.java | 17 +++- .../wpi/first/math/kinematics/Odometry3d.java | 27 ++++- .../include/frc/geometry/CoordinateSystem.h | 26 ++++- .../main/native/include/frc/geometry/Pose2d.h | 2 +- .../main/native/include/frc/geometry/Pose3d.h | 5 +- .../native/include/frc/geometry/Rotation2d.h | 13 +++ .../native/include/frc/geometry/Rotation3d.h | 99 ++++++++++++++++++- .../native/include/frc/geometry/Transform2d.h | 7 +- .../native/include/frc/geometry/Transform3d.h | 11 ++- .../interpolation/TimeInterpolatableBuffer.h | 21 +++- .../native/include/frc/kinematics/Odometry.h | 14 ++- .../include/frc/kinematics/Odometry3d.h | 24 ++++- .../first/math/geometry/Rotation2dTest.java | 10 ++ .../first/math/geometry/Rotation3dTest.java | 43 ++++++++ .../DifferentialDriveOdometry3dTest.java | 19 ++++ .../MecanumDriveOdometry3dTest.java | 18 ++++ .../kinematics/SwerveDriveOdometry3dTest.java | 18 ++++ .../native/cpp/geometry/Rotation2dTest.cpp | 9 ++ .../native/cpp/geometry/Rotation3dTest.cpp | 43 ++++++++ .../DifferentialDriveOdometry3dTest.cpp | 15 +++ .../kinematics/MecanumDriveOdometry3dTest.cpp | 16 +++ .../kinematics/SwerveDriveOdometry3dTest.cpp | 15 +++ 29 files changed, 561 insertions(+), 63 deletions(-) diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateSystem.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateSystem.java index 9e827c3e48..95788c7798 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateSystem.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/CoordinateSystem.java @@ -16,7 +16,7 @@ public class CoordinateSystem { private static final CoordinateSystem m_ned = new CoordinateSystem(CoordinateAxis.N(), CoordinateAxis.E(), CoordinateAxis.D()); - // Rotation from this coordinate system to NWU coordinate system + // Rotation from this coordinate system to NWU coordinate system when applied extrinsically private final Rotation3d m_rotation; /** @@ -85,7 +85,8 @@ public class CoordinateSystem { */ public static Translation3d convert( Translation3d translation, CoordinateSystem from, CoordinateSystem to) { - return translation.rotateBy(from.m_rotation.minus(to.m_rotation)); + // Convert to NWU, then convert to the new coordinate system + return translation.rotateBy(from.m_rotation).rotateBy(to.m_rotation.unaryMinus()); } /** @@ -98,7 +99,8 @@ public class CoordinateSystem { */ public static Rotation3d convert( Rotation3d rotation, CoordinateSystem from, CoordinateSystem to) { - return rotation.rotateBy(from.m_rotation.minus(to.m_rotation)); + // Convert to NWU, then convert to the new coordinate system + return rotation.rotateBy(from.m_rotation).rotateBy(to.m_rotation.unaryMinus()); } /** @@ -124,9 +126,23 @@ public class CoordinateSystem { */ public static Transform3d convert( Transform3d transform, CoordinateSystem from, CoordinateSystem to) { - var coordRot = from.m_rotation.minus(to.m_rotation); + // coordRot is the rotation that converts between the coordinate systems when applied + // extrinsically. It first converts to NWU, then converts to the new coordinate system. + var coordRot = from.m_rotation.rotateBy(to.m_rotation.unaryMinus()); + // The new rotation is the extrinsic rotation from convert(zero) to + // convert(transformRot). That is, applying convertedRot extrinsically to + // convert(zero) produces convert(transformRot). In the below snippet, we + // use matrix notation, so rotA rotB applies rotA extrinsically to rotB. + // + // convertedRot convert(zero) = convert(transformRot) + // convertedRot = convert(transformRot) convert(zero)⁻¹ + // = (coordRot transformRot) (coordRot zero)⁻¹ + // = (coordRot transformRot) coordRot⁻¹ + // + // In code, the equivalent for rotA rotB is rotB.rotateBy(rotA) (note the + // change in order), and the equivalent for rot⁻¹ is rot.unaryMinus(). return new Transform3d( convert(transform.getTranslation(), from, to), - coordRot.unaryMinus().plus(transform.getRotation().rotateBy(coordRot))); + coordRot.unaryMinus().rotateBy(transform.getRotation().rotateBy(coordRot))); } } diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java index 4a84ef6543..4b80cc4801 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose2d.java @@ -220,7 +220,7 @@ public class Pose2d implements Interpolatable, ProtobufSerializable, Str public Pose2d transformBy(Transform2d other) { return new Pose2d( m_translation.plus(other.getTranslation().rotateBy(m_rotation)), - other.getRotation().plus(m_rotation)); + other.getRotation().rotateBy(m_rotation)); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java index 20204235bc..ca3a8ebab5 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Pose3d.java @@ -254,9 +254,12 @@ public class Pose3d implements Interpolatable, ProtobufSerializable, Str * @return The transformed pose. */ public Pose3d transformBy(Transform3d other) { + // Rotating the transform's rotation by the pose's rotation extrinsically is equivalent to + // rotating the pose's rotation by the transform's rotation intrinsically. (We define transforms + // as being applied intrinsically.) return new Pose3d( m_translation.plus(other.getTranslation().rotateBy(m_rotation)), - other.getRotation().plus(m_rotation)); + other.getRotation().rotateBy(m_rotation)); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java index 2d4206b8c6..01ad00cb1b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation2d.java @@ -275,6 +275,17 @@ public class Rotation2d m_cos * other.m_cos - m_sin * other.m_sin, m_cos * other.m_sin + m_sin * other.m_cos); } + /** + * Returns the current rotation relative to the given rotation. + * + * @param other The rotation describing the orientation of the new coordinate frame that the + * current rotation will be converted into. + * @return The current rotation relative to the new orientation of the coordinate frame. + */ + public Rotation2d relativeTo(Rotation2d other) { + return rotateBy(other.unaryMinus()); + } + /** * Returns matrix representation of this rotation. * diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java index 5d3f479a97..46a258e117 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Rotation3d.java @@ -26,7 +26,49 @@ import edu.wpi.first.util.protobuf.ProtobufSerializable; import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; -/** A rotation in a 3D coordinate frame represented by a quaternion. */ +/** + * A rotation in a 3D coordinate frame, represented by a quaternion. Note that unlike 2D rotations, + * 3D rotations are not always commutative, so changing the order of rotations changes the result. + * + *

As an example of the order of rotations mattering, suppose we have a card that looks like + * this: + * + *

+ *          ┌───┐        ┌───┐
+ *          │ X │        │ x │
+ *   Front: │ | │  Back: │ · │
+ *          │ | │        │ · │
+ *          └───┘        └───┘
+ * 
+ * + *

If we rotate 90º clockwise around the axis into the page, then flip around the left/right + * axis, we get one result: + * + *

+ *   ┌───┐
+ *   │ X │   ┌───────┐   ┌───────┐
+ *   │ | │ → │------X│ → │······x│
+ *   │ | │   └───────┘   └───────┘
+ *   └───┘
+ * 
+ * + *

If we flip around the left/right axis, then rotate 90º clockwise around the axis into the + * page, we get a different result: + * + *

+ *   ┌───┐   ┌───┐
+ *   │ X │   │ · │   ┌───────┐
+ *   │ | │ → │ · │ → │x······│
+ *   │ | │   │ x │   └───────┘
+ *   └───┘   └───┘
+ * 
+ * + *

Because order matters for 3D rotations, we need to distinguish between extrinsic + * rotations and intrinsic rotations. Rotating extrinsically means rotating around the + * global axes, while rotating intrinsically means rotating from the perspective of the other + * rotation. A neat property is that applying a series of rotations extrinsically is the same as + * applying the same series in the opposite order intrinsically. + */ @JsonIgnoreProperties(ignoreUnknown = true) @JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE) public class Rotation3d @@ -286,9 +328,17 @@ public class Rotation3d } /** - * Adds two rotations together. + * Adds two rotations together. The other rotation is applied extrinsically to this rotation, + * which is equivalent to this rotation being applied intrinsically to the other rotation. See the + * class comment for definitions of extrinsic and intrinsic rotations. * - * @param other The rotation to add. + *

Note that {@code a.minus(b).plus(b)} always equals {@code a}, but {@code b.plus(a.minus(b))} + * sometimes doesn't. To apply a rotation offset, use either {@code offset = + * measurement.unaryMinus().plus(actual); newAngle = angle.plus(offset);} or {@code offset = + * actual.minus(measurement); newAngle = offset.plus(angle);}, depending on how the corrected + * angle needs to change as the input angle changes. + * + * @param other The rotation to add (applied extrinsically). * @return The sum of the two rotations. */ public Rotation3d plus(Rotation3d other) { @@ -296,10 +346,19 @@ public class Rotation3d } /** - * Subtracts the new rotation from the current rotation and returns the new rotation. + * Subtracts the other rotation from the current rotation and returns the new rotation. The new + * rotation is from the perspective of the other rotation (like {@link Pose3d#minus}), so it needs + * to be applied intrinsically. See the class comment for definitions of extrinsic and intrinsic + * rotations. + * + *

Note that {@code a.minus(b).plus(b)} always equals {@code a}, but {@code b.plus(a.minus(b))} + * sometimes doesn't. To apply a rotation offset, use either {@code offset = + * measurement.unaryMinus().plus(actual); newAngle = angle.plus(offset);} or {@code offset = + * actual.minus(measurement); newAngle = offset.plus(angle);}, depending on how the corrected + * angle needs to change as the input angle changes. * * @param other The rotation to subtract. - * @return The difference between the two rotations. + * @return The difference between the two rotations, from the perspective of the other rotation. */ public Rotation3d minus(Rotation3d other) { return rotateBy(other.unaryMinus()); @@ -358,6 +417,24 @@ public class Rotation3d return new Rotation3d(other.m_q.times(m_q)); } + /** + * Returns the current rotation relative to the given rotation. Because the result is in the + * perspective of the given rotation, it must be applied intrinsically. See the class comment for + * definitions of extrinsic and intrinsic rotations. + * + * @param other The rotation describing the orientation of the new coordinate frame that the + * current rotation will be converted into. + * @return The current rotation relative to the new orientation of the coordinate frame. + */ + public Rotation3d relativeTo(Rotation3d other) { + // To apply a quaternion intrinsically, we must right-multiply by that quaternion. + // Therefore, "this_q relative to other_q" is the q such that other_q q = this_q: + // + // other_q q = this_q + // q = other_q⁻¹ this_q + return new Rotation3d(other.m_q.inverse().times(m_q)); + } + /** * Returns the quaternion representation of the Rotation3d. * @@ -562,7 +639,7 @@ public class Rotation3d @Override public Rotation3d interpolate(Rotation3d endValue, double t) { - return plus(endValue.minus(this).times(MathUtil.clamp(t, 0, 1))); + return endValue.minus(this).times(MathUtil.clamp(t, 0, 1)).plus(this); } /** Rotation3d protobuf for serialization. */ diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java index 7a4cf8f4f9..79e8955220 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform2d.java @@ -36,15 +36,14 @@ public class Transform2d implements ProtobufSerializable, StructSerializable { * @param last The final pose for the transformation. */ public Transform2d(Pose2d initial, Pose2d last) { - // We are rotating the difference between the translations - // using a clockwise rotation matrix. This transforms the global - // delta into a local delta (relative to the initial pose). + // To transform the global translation delta to be relative to the initial + // pose, rotate by the inverse of the initial pose's orientation. m_translation = last.getTranslation() .minus(initial.getTranslation()) .rotateBy(initial.getRotation().unaryMinus()); - m_rotation = last.getRotation().minus(initial.getRotation()); + m_rotation = last.getRotation().relativeTo(initial.getRotation()); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java b/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java index d993d86100..67a4ba6173 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/geometry/Transform3d.java @@ -17,7 +17,10 @@ import edu.wpi.first.util.protobuf.ProtobufSerializable; import edu.wpi.first.util.struct.StructSerializable; import java.util.Objects; -/** Represents a transformation for a Pose3d in the pose's frame. */ +/** + * Represents a transformation for a Pose3d in the pose's frame. Translation is applied before + * rotation. (The translation is applied in the pose's original frame, not the transformed frame.) + */ public class Transform3d implements ProtobufSerializable, StructSerializable { /** * A preallocated Transform3d representing no transformation. @@ -36,15 +39,14 @@ public class Transform3d implements ProtobufSerializable, StructSerializable { * @param last The final pose for the transformation. */ public Transform3d(Pose3d initial, Pose3d last) { - // We are rotating the difference between the translations - // using a clockwise rotation matrix. This transforms the global - // delta into a local delta (relative to the initial pose). + // To transform the global translation delta to be relative to the initial + // pose, rotate by the inverse of the initial pose's orientation. m_translation = last.getTranslation() .minus(initial.getTranslation()) .rotateBy(initial.getRotation().unaryMinus()); - m_rotation = last.getRotation().minus(initial.getRotation()); + m_rotation = last.getRotation().relativeTo(initial.getRotation()); } /** diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java index 6a09f92bff..acc72ea55f 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry.java @@ -24,7 +24,10 @@ public class Odometry { private Pose2d m_poseMeters; private Rotation2d m_gyroOffset; + + // Always equal to m_poseMeters.getRotation() private Rotation2d m_previousAngle; + private final T m_previousWheelPositions; /** @@ -42,7 +45,7 @@ public class Odometry { Pose2d initialPoseMeters) { m_kinematics = kinematics; m_poseMeters = initialPoseMeters; - m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle); + m_gyroOffset = gyroAngle.unaryMinus().rotateBy(m_poseMeters.getRotation()); m_previousAngle = m_poseMeters.getRotation(); m_previousWheelPositions = m_kinematics.copy(wheelPositions); } @@ -60,7 +63,7 @@ public class Odometry { public void resetPosition(Rotation2d gyroAngle, T wheelPositions, Pose2d poseMeters) { m_poseMeters = poseMeters; m_previousAngle = m_poseMeters.getRotation(); - m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle); + m_gyroOffset = gyroAngle.unaryMinus().rotateBy(m_poseMeters.getRotation()); m_kinematics.copyInto(wheelPositions, m_previousWheelPositions); } @@ -70,7 +73,10 @@ public class Odometry { * @param poseMeters The pose to reset to. */ public void resetPose(Pose2d poseMeters) { - m_gyroOffset = m_gyroOffset.plus(poseMeters.getRotation().minus(m_poseMeters.getRotation())); + m_gyroOffset = + m_gyroOffset + .rotateBy(m_poseMeters.getRotation().unaryMinus()) + .rotateBy(poseMeters.getRotation()); m_poseMeters = poseMeters; m_previousAngle = m_poseMeters.getRotation(); } @@ -90,7 +96,8 @@ public class Odometry { * @param rotation The rotation to reset to. */ public void resetRotation(Rotation2d rotation) { - m_gyroOffset = m_gyroOffset.plus(rotation.minus(m_poseMeters.getRotation())); + m_gyroOffset = + m_gyroOffset.rotateBy(m_poseMeters.getRotation().unaryMinus()).rotateBy(rotation); m_poseMeters = new Pose2d(m_poseMeters.getTranslation(), rotation); m_previousAngle = m_poseMeters.getRotation(); } @@ -115,7 +122,7 @@ public class Odometry { * @return The new pose of the robot. */ public Pose2d update(Rotation2d gyroAngle, T wheelPositions) { - var angle = gyroAngle.plus(m_gyroOffset); + var angle = gyroAngle.rotateBy(m_gyroOffset); var twist = m_kinematics.toTwist2d(m_previousWheelPositions, wheelPositions); twist.dtheta = angle.minus(m_previousAngle).getRadians(); diff --git a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry3d.java b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry3d.java index f79403ef92..9e5122731b 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/kinematics/Odometry3d.java @@ -32,8 +32,15 @@ public class Odometry3d { private final Kinematics m_kinematics; private Pose3d m_poseMeters; + // Applying a rotation intrinsically to the measured gyro angle should cause the corrected angle + // to be rotated intrinsically in the same way, so the measured gyro angle must be applied + // intrinsically. This is equivalent to applying the offset extrinsically to the measured gyro + // angle. private Rotation3d m_gyroOffset; + + // Always equal to m_poseMeters.getRotation() private Rotation3d m_previousAngle; + private final T m_previousWheelPositions; /** @@ -51,7 +58,9 @@ public class Odometry3d { Pose3d initialPoseMeters) { m_kinematics = kinematics; m_poseMeters = initialPoseMeters; - m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle); + // When applied extrinsically, m_gyroOffset cancels the current gyroAngle and + // then rotates to m_poseMeters.getRotation() + m_gyroOffset = gyroAngle.unaryMinus().rotateBy(m_poseMeters.getRotation()); m_previousAngle = m_poseMeters.getRotation(); m_previousWheelPositions = m_kinematics.copy(wheelPositions); } @@ -69,7 +78,9 @@ public class Odometry3d { public void resetPosition(Rotation3d gyroAngle, T wheelPositions, Pose3d poseMeters) { m_poseMeters = poseMeters; m_previousAngle = m_poseMeters.getRotation(); - m_gyroOffset = m_poseMeters.getRotation().minus(gyroAngle); + // When applied extrinsically, m_gyroOffset cancels the current gyroAngle and + // then rotates to m_poseMeters.getRotation() + m_gyroOffset = gyroAngle.unaryMinus().rotateBy(m_poseMeters.getRotation()); m_kinematics.copyInto(wheelPositions, m_previousWheelPositions); } @@ -79,7 +90,11 @@ public class Odometry3d { * @param poseMeters The pose to reset to. */ public void resetPose(Pose3d poseMeters) { - m_gyroOffset = m_gyroOffset.plus(poseMeters.getRotation().minus(m_poseMeters.getRotation())); + // Cancel the previous m_pose.Rotation() and then rotate to the new angle + m_gyroOffset = + m_gyroOffset + .rotateBy(m_poseMeters.getRotation().unaryMinus()) + .rotateBy(poseMeters.getRotation()); m_poseMeters = poseMeters; m_previousAngle = m_poseMeters.getRotation(); } @@ -99,7 +114,9 @@ public class Odometry3d { * @param rotation The rotation to reset to. */ public void resetRotation(Rotation3d rotation) { - m_gyroOffset = m_gyroOffset.plus(rotation.minus(m_poseMeters.getRotation())); + // Cancel the previous m_pose.Rotation() and then rotate to the new angle + m_gyroOffset = + m_gyroOffset.rotateBy(m_poseMeters.getRotation().unaryMinus()).rotateBy(rotation); m_poseMeters = new Pose3d(m_poseMeters.getTranslation(), rotation); m_previousAngle = m_poseMeters.getRotation(); } @@ -124,7 +141,7 @@ public class Odometry3d { * @return The new pose of the robot. */ public Pose3d update(Rotation3d gyroAngle, T wheelPositions) { - var angle = gyroAngle.plus(m_gyroOffset); + var angle = gyroAngle.rotateBy(m_gyroOffset); var angle_difference = angle.minus(m_previousAngle).toVector(); var twist2d = m_kinematics.toTwist2d(m_previousWheelPositions, wheelPositions); diff --git a/wpimath/src/main/native/include/frc/geometry/CoordinateSystem.h b/wpimath/src/main/native/include/frc/geometry/CoordinateSystem.h index 0d4ba8f6c8..eff347f10d 100644 --- a/wpimath/src/main/native/include/frc/geometry/CoordinateSystem.h +++ b/wpimath/src/main/native/include/frc/geometry/CoordinateSystem.h @@ -86,7 +86,8 @@ class WPILIB_DLLEXPORT CoordinateSystem { constexpr static Translation3d Convert(const Translation3d& translation, const CoordinateSystem& from, const CoordinateSystem& to) { - return translation.RotateBy(from.m_rotation - to.m_rotation); + // Convert to NWU, then convert to the new coordinate system + return translation.RotateBy(from.m_rotation).RotateBy(-to.m_rotation); } /** @@ -100,7 +101,8 @@ class WPILIB_DLLEXPORT CoordinateSystem { constexpr static Rotation3d Convert(const Rotation3d& rotation, const CoordinateSystem& from, const CoordinateSystem& to) { - return rotation.RotateBy(from.m_rotation - to.m_rotation); + // Convert to NWU, then convert to the new coordinate system + return rotation.RotateBy(from.m_rotation).RotateBy(-to.m_rotation); } /** @@ -129,14 +131,30 @@ class WPILIB_DLLEXPORT CoordinateSystem { constexpr static Transform3d Convert(const Transform3d& transform, const CoordinateSystem& from, const CoordinateSystem& to) { - const auto coordRot = from.m_rotation - to.m_rotation; + // coordRot is the rotation that converts between the coordinate systems + // when applied extrinsically. It first converts to NWU, then converts to + // the new coordinate system. + const auto coordRot = from.m_rotation.RotateBy(-to.m_rotation); + // The new rotation is the extrinsic rotation from convert(zero) to + // convert(transformRot). That is, applying convertedRot extrinsically to + // convert(zero) produces convert(transformRot). In the below snippet, we + // use matrix notation, so rotA rotB applies rotA extrinsically to rotB. + // + // convertedRot convert(zero) = convert(transformRot) + // convertedRot = convert(transformRot) convert(zero)⁻¹ + // = (coordRot transformRot) (coordRot zero)⁻¹ + // = (coordRot transformRot) coordRot⁻¹ + // + // In code, the equivalent for rotA rotB is rotB.RotateBy(rotA) (note the + // change in order), and the equivalent for rot⁻¹ is -rot. return Transform3d{ Convert(transform.Translation(), from, to), (-coordRot).RotateBy(transform.Rotation().RotateBy(coordRot))}; } private: - // Rotation from this coordinate system to NWU coordinate system + // Rotation from this coordinate system to NWU coordinate system when applied + // extrinsically Rotation3d m_rotation; }; diff --git a/wpimath/src/main/native/include/frc/geometry/Pose2d.h b/wpimath/src/main/native/include/frc/geometry/Pose2d.h index d488e312a7..ea0a1e6767 100644 --- a/wpimath/src/main/native/include/frc/geometry/Pose2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Pose2d.h @@ -320,7 +320,7 @@ constexpr Transform2d Pose2d::operator-(const Pose2d& other) const { constexpr Pose2d Pose2d::TransformBy(const frc::Transform2d& other) const { return {m_translation + (other.Translation().RotateBy(m_rotation)), - other.Rotation() + m_rotation}; + other.Rotation().RotateBy(m_rotation)}; } constexpr Pose2d Pose2d::RelativeTo(const Pose2d& other) const { diff --git a/wpimath/src/main/native/include/frc/geometry/Pose3d.h b/wpimath/src/main/native/include/frc/geometry/Pose3d.h index 17aac42648..fb1eb96a76 100644 --- a/wpimath/src/main/native/include/frc/geometry/Pose3d.h +++ b/wpimath/src/main/native/include/frc/geometry/Pose3d.h @@ -392,8 +392,11 @@ constexpr Transform3d Pose3d::operator-(const Pose3d& other) const { } constexpr Pose3d Pose3d::TransformBy(const Transform3d& other) const { + // Rotating the transform's rotation by the pose's rotation extrinsically is + // equivalent to rotating the pose's rotation by the transform's rotation + // intrinsically. (We define transforms as being applied intrinsically.) return {m_translation + (other.Translation().RotateBy(m_rotation)), - other.Rotation() + m_rotation}; + other.Rotation().RotateBy(m_rotation)}; } constexpr Pose3d Pose3d::RelativeTo(const Pose3d& other) const { diff --git a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h index 82d9e39d78..61e39b148f 100644 --- a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h @@ -198,6 +198,19 @@ class WPILIB_DLLEXPORT Rotation2d { Cos() * other.Sin() + Sin() * other.Cos()}; } + /** + * Returns the current rotation relative to the given rotation. + * + * @param other The rotation describing the orientation of the new coordinate + * frame that the current rotation will be converted into. + * + * @return The current rotation relative to the new orientation of the + * coordinate frame. + */ + constexpr Rotation2d RelativeTo(const Rotation2d& other) const { + return RotateBy(-other); + } + /** * Returns matrix representation of this rotation. */ diff --git a/wpimath/src/main/native/include/frc/geometry/Rotation3d.h b/wpimath/src/main/native/include/frc/geometry/Rotation3d.h index 8d1e975299..d972e85636 100644 --- a/wpimath/src/main/native/include/frc/geometry/Rotation3d.h +++ b/wpimath/src/main/native/include/frc/geometry/Rotation3d.h @@ -10,6 +10,7 @@ #include #include #include +#include #include #include @@ -24,7 +25,49 @@ namespace frc { /** - * A rotation in a 3D coordinate frame represented by a quaternion. + * A rotation in a 3D coordinate frame, represented by a quaternion. Note that + * unlike 2D rotations, 3D rotations are not always commutative, so changing the + * order of rotations changes the result. + * + * As an example of the order of rotations mattering, suppose we have a card + * that looks like this: + * + *

+ *          ┌───┐        ┌───┐
+ *          │ X │        │ x │
+ *   Front: │ | │  Back: │ · │
+ *          │ | │        │ · │
+ *          └───┘        └───┘
+ * 
+ * + * If we rotate 90º clockwise around the axis into the page, then flip around + * the left/right axis, we get one result: + * + *
+ *   ┌───┐
+ *   │ X │   ┌───────┐   ┌───────┐
+ *   │ | │ → │------X│ → │······x│
+ *   │ | │   └───────┘   └───────┘
+ *   └───┘
+ * 
+ * + * If we flip around the left/right axis, then rotate 90º clockwise around the + * axis into the page, we get a different result: + * + *
+ *   ┌───┐   ┌───┐
+ *   │ X │   │ · │   ┌───────┐
+ *   │ | │ → │ · │ → │x······│
+ *   │ | │   │ x │   └───────┘
+ *   └───┘   └───┘
+ * 
+ * + * Because order matters for 3D rotations, we need to distinguish between + * extrinsic rotations and intrinsic rotations. Rotating + * extrinsically means rotating around the global axes, while rotating + * intrinsically means rotating from the perspective of the other rotation. A + * neat property is that applying a series of rotations extrinsically is the + * same as applying the same series in the opposite order intrinsically. */ class WPILIB_DLLEXPORT Rotation3d { public: @@ -242,9 +285,18 @@ class WPILIB_DLLEXPORT Rotation3d { : Rotation3d{0_rad, 0_rad, rotation.Radians()} {} /** - * Adds two rotations together. + * Adds two rotations together. The other rotation is applied extrinsically to + * this rotation, which is equivalent to this rotation being applied + * intrinsically to the other rotation. See the class comment for definitions + * of extrinsic and intrinsic rotations. * - * @param other The rotation to add. + * Note that `a - b + b` always equals `a`, but `b + (a - b)` + * sometimes doesn't. To apply a rotation offset, use either `offset = + * -measurement + actual; newAngle = angle + offset;` or `offset = actual - + * measurement; newAngle = offset + angle;`, depending on how the corrected + * angle needs to change as the input angle changes. + * + * @param other The rotation to add (applied extrinsically). * * @return The sum of the two rotations. */ @@ -254,11 +306,20 @@ class WPILIB_DLLEXPORT Rotation3d { /** * Subtracts the new rotation from the current rotation and returns the new - * rotation. + * rotation. The new rotation is from the perspective of the other rotation + * (like Pose3d::operator-), so it needs to be applied intrinsically. See the + * class comment for definitions of extrinsic and intrinsic rotations. + * + * Note that `a - b + b` always equals `a`, but `b + (a - b)` sometimes + * doesn't. To apply a rotation offset, use either `offset = -measurement + + * actual; newAngle = angle + offset;` or `offset = actual - measurement; + * newAngle = offset + angle;`, depending on how the corrected angle needs to + * change as the input angle changes. * * @param other The rotation to subtract. * - * @return The difference between the two rotations. + * @return The difference between the two rotations, from the perspective of + * the other rotation. */ constexpr Rotation3d operator-(const Rotation3d& other) const { return *this + -other; @@ -323,6 +384,28 @@ class WPILIB_DLLEXPORT Rotation3d { return Rotation3d{other.m_q * m_q}; } + /** + * Returns the current rotation relative to the given rotation. Because the + * result is in the perspective of the given rotation, it must be applied + * intrinsically. See the class comment for definitions of extrinsic and + * intrinsic rotations. + * + * @param other The rotation describing the orientation of the new coordinate + * frame that the current rotation will be converted into. + * + * @return The current rotation relative to the new orientation of the + * coordinate frame. + */ + constexpr Rotation3d RelativeTo(const Rotation3d& other) const { + // To apply a quaternion intrinsically, we must right-multiply by that + // quaternion. Therefore, "this_q relative to other_q" is the q such that + // other_q q = this_q: + // + // other_q q = this_q + // q = other_q⁻¹ this_q + return Rotation3d{other.m_q.Inverse() * m_q}; + } + /** * Returns the quaternion representation of the Rotation3d. */ @@ -449,5 +532,11 @@ void from_json(const wpi::json& json, Rotation3d& rotation); } // namespace frc +template <> +constexpr frc::Rotation3d wpi::Lerp(const frc::Rotation3d& startValue, + const frc::Rotation3d& endValue, double t) { + return (endValue - startValue) * t + startValue; +} + #include "frc/geometry/proto/Rotation3dProto.h" #include "frc/geometry/struct/Rotation3dStruct.h" diff --git a/wpimath/src/main/native/include/frc/geometry/Transform2d.h b/wpimath/src/main/native/include/frc/geometry/Transform2d.h index 88c00550d0..2055ee489f 100644 --- a/wpimath/src/main/native/include/frc/geometry/Transform2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Transform2d.h @@ -167,13 +167,12 @@ class WPILIB_DLLEXPORT Transform2d { namespace frc { constexpr Transform2d::Transform2d(const Pose2d& initial, const Pose2d& final) { - // We are rotating the difference between the translations - // using a clockwise rotation matrix. This transforms the global - // delta into a local delta (relative to the initial pose). + // To transform the global translation delta to be relative to the initial + // pose, rotate by the inverse of the initial pose's orientation. m_translation = (final.Translation() - initial.Translation()) .RotateBy(-initial.Rotation()); - m_rotation = final.Rotation() - initial.Rotation(); + m_rotation = final.Rotation().RelativeTo(initial.Rotation()); } constexpr Transform2d Transform2d::operator+(const Transform2d& other) const { diff --git a/wpimath/src/main/native/include/frc/geometry/Transform3d.h b/wpimath/src/main/native/include/frc/geometry/Transform3d.h index bd6ca9c41e..38cf39d69f 100644 --- a/wpimath/src/main/native/include/frc/geometry/Transform3d.h +++ b/wpimath/src/main/native/include/frc/geometry/Transform3d.h @@ -16,7 +16,9 @@ namespace frc { class Pose3d; /** - * Represents a transformation for a Pose3d in the pose's frame. + * Represents a transformation for a Pose3d in the pose's frame. Translation is + * applied before rotation. (The translation is applied in the pose's original + * frame, not the transformed frame.) */ class WPILIB_DLLEXPORT Transform3d { public: @@ -192,13 +194,12 @@ class WPILIB_DLLEXPORT Transform3d { namespace frc { constexpr Transform3d::Transform3d(const Pose3d& initial, const Pose3d& final) { - // We are rotating the difference between the translations - // using a clockwise rotation matrix. This transforms the global - // delta into a local delta (relative to the initial pose). + // To transform the global translation delta to be relative to the initial + // pose, rotate by the inverse of the initial pose's orientation. m_translation = (final.Translation() - initial.Translation()) .RotateBy(-initial.Rotation()); - m_rotation = final.Rotation() - initial.Rotation(); + m_rotation = final.Rotation().RelativeTo(initial.Rotation()); } constexpr Transform3d Transform3d::operator+(const Transform3d& other) const { diff --git a/wpimath/src/main/native/include/frc/interpolation/TimeInterpolatableBuffer.h b/wpimath/src/main/native/include/frc/interpolation/TimeInterpolatableBuffer.h index 47bcc46b14..f07df67cf0 100644 --- a/wpimath/src/main/native/include/frc/interpolation/TimeInterpolatableBuffer.h +++ b/wpimath/src/main/native/include/frc/interpolation/TimeInterpolatableBuffer.h @@ -14,6 +14,8 @@ #include #include "frc/geometry/Pose2d.h" +#include "frc/geometry/Pose3d.h" +#include "frc/geometry/Rotation3d.h" #include "units/time.h" namespace frc { @@ -155,7 +157,8 @@ class TimeInterpolatableBuffer { std::function m_interpolatingFunc; }; -// Template specialization to ensure that Pose2d uses pose exponential +// Template specializations to ensure that Pose2d and Pose3d use pose +// exponential template <> inline TimeInterpolatableBuffer::TimeInterpolatableBuffer( units::second_t historySize) @@ -172,4 +175,20 @@ inline TimeInterpolatableBuffer::TimeInterpolatableBuffer( } }) {} +template <> +inline TimeInterpolatableBuffer::TimeInterpolatableBuffer( + units::second_t historySize) + : m_historySize(historySize), + m_interpolatingFunc([](const Pose3d& start, const Pose3d& end, double t) { + if (t < 0) { + return start; + } else if (t >= 1) { + return end; + } else { + Twist3d twist = start.Log(end); + Twist3d scaledTwist = twist * t; + return start.Exp(scaledTwist); + } + }) {} + } // namespace frc diff --git a/wpimath/src/main/native/include/frc/kinematics/Odometry.h b/wpimath/src/main/native/include/frc/kinematics/Odometry.h index c73eed2248..991bd1a34d 100644 --- a/wpimath/src/main/native/include/frc/kinematics/Odometry.h +++ b/wpimath/src/main/native/include/frc/kinematics/Odometry.h @@ -45,7 +45,7 @@ class WPILIB_DLLEXPORT Odometry { m_pose(initialPose), m_previousWheelPositions(wheelPositions) { m_previousAngle = m_pose.Rotation(); - m_gyroOffset = m_pose.Rotation() - gyroAngle; + m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation()); } /** @@ -62,7 +62,7 @@ class WPILIB_DLLEXPORT Odometry { const WheelPositions& wheelPositions, const Pose2d& pose) { m_pose = pose; m_previousAngle = pose.Rotation(); - m_gyroOffset = m_pose.Rotation() - gyroAngle; + m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation()); m_previousWheelPositions = wheelPositions; } @@ -72,7 +72,8 @@ class WPILIB_DLLEXPORT Odometry { * @param pose The pose to reset to. */ void ResetPose(const Pose2d& pose) { - m_gyroOffset = m_gyroOffset + (pose.Rotation() - m_pose.Rotation()); + m_gyroOffset = + m_gyroOffset.RotateBy(-m_pose.Rotation()).RotateBy(pose.Rotation()); m_pose = pose; m_previousAngle = pose.Rotation(); } @@ -92,7 +93,7 @@ class WPILIB_DLLEXPORT Odometry { * @param rotation The rotation to reset to. */ void ResetRotation(const Rotation2d& rotation) { - m_gyroOffset = m_gyroOffset + (rotation - m_pose.Rotation()); + m_gyroOffset = m_gyroOffset.RotateBy(m_pose.Rotation()).RotateBy(rotation); m_pose = Pose2d{m_pose.Translation(), rotation}; m_previousAngle = rotation; } @@ -116,7 +117,7 @@ class WPILIB_DLLEXPORT Odometry { */ const Pose2d& Update(const Rotation2d& gyroAngle, const WheelPositions& wheelPositions) { - auto angle = gyroAngle + m_gyroOffset; + auto angle = gyroAngle.RotateBy(m_gyroOffset); auto twist = m_kinematics.ToTwist2d(m_previousWheelPositions, wheelPositions); @@ -136,7 +137,10 @@ class WPILIB_DLLEXPORT Odometry { Pose2d m_pose; WheelPositions m_previousWheelPositions; + + // Always equal to m_pose.Rotation() Rotation2d m_previousAngle; + Rotation2d m_gyroOffset; }; diff --git a/wpimath/src/main/native/include/frc/kinematics/Odometry3d.h b/wpimath/src/main/native/include/frc/kinematics/Odometry3d.h index f24d6f86f6..9b67a75176 100644 --- a/wpimath/src/main/native/include/frc/kinematics/Odometry3d.h +++ b/wpimath/src/main/native/include/frc/kinematics/Odometry3d.h @@ -48,7 +48,9 @@ class WPILIB_DLLEXPORT Odometry3d { m_pose(initialPose), m_previousWheelPositions(wheelPositions) { m_previousAngle = m_pose.Rotation(); - m_gyroOffset = m_pose.Rotation() - gyroAngle; + // When applied extrinsically, m_gyroOffset cancels the + // current gyroAngle and then rotates to m_pose.Rotation() + m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation()); } /** @@ -65,7 +67,9 @@ class WPILIB_DLLEXPORT Odometry3d { const WheelPositions& wheelPositions, const Pose3d& pose) { m_pose = pose; m_previousAngle = pose.Rotation(); - m_gyroOffset = m_pose.Rotation() - gyroAngle; + // When applied extrinsically, m_gyroOffset cancels the + // current gyroAngle and then rotates to m_pose.Rotation() + m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation()); m_previousWheelPositions = wheelPositions; } @@ -75,7 +79,9 @@ class WPILIB_DLLEXPORT Odometry3d { * @param pose The pose to reset to. */ void ResetPose(const Pose3d& pose) { - m_gyroOffset = m_gyroOffset + (pose.Rotation() - m_pose.Rotation()); + // Cancel the previous m_pose.Rotation() and then rotate to the new angle + m_gyroOffset = + m_gyroOffset.RotateBy(-m_pose.Rotation()).RotateBy(pose.Rotation()); m_pose = pose; m_previousAngle = pose.Rotation(); } @@ -95,7 +101,8 @@ class WPILIB_DLLEXPORT Odometry3d { * @param rotation The rotation to reset to. */ void ResetRotation(const Rotation3d& rotation) { - m_gyroOffset = m_gyroOffset + (rotation - m_pose.Rotation()); + // Cancel the previous m_pose.Rotation() and then rotate to the new angle + m_gyroOffset = m_gyroOffset.RotateBy(-m_pose.Rotation()).RotateBy(rotation); m_pose = Pose3d{m_pose.Translation(), rotation}; m_previousAngle = rotation; } @@ -119,7 +126,7 @@ class WPILIB_DLLEXPORT Odometry3d { */ const Pose3d& Update(const Rotation3d& gyroAngle, const WheelPositions& wheelPositions) { - auto angle = gyroAngle + m_gyroOffset; + auto angle = gyroAngle.RotateBy(m_gyroOffset); auto angle_difference = (angle - m_previousAngle).ToVector(); auto twist2d = @@ -145,7 +152,14 @@ class WPILIB_DLLEXPORT Odometry3d { Pose3d m_pose; WheelPositions m_previousWheelPositions; + + // Always equal to m_pose.Rotation() Rotation3d m_previousAngle; + + // Applying a rotation intrinsically to the measured gyro angle should cause + // the corrected angle to be rotated intrinsically in the same way, so the + // measured gyro angle must be applied intrinsically. This is equivalent to + // applying the offset extrinsically to the measured gyro angle. Rotation3d m_gyroOffset; }; diff --git a/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation2dTest.java b/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation2dTest.java index 6eaa2a3f98..223256bb6f 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation2dTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation2dTest.java @@ -59,6 +59,16 @@ class Rotation2dTest { assertEquals(120.0, rot.getDegrees(), kEpsilon); } + @Test + void testRelativeTo() { + var start = Rotation2d.fromDegrees(30.0); + var end = Rotation2d.kCCW_Pi_2; + + var result = end.relativeTo(start); + + assertEquals(60.0, result.getDegrees(), kEpsilon); + } + @Test void testMinus() { var rot1 = Rotation2d.fromDegrees(70.0); diff --git a/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation3dTest.java b/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation3dTest.java index 3e96a1cb3d..c87c7d0bad 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation3dTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/geometry/Rotation3dTest.java @@ -281,6 +281,22 @@ class Rotation3dTest { assertEquals(expected, rot); } + @Test + void testRelativeTo() { + final var yAxis = VecBuilder.fill(0.0, 1.0, 0.0); + final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0); + + var start = new Rotation3d(yAxis, Units.degreesToRadians(-90.0)); + var end = new Rotation3d(zAxis, Units.degreesToRadians(90.0)); + + final var intrinsicAxis = VecBuilder.fill(1.0, 1.0, 1.0); + var expected = new Rotation3d(intrinsicAxis, Units.degreesToRadians(120.0)); + + var result = end.relativeTo(start); + + assertEquals(expected, result); + } + @Test void testMinus() { final var zAxis = VecBuilder.fill(0.0, 0.0, 1.0); @@ -409,5 +425,32 @@ class Rotation3dTest { assertEquals(Units.degreesToRadians(0.0), interpolated.getX(), kEpsilon); assertEquals(Units.degreesToRadians(0.0), interpolated.getY(), kEpsilon); assertEquals(Units.degreesToRadians(-175.0), interpolated.getZ(), kEpsilon); + + // t value of 0 should always produce the start + rot1 = new Rotation3d(yAxis, -Units.degreesToRadians(90)); + rot2 = new Rotation3d(zAxis, Units.degreesToRadians(90)); + interpolated = rot1.interpolate(rot2, 0.0); + assertEquals(rot1.getX(), interpolated.getX(), kEpsilon); + assertEquals(rot1.getY(), interpolated.getY(), kEpsilon); + assertEquals(rot1.getZ(), interpolated.getZ(), kEpsilon); + + // The full rotation from rot1 to rot2 to 120 degrees around extrinsic <-1.0, 1.0, 1.0> + var extrinsicAxis = VecBuilder.fill(-1.0, 1.0, 1.0); + rot1 = new Rotation3d(yAxis, -Units.degreesToRadians(90)); + rot2 = new Rotation3d(zAxis, Units.degreesToRadians(90)); + assertEquals(rot2, rot1.rotateBy(new Rotation3d(extrinsicAxis, Units.degreesToRadians(120)))); + interpolated = rot1.interpolate(rot2, 0.5); + var expected = rot1.rotateBy(new Rotation3d(extrinsicAxis, Units.degreesToRadians(60))); + assertEquals(expected.getX(), interpolated.getX(), kEpsilon); + assertEquals(expected.getY(), interpolated.getY(), kEpsilon); + assertEquals(expected.getZ(), interpolated.getZ(), kEpsilon); + + // t value of 1 should always produce the end + rot1 = new Rotation3d(yAxis, -Units.degreesToRadians(90)); + rot2 = new Rotation3d(zAxis, Units.degreesToRadians(90)); + interpolated = rot1.interpolate(rot2, 1.0); + assertEquals(rot2.getX(), interpolated.getX(), kEpsilon); + assertEquals(rot2.getY(), interpolated.getY(), kEpsilon); + assertEquals(rot2.getZ(), interpolated.getZ(), kEpsilon); } } diff --git a/wpimath/src/test/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry3dTest.java b/wpimath/src/test/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry3dTest.java index 166a615ca9..b72b4ce8f5 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry3dTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/kinematics/DifferentialDriveOdometry3dTest.java @@ -9,6 +9,7 @@ import static org.junit.jupiter.api.Assertions.assertEquals; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation3d; +import edu.wpi.first.math.geometry.Translation3d; import edu.wpi.first.math.util.Units; import org.junit.jupiter.api.Test; @@ -45,4 +46,22 @@ class DifferentialDriveOdometry3dTest { () -> assertEquals(pose.getZ(), 0.0, kEpsilon), () -> assertEquals(pose.getRotation().toRotation2d().getDegrees(), 90.0, kEpsilon)); } + + @Test + void testGyroOffset() { + m_odometry.resetPosition( + new Rotation3d(0, Units.degreesToRadians(5), 0), + 0, + 0, + new Pose3d(Translation3d.kZero, new Rotation3d(0, 0, Units.degreesToRadians(90)))); + var pose = m_odometry.update(new Rotation3d(0, Units.degreesToRadians(10), 0), 0, 0); + + assertAll( + () -> assertEquals(pose.getX(), 0.0, kEpsilon), + () -> assertEquals(pose.getY(), 0.0, kEpsilon), + () -> assertEquals(pose.getZ(), 0.0, kEpsilon), + () -> assertEquals(pose.getRotation().getX(), Units.degreesToRadians(0), kEpsilon), + () -> assertEquals(pose.getRotation().getY(), Units.degreesToRadians(5), kEpsilon), + () -> assertEquals(pose.getRotation().getZ(), Units.degreesToRadians(90), kEpsilon)); + } } diff --git a/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3dTest.java b/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3dTest.java index d417e2a120..4e1857d251 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3dTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/kinematics/MecanumDriveOdometry3dTest.java @@ -295,4 +295,22 @@ class MecanumDriveOdometry3dTest { 0.05, "Incorrect distance travelled"); } + + @Test + void testGyroOffset() { + var wheelPositions = new MecanumDriveWheelPositions(); + m_odometry.resetPosition( + new Rotation3d(0, Units.degreesToRadians(5), 0), + wheelPositions, + new Pose3d(Translation3d.kZero, new Rotation3d(0, 0, Units.degreesToRadians(90)))); + var pose = m_odometry.update(new Rotation3d(0, Units.degreesToRadians(10), 0), wheelPositions); + + assertAll( + () -> assertEquals(pose.getX(), 0.0, 1e-9), + () -> assertEquals(pose.getY(), 0.0, 1e-9), + () -> assertEquals(pose.getZ(), 0.0, 1e-9), + () -> assertEquals(pose.getRotation().getX(), Units.degreesToRadians(0), 1e-9), + () -> assertEquals(pose.getRotation().getY(), Units.degreesToRadians(5), 1e-9), + () -> assertEquals(pose.getRotation().getZ(), Units.degreesToRadians(90), 1e-9)); + } } diff --git a/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry3dTest.java b/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry3dTest.java index dfc446fcee..43058defe3 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry3dTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/kinematics/SwerveDriveOdometry3dTest.java @@ -305,4 +305,22 @@ class SwerveDriveOdometry3dTest { 0.0, errorSum / (trajectory.getTotalTimeSeconds() / dt), 0.06, "Incorrect mean error"); assertEquals(0.0, maxError, 0.125, "Incorrect max error"); } + + @Test + void testGyroOffset() { + SwerveModulePosition[] modulePositions = {zero, zero, zero, zero}; + m_odometry.resetPosition( + new Rotation3d(0, Units.degreesToRadians(5), 0), + modulePositions, + new Pose3d(Translation3d.kZero, new Rotation3d(0, 0, Units.degreesToRadians(90)))); + var pose = m_odometry.update(new Rotation3d(0, Units.degreesToRadians(10), 0), modulePositions); + + assertAll( + () -> assertEquals(pose.getX(), 0.0, 1e-9), + () -> assertEquals(pose.getY(), 0.0, 1e-9), + () -> assertEquals(pose.getZ(), 0.0, 1e-9), + () -> assertEquals(pose.getRotation().getX(), Units.degreesToRadians(0), 1e-9), + () -> assertEquals(pose.getRotation().getY(), Units.degreesToRadians(5), 1e-9), + () -> assertEquals(pose.getRotation().getZ(), Units.degreesToRadians(90), 1e-9)); + } } diff --git a/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp index ffbbd20c4a..66e000a8e2 100644 --- a/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp @@ -42,6 +42,15 @@ TEST(Rotation2dTest, RotateByNonZero) { EXPECT_DOUBLE_EQ(120.0, rot.Degrees().value()); } +TEST(Rotation2dTest, RelativeTo) { + auto start = Rotation2d{30_deg}; + auto end = Rotation2d{90_deg}; + + auto result = end.RelativeTo(start); + + EXPECT_DOUBLE_EQ(60.0, result.Degrees().value()); +} + TEST(Rotation2dTest, Minus) { const auto rot1 = Rotation2d{70_deg}; const auto rot2 = Rotation2d{30_deg}; diff --git a/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp b/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp index 903d4144bc..6c0d4f6e14 100644 --- a/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp @@ -253,6 +253,21 @@ TEST(Rotation3dTest, RotateByNonZeroZ) { EXPECT_EQ(expected, rot); } +TEST(Rotation3dTest, RelativeTo) { + const Eigen::Vector3d yAxis{0.0, 1.0, 0.0}; + const Eigen::Vector3d zAxis{0.0, 0.0, 1.0}; + + auto start = Rotation3d{yAxis, -90_deg}; + auto end = Rotation3d{zAxis, 90_deg}; + + const Eigen::Vector3d intrinsicAxis{1.0, 1.0, 1.0}; + auto expected = Rotation3d{intrinsicAxis, 120_deg}; + + auto result = end.RelativeTo(start); + + EXPECT_EQ(expected, result); +} + TEST(Rotation3dTest, Minus) { const Eigen::Vector3d zAxis{0.0, 0.0, 1.0}; @@ -371,4 +386,32 @@ TEST(Rotation3dTest, Interpolate) { EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.X()}.value()); EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Y()}.value()); EXPECT_DOUBLE_EQ(-175.0, units::degree_t{interpolated.Z()}.value()); + + // t value of 0 should always produce the start + rot1 = Rotation3d{yAxis, -90_deg}; + rot2 = Rotation3d{zAxis, 90_deg}; + interpolated = wpi::Lerp(rot1, rot2, 0.0); + EXPECT_DOUBLE_EQ(rot1.X().value(), interpolated.X().value()); + EXPECT_DOUBLE_EQ(rot1.Y().value(), interpolated.Y().value()); + EXPECT_DOUBLE_EQ(rot1.Z().value(), interpolated.Z().value()); + + // The full rotation from rot1 to rot2 is 120 degrees around extrinsic + // <-1.0, 1.0, 1.0> + const Eigen::Vector3d extrinsicAxis{-1.0, 1.0, 1.0}; + rot1 = Rotation3d{yAxis, -90_deg}; + rot2 = Rotation3d{zAxis, 90_deg}; + EXPECT_EQ(rot2, rot1.RotateBy(Rotation3d{extrinsicAxis, 120_deg})); + interpolated = wpi::Lerp(rot1, rot2, 0.5); + auto expected = rot1.RotateBy(Rotation3d{extrinsicAxis, 60_deg}); + EXPECT_DOUBLE_EQ(expected.X().value(), interpolated.X().value()); + EXPECT_DOUBLE_EQ(expected.Y().value(), interpolated.Y().value()); + EXPECT_DOUBLE_EQ(expected.Z().value(), interpolated.Z().value()); + + // t value of 1 should always produce the end + rot1 = Rotation3d{yAxis, -90_deg}; + rot2 = Rotation3d{zAxis, 90_deg}; + interpolated = wpi::Lerp(rot1, rot2, 1.0); + EXPECT_NEAR(rot2.X().value(), interpolated.X().value(), 1e-9); + EXPECT_NEAR(rot2.Y().value(), interpolated.Y().value(), 1e-9); + EXPECT_NEAR(rot2.Z().value(), interpolated.Z().value(), 1e-9); } diff --git a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometry3dTest.cpp b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometry3dTest.cpp index 76f5f3292c..df7099368f 100644 --- a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometry3dTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometry3dTest.cpp @@ -38,3 +38,18 @@ TEST(DifferentialDriveOdometry3dTest, EncoderDistances) { EXPECT_NEAR(pose.Z().value(), 0.0, kEpsilon); EXPECT_NEAR(pose.Rotation().ToRotation2d().Degrees().value(), 90.0, kEpsilon); } + +TEST(DifferentialDriveOdometry3dTest, GyroOffset) { + DifferentialDriveOdometry3d odometry{ + frc::Rotation3d{0_deg, 5_deg, 0_deg}, 0_m, 0_m, + frc::Pose3d{frc::Translation3d{}, frc::Rotation3d{0_deg, 0_deg, 90_deg}}}; + const auto& pose = + odometry.Update(frc::Rotation3d{0_deg, 10_deg, 0_deg}, 0_m, 0_m); + + EXPECT_NEAR(pose.X().value(), 0.0, kEpsilon); + EXPECT_NEAR(pose.Y().value(), 0.0, kEpsilon); + EXPECT_NEAR(pose.Z().value(), 0.0, kEpsilon); + EXPECT_NEAR(units::degree_t{pose.Rotation().X()}.value(), 0.0, kEpsilon); + EXPECT_NEAR(units::degree_t{pose.Rotation().Y()}.value(), 5.0, kEpsilon); + EXPECT_NEAR(units::degree_t{pose.Rotation().Z()}.value(), 90.0, kEpsilon); +} diff --git a/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometry3dTest.cpp b/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometry3dTest.cpp index b195e8507b..e957ae31c2 100644 --- a/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometry3dTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometry3dTest.cpp @@ -221,3 +221,19 @@ TEST_F(MecanumDriveOdometry3dTest, AccuracyFacingXAxis) { EXPECT_LT(errorSum / (trajectory.TotalTime().value() / dt.value()), 0.06); EXPECT_LT(maxError, 0.125); } + +TEST_F(MecanumDriveOdometry3dTest, GyroOffset) { + frc::MecanumDriveWheelPositions wheelPositions; + odometry.ResetPosition( + frc::Rotation3d{0_deg, 5_deg, 0_deg}, wheelPositions, + frc::Pose3d{frc::Translation3d{}, frc::Rotation3d{0_deg, 0_deg, 90_deg}}); + auto pose = + odometry.Update(frc::Rotation3d{0_deg, 10_deg, 0_deg}, wheelPositions); + + EXPECT_NEAR(pose.X().value(), 0.0, 1e-9); + EXPECT_NEAR(pose.Y().value(), 0.0, 1e-9); + EXPECT_NEAR(pose.Z().value(), 0.0, 1e-9); + EXPECT_NEAR(units::degree_t{pose.Rotation().X()}.value(), 0.0, 1e-9); + EXPECT_NEAR(units::degree_t{pose.Rotation().Y()}.value(), 5.0, 1e-9); + EXPECT_NEAR(units::degree_t{pose.Rotation().Z()}.value(), 90.0, 1e-9); +} diff --git a/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometry3dTest.cpp b/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometry3dTest.cpp index d9fd52a559..01a2cea03a 100644 --- a/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometry3dTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometry3dTest.cpp @@ -222,3 +222,18 @@ TEST_F(SwerveDriveOdometry3dTest, AccuracyFacingXAxis) { EXPECT_LT(errorSum / (trajectory.TotalTime().value() / dt.value()), 0.06); EXPECT_LT(maxError, 0.125); } + +TEST_F(SwerveDriveOdometry3dTest, GyroOffset) { + m_odometry.ResetPosition( + frc::Rotation3d{0_deg, 5_deg, 0_deg}, {zero, zero, zero, zero}, + frc::Pose3d{frc::Translation3d{}, frc::Rotation3d{0_deg, 0_deg, 90_deg}}); + auto pose = m_odometry.Update(frc::Rotation3d{0_deg, 10_deg, 0_deg}, + {zero, zero, zero, zero}); + + EXPECT_NEAR(pose.X().value(), 0.0, 1e-9); + EXPECT_NEAR(pose.Y().value(), 0.0, 1e-9); + EXPECT_NEAR(pose.Z().value(), 0.0, 1e-9); + EXPECT_NEAR(units::degree_t{pose.Rotation().X()}.value(), 0.0, 1e-9); + EXPECT_NEAR(units::degree_t{pose.Rotation().Y()}.value(), 5.0, 1e-9); + EXPECT_NEAR(units::degree_t{pose.Rotation().Z()}.value(), 90.0, 1e-9); +} From 21b5389bbefa08e50803cdf6b206d5440839c818 Mon Sep 17 00:00:00 2001 From: Michael Lesirge <100492377+MichaelLesirge@users.noreply.github.com> Date: Wed, 14 Jan 2026 20:22:07 -0800 Subject: [PATCH 17/27] [wpimath,cmd] Add multi tap boolean stream filter and multi tap trigger modifier (double tap detector) (#8307) Add a simple tap counting filter for boolean streams. The filter activates when the input has risen (transitioned from false to true, like when a button is tapped) the required number of times within the time window after the first rising edge. Once activated, the output remains true as long as the input is true. The tap count resets when the time window expires or when the input goes false after activation. Example usage: ```java xbox.a() .multiPress(2, 0.2) // Detect a double tap within 0.2 seconds .onTrue(Commands.print("Double tapped A button")); xbox.y() .multiPress(2, 0.5) // Detect a double tap within 0.5 seconds .whileTrue(Commands.print("Y held after tap").repeatedly()); ``` This is not a noise reduction and/or input smoothing filter, but it is similar in usage to debounce, so I believe it could be considered a filter, but am open to a better location. I believe this would be a useful addition, as double/triple tapping a button is a common control option in games, yet is not often utilized by newer FRC teams. I believe adding it to WPILib in a standard way will allow more teams to make the most out of their controls. --- .../wpilibj2/command/button/Trigger.java | 28 ++++ .../cpp/frc2/command/button/Trigger.cpp | 9 ++ .../include/frc2/command/button/Trigger.h | 16 +++ .../first/math/filter/EdgeCounterFilter.java | 120 ++++++++++++++++++ .../native/cpp/filter/EdgeCountFilter.cpp | 46 +++++++ .../include/frc/filter/EdgeCountFilter.h | 94 ++++++++++++++ .../math/filter/EdgeCounterFilterTest.java | 82 ++++++++++++ .../native/cpp/filter/EdgeCountFilterTest.cpp | 75 +++++++++++ 8 files changed, 470 insertions(+) create mode 100644 wpimath/src/main/java/edu/wpi/first/math/filter/EdgeCounterFilter.java create mode 100644 wpimath/src/main/native/cpp/filter/EdgeCountFilter.cpp create mode 100644 wpimath/src/main/native/include/frc/filter/EdgeCountFilter.h create mode 100644 wpimath/src/test/java/edu/wpi/first/math/filter/EdgeCounterFilterTest.java create mode 100644 wpimath/src/test/native/cpp/filter/EdgeCountFilterTest.cpp diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java index 65c6145f6b..fc8b3b1bbe 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/button/Trigger.java @@ -7,6 +7,7 @@ package edu.wpi.first.wpilibj2.command.button; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.math.filter.Debouncer; +import edu.wpi.first.math.filter.EdgeCounterFilter; import edu.wpi.first.wpilibj.event.EventLoop; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.CommandScheduler; @@ -287,4 +288,31 @@ public class Trigger implements BooleanSupplier { } }); } + + /** + * Creates a new multi-press trigger from this trigger - it will become active when this trigger + * has been activated the required number of times within the specified time window. + * + *

This is useful for implementing "double-click" style functionality. + * + *

Input for this must be stable, consider using a Debouncer before this to avoid counting + * noise as multiple presses. + * + * @param requiredPresses The number of presses required. + * @param windowTime The number of seconds in which the presses must occur. + * @return The multi-press trigger. + */ + public Trigger multiPress(int requiredPresses, double windowTime) { + return new Trigger( + m_loop, + new BooleanSupplier() { + final EdgeCounterFilter m_edgeCounterFilter = + new EdgeCounterFilter(requiredPresses, windowTime); + + @Override + public boolean getAsBoolean() { + return m_edgeCounterFilter.calculate(m_condition.getAsBoolean()); + } + }); + } } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp index 6afdbb2b2c..6716fe6bc2 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/button/Trigger.cpp @@ -7,6 +7,7 @@ #include #include +#include #include "frc2/command/CommandPtr.h" @@ -184,6 +185,14 @@ Trigger Trigger::Debounce(units::second_t debounceTime, }); } +Trigger Trigger::MultiPress(int requiredPresses, units::second_t windowTime) { + return Trigger(m_loop, + [filter = frc::EdgeCounterFilter(requiredPresses, windowTime), + condition = m_condition]() mutable { + return filter.Calculate(condition()); + }); +} + bool Trigger::Get() const { return m_condition(); } diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h b/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h index 9e86b1b700..c3b3b76c27 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/button/Trigger.h @@ -284,6 +284,22 @@ class Trigger { frc::Debouncer::DebounceType type = frc::Debouncer::DebounceType::kRising); + /** + * Creates a new multi-press trigger from this trigger - it will become active + * when this trigger has been activated the required number of times within + * the specified time window. + * + *

This is useful for implementing "double-click" style functionality. + * + *

Input for this must be stable, consider using a Debouncer before this to + * avoid counting noise as multiple presses. + * + * @param requiredPresses The number of presses required. + * @param windowTime The time in which the presses must occur. + * @return The multi-press trigger. + */ + Trigger MultiPress(int requiredPresses, units::second_t windowTime); + /** * Returns the current state of this trigger. * diff --git a/wpimath/src/main/java/edu/wpi/first/math/filter/EdgeCounterFilter.java b/wpimath/src/main/java/edu/wpi/first/math/filter/EdgeCounterFilter.java new file mode 100644 index 0000000000..7a4d80e296 --- /dev/null +++ b/wpimath/src/main/java/edu/wpi/first/math/filter/EdgeCounterFilter.java @@ -0,0 +1,120 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.math.filter; + +import edu.wpi.first.math.MathSharedStore; + +/** + * A rising edge counter for boolean streams. Requires that the boolean change value to true for a + * specified number of times within a specified time window after the first rising edge before the + * filtered value changes. + * + *

The filter activates when the input has risen (transitioned from false to true) the required + * number of times within the time window. Once activated, the output remains true as long as the + * input is true. The edge count resets when the time window expires or when the input goes false + * after activation. + * + *

Input must be stable; consider using a Debouncer before this filter to avoid counting noise as + * multiple edges. + */ +public class EdgeCounterFilter { + private int m_requiredEdges; + private double m_windowTimeSeconds; + + private double m_firstEdgeTimeSeconds; + private int m_currentCount; + + private boolean m_lastInput; + + /** + * Creates a new EdgeCounterFilter. + * + * @param requiredEdges The number of rising edges required before the output goes true. + * @param windowTime The maximum number of seconds in which all required edges must occur after + * the first rising edge. + */ + public EdgeCounterFilter(int requiredEdges, double windowTime) { + m_requiredEdges = requiredEdges; + m_windowTimeSeconds = windowTime; + + resetTimer(); + } + + private void resetTimer() { + m_firstEdgeTimeSeconds = MathSharedStore.getTimestamp(); + } + + private boolean hasElapsed() { + return MathSharedStore.getTimestamp() - m_firstEdgeTimeSeconds >= m_windowTimeSeconds; + } + + /** + * Applies the edge counter filter to the input stream. + * + * @param input The current value of the input stream. + * @return True if the required number of edges have occurred within the time window and the input + * is currently true; false otherwise. + */ + public boolean calculate(boolean input) { + boolean enoughEdges = m_currentCount >= m_requiredEdges; + + boolean expired = hasElapsed() && !enoughEdges; + boolean activationEnded = !input && enoughEdges; + + if (expired || activationEnded) { + m_currentCount = 0; + } + + if (input && !m_lastInput) { + if (m_currentCount == 0) { + resetTimer(); // Start timer on first rising edge + } + + m_currentCount++; + } + + m_lastInput = input; + + return input && m_currentCount >= m_requiredEdges; + } + + /** + * Sets the time window duration. + * + * @param windowTime The maximum window of seconds in which all required edges must occur after + * the first rising edge. + */ + public void setWindowTime(double windowTime) { + m_windowTimeSeconds = windowTime; + } + + /** + * Gets the time window duration. + * + * @return The maximum window of seconds in which all required edges must occur after the first + * rising edge. + */ + public double getWindowTime() { + return m_windowTimeSeconds; + } + + /** + * Sets the required number of edges. + * + * @param requiredEdges The number of rising edges required before the output goes true. + */ + public void setRequiredEdges(int requiredEdges) { + m_requiredEdges = requiredEdges; + } + + /** + * Gets the required number of edges. + * + * @return The number of rising edges required before the output goes true. + */ + public int getRequiredEdges() { + return m_requiredEdges; + } +} diff --git a/wpimath/src/main/native/cpp/filter/EdgeCountFilter.cpp b/wpimath/src/main/native/cpp/filter/EdgeCountFilter.cpp new file mode 100644 index 0000000000..dfa5e47ff4 --- /dev/null +++ b/wpimath/src/main/native/cpp/filter/EdgeCountFilter.cpp @@ -0,0 +1,46 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "frc/filter/EdgeCountFilter.h" + +#include "wpimath/MathShared.h" + +using namespace frc; + +EdgeCounterFilter::EdgeCounterFilter(int requiredEdges, units::second_t window) + : m_requiredEdges(requiredEdges), m_windowTime(window) { + ResetTimer(); +} + +void EdgeCounterFilter::ResetTimer() { + m_firstEdgeTime = wpi::math::MathSharedStore::GetTimestamp(); +} + +bool EdgeCounterFilter::HasElapsed() const { + return wpi::math::MathSharedStore::GetTimestamp() - m_firstEdgeTime >= + m_windowTime; +} + +bool EdgeCounterFilter::Calculate(bool input) { + bool enoughEdges = m_currentCount >= m_requiredEdges; + + bool expired = HasElapsed() && !enoughEdges; + bool activationEnded = !input && enoughEdges; + + if (expired || activationEnded) { + m_currentCount = 0; + } + + if (input && !m_lastInput) { + if (m_currentCount == 0) { + ResetTimer(); // Start timer on first rising edge + } + + m_currentCount++; + } + + m_lastInput = input; + + return input && m_currentCount >= m_requiredEdges; +} diff --git a/wpimath/src/main/native/include/frc/filter/EdgeCountFilter.h b/wpimath/src/main/native/include/frc/filter/EdgeCountFilter.h new file mode 100644 index 0000000000..3fb682d24c --- /dev/null +++ b/wpimath/src/main/native/include/frc/filter/EdgeCountFilter.h @@ -0,0 +1,94 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include + +#include "units/time.h" + +namespace frc { +/** + * A rising edge counter for boolean streams. Requires that the boolean change + * value to true for a specified number of times within a specified time window + * after the first rising edge before the filtered value changes. + * + * The filter activates when the input has risen (transitioned from false to + * true) the required number of times within the time window. Once activated, + * the output remains true as long as the input is true. The edge count resets + * when the time window expires or when the input goes false after activation. + * + * Input must be stable; consider using a Debouncer before this filter to avoid + * counting noise as multiple edges. + */ +class WPILIB_DLLEXPORT EdgeCounterFilter { + public: + /** + * Creates a new EdgeCounterFilter. + * + * @param requiredEdges The number of rising edges required before the output + * goes true. + * @param windowTime The maximum time window in which all required edges must + * occur after the first rising edge. + */ + explicit EdgeCounterFilter(int requiredEdges, units::second_t windowTime); + + /** + * Applies the edge counter filter to the input stream. + * + * @param input The current value of the input stream. + * @return True if the required number of edges have occurred within the time + * window and the input is currently true; false otherwise. + */ + bool Calculate(bool input); + + /** + * Sets the time window duration. + * + * @param windowTime The maximum time window in which all required edges must + * occur after the first rising edge. + */ + constexpr void SetWindowTime(units::second_t windowTime) { + m_windowTime = windowTime; + } + + /** + * Gets the time window duration. + * + * @return The maximum time window in which all required edges must occur + * after the first rising edge. + */ + constexpr units::second_t GetWindowTime() const { return m_windowTime; } + + /** + * Sets the required number of edges. + * + * @param requiredEdges The number of rising edges required before the output + * goes true. + */ + constexpr void SetRequiredEdges(int requiredEdges) { + m_requiredEdges = requiredEdges; + } + + /** + * Gets the required number of edges. + * + * @return The number of rising edges required before the output goes true. + */ + constexpr int GetRequiredEdges() const { return m_requiredEdges; } + + private: + int m_requiredEdges; + units::second_t m_windowTime; + + units::second_t m_firstEdgeTime; + int m_currentCount = 0; + + bool m_lastInput = false; + + void ResetTimer(); + + bool HasElapsed() const; +}; +} // namespace frc diff --git a/wpimath/src/test/java/edu/wpi/first/math/filter/EdgeCounterFilterTest.java b/wpimath/src/test/java/edu/wpi/first/math/filter/EdgeCounterFilterTest.java new file mode 100644 index 0000000000..9da4c59cd2 --- /dev/null +++ b/wpimath/src/test/java/edu/wpi/first/math/filter/EdgeCounterFilterTest.java @@ -0,0 +1,82 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.math.filter; + +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; + +import edu.wpi.first.util.WPIUtilJNI; +import org.junit.jupiter.api.AfterEach; +import org.junit.jupiter.api.BeforeEach; +import org.junit.jupiter.api.Test; + +class EdgeCounterFilterTest { + @BeforeEach + void setUp() { + WPIUtilJNI.enableMockTime(); + WPIUtilJNI.setMockTime(0L); + } + + @AfterEach + void tearDown() { + WPIUtilJNI.setMockTime(0L); + WPIUtilJNI.disableMockTime(); + } + + @Test + void edgeCounterFilterActivatedTest() { + var filter = new EdgeCounterFilter(2, 0.2); + + assertFalse(filter.calculate(true)); // First edge + + WPIUtilJNI.setMockTime(50_000L); + assertFalse(filter.calculate(false)); // First edge ended + + WPIUtilJNI.setMockTime(100_000L); + assertTrue(filter.calculate(true)); // Second edge + + WPIUtilJNI.setMockTime(150_000L); + assertTrue(filter.calculate(true)); // Still true + + WPIUtilJNI.setMockTime(250_000L); + assertTrue(filter.calculate(true)); // Still true + + WPIUtilJNI.setMockTime(300_000L); + assertFalse(filter.calculate(false)); // Input false, should reset + } + + @Test + void edgeCounterFilterExpiredTest() { + var filter = new EdgeCounterFilter(2, 0.2); + + assertFalse(filter.calculate(true)); // First edge + + WPIUtilJNI.setMockTime(50_000L); + filter.calculate(false); // First edge ended + + WPIUtilJNI.setMockTime(250_000L); + assertFalse(filter.calculate(true)); // Second edge after window expired + + WPIUtilJNI.setMockTime(300_000L); + assertFalse(filter.calculate(true)); // Still false + } + + @Test + void edgeCounterFilterParamsTest() { + var filter = new EdgeCounterFilter(2, 0.2); + + assertEquals(filter.getRequiredEdges(), 2); + assertEquals(filter.getWindowTime(), 0.2); + + filter.setRequiredEdges(3); + + assertEquals(filter.getRequiredEdges(), 3); + + filter.setWindowTime(0.5); + + assertEquals(filter.getWindowTime(), 0.5); + } +} diff --git a/wpimath/src/test/native/cpp/filter/EdgeCountFilterTest.cpp b/wpimath/src/test/native/cpp/filter/EdgeCountFilterTest.cpp new file mode 100644 index 0000000000..a6ae79756c --- /dev/null +++ b/wpimath/src/test/native/cpp/filter/EdgeCountFilterTest.cpp @@ -0,0 +1,75 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include +#include + +#include "frc/filter/EdgeCountFilter.h" +#include "units/time.h" + +static units::second_t now = 0_s; + +class EdgeCounterFilterTest : public ::testing::Test { + protected: + void SetUp() override { + WPI_SetNowImpl([] { return units::microsecond_t{now}.to(); }); + now = 0_ms; + } + + void TearDown() override { + now = 0_ms; + WPI_SetNowImpl(nullptr); + } +}; + +TEST_F(EdgeCounterFilterTest, EdgeCounterFilterActivated) { + frc::EdgeCounterFilter filter{2, 0.2_s}; + + EXPECT_FALSE(filter.Calculate(true)); // First edge + + now = 50_ms; + EXPECT_FALSE(filter.Calculate(false)); // First edge ended + + now = 100_ms; + EXPECT_TRUE(filter.Calculate(true)); // Second edge + + now = 150_ms; + EXPECT_TRUE(filter.Calculate(true)); // Still true + + now = 250_ms; + EXPECT_TRUE(filter.Calculate(true)); // Still true + + now = 300_ms; + EXPECT_FALSE(filter.Calculate(false)); // Input false, should reset +} + +TEST_F(EdgeCounterFilterTest, EdgeCounterFilterExpired) { + frc::EdgeCounterFilter filter{2, 0.2_s}; + + EXPECT_FALSE(filter.Calculate(true)); // First edge + + now = 50_ms; + filter.Calculate(false); // First edge ended + + now = 250_ms; + EXPECT_FALSE(filter.Calculate(true)); // Second edge after window expired + + now = 300_ms; + EXPECT_FALSE(filter.Calculate(true)); // Still false +} + +TEST_F(EdgeCounterFilterTest, EdgeCounterFilterParams) { + frc::EdgeCounterFilter filter{2, 0.2_s}; + + EXPECT_EQ(filter.GetRequiredEdges(), 2); + EXPECT_EQ(filter.GetWindowTime(), 0.2_s); + + filter.SetRequiredEdges(3); + + EXPECT_EQ(filter.GetRequiredEdges(), 3); + + filter.SetWindowTime(0.5_s); + + EXPECT_EQ(filter.GetWindowTime(), 0.5_s); +} From 8be7720a688523d0e7bd3933ad6697ebe3037f63 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Thu, 15 Jan 2026 17:57:38 -0800 Subject: [PATCH 18/27] [sysid] Fix crash on partially empty raw data (#8572) Fixes #8570. --- .../native/cpp/analysis/AnalysisManager.cpp | 27 +++++++++++++++++-- 1 file changed, 25 insertions(+), 2 deletions(-) diff --git a/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp b/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp index ba24cb0d38..c05fc0a17d 100644 --- a/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp +++ b/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp @@ -57,7 +57,8 @@ static double Lerp(units::second_t time, */ static std::vector ConvertToPrepared(const MotorData& data) { std::vector prepared; - // assume we've selected down to a single contiguous run by this point + + // Assume we've selected down to a single contiguous run by this point auto run = data.runs[0]; for (int i = 0; i < static_cast(run.voltage.size()) - 1; ++i) { @@ -101,7 +102,7 @@ static void CopyRawData(wpi::StringMap* dataset) { } /** - * Assigns the combines the various datasets into a single one for analysis. + * Combines the various datasets into a single one for analysis. * * @param slowForward The slow forward dataset * @param slowBackward The slow backward dataset @@ -127,6 +128,28 @@ void AnalysisManager::PrepareGeneralData() { // Convert data to PreparedData structs for (auto& it : m_data.motorData) { auto key = it.first; + + // Assume we've selected down to a single contiguous run by this point + auto run = m_data.motorData[key].runs[0]; + + // Ensure data has at least two samples in it or linear interpolation within + // ConvertToPrepared() will fail + if (run.voltage.size() < 2) { + throw sysid::InvalidDataError(fmt::format( + "{} data has {} voltage samples and at least 2 are required.", key, + run.voltage.size())); + } + if (run.position.size() < 2) { + throw sysid::InvalidDataError(fmt::format( + "{} data has {} position samples and at least 2 are required.", key, + run.position.size())); + } + if (run.velocity.size() < 2) { + throw sysid::InvalidDataError(fmt::format( + "{} data has {} velocity samples and at least 2 are required.", key, + run.velocity.size())); + } + preparedData[key] = ConvertToPrepared(m_data.motorData[key]); WPI_INFO(m_logger, "SAMPLES {}", preparedData[key].size()); } From c89401250fbd412ba050f595551d0a451b7307a2 Mon Sep 17 00:00:00 2001 From: crueter Date: Thu, 15 Jan 2026 21:55:55 -0500 Subject: [PATCH 19/27] [hal, wpilib] Usage Reporting: QFRCDashboard -> QDash (#8571) --- hal/src/generate/Instances.txt | 2 +- .../generated/main/java/edu/wpi/first/hal/FRCNetComm.java | 4 ++-- .../generated/main/native/include/hal/FRCUsageReporting.h | 2 +- hal/src/generated/main/native/include/hal/UsageReporting.h | 2 +- wpilibc/src/main/native/cppcs/RobotBase.cpp | 5 +++-- wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java | 6 +++--- 6 files changed, 11 insertions(+), 10 deletions(-) diff --git a/hal/src/generate/Instances.txt b/hal/src/generate/Instances.txt index 93b09f78e4..3211479de1 100644 --- a/hal/src/generate/Instances.txt +++ b/hal/src/generate/Instances.txt @@ -70,7 +70,7 @@ kDashboard_Shuffleboard = 4 kDashboard_Elastic = 5 kDashboard_LabVIEW = 6 kDashboard_AdvantageScope = 7 -kDashboard_QFRCDashboard = 8 +kDashboard_QDash = 8 kDashboard_FRCWebComponents = 9 kDataLogLocation_Onboard = 1 kDataLogLocation_USB = 2 diff --git a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java b/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java index d2b5ebd93a..8931ffde21 100644 --- a/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java +++ b/hal/src/generated/main/java/edu/wpi/first/hal/FRCNetComm.java @@ -447,8 +447,8 @@ public final class FRCNetComm { public static final int kDashboard_LabVIEW = 6; /** kDashboard_AdvantageScope = 7. */ public static final int kDashboard_AdvantageScope = 7; - /** kDashboard_QFRCDashboard = 8. */ - public static final int kDashboard_QFRCDashboard = 8; + /** kDashboard_QDash = 8. */ + public static final int kDashboard_QDash = 8; /** kDashboard_FRCWebComponents = 9. */ public static final int kDashboard_FRCWebComponents = 9; /** kDataLogLocation_Onboard = 1. */ diff --git a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h b/hal/src/generated/main/native/include/hal/FRCUsageReporting.h index 6d6c2b01b3..06707a4235 100644 --- a/hal/src/generated/main/native/include/hal/FRCUsageReporting.h +++ b/hal/src/generated/main/native/include/hal/FRCUsageReporting.h @@ -262,7 +262,7 @@ namespace HALUsageReporting { kDashboard_Elastic = 5, kDashboard_LabVIEW = 6, kDashboard_AdvantageScope = 7, - kDashboard_QFRCDashboard = 8, + kDashboard_QDash = 8, kDashboard_FRCWebComponents = 9, kDataLogLocation_Onboard = 1, kDataLogLocation_USB = 2, diff --git a/hal/src/generated/main/native/include/hal/UsageReporting.h b/hal/src/generated/main/native/include/hal/UsageReporting.h index 1230e187f6..c9f7a0dcc7 100644 --- a/hal/src/generated/main/native/include/hal/UsageReporting.h +++ b/hal/src/generated/main/native/include/hal/UsageReporting.h @@ -235,7 +235,7 @@ typedef enum kDashboard_Elastic = 5, kDashboard_LabVIEW = 6, kDashboard_AdvantageScope = 7, - kDashboard_QFRCDashboard = 8, + kDashboard_QDash = 8, kDashboard_FRCWebComponents = 9, kDataLogLocation_Onboard = 1, kDataLogLocation_USB = 2, diff --git a/wpilibc/src/main/native/cppcs/RobotBase.cpp b/wpilibc/src/main/native/cppcs/RobotBase.cpp index 69dc19e9b4..fe4cd3f866 100644 --- a/wpilibc/src/main/native/cppcs/RobotBase.cpp +++ b/wpilibc/src/main/native/cppcs/RobotBase.cpp @@ -306,10 +306,11 @@ RobotBase::RobotBase() { HAL_Report(HALUsageReporting::kResourceType_Dashboard, HALUsageReporting::kDashboard_AdvantageScope); m_dashboardDetected = true; - } else if (event.GetConnectionInfo()->remote_id.starts_with( + } else if (event.GetConnectionInfo()->remote_id.starts_with("QDash") || + event.GetConnectionInfo()->remote_id.starts_with( "QFRCDashboard")) { HAL_Report(HALUsageReporting::kResourceType_Dashboard, - HALUsageReporting::kDashboard_QFRCDashboard); + HALUsageReporting::kDashboard_QDash); m_dashboardDetected = true; } else if (event.GetConnectionInfo()->remote_id.starts_with( "FRC Web Components")) { diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java index 02b9c84137..aa927f3e32 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java @@ -211,9 +211,9 @@ public abstract class RobotBase implements AutoCloseable { HAL.report( tResourceType.kResourceType_Dashboard, tInstances.kDashboard_AdvantageScope); m_dashboardDetected = true; - } else if (event.connInfo.remote_id.startsWith("QFRCDashboard")) { - HAL.report( - tResourceType.kResourceType_Dashboard, tInstances.kDashboard_QFRCDashboard); + } else if (event.connInfo.remote_id.startsWith("QDash") + || event.connInfo.remote_id.startsWith("QFRCDashboard")) { + HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_QDash); m_dashboardDetected = true; } else if (event.connInfo.remote_id.startsWith("FRC Web Components")) { HAL.report( From 3d92547d62ff0e65bd3c58816b9df04908e6e1cb Mon Sep 17 00:00:00 2001 From: Vasista Vovveti Date: Thu, 5 Feb 2026 17:56:52 -0800 Subject: [PATCH 20/27] [cscore] Fix format specifier on Mac (#8602) --- cscore/src/main/native/objcpp/UvcControlImpl.mm | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/cscore/src/main/native/objcpp/UvcControlImpl.mm b/cscore/src/main/native/objcpp/UvcControlImpl.mm index 05b7229a78..609b2f7af8 100644 --- a/cscore/src/main/native/objcpp/UvcControlImpl.mm +++ b/cscore/src/main/native/objcpp/UvcControlImpl.mm @@ -484,7 +484,7 @@ const propertyInfo_t propertyInfo[] = UVCERROR("USB control interface not found"); break; default: - UVCERROR("ControlRequest failed (KR=sys:sub:code) = {:02Xh}:{:03Xh}:{:04Xh}", + UVCERROR("ControlRequest failed (KR=sys:sub:code) = {:02X}h:{:03X}h:{:04X}h", sys, sub, code); break; } From 6b225bb1f1c88ab06aa721489a7c90a97f374651 Mon Sep 17 00:00:00 2001 From: FirstFox3 Date: Thu, 5 Feb 2026 20:57:49 -0500 Subject: [PATCH 21/27] [wpilib] Fix typo in TimedRobot.getLoopStartTime() docs (#8590) Fixed a typo in the description of the getLoopStartTime function in both C++ and Java TimedRobot class. --------- Co-authored-by: Tyler Veness --- wpilibc/src/main/native/include/frc/TimedRobot.h | 2 +- wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/wpilibc/src/main/native/include/frc/TimedRobot.h b/wpilibc/src/main/native/include/frc/TimedRobot.h index 9d1e8ca1a1..0015f9ae6b 100644 --- a/wpilibc/src/main/native/include/frc/TimedRobot.h +++ b/wpilibc/src/main/native/include/frc/TimedRobot.h @@ -65,7 +65,7 @@ class TimedRobot : public IterativeRobotBase { ~TimedRobot() override; /** - * Return the system clock time in micrseconds for the start of the current + * Return the system clock time in microseconds for the start of the current * periodic loop. This is in the same time base as Timer.GetFPGATimestamp(), * but is stable through a loop. It is updated at the beginning of every * periodic callback (including the normal periodic loop). diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java index de0fab0f26..6c4024d7c5 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java @@ -181,9 +181,9 @@ public class TimedRobot extends IterativeRobotBase { } /** - * Return the system clock time in micrseconds for the start of the current periodic loop. This is - * in the same time base as Timer.getFPGATimestamp(), but is stable through a loop. It is updated - * at the beginning of every periodic callback (including the normal periodic loop). + * Return the system clock time in microseconds for the start of the current periodic loop. This + * is in the same time base as Timer.getFPGATimestamp(), but is stable through a loop. It is + * updated at the beginning of every periodic callback (including the normal periodic loop). * * @return Robot running time in microseconds, as of the start of the current periodic function. */ From 0a3731746710a6155ce3dbfcde4327262bb01ce2 Mon Sep 17 00:00:00 2001 From: jpokornyiii Date: Sat, 7 Feb 2026 00:36:35 -0500 Subject: [PATCH 22/27] [examples] Adding XRP java and cpp examples for Timed Robot (#8599) Adding an example (one C++ and one Java) for using TimedRobot with the XRP. --- .../main/cpp/examples/Xrptimed/cpp/Robot.cpp | 57 +++++++++++++++ .../cpp/examples/Xrptimed/include/Robot.h | 31 ++++++++ .../src/main/cpp/examples/examples.json | 16 ++++ .../wpi/first/wpilibj/examples/examples.json | 16 ++++ .../first/wpilibj/examples/xrptimed/Main.java | 25 +++++++ .../wpilibj/examples/xrptimed/Robot.java | 73 +++++++++++++++++++ 6 files changed, 218 insertions(+) create mode 100644 wpilibcExamples/src/main/cpp/examples/Xrptimed/cpp/Robot.cpp create mode 100644 wpilibcExamples/src/main/cpp/examples/Xrptimed/include/Robot.h create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrptimed/Main.java create mode 100644 wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrptimed/Robot.java diff --git a/wpilibcExamples/src/main/cpp/examples/Xrptimed/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Xrptimed/cpp/Robot.cpp new file mode 100644 index 0000000000..0001613df4 --- /dev/null +++ b/wpilibcExamples/src/main/cpp/examples/Xrptimed/cpp/Robot.cpp @@ -0,0 +1,57 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "Robot.h" + +Robot::Robot() { + wpi::SendableRegistry::AddChild(&m_drive, &m_leftMotor); + wpi::SendableRegistry::AddChild(&m_drive, &m_rightMotor); + + // We need to invert one side of the drivetrain so that positive voltages + // result in both sides moving forward. Depending on how your robot's + // gearbox is constructed, you might have to invert the left side instead. + m_rightMotor.SetInverted(true); +} + +/** + * This function is called every 20 ms, no matter the mode. Use + * this for items like diagnostics that you want ran during disabled, + * autonomous, teleoperated and test. + * + *

This runs after the mode specific periodic functions, but before + * LiveWindow and SmartDashboard integrated updating. + */ +void Robot::RobotPeriodic() {} + +// This function is only once each time Autonomous is enabled +void Robot::AutonomousInit() { + m_timer.Restart(); +} + +// This function is called periodically during autonomous mode +void Robot::AutonomousPeriodic() { + // Drive for 2 seconds + if (m_timer.Get() < 2_s) { + // Drive forwards half speed, make sure to turn input squaring off + m_drive.ArcadeDrive(0.5, 0.0, false); + } else { + // Stop robot + m_drive.ArcadeDrive(0.0, 0.0, false); + } +} + +// This function is only once each time telop is enabled +void Robot::TeleopInit() {} + +// This function is called periodically during teleop mode +void Robot::TeleopPeriodic() { + m_drive.ArcadeDrive(-m_XboxController.GetLeftY(), + -m_XboxController.GetRightX()); +} + +#ifndef RUNNING_FRC_TESTS +int main() { + return frc::StartRobot(); +} +#endif diff --git a/wpilibcExamples/src/main/cpp/examples/Xrptimed/include/Robot.h b/wpilibcExamples/src/main/cpp/examples/Xrptimed/include/Robot.h new file mode 100644 index 0000000000..4f028475e9 --- /dev/null +++ b/wpilibcExamples/src/main/cpp/examples/Xrptimed/include/Robot.h @@ -0,0 +1,31 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include +#include +#include + +class Robot : public frc::TimedRobot { + public: + Robot(); + void RobotPeriodic() override; + void AutonomousInit() override; + void AutonomousPeriodic() override; + void TeleopInit() override; + void TeleopPeriodic() override; + + private: + frc::XRPMotor m_leftMotor{0}; + frc::XRPMotor m_rightMotor{1}; + frc::XboxController m_XboxController{0}; + frc::Timer m_timer; + + frc::DifferentialDrive m_drive{ + [&](double output) { m_leftMotor.Set(output); }, + [&](double output) { m_rightMotor.Set(output); }}; +}; diff --git a/wpilibcExamples/src/main/cpp/examples/examples.json b/wpilibcExamples/src/main/cpp/examples/examples.json index 8723e307ca..40deb292fb 100644 --- a/wpilibcExamples/src/main/cpp/examples/examples.json +++ b/wpilibcExamples/src/main/cpp/examples/examples.json @@ -609,6 +609,22 @@ "xrp" ] }, + { + "name": "XRP Timed", + "description": "An very basic timed robot program that can be used with the XRP reference robot design.", + "tags": [ + "XRP", + "Differential Drive", + "XboxController" + ], + "foldername": "Xrptimed", + "gradlebase": "cppxrp", + "mainclass": "Main", + "commandversion": 2, + "extravendordeps": [ + "xrp" + ] + }, { "name": "StateSpaceFlywheel", "description": "Control a flywheel using a state-space model (based on values from CAD), with a Kalman Filter and LQR.", diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json index 1abd22855b..255a7cf2e3 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json @@ -812,6 +812,22 @@ "xrp" ] }, + { + "name": "XRP Timed", + "description": "An very basic timed robot program that can be used with the XRP reference robot design.", + "tags": [ + "XRP", + "Differential Drive", + "XboxController" + ], + "foldername": "xrptimed", + "gradlebase": "javaxrp", + "mainclass": "Main", + "commandversion": 2, + "extravendordeps": [ + "xrp" + ] + }, { "name": "Digital Communication Sample", "description": "Communicates with external devices (such as an Arduino) using the roboRIO's DIO.", diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrptimed/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrptimed/Main.java new file mode 100644 index 0000000000..a8f11df99a --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrptimed/Main.java @@ -0,0 +1,25 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.wpilibj.examples.xrptimed; + +import edu.wpi.first.wpilibj.RobotBase; + +/** + * Do NOT add any static variables to this class, or any initialization at all. Unless you know what + * you are doing, do not modify this file except to change the parameter class to the startRobot + * call. + */ +public final class Main { + private Main() {} + + /** + * Main initialization function. Do not perform any initialization here. + * + *

If you change your main robot class, change the parameter type. + */ + public static void main(String... args) { + RobotBase.startRobot(Robot::new); + } +} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrptimed/Robot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrptimed/Robot.java new file mode 100644 index 0000000000..27ea6275f8 --- /dev/null +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/xrptimed/Robot.java @@ -0,0 +1,73 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.wpilibj.examples.xrptimed; + +import edu.wpi.first.util.sendable.SendableRegistry; +import edu.wpi.first.wpilibj.TimedRobot; +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj.drive.DifferentialDrive; +import edu.wpi.first.wpilibj.xrp.XRPMotor; + +/** + * The methods in this class are called automatically corresponding to each mode, as described in + * the TimedRobot documentation. If you change the name of this class or the package after creating + * this project, you must also update the manifest file in the resource directory. + */ +public class Robot extends TimedRobot { + private final XRPMotor m_leftDrive = new XRPMotor(0); + private final XRPMotor m_rightDrive = new XRPMotor(1); + private final DifferentialDrive m_robotDrive = + new DifferentialDrive(m_leftDrive::set, m_rightDrive::set); + private final XboxController m_controller = new XboxController(0); + private final Timer m_timer = new Timer(); + + /** Called once at the beginning of the robot program. */ + public Robot() { + SendableRegistry.addChild(m_robotDrive, m_leftDrive); + SendableRegistry.addChild(m_robotDrive, m_rightDrive); + + // We need to invert one side of the drivetrain so that positive voltages + // result in both sides moving forward. Depending on how your robot's + // gearbox is constructed, you might have to invert the left side instead. + m_rightDrive.setInverted(true); + } + + /** This function is run once each time the robot enters autonomous mode. */ + @Override + public void autonomousInit() { + m_timer.restart(); + } + + /** This function is called periodically during autonomous. */ + @Override + public void autonomousPeriodic() { + // Drive for 2 seconds + if (m_timer.get() < 2.0) { + // Drive forwards half speed, make sure to turn input squaring off + m_robotDrive.arcadeDrive(0.5, 0.0, false); + } else { + m_robotDrive.stopMotor(); // stop robot + } + } + + /** This function is called once each time the robot enters teleoperated mode. */ + @Override + public void teleopInit() {} + + /** This function is called periodically during teleoperated mode. */ + @Override + public void teleopPeriodic() { + m_robotDrive.arcadeDrive(-m_controller.getLeftY(), -m_controller.getRightX()); + } + + /** This function is called once each time the robot enters test mode. */ + @Override + public void testInit() {} + + /** This function is called periodically during test mode. */ + @Override + public void testPeriodic() {} +} From 664484306cc3d76e57cedeaa3bb00968549fdeb6 Mon Sep 17 00:00:00 2001 From: NotTacos <128665709+NotTacos2@users.noreply.github.com> Date: Fri, 6 Feb 2026 22:39:12 -0700 Subject: [PATCH 23/27] [glass] Change match times for rebuilt (#8575) The timer has changed for rebuilt's auto and teleop. --- glass/src/lib/native/cpp/other/FMS.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/glass/src/lib/native/cpp/other/FMS.cpp b/glass/src/lib/native/cpp/other/FMS.cpp index 22de23304b..55e56424f2 100644 --- a/glass/src/lib/native/cpp/other/FMS.cpp +++ b/glass/src/lib/native/cpp/other/FMS.cpp @@ -71,11 +71,11 @@ void glass::DisplayFMS(FMSModel* model, bool editableDsAttached) { } ImGui::SameLine(); if (ImGui::Button("Auto") && !enabled) { - model->SetMatchTime(15.0); + model->SetMatchTime(20.0); } ImGui::SameLine(); if (ImGui::Button("Teleop") && !enabled) { - model->SetMatchTime(135.0); + model->SetMatchTime(140.0); } } From 7cd3790c7c0209d2242913e7f1c7306201984b07 Mon Sep 17 00:00:00 2001 From: Gavin P <62412298+gavinskycastle@users.noreply.github.com> Date: Fri, 6 Feb 2026 21:47:08 -0800 Subject: [PATCH 24/27] [wpiunits] Make RPM an alias of RotationsPerMinute (#8595) Currently the only name for this unit is `RPM`. This caused a bit of confusion for a couple of my team members when we failed to find an RPM unit, assuming it would be named `RotationsPerMinute` as is the standard for almost all other units, such as `RotationsPerSecond`. No corresponding changes have been made to wpilibc as it seems to already work this way, with `rpm` being the abbreviation for `revolutions_per_minute`. --- wpiunits/src/main/java/edu/wpi/first/units/Units.java | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/wpiunits/src/main/java/edu/wpi/first/units/Units.java b/wpiunits/src/main/java/edu/wpi/first/units/Units.java index 04b1c5f990..67cef3bbe9 100644 --- a/wpiunits/src/main/java/edu/wpi/first/units/Units.java +++ b/wpiunits/src/main/java/edu/wpi/first/units/Units.java @@ -166,7 +166,13 @@ public final class Units { * A unit of angular velocity equivalent to spinning at a rate of one {@link #Rotations Rotation} * per {@link #Minute}. Motor spec sheets often list maximum speeds in terms of RPM. */ - public static final AngularVelocityUnit RPM = Rotations.per(Minute); + public static final AngularVelocityUnit RotationsPerMinute = Rotations.per(Minute); + + /** + * A unit of angular velocity equivalent to spinning at a rate of one {@link #Rotations Rotation} + * per {@link #Minute}. Motor spec sheets often list maximum speeds in terms of RPM. + */ + public static final AngularVelocityUnit RPM = RotationsPerMinute; // alias /** * The standard SI unit of angular velocity, equivalent to spinning at a rate of one {@link From 2c5529d714775c19fe5a21876cefc4fbaff305f7 Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Fri, 6 Feb 2026 21:47:49 -0800 Subject: [PATCH 25/27] [wpimath] Speed up pose estimator correction computation (#8574) In C++, we use a diagonal matrix to avoid an expensive matrix multiplication. EJML doesn't have a diagonal matrix type, so in Java, we use a double array and implement the multiplication manually. --- .../first/math/estimator/PoseEstimator.java | 42 ++++++------- .../first/math/estimator/PoseEstimator3d.java | 60 ++++++++----------- .../include/frc/estimator/PoseEstimator.h | 18 ++++-- .../include/frc/estimator/PoseEstimator3d.h | 30 ++++++---- 4 files changed, 74 insertions(+), 76 deletions(-) diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java index 4c31748329..4cae330248 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator.java @@ -8,8 +8,6 @@ import edu.wpi.first.math.MathSharedStore; import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.Matrix; -import edu.wpi.first.math.Nat; -import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Rotation2d; import edu.wpi.first.math.geometry.Transform2d; @@ -40,8 +38,12 @@ import java.util.TreeMap; */ public class PoseEstimator { private final Odometry m_odometry; - private final Matrix m_q = new Matrix<>(Nat.N3(), Nat.N1()); - private final Matrix m_visionK = new Matrix<>(Nat.N3(), Nat.N3()); + + // Diagonal of process noise covariance matrix Q + private final double[] m_q = new double[] {0.0, 0.0, 0.0}; + + // Diagonal of Kalman gain matrix K + private final double[] m_vision_k = new double[] {0.0, 0.0, 0.0}; private static final double kBufferDuration = 1.5; // Maps timestamps to odometry-only pose estimates @@ -79,7 +81,7 @@ public class PoseEstimator { m_poseEstimate = m_odometry.getPoseMeters(); for (int i = 0; i < 3; ++i) { - m_q.set(i, 0, stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0)); + m_q[i] = stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0); } setVisionMeasurementStdDevs(visionMeasurementStdDevs); MathSharedStore.getMathShared().reportUsage(MathUsageId.kEstimator_PoseEstimator, 1); @@ -95,6 +97,7 @@ public class PoseEstimator { * theta]ᵀ, with units in meters and radians. */ public final void setVisionMeasurementStdDevs(Matrix visionMeasurementStdDevs) { + // Diagonal of measurement noise covariance matrix R var r = new double[3]; for (int i = 0; i < 3; ++i) { r[i] = visionMeasurementStdDevs.get(i, 0) * visionMeasurementStdDevs.get(i, 0); @@ -103,11 +106,10 @@ public class PoseEstimator { // Solve for closed form Kalman gain for continuous Kalman filter with A = 0 // and C = I. See wpimath/algorithms.md. for (int row = 0; row < 3; ++row) { - if (m_q.get(row, 0) == 0.0) { - m_visionK.set(row, row, 0.0); + if (m_q[row] == 0.0) { + m_vision_k[row] = 0.0; } else { - m_visionK.set( - row, row, m_q.get(row, 0) / (m_q.get(row, 0) + Math.sqrt(m_q.get(row, 0) * r[row]))); + m_vision_k[row] = m_q[row] / (m_q[row] + Math.sqrt(m_q[row] * r[row])); } } } @@ -307,29 +309,23 @@ public class PoseEstimator { var transform = visionRobotPoseMeters.minus(visionSample.get()); // Step 5: We should not trust the transform entirely, so instead we scale this transform by a - // Kalman - // gain matrix representing how much we trust vision measurements compared to our current pose. - var k_times_transform = - m_visionK.times( - VecBuilder.fill( - transform.getX(), transform.getY(), transform.getRotation().getRadians())); - - // Step 6: Convert back to Transform2d. + // Kalman gain matrix representing how much we trust vision measurements compared to our current + // pose. Then, we convert the result back to a Transform2d. var scaledTransform = new Transform2d( - k_times_transform.get(0, 0), - k_times_transform.get(1, 0), - Rotation2d.fromRadians(k_times_transform.get(2, 0))); + m_vision_k[0] * transform.getX(), + m_vision_k[1] * transform.getY(), + Rotation2d.fromRadians(m_vision_k[2] * transform.getRotation().getRadians())); - // Step 7: Calculate and record the vision update. + // Step 6: Calculate and record the vision update. var visionUpdate = new VisionUpdate(visionSample.get().plus(scaledTransform), odometrySample.get()); m_visionUpdates.put(timestampSeconds, visionUpdate); - // Step 8: Remove later vision measurements. (Matches previous behavior) + // Step 7: Remove later vision measurements. (Matches previous behavior) m_visionUpdates.tailMap(timestampSeconds, false).entrySet().clear(); - // Step 9: Update latest pose estimate. Since we cleared all updates after this vision update, + // Step 8: Update latest pose estimate. Since we cleared all updates after this vision update, // it's guaranteed to be the latest vision update. m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters()); } diff --git a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java index ad0d1404b8..99feba9632 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java +++ b/wpimath/src/main/java/edu/wpi/first/math/estimator/PoseEstimator3d.java @@ -8,8 +8,6 @@ import edu.wpi.first.math.MathSharedStore; import edu.wpi.first.math.MathUsageId; import edu.wpi.first.math.MathUtil; import edu.wpi.first.math.Matrix; -import edu.wpi.first.math.Nat; -import edu.wpi.first.math.VecBuilder; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.geometry.Pose3d; import edu.wpi.first.math.geometry.Rotation2d; @@ -22,7 +20,6 @@ import edu.wpi.first.math.kinematics.Kinematics; import edu.wpi.first.math.kinematics.Odometry3d; import edu.wpi.first.math.numbers.N1; import edu.wpi.first.math.numbers.N4; -import edu.wpi.first.math.numbers.N6; import java.util.NavigableMap; import java.util.Optional; import java.util.TreeMap; @@ -48,8 +45,12 @@ import java.util.TreeMap; */ public class PoseEstimator3d { private final Odometry3d m_odometry; - private final Matrix m_q = new Matrix<>(Nat.N4(), Nat.N1()); - private final Matrix m_visionK = new Matrix<>(Nat.N6(), Nat.N6()); + + // Diagonal of process noise covariance matrix Q + private final double[] m_q = new double[] {0.0, 0.0, 0.0, 0.0}; + + // Diagonal of Kalman gain matrix K + private final double[] m_vision_k = new double[] {0.0, 0.0, 0.0, 0.0, 0.0, 0.0}; private static final double kBufferDuration = 1.5; // Maps timestamps to odometry-only pose estimates @@ -87,7 +88,7 @@ public class PoseEstimator3d { m_poseEstimate = m_odometry.getPoseMeters(); for (int i = 0; i < 4; ++i) { - m_q.set(i, 0, stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0)); + m_q[i] = stateStdDevs.get(i, 0) * stateStdDevs.get(i, 0); } setVisionMeasurementStdDevs(visionMeasurementStdDevs); MathSharedStore.getMathShared().reportUsage(MathUsageId.kEstimator_PoseEstimator3d, 1); @@ -103,6 +104,7 @@ public class PoseEstimator3d { * theta]ᵀ, with units in meters and radians. */ public final void setVisionMeasurementStdDevs(Matrix visionMeasurementStdDevs) { + // Diagonal of measurement covariance matrix R var r = new double[4]; for (int i = 0; i < 4; ++i) { r[i] = visionMeasurementStdDevs.get(i, 0) * visionMeasurementStdDevs.get(i, 0); @@ -111,17 +113,16 @@ public class PoseEstimator3d { // Solve for closed form Kalman gain for continuous Kalman filter with A = 0 // and C = I. See wpimath/algorithms.md. for (int row = 0; row < 4; ++row) { - if (m_q.get(row, 0) == 0.0) { - m_visionK.set(row, row, 0.0); + if (m_q[row] == 0.0) { + m_vision_k[row] = 0.0; } else { - m_visionK.set( - row, row, m_q.get(row, 0) / (m_q.get(row, 0) + Math.sqrt(m_q.get(row, 0) * r[row]))); + m_vision_k[row] = m_q[row] / (m_q[row] + Math.sqrt(m_q[row] * r[row])); } } // Fill in the gains for the other components of the rotation vector - double angle_gain = m_visionK.get(3, 3); - m_visionK.set(4, 4, angle_gain); - m_visionK.set(5, 5, angle_gain); + double angle_gain = m_vision_k[3]; + m_vision_k[4] = angle_gain; + m_vision_k[5] = angle_gain; } /** @@ -320,38 +321,27 @@ public class PoseEstimator3d { var transform = visionRobotPoseMeters.minus(visionSample.get()); // Step 5: We should not trust the transform entirely, so instead we scale this transform by a - // Kalman - // gain matrix representing how much we trust vision measurements compared to our current pose. - var k_times_transform = - m_visionK.times( - VecBuilder.fill( - transform.getX(), - transform.getY(), - transform.getZ(), - transform.getRotation().getX(), - transform.getRotation().getY(), - transform.getRotation().getZ())); - - // Step 6: Convert back to Transform3d. + // Kalman gain matrix representing how much we trust vision measurements compared to our current + // pose. Then we convert the result back to a Transform3d. var scaledTransform = new Transform3d( - k_times_transform.get(0, 0), - k_times_transform.get(1, 0), - k_times_transform.get(2, 0), + m_vision_k[0] * transform.getX(), + m_vision_k[1] * transform.getY(), + m_vision_k[2] * transform.getZ(), new Rotation3d( - k_times_transform.get(3, 0), - k_times_transform.get(4, 0), - k_times_transform.get(5, 0))); + m_vision_k[3] * transform.getRotation().getX(), + m_vision_k[4] * transform.getRotation().getY(), + m_vision_k[5] * transform.getRotation().getZ())); - // Step 7: Calculate and record the vision update. + // Step 6: Calculate and record the vision update. var visionUpdate = new VisionUpdate(visionSample.get().plus(scaledTransform), odometrySample.get()); m_visionUpdates.put(timestampSeconds, visionUpdate); - // Step 8: Remove later vision measurements. (Matches previous behavior) + // Step 7: Remove later vision measurements. (Matches previous behavior) m_visionUpdates.tailMap(timestampSeconds, false).entrySet().clear(); - // Step 9: Update latest pose estimate. Since we cleared all updates after this vision update, + // Step 8: Update latest pose estimate. Since we cleared all updates after this vision update, // it's guaranteed to be the latest vision update. m_poseEstimate = visionUpdate.compensate(m_odometry.getPoseMeters()); } diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h index 9187889ff6..850ea1707f 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator.h @@ -86,6 +86,7 @@ class WPILIB_DLLEXPORT PoseEstimator { */ void SetVisionMeasurementStdDevs( const wpi::array& visionMeasurementStdDevs) { + // Diagonal of measurement covariance matrix R wpi::array r{wpi::empty_array}; for (size_t i = 0; i < 3; ++i) { r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i]; @@ -95,9 +96,9 @@ class WPILIB_DLLEXPORT PoseEstimator { // and C = I. See wpimath/algorithms.md. for (size_t row = 0; row < 3; ++row) { if (m_q[row] == 0.0) { - m_visionK(row, row) = 0.0; + m_vision_K.diagonal()[row] = 0.0; } else { - m_visionK(row, row) = + m_vision_K.diagonal()[row] = m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row])); } } @@ -318,9 +319,9 @@ class WPILIB_DLLEXPORT PoseEstimator { // this transform by a Kalman gain matrix representing how much we trust // vision measurements compared to our current pose. Eigen::Vector3d k_times_transform = - m_visionK * Eigen::Vector3d{transform.X().value(), - transform.Y().value(), - transform.Rotation().Radians().value()}; + m_vision_K * Eigen::Vector3d{transform.X().value(), + transform.Y().value(), + transform.Rotation().Radians().value()}; // Step 6: Convert back to Transform2d. Transform2d scaledTransform{ @@ -475,8 +476,13 @@ class WPILIB_DLLEXPORT PoseEstimator { static constexpr units::second_t kBufferDuration = 1.5_s; Odometry& m_odometry; + + // Diagonal of process noise covariance matrix Q wpi::array m_q{wpi::empty_array}; - Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero(); + + // Kalman gain matrix K + Eigen::DiagonalMatrix m_vision_K = + Eigen::DiagonalMatrix::Zero(); // Maps timestamps to odometry-only pose estimates TimeInterpolatableBuffer m_odometryPoseBuffer{kBufferDuration}; diff --git a/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h b/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h index 490a6cbcb2..6699e98d76 100644 --- a/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h +++ b/wpimath/src/main/native/include/frc/estimator/PoseEstimator3d.h @@ -92,6 +92,7 @@ class WPILIB_DLLEXPORT PoseEstimator3d { */ void SetVisionMeasurementStdDevs( const wpi::array& visionMeasurementStdDevs) { + // Diagonal of measurement noise covariance matrix R wpi::array r{wpi::empty_array}; for (size_t i = 0; i < 4; ++i) { r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i]; @@ -101,15 +102,15 @@ class WPILIB_DLLEXPORT PoseEstimator3d { // and C = I. See wpimath/algorithms.md. for (size_t row = 0; row < 4; ++row) { if (m_q[row] == 0.0) { - m_visionK(row, row) = 0.0; + m_vision_K.diagonal()[row] = 0.0; } else { - m_visionK(row, row) = + m_vision_K.diagonal()[row] = m_q[row] / (m_q[row] + std::sqrt(m_q[row] * r[row])); } } - double angle_gain = m_visionK(3, 3); - m_visionK(4, 4) = angle_gain; - m_visionK(5, 5) = angle_gain; + double angle_gain = m_vision_K.diagonal()[3]; + m_vision_K.diagonal()[4] = angle_gain; + m_vision_K.diagonal()[5] = angle_gain; } /** @@ -327,12 +328,12 @@ class WPILIB_DLLEXPORT PoseEstimator3d { // this transform by a Kalman gain matrix representing how much we trust // vision measurements compared to our current pose. frc::Vectord<6> k_times_transform = - m_visionK * frc::Vectord<6>{transform.X().value(), - transform.Y().value(), - transform.Z().value(), - transform.Rotation().X().value(), - transform.Rotation().Y().value(), - transform.Rotation().Z().value()}; + m_vision_K * frc::Vectord<6>{transform.X().value(), + transform.Y().value(), + transform.Z().value(), + transform.Rotation().X().value(), + transform.Rotation().Y().value(), + transform.Rotation().Z().value()}; // Step 6: Convert back to Transform3d. Transform3d scaledTransform{ @@ -490,8 +491,13 @@ class WPILIB_DLLEXPORT PoseEstimator3d { static constexpr units::second_t kBufferDuration = 1.5_s; Odometry3d& m_odometry; + + // Diagonal of process noise covariance matrix Q wpi::array m_q{wpi::empty_array}; - frc::Matrixd<6, 6> m_visionK = frc::Matrixd<6, 6>::Zero(); + + // Kalman gain matrix K + Eigen::DiagonalMatrix m_vision_K = + Eigen::DiagonalMatrix::Zero(); // Maps timestamps to odometry-only pose estimates TimeInterpolatableBuffer m_odometryPoseBuffer{kBufferDuration}; From 7ac061239703b8573beeb0bf43f9403cf5d5f228 Mon Sep 17 00:00:00 2001 From: sciencewhiz Date: Mon, 9 Feb 2026 17:14:42 -0800 Subject: [PATCH 26/27] [hal,wpilib] Update MatchTime docs for teleop and auto mode (NFC) (#8606) Update Timer and JNI MatchTime functions to latest docs --- .../edu/wpi/first/hal/DriverStationJNI.java | 17 ++++++++------ .../main/native/include/hal/DriverStation.h | 3 +-- .../main/native/include/frc/DriverStation.h | 3 +-- wpilibc/src/main/native/include/frc/Timer.h | 22 +++++++++++-------- .../edu/wpi/first/wpilibj/DriverStation.java | 3 +-- .../java/edu/wpi/first/wpilibj/Timer.java | 12 ++++++++-- 6 files changed, 36 insertions(+), 24 deletions(-) diff --git a/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java b/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java index 580dcd1d32..b5a3fcd56f 100644 --- a/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java +++ b/hal/src/main/java/edu/wpi/first/hal/DriverStationJNI.java @@ -308,16 +308,19 @@ public class DriverStationJNI extends JNIWrapper { public static native int getJoystickAxisType(byte joystickNum, byte axis); /** - * Returns the approximate match time. + * Return the approximate match time. The FMS does not send an official match time to the robots, + * but does send an approximate match time. The value will count down the time remaining in the + * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to + * dispute ref calls or guarantee that a function will trigger before the match ends). * - *

The FMS does not send an official match time to the robots, but does send an approximate - * match time. The value will count down the time remaining in the current period (auto or - * teleop). + *

When connected to the real field, this number only changes in full integer increments, and + * always counts down. * - *

Warning: This is not an official time (so it cannot be used to dispute ref calls or - * guarantee that a function will trigger before the match ends). + *

When the DS is in practice mode, this number is a floating point number, and counts down. * - *

The Practice Match function of the DS approximates the behavior seen on the field. + *

When the DS is in teleop or autonomous mode, this number returns -1.0. + * + *

Simulation matches DS behavior without an FMS connected. * * @return time remaining in current match period (auto or teleop) * @see "HAL_GetMatchTime" diff --git a/hal/src/main/native/include/hal/DriverStation.h b/hal/src/main/native/include/hal/DriverStation.h index 59270afae1..4fe5dcdcda 100644 --- a/hal/src/main/native/include/hal/DriverStation.h +++ b/hal/src/main/native/include/hal/DriverStation.h @@ -187,8 +187,7 @@ int32_t HAL_SetJoystickOutputs(int32_t joystickNum, int64_t outputs, *

When the DS is in practice mode, this number is a floating point number, * and counts down. * - *

When the DS is in teleop or autonomous mode, this number is a floating - * point number, and counts up. + *

When the DS is in teleop or autonomous mode, this number returns -1.0. * *

Simulation matches DS behavior without an FMS connected. * diff --git a/wpilibc/src/main/native/include/frc/DriverStation.h b/wpilibc/src/main/native/include/frc/DriverStation.h index b9b683f11b..97c4885270 100644 --- a/wpilibc/src/main/native/include/frc/DriverStation.h +++ b/wpilibc/src/main/native/include/frc/DriverStation.h @@ -339,8 +339,7 @@ class DriverStation final { *

When the DS is in practice mode, this number is a floating point number, * and counts down. * - *

When the DS is in teleop or autonomous mode, this number is a floating - * point number, and counts up. + *

When the DS is in teleop or autonomous mode, this number returns -1.0. * *

Simulation matches DS behavior without an FMS connected. * diff --git a/wpilibc/src/main/native/include/frc/Timer.h b/wpilibc/src/main/native/include/frc/Timer.h index b3bbfd3539..f058b4a578 100644 --- a/wpilibc/src/main/native/include/frc/Timer.h +++ b/wpilibc/src/main/native/include/frc/Timer.h @@ -139,19 +139,23 @@ class Timer { static units::second_t GetFPGATimestamp(); /** - * Return the approximate match time. - * - * The FMS does not send an official match time to the robots, but does send - * an approximate match time. The value will count down the time remaining in - * the current period (auto or teleop). - * + * Return the approximate match time. The FMS does not send an official match + * time to the robots, but does send an approximate match time. The value will + * count down the time remaining in the current period (auto or teleop). * Warning: This is not an official time (so it cannot be used to dispute ref * calls or guarantee that a function will trigger before the match ends). * - * The Practice Match function of the DS approximates the behavior seen on the - * field. + *

When connected to the real field, this number only changes in full + * integer increments, and always counts down. * - * @return Time remaining in current match period (auto or teleop) + *

When the DS is in practice mode, this number is a floating point number, + * and counts down. + * + *

When the DS is in teleop or autonomous mode, this number returns -1.0. + * + *

Simulation matches DS behavior without an FMS connected. + * + * @return Time remaining in current match period (auto or teleop) in seconds */ static units::second_t GetMatchTime(); diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java index befa01636c..607713abfe 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java @@ -1182,8 +1182,7 @@ public final class DriverStation { * *

When the DS is in practice mode, this number is a floating point number, and counts down. * - *

When the DS is in teleop or autonomous mode, this number is a floating point number, and - * counts up. + *

When the DS is in teleop or autonomous mode, this number returns -1.0. * *

Simulation matches DS behavior without an FMS connected. * diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java index af55a43208..8f26a7a42b 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java @@ -40,8 +40,16 @@ public class Timer { * Return the approximate match time. The FMS does not send an official match time to the robots, * but does send an approximate match time. The value will count down the time remaining in the * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to - * dispute ref calls or guarantee that a function will trigger before the match ends) The Practice - * Match function of the DS approximates the behavior seen on the field. + * dispute ref calls or guarantee that a function will trigger before the match ends). + * + *

When connected to the real field, this number only changes in full integer increments, and + * always counts down. + * + *

When the DS is in practice mode, this number is a floating point number, and counts down. + * + *

When the DS is in teleop or autonomous mode, this number returns -1.0. + * + *

Simulation matches DS behavior without an FMS connected. * * @return Time remaining in current match period (auto or teleop) in seconds */ From 77dfad97c66fd4922fb19fd7f805c96357ea13cb Mon Sep 17 00:00:00 2001 From: sciencewhiz Date: Sat, 14 Feb 2026 11:32:57 -0800 Subject: [PATCH 27/27] [ci] Use wpilib docker-run-action fork (#8615) --- .github/workflows/gradle.yml | 2 +- .github/workflows/sentinel-build.yml | 2 +- .github/workflows/tools.yml | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.github/workflows/gradle.yml b/.github/workflows/gradle.yml index 32e6d3491b..bfae785ff2 100644 --- a/.github/workflows/gradle.yml +++ b/.github/workflows/gradle.yml @@ -52,7 +52,7 @@ jobs: run: echo "EXTRA_GRADLE_ARGS=-PreleaseMode" >> $GITHUB_ENV if: startsWith(github.ref, 'refs/tags/v') && !contains(github.ref, '2027') - name: Build with Gradle - uses: addnab/docker-run-action@3e77f186b7a929ef010f183a9e24c0f9955ea609 + uses: wpilibsuite/docker-run-action@v4 with: image: ${{ matrix.container }} options: -v ${{ github.workspace }}:/work -w /work -e ARTIFACTORY_PUBLISH_USERNAME -e ARTIFACTORY_PUBLISH_PASSWORD -e GITHUB_REF -e CI diff --git a/.github/workflows/sentinel-build.yml b/.github/workflows/sentinel-build.yml index 43d44191c3..3b84bb439a 100644 --- a/.github/workflows/sentinel-build.yml +++ b/.github/workflows/sentinel-build.yml @@ -53,7 +53,7 @@ jobs: with: fetch-depth: 0 - name: Build with Gradle - uses: addnab/docker-run-action@3e77f186b7a929ef010f183a9e24c0f9955ea609 + uses: wpilibsuite/docker-run-action@v4 with: image: ${{ matrix.container }} options: -v ${{ github.workspace }}:/work -w /work -e GITHUB_REF -e CI diff --git a/.github/workflows/tools.yml b/.github/workflows/tools.yml index 58e9ad449e..0c4d44fd07 100644 --- a/.github/workflows/tools.yml +++ b/.github/workflows/tools.yml @@ -31,11 +31,11 @@ jobs: fetch-depth: 0 - uses: gradle/actions/wrapper-validation@v4 - name: Build WPILib with Gradle - uses: addnab/docker-run-action@v3 + uses: wpilibsuite/docker-run-action@v4 with: image: wpilib/roborio-cross-ubuntu:2025-22.04 options: -v ${{ github.workspace }}:/work -w /work -e GITHUB_REF -e CI -e DISPLAY - run: df . && rm -f semicolon_delimited_script && ./gradlew :wpilibc:publish :wpilibj:publish :wpilibNewCommands:publish :hal:publish :cameraserver:publish :ntcore:publish :cscore:publish :wpimath:publish :wpinet:publish :wpiutil:publish :apriltag:publish :wpiunits:publish :simulation:halsim_gui:publish :simulation:halsim_ds_socket:publish :simulation:halsim_ws_server:publish :simulation:halsim_ws_client:publish :simulation:halsim_xrp:publish :fieldImages:publish :romiVendordep:publish :xrpVendordep:publish :epilogue-processor:publish :epilogue-runtime:publish :thirdparty:googletest:publish -x test -x Javadoc -x doxygen --build-cache && cp -r /root/releases/maven/development /work + run: df . && ./gradlew :wpilibc:publish :wpilibj:publish :wpilibNewCommands:publish :hal:publish :cameraserver:publish :ntcore:publish :cscore:publish :wpimath:publish :wpinet:publish :wpiutil:publish :apriltag:publish :wpiunits:publish :simulation:halsim_gui:publish :simulation:halsim_ds_socket:publish :simulation:halsim_ws_server:publish :simulation:halsim_ws_client:publish :simulation:halsim_xrp:publish :fieldImages:publish :romiVendordep:publish :xrpVendordep:publish :epilogue-processor:publish :epilogue-runtime:publish :thirdparty:googletest:publish -x test -x Javadoc -x doxygen --build-cache && cp -r /root/releases/maven/development /work - uses: actions/upload-artifact@v4 with: name: MavenArtifacts

h*Tz z4~HkJWA^*oB>I+j2WAt~_`mHHha{Mcbjz-C`k}+%-n-Yc_}4DnV1pk}fVg(?@bK{Y z?OCtumG^K+{AZO~)lX zW>rQszp^$bEeaK=umO)ak!3la5_t3?d%DrPQp+AQk%(Zz$5EEu)}#AB7H-iKL@M31 zl1>De1L-{FfUXyO%I+>Mq&0NQ0T#1u5WkDdbI$vneZABB+o|09n@yzGS_9Ji4wX&R z?!M>c?BsDrvb*=C(a*cZ$d_JcxB{a0kuOD0G$uS(_SyxhzbGuPPV!Q5)`*}7$e~jH zu|E8zLiI%If2;jE9 zu#YxvX9_qsc3Lf!{q0K1=`(@T!&j+gAY}r-be0)IXh}<*)9Nnq zoP!q}HW`qf1?{p|$VKBUEhC~R?C?zsh3i$qiEZi&&iiTxgZ@N^O@6ySA9L2_`U^nj zJCSp)h+oIP#1P|x6cRE-a$o(;!PdaNU8b$k8(izHuiULa0C8g!?0UkG)e7&gu$`^@ zl=8tKk?TwH^y{0^on>9u*PL9Y?I@|_3e&!>J}nUm7#d!pL3e^)AqMNeqjBcB7I0q!xLOxpDP;Lt)5R*1tBD9X@W&8P1Yqd{g(tw? zXe5w)X)Dwk%!LlaUk(SE41|)0GI%m*11e1I$dHN2Jb|0u>mSg=VB8W(8kOj|sk(^5w(=1SwqriAMzI;qXE- zz z#yO)s?TWvo?t1vGYEw>xH{Dxg*!|ZtWR<{?KURdNzQ>4p4e+cai8K8Yqk^&9^766! z$$rbh`4xH#$fTD+^hQspMGPxf;90!>cu*U zj&Ofz2n$Q-xzWCEfZwAM1`J;d2ochK4&T8rN-kqcsnf7~Ivo;WG~;Y|XkLPZ?A2ei zPstd@xEcP5`)pKunp9GWmQ(0&SbJX_npjlXV8GDS&OE5)M!yWqHo}`Lc&4mJ-zQTHlI| znX??G;L!55Nj?T9lxo?#dY7D-;r%H($c@Y|&21n9aY5CBZ~McWeNfCY<*P4Fwz|C* za=d{qBIi-4vovFfomT@`t&c|lpUofI0|B{{`vG1kye_{Ce8nwz#wShal_HE8iuaZd z-`CY}`#UqL=W4#e_LSc4e-w0EExX~5!V0=39CyU(zzH1-f$Az#9> zWTJ7Zzs_b9wcA&FHFKg(HM|S68#Ogo;jX1QQ#M`Q9Zxya+2-kYlYQge(mq?gzq(lo zRG+o8noznO+M~g+J$^Zi0r^x{SzH{xbJlMI>1d{XBJ9!k^Y?<=O#OUGz?yVv7JFd7 zc2a#n%7i||Rc~4iU7i8F0wGrQx@u+HcX0x)WH985jQ~Kd65#W+&&E_V$kd5Ah@!4L z2;x#B3K?7tL#tw9V^6;t?3pPouB@!C9{wfA(!JDiw5IJIgAY6UJ#CLoq%hw)s2RFH z6r@)37kpgFAYy1!TU^70a7is@QDB8vcN^=9o-W3@yy#PyM(OeeHHYWqWtl?qMV|km z-L0pGr(b;g)bjNlYa&xBbb~AlYabe7M52-aT^kE)*D;Oom)_x@c;D^|3o|T8@SNP; zX<8lUQQ*0Do%;T>l9^rjSg{}$1^&83(eTd^F&P5rk*=w%{NA1#e|Tu;9zMp)>5>tf zcno~PpY{)46CcK{Q4Z^-3yICCVnIyeS0Dz141}1$P(V0d+hS7|LRmbCA&f}` zxB2#uASMUy>Pv(@&xTwb0??SUSpA-b>)mYhOz2G9W;OjLyfrE&GW7=9FE4gR_@6S< zYJYeJdkuRC&Rt#aCq!CpmoWYfX1&q69xWh;a2SC~I>~`8K;tN1pwZ(!#hs$*YmmS^ zj25%~1CMod6i4|3Dnn-Vb!>5{9QheFISE658m?r>AoQ7!gq@!Cr*VQ&vsVr!xeO`A z48A6YJ*vELeWB3n&py(>PUfAdCp#^Jxiwt=H-$- zk0(eZ(qz?DT~1lKA%E#~w>VJJU}=@C`mCuDz=gNZ-BO+#8@apJh2CEM6q>jFpcDb2 za`HvVcZa=jVlne2YUH%>U0oly;sfva<0_B_l%UPb#H!AunQWl^-QPJzlzdba{U9=-$ zB2<&a=Ji!EPs`Rd>|iudCLoik65{{A3|c~waTCxJptTJ!flQ@ZyL@`mn#hn4KNCSI zP|=q2>x!K%&#(B?#*-WI2aNgbY`tk;Qf_W;Ap%CE4;Y}q$Zl_%*!OjD8-nShJnKj( z=4cwH{BLNt#E*lzCxV)1gH0CIgs-jr|)PejR0cCE^jblq8ri zY9ABEZ4_s5=;=sHm@K2oY2Fr%M!I3?0wIVS{Oj^wd)(FPfK2AUGqeDM1h+;hyJH1O z72_GeEB)F{n67Cm+{S)+?p(zLR9~ttx+C_(-0J^bvK^2!rIi$YdzZ`uNh3?b(Gu)MzF85K~k+=!7LIpR*P%S8ZX!8BX8Dl+9bds z3>YZ0)9=Bv4W8?#Ku1g2g%zViJ0F5ic7UV=jr_7{6F!gIYH0XCpbE4P+fk6O#{k}t zkZxQWykNX2F3HCk%aqYe>z7LMD+THW0-NcEq1n{}sj~56^UeoIM2<5Ac)owkH3yKh2w z>i>SIje-2?FxM@UZqe%9G15I!gShs}I)OyhAMHODsoy; zw~7j8aN9^*I3_UR)CZ+wqo$;cY}bB7|5_Vf4NXQJ;elh%dqC-1m>uqt*vbVMHVboe z+j~*goHiuR4VfFjndJ!_9M1xoWGk*%n4bI=lJm_gYQC*(zjmQAIVO~K7A9;oN@^B9 zCr8JN#>m;F+i!1j+xs{dgM72^KZC}6$WlN1F~lR;Kh-$~fInHQsId$31Vb5<%SNBT z0iJ+V5$f?WW!&dr3Ix;Ot2*Ogre}vkBWQMZ&Hok6J>)$nKo+j+%m*HT)!$BA|8Dv{ zE)klI!AG!>AYx6G5CF0oK13J$J)Tk=W$;LEDgzr$-Q)*%)9=SMCJHHL?4zF5Qt>c) z`Z5=kSI=1?KuBz?IT%xov78W$=F-w(e|O_LA%U2E652qVjFl@B{jp-h643=DXoir4 zh?AhX%5JTEYHdDOsXkW(V)h;`<=nPa8C1#e8eCp~-v_d&Ag6aFrJ|C4kUWPz{px;V z(dL(;0-@nIRE_pG{KJEpMAE~8cr-DY`(Ef3F-YWHy9BPODWZZC<7XN8Q@Y7WojMt} zj!_&uO$bsKfq%R*wmsA33oGggGSJOMC>td~1>lB%g3#WGgL_!sRB-MVeS|tzOU2N# z7}uU1IhX6pJ%xMxm(%*!r18M3jMifx7R;i_ASY7y6`8$C~U8HbpR1Bz?m1&P5}K_2IR6^?4G4!tM9~v_o97^8VagER9*c&J_wx7KFhv4Q(j*lzlo(q`SuaK%`vDl7j6CN}!mBIk#e zp80UGWU#0dsW77Qzn=rY_QS!>gCe2ALSWo5$@RdNMxVc>_opjVMsGT>c2100)K#;7?E zsLj4ngu^&sHlGh@EK|xc$~SmI%NVRS&HJ3H!A2QG6i}_Nzk3b-u(5!jNMN$z;h-Ge zN~%=m*FgaFd7@vU_FuTcvpVk)g5U+MdgI<*dXNdEa27cIbbTsM2jAZ8S}3pGZjC^z zh;&UX=VO3(Je^87?=m!uN`!AAR%{yUw%?lS9#Ad=1tI({A5`?6dOk%4S6d@|O|VdB zm1Fhl3t!+sDS@QTP-cfr$0+<)ba8vQ6kBR}>|RT$RR;cBMQ{ijZA@{?+x45V&vm^YFybe#vKO&)DCc&%!9p^04%_Crtcq=amFUQEt{90ys1G}G~z zN0qFoMaT4-n`zT80Lu9?6x`k0&W@TrO8n=3h-%O2v^hWAGYpopoyFkdw|Q3tpz*q9 z6cSA!Y3Zw!EZfLdI`50&e%BsdL=a59z~fS0`qz~T0+jgQU?bD$mbG(3(P+s*B979% zYehjU@J?L{Unw2F|7r1TwJ>k^d^@5q!xh$FPVXMXjmujUZZ>*blGvDOoD}`YOUcGV zVK=BbdD*b&E(^6SePtEXRF?N=zAUG5x6CV)&L=CtzdD<AVf?q74}ja{Rm?oPZ_z9t66 z5caZtcJeEJ19VYx#Al^r$EreQ#eerKW~{rC4CrxakGMNnu1^VFG^2}tQelLI%;Xv0~4&{?nr$c}dWIu83pD>H6ZmM9UN5z1P(G*sY=N z(tdbzb8~>$-mxcjC_^T5OXNH4^Kh_)({e}uN@~rD@=F0(7^Xk-6O<4NmLB$JV3w%F z$7W}^0npZimc6#&nVC=%0%J_yM@_s|Gd7T9{l|@nNhm>Iwx5(bbR$IkLICa%k&~B) ze!DE>1A^0oW0;p2jfRAR8Ptgp%&_k3;bX&v_@}&v!%#nQa711;wpa};q2y%}Q6PoX z;%Hid$)|~TR~YTx|5;D&f!u1!OF7>bz1@Mt*0sCI!2#x>7IYo9EGT`w_Vabj?hFg= zHzpCKX)LT9@}8mZ@`(XVb~>3aoa|b?UU(?|kXleSz`X!YH#SFJ2b@t*brugBkWROu ztRZW%N&Ud5&?i_WIWIWF+dKD;26jm2oy@WHQ0u_dAv#A^#N67Uc?K5phL^LbdCawv zL{cW;55i>JG?lR6xRYV34-28< zi8%!?OzhVDAyR(gEES|u{Gqn%{t)2sW_ZApA3>wYaYU~_NPrAziFN(@z1Ap?A1G^+ztZZQ0)J^!HaZhaF8@nbQK1BW z%mYDeP9eUA;VZODbaNcJZYsP}R0DmQlnT|TRK9Py8Ilz}l?duKJ>85fx}m<`7o4s< zKn>0vX`-7<0({Wr<9pV=|K9oa^!K0OQlja4)t{%L859NqCaH6*z1Hk2LqB^xB%oJt zKSX_tZ)J}k}5;5$y-552^ z!pOYPV*G*@3=vm-`KBEBa3@Vq{hj z&b@+GUmSxs2r!)lDs2(_A9>7>)l98~uK)gkzyk{ga32g>4MdL^>?xy}+%AjPTmJ>P-y)pS3P9*?NJT#Ih!}`=sekNw@1nf}iou$!7tFQT~ z^4+_4KZa%!Wegwl$x1euKqZF^eTjz^AZh#1%DMZy)Gz&|Ws^`pXH~Tyqm{A)$d~kB z6ZRy$zjLLZl-qgY>U|{!BmCaNtC43Y(jWMtM z45_PQaE55fG9S3UY1Jh^(JH?=cpd)($%TbrWWqoJYE1uC)C3;%vRQa`0TEl8#}QB| zP+B6FxMC$Z0JDZM>B?~pzacHD+hSE&>P_Sw5WOz4$8*YB!&>}-&7VfhV*C5veg2q= zj|w2#e~<(QL=Hr(&pSbE@1@@dc*=AJNYlkGA_^pAp2|e~7UASwgYvGv#d!J?GMh1} zM5HISwR(G>%xX|?%82##^+7)k4i6hHut(^tz5VckFyiwR2zk*g8>H&^%3rc;%Qn|I z1Eu}2!av50iP|OmzBaX$7;GUd*YgB`0A-b(9)TbRrv|_lRV}S<6p}9EEKOrTzB3PfOs^%qb0JbZXX;B@=6I= zt;;^0rs1IdPfgNMRaN$z{)JfhbHJ0BMhrczN$v0&2)F{u$d#-2 zzX>h>h%pe%fL!YJ>h>*BmS6k@t_zdmn3%MiS`9Y&L(85Glar8#Y_cVq>WP1dL>n@A z{PtRnoST!f;ke2fBJlxo{_0plgGU;R_7VOkeLi`9$VGjPm6sZ*1W`hj!;orIM-n@- zoHt()2J{r!0g@+b5@t02nPCo;Y?g{|{|54FSJqEVY~2|-TJ+x9#&B%`a?&A0lQLca zpsLct*A;E)5YN^=ScgN#iar$(A+yDM!ddYMkP|)bR`NPZzrRe6@_H&nLoecJKEhhmKjs}2q)TlfX>@j*afBy8 zq*X9ZVziNvjpFLn!{ToMRoTr692)on!uk~r@tOK+R>Rn zcnaCi3=Cb}uJJk&=gGrKP44yoXGL9CE0dY*`SXmkQw^sd0zYy6(zIyaR51(m-i}l& zwjUp7UaDmt&d-L#Nw~z$inFkyG&Hn+hAZ{%b1-_8y@6@${3ZU(ZL2e55R)^jyzCq3@Dl46^APy#(Cn;MW&TG9Z)IBqgQ}oj z$UK@vy<*X?+6=^0)o7R$s+y=_uJV9IC=(b0Ub0492^lBkPh`$PnNybd@#3`e;c1+1 z@tB7=2(OC$b-VHytn7{*5~(<_+T4=st04p{LdVPh#NK)jCxl^yHl$W`r#;0&g=}As zuT&8Nn*eRj;Nr{Ea>J=zCkPxVNZTC$mvzM=>_q%J!ED7t(u%I%OX}v(S8}GUy_DIq`(@IVld}V>3jbl=$hu@pt=-ni`T+ zcbuNDZ=~;@ES&orT;FAya6)9ezFJ$|e+<#2Y3ZzKwkJT+4}&*vQi5Mpmf~ZgHzYw9V5>Y#=j_Go zcGI3QAYvN=2JGpxch3}co(}i%EW$y*)uaC_Pkso;o6_6%pG>}aOUjIk8e~Yx5ArciT)<>XiGjYDuQs zxYs(>M7XSk$Yy089Ybv{9%)2dp<|@WM3k}a?WirOL}t3fbnsq%I2r?nk>^$z zo>Gwh{)Ob9sMsNSRNDMxi?P>M&lkWY2^axEcOa>DPJxaogQ&>}yQ2B%)uvPkTlu^kK4yh*`@F zYN(O%c0!_E%aET>Sm@%y$Vkcib|+DE!thJEhLfghyB2L50WJ;>uE^cN#)pNyZ87S0 zr%r+bHwZJI;d(zVj>utZ6ce>@I^<^1A~b0}v+&%8Jws^bi}gjf4YtT(*LTf}#W3g` z{MW-eSsuw7z!AF)|I?XHLG?Vjd{UglF9%N&5ML*A-GZSG2nTAfe*hDyER$ssyf;#b z@jtkTGNMxwvAy#zHX`&NuIRTNvttO%uYjl+CNe)^!lCfZ@xJa4?tY|{BU4lY%}jy^ z|6NJ*EIZkq3jMVNpzzveVUt>_9OYr*N@>#w*hM#bKb4^0tHR3f=0XbQuO)*=g!p-c zyxfr0i%d=9UslZVr2D0;9W!~m@4&eoQyd~iGoK&+-)YtK;i zoRKLZeg)^QcE9-U*v_ne-4#Hgg>eBTe7eb<`-Xi_8`1PmJ1qsIko)0ekjo&&I_AI&r3yKXE(h26u` z(?X)6ILN_4VMfiDs~eWRwaI{51F@|CHjmhn+~Foqa7AJ<;N^8vBM^ z;Cg?Yrg>W?Gvdc5*GN}2kTj>fHb(iA+o7+qaloM&!0LBw$nI5?DSJh=#%vO00_PG+ zFCVNQ3>#b+&%#0%s<-L9e$C!wNJ$?>9>;~$`&Bq~#wkd>5 zIT7gpq3Wxnnr#376+w}q0^&eIN=im|3(}(%86h!1VuT2SND0!TV{}SOjqXnAknRRa zN9XV6iSO_Ec=iX!qvx>gy03S)jQK_2bG>+s^n>o0I4K#DvBmZ@dmm{DDRktf zHoDcq9!qO=7)7n<^CEyI_hZmR50RUf_KDjQB&6cyE7ZsqNa3~`=kXJ89A#y$jy?S8 zGfJxDn7!wH5@BWo*Mk>nq5pPOe>WpBlMQu%wgQuUxn(-oNLiA!)@G}FSXNfi(q0n1 zvrBz5h3ZKxe-z9^zGTHevAWwuUk@ZS4$sv?leVOZH@xn%va-Tnd^Ndqc!AR)sHCJM z&`?!1kt9w6PVmR<=W4o)&=ZWBlr6JoftF;!Xmez$Em zY_hz&M4fQB$L73KFK&?%L_are zn{Ju&=KT9a_u$atdfp^c0-jZp=fIo-2Xo-FqYO%4U7C)D#L?{hunz!Sm8XF%m_rva z5e^VltADyk(%|>RXxuh8RAQch%u~n@-!LF=Ng^P(@G{H&EDMM!*B7^24P?4UBLZZT z!|pgW0;mdLr+v~HMhE;keEy_au%)F%_Ce>u%fzhnV+sR7#~ljD=dM7= zXU)$~AnUg;jiqTGd}j3XhJ3b41lLksa6e*i^2-=jko#tuas+|Xblcu3;LQKT7L9q3 zhBrh^64dJS|IKwK+Nzxt(4Uv{~(ek^dkz!i) zTJsiQXf2UUAhPS!$J_5;#G*T$n+4`KHtiSnU8P#oADHl?s@ill8rI0YlLFM%E7OEt zh??wnhrF3kIyH+R@x3ENleVa>N&$UiIB1+od8wwzg`JuJW8!#0qm^BL**`)A8Xwr-Y7#iFuHYg-kVz-F!9B?Gl@mJ46LR-*ycJ-3pefhH7> z`}SFYMFP8J6je;s4z-BuLg5~A8ZLU+0c8dTC9FFJ?XOYPQnAIY#%dZ6ZOww$A6X4~ zk%QiQ41AIkA`XLwa7{f^zyJ5uJC$~~;O3poF- z1=y*Itqs~&Co9noOYK2sb051|6_`0$A|*I_+LV+z0u6!WTENP?vP+K?$fzpPgIii| zjq2FED|sJO=?Cz)T`%@K!WIo&Ty)cc*5G-u@zywc35bNgLQ|ci`}&kGqDYv{Ccech zE*&9i^c-KQKqGd~i#c~s>-R)AoWh3^-8X7X8_qt6=NFTbk~VfTn>GW>bE&(q%@2#M z{v7x-?tIhxn>+l|uu`67dg3Zwbwnbp{v@&F`baeyA(824&I$`qHLoiFeaL^r$NR;f zo>6VhMXN`RZH1)4&IfMGO4=XAqS@CeiRK}PifK}C5@#UkjvDEtL8C?nzp#Tywf?!U zKtGjBV3P4i_q@h=?gh}$OlGeME`<^}(YOu4u3)-wOM=C_G*`3B$LoY7Ndp%zFCx_f zQ!v*rT5G(=Wgg$`VdtKpe(poGbHEw{J6 zV2YL*3^UH~X8St+xSmnu5t!A3z|a_yc|+6dVF_WN3C2ag!)0w<>m4&B0o(uZS|^eW z5L~YC#>K8YsK<5wX<0SM(yG#*vG__dk9g6IW+yRzx0wJ7kN8^ppT44p#S<_`GU`7N zKQ9rVDmLjJRuO02^feSH!T$c>a4k%ZO65Dnrh63htc*<{rhlyvNa*_YLvv{XaODL^ zYopMMkn4T%(9(q)^fZ8jlao^`Lh|l`rRX-#hTV%|MFSkHS<<&se)vV|Sci{QME2Le zhb$UTGUvi=$#$<{ncao$>L0-2=wDg=`^(VW-FYnD3n{9ZuOJm5u z{ZL{k_<40}S&{8&T4wTfd zUd#YRSTA^D9Tt1bLsav0rw{heH5>oY z-X|I~<#Au)V;;W+aZd^rHfM5{oPfFZOyUL} zkeJDutZw2oKdoOW;gYBHdmK`>d|%kX6_jyAN>S8rvOyk_sh3-WDd$=DOLN?@s{PIq zs&IIpVDdiNfm-qKUfj1O3f^ddjTK`vgP1*+v7bbDU}Y79A9v@mW~zSgku-mx>PLo3 zsg~A)HrZRRMV=|P0n=T!?*we%m2McLL{*7?w0A&RO6Ep6eZcfY7K~c5tGrbjs%^+h zjK!RQfH>>H8T(%)6sxW=gEEvp6fPfZ4g38ne)Bvmn+Rzx08U8B4T|BDQh0vpE5Bt8 zDPuLXII`8A@M|N6mU}D26nl+&_HFoa(MGnKT{m~~p~#n&@H z|J?*$9^WRL$~&)5-YH7D68%;=zh^UiQ>AYd-#YlF$V2ls_o4Snbn*ih9nkX-Zo8vJ(gAsM#9}mw@ZCv{$RegOci;tPgm8>5!`z7Ea%k*ryw_~3Zhd(?mCAnoy%|_I z%w`>4W=SQ$RoZ6SLt?1(uQo`J@T7ijXlQ7BoJr4tLg2%#3Zd8Wh9aED9FsJkT=)P{ z5cgbmybW2s$w_&OBmNw(h}q}$RNo@h*J3cPFH=A;mG~9ly0Q)E_^vV0?x)e$+YOf$ z{VuEAz#V(l(U2YAz@vK3?Q;!JDTi*4T{*T~^IYh+%w5jR4F;X_7A;r;0&yU-UV%B} z?R^1Vca07mo9)ZgF*X=aVT>%6$R|X$x*Q`` zuX}g(oB-WKO0tK?ZHVyw7S(9KB~sbD_wMa)Js=mJ{cN{eqhFB{IZLxKebnHR%8Uf= zXg2M)sStC$nmm*3Kd6d1&RrX~>T$^mlYy% zC8~6T1w)va54SG&ud)m@P8*zH%=}ls{`Dn22RwJ(FF7=2& zT15iBnRHP-U}@oPp?@A~6fU|momYS>8hP7==3)Pe&44EEz8j4-Vf1qw;xx@3)1|I{_3h`F=-J(Z|o@^ zDW#UbmZXsXDJ8Kj!0~0T)hoV<`o#*xOB(3M4(?Ct$vA7@2ktL7&&>K#Ky{0WkGnO= z+R9Y7wby-Y{1nNhUn{98g5e{=kAkaFOqqn=VNBe2;I?P{iRp0W(KouFpC`t(zvp4G z83J@WepM*@LF<+v@7cR`1n4(?NbX%Jco)%NprYwS7#U|qHZCzOu7#F*P@11ipkC$g z52sr{HdrGLfo4f{32Qv6x}7?pgq4T5&+4+Et^S_H{ANH`F}F#oQw|-_mzIYniZN#p zvQ&)!KtdufX}Y;$&27cmf4b=9>L?!nV)ZVihm;JMFGa{dP4tuPSXy&<_{!_5rn(wf zi_VA;ftvs}II&Lyut@ZyitjeLJF{9-lpMqD&2y-uL`+2x{j9H_&anYHvbHM$5Cq+5WV-cf7meu7O>yfo~Z=^b1~u^FbW4^ zE$#N^n-axeItXs@ZE+f$MxR^%U^qZCT27Yc0A51DOC$RH(`R$?_rW6mlIiEnya9!h zsSyiNfLbWcS+C+&hwX27cXx4lHKV%Q&(cI2Y8Eno)G!@;YNSJg8_}VinAY>z+R(RL zmEa8GXS8#;TGkBEjXE`&5M|$2azroAK=n;=qk)K-C%Y z{~R_pf}snZs^;a4WMMY`fGRqhO^xW)>WOYI7~LxB5Z+fch3^(|v;NnUr{1@emAyyC zzV%Gd?Y(+>kz>!jREMb}y*;CDG)MQ=CT{B z0NPYUmN3>KQp1D2ANKu}q^ATa@FEE{0>`h6hGBThko1^Yq7iavT6U3_21KIWPt**e zuCS%SmrtK2$wR!!sle4dSRtyBG}z|M)x-X7;2z)9AW8zqP9Eg z1(>!oXkrTF_5gamQZVT4ht!87K%FSTh*b68#2?Q3}z0#`N2&^poD8q!f zoRyQsE&+BX<(!0CU=~%idH1#p_NGCpGXlS{D z=e#$_Eagb`Ls5QPhdGmI;^}PPMf2?4$kUnAWVil5W!>>h0__1<3Jo8Cy;vT$ssihl z`RBDnjP0M=0vAo$f*QK9iQs2{ta=3xeEJ5hUVk?Yn44a%phrd69sH6x_$H3v_4AtG0ToNLQWc);JSn)ul7QKYAql|2zB9T21SRZ$vxxX%Q@>SkG| zlAKCXB3i0U8GNEr=<~%N{_-LjMKkB?Fdh+bL#65R`iA_$^vKA_!~`=w;~4`;RZ6Hx z@Nwx&iAUv?I=eOCF9Kp=#s*(aj3Mnie{_z6Gg2L!N*)9~@$nnSjIF8A8Xk z6(NJj8YG&BpI@gNRO7R;V;4yp5KixOJtD5~BI>r*PdJ*c-0`O*64oPxTHsKRY)f;1 z@W=vp7&=fXMuObe4WvdkO)6DY9c(It2e6Win$qz@WB@XsP&%w=?i$#DC}6le zf9G029$Q0xL2%Z{UO|i)P^=jU{NJ3J@Ck0B-agOpxXV^`SKyMe6hjTwwk{WE(4q$Y zanopYjdEal-U@lx0fE`5KV%-1~1sO)l83AVVf}C{`z6)NLBbSASpfoc*5qO zCu_NxfT6)RpDQ|IT_Y76s!3;K3Q;5V^<9|s`}?-ce=$|-E1#Pae{BF6{oM-biG6Up z|87yei+RCmR(N(l7(gShPLr>leg&oN)MAuf#uNxSU5)_>GMAvBzX=hbpGGHJU3)H? zP(O&?f&2d`sI~w`_~SYEYn|CYC`4i1+czx{o{}S(k2AdA(&ju~_Zw|9MS4HeNj{yC zzL-9LtBUtf@i7DF2WX%@3{ZuO_QRyG4&`Uk-sNTmzozT{gVI?G!wCSw$D5>4{L>>k z)`J0%bkz| zHUbUg-jF$$KQ2+Qhsuwksj%NE4?%qw4yS&G zryYvGxMU9v81YNJ%H)Rgp|;Ou5n9tQ3+fg%33zll(LGj{^Z7pjL(T z46Uy>JLO5xhe-{JADV^jV(Lf|_Ie-!7|0*~ntV3>{4Pot;Gl&E9HeXEf0Y2&v%9LK z^$9*8?pK+7;8aM%9#19`sT>i7#Z2i2XeGTGL9RU{mt}RA8t;IHOl=1@z09nWzA()# z`*6BpV8C3G)&3{3af0 zKSbS!GYj-D7c}hAYJgBIi}#5U=gj1Bpf`r1myvayPM{ZEdlFnW99Z|gPUFF!PW{fAs z?q4PaXGh8nkd6r<##l_>S{52V*jsamhU(f0|{`COTjf-ItvNQ%b^Up=L`|0ppgh4p$+Tpc+M3!S)?m}1<6eB5o^6%K$# z!BR{ywo-%Qq_h-%1fUs~2A9)6NlDKX*d)*c&U{YyE!w$a18{KC!f=heu>f7=yLWy# zgcC4bC_ze(Wouv7Dh?`OLbg7v)Vny-U{kGKPHl?It2+=LTZ%S@g-g=OfH#MOyu}*& zczp;#oba}Opo4G@3iJMw?cOS*1mQU+2EA`^=lJTk>P=)j|3%sT2mrvNrH^V~8e`c) zV#pvnlaBTju8Xp&7nW-Kng#F<;lD~m>A%N!^~o20Pri|1|BnRGSO?_y{y;Bod_JzX z`mZbj79(#tJUPM!^b{b6OQ{`fmGrx9K=seY+%Ly~c~%SObvN@B*UF=+rGdS+aC!Y zP6;<8WCkTELS|m0(%)!fYf-#Yhd(LCD_4U0j zxXSQbLr)JAj8A#RET76hJF36e>m(ghq9j*oX|M*ks*tW- z9z1w(*g-Tx*iFZ-*eeDIZxIu&pWDGx+!hs=*+xxY{JFXzaKPp(bvx?4_?HumbTs(C zH+Kt1;mbd#7XYWQs7dIO=jC3tpQeByCkaQ6w44ONMR&tR_xifo_VD{c11?f3DjSVP~(8mG+1pq2{SVByS#FR;o7I4Ljwcp8l+EHJ2wef!ny@fJ3a}TrE4(KrE}Vd?;2@Gb?FRyv_JLZFzG{GuQITclJSWXI>q<4f>YNVfT$QzfEHh=<}dRbMNRK2b7?ng8OD!Z$&NKPIFml@3kTMAwW8Z}X#5>r~=u0Zt* zp$1@ohIQ6KLTV|nb|jdL1*SR$+Y>b=>b{d@U6qMoZ5tACg-nXPQP2VXxg}C#cXAqz zGu5ODf!#7-y}mNLUiqPe2qE2sFHZa+WbrEU=M11XNhPG~)}-1gL4nE8ffHHNB|LA} zDG8N`36Sl6G$;}WMwDa2`OFF56EKDE4zS#p7Bbl)IEeB+XVdwmKnLa( z@oK9wdU;S>$W})2t+v;xq%b~kxn?I#bDfMF87i~|Qb}}$U$LxF#M<3-Px-vR5=^5O zo3*}dY%Ugdg`{c2JCGVA(a z?ct3uw7tFE>khp}3J>m^jwma_4l??H-dC@k^$N@nxR+TRrAU zc}v!|YL}8Wm}$KMEaJn^0}{n2ZuREd)dl1>Nn^sv5QW!kysVQxs#EHDc5bhReY%Bg zD$ze`G|iRJDaJ5+X4EE_xR^AI@?}^z|0;V!@qTr@c1^X?qc|D8n>pbBUaPb}HR=Gm z1t78-%=H0i90D`?1QSg3o~nR(!)FO4;zj?ibQxz$u68mX#`1@YY!20roPn&@?Cp@p zt?ZMS!X;t@-*rdm z_$IMyae#o;Ykr11M>;GsG5S8^4S3(42>U=H78FxvV05JgBf!Ct+_nucnIg!Ke5v4} z%VuhKomOYRG34)mzqJ2>&!^yVsWv~QxBfU7&%gaKni82F+A@m3*`)GJ|I|D+C39OBfqT_oFYQq75A?okA`H_u< zcgXoHze4|~Alw`#rM~78OA$g(@9oFz{Edinxenv)l2v(;nt6w@g~QVPPb7HP zsik>WzK$HrT+f{i&7lb@4v?sM=80K|1QlxP+a=Z*Wr!(mJ)AIqK7rWvlW0 zl%=$O_YhQnZa-LDRFT>&iF~?=rWR^V`;cc>MNoKLc%`tj_Y~j!_4jDlY|-A-1UghY zgS8PY;LnwAru6`zm|P-TivMFqJn!Z)Dsjh&TvYGxsqOmR(*)m1z+L(Q`KDxw>OI4uB>Y9ja{NSc zybZDU5bZ|Fp-~gPouyzW7m_c)(uNwh{S)kDUcmj+khQ=*UU-O33Ak_mP_5=ts*P}dlcp;WaqK6$H<;M?}~ ze0P72efV-K3*Hsuiq}@FP=%2!*$pHGo*X`Kb?pY(@87?_wbg|)qg<3nPqyg5Tw-U< zw@^Csy>x^-(z-w{KkS2-P^|HVlo;uf940*F?34K$n2$tlu=kPaK zcNzLd$!YfgFDw9pVyL)N!TLpp<6`XN3za5i%+~sDr|HP>{0Sf%uk*d^FnAi@<`wBO~1p<4iLQ3LE5KT4tqVSUwI+9ih#Pl_tj|Np4EB7-_Sl>PUtJw*+ z$DnrOnd(olRhs|4x4(YohF;7A*8I2@+7O8#&(x-`$=G}Gs`Uv8O-lX*J~X3hpOg5< z5ZxAQkspFB-+GacA zeqwg@MxXR6?hGU5yUD9>tzxi~PgxZ#yYdn#uU;4qxevYECMS_v2ivI14U0c5O*z(4 zU8uUehmloThy#qsI$Tv=ByJV)n$QFp`EQnv!`^&$>#v_~GJ*vY$#6~^cdePcQl_mu zdP@~f1|AtgcUqwQyBep^KQazGms=~$Z8y5KCL@J){jbLP#jzMeO$o0+Mvb^V|;4+Y%7#*+&7MDS+dO zAn-u};1*fRwQ(yGN{&U8L*2Y-O1VR_>uDa2@YOis4|l!kLSw_hyT@d}zn2eziLD9J zp#;wxgW7Of z@AZF=)Cz#}DjSQbcnCncBkpfk6QVzi+5P?5niKrfD%r_j{$}|#Y#cl9ete^Q{ALw& zc784$(3nzY%`t95^ybdV!F{&JBx)kvSQx-?Fn&oDv z7KD)Ta74wqen3)H_*rtG41)=Clv7^mkYpQe(2#0&XY~5S@f%Wkm9*Q)cLpig!4oD# z^?QnURN9Op2KTU8H;cd+3_KIZ^o#L+Db+7PfpcIcLfF1!mU?fj7%q>w`o0u}f_<+< z4FrZG2=9)iX^4mj@d@#<(L>@!-!Vm1ez^PJ*~N~~6M~ntX4pcK-a<)w-+Q6S^q!Pb zXb4u#N5D~qxI%Xflh5E#*>Rk95=X2b&^O|#Wbq;54B#z2K|Rpz0RuG}%=AIO9^Lc4 zH9hiEyQlNSKF(nvT;dvtSoi*Mm0URafKeHL%%-VE66lIodBDZ< zb?2jv*Z#2g7ENiMfINTcwbt5JizlGfkLg$#G?M{8pNJXs8?5aa@hp7;3sIZ;cb)yu zmvTe7eQzC2HIBceB6hmm%RiSO255OM@LyWhz?zR;)58hq2gIEIq^~)t|D@W(@;^(? z52``Dxg7X0#O4@_O&Nk;LPkLNItjbvCGB1*aij^BwEV^?;kHzU>Vn~Zy}LO2?1dJJ zI^$hu7;!%d_Iu4K}M=#uxruk1CaC*&#V$1z!C z{EAEE8y+4WvD$I*@i`AH4pex^LYvdvK)i8raZK1k>dpt9T;E~Y?S2!LLzQe~=n0^g z6NZ;*e&u<}0T+0%FlOE~bNxgIcM!4v7ANe_P;tUjEwiJtrXzG@58nNLnPkKW8qdR7mNczyXlBoR!t?8Imrt)B`cP5Li*8_FFdVYD{%C1n>el)Y+4!g+!sJht5Z*R$Ujb zo+O{`0fuZNB@Ry^O2$pBt3?#zZZ4UC1oACew~itt`C|U3ii%cTJ`Q_=^bP9sqC{7- z)a3&Bk0&XQkwyTkDcLnZnt7!Uq{X4za4;A}TKB12=dCb$Yq~1J0XO$?Ego&4-GlCU zB4`vL`LkyQ;$UNrMn5G}^PD;LYrh37=kslh*ftFNROa1L<9-s)8hkfD5?tgQW?4j%(Bh172*Wg zj*>A5t-Z$J7(v;%Yvr}yUI02Lvm^Z!fxJd4AeU0p3gDi zycL6BH{gWU13g?D%SX5u-e3zlKLB0Ik4PfJx%0VVv!%&$pITthzz9wZZLNvKVlsBS ze-~~Zq~p@kdsD;*ULQJ}HvIV@&gbo)#uU6XJFC}^8ImbB7$coN3My0#%DAqx(XBKW zh3Fyd2C;CY%2*rA(%+qk5gZ%SiQmN9F3~ms5g+x1`+&MFhE4J87O_vb=Mh_rsOYOo_d`yHngnP4C{~J zx7z&r5M>V#P8}U9%DxI2ncD#9+D+YL{6>KG3)_c7tcyW~Ubn1+3GXF50*w;cm#rCa zqUCymcl+uY@oqyt+S7hC(yIN;83a4Cs6YcYLf?w!SI_&(wNca~pC{I(CTbhi`~AYC zeJ+9XsX>`976f}nH>yatIziaN-(?LkZi@3b*wR_Y0EK`THM;r}#()<9KmGa2^^r(8 zY+a$8?(NcRd2n2G>yT<`ii2tLD$u@ndBTcUaqh7gd92W})G&bqWBk3v*p1N`PnOf} zx!>m%zGncP?ZyB_!Wi?h23=|Nw?q~*l=k3XE(lwuGtnN-I|A%9x9Qz?Gh3A|Yj;~5 zy*L1{!0jfZx_`~v5Qs)ERfiWCzRlM@M2EO;$+{oNx;O7F`8d`tQOcRJ|5OY3$gCQN zWAd2#`J-1nswBg7*sEUDJl;tej}vIQQi#DvrP*8!ULULD`iMwa&BlsVrI?|rn~W*G z8jt`BL)>Nss3nBy6O0KQ@R0WbgS4j0oqvD7zn-qD&PK`}IVKPC%qVr_8gKos5^@w` zbtJmrR17m#hf;(!mvp#>VO9Xz2Z3MaD`B_pybM(IN?dEN&Kg)u zNqoddIPFFP%6ZixG`0A*pbX`1T9}!hi!i$+8K^AhW_y5toCDAi^MRc(A0rsAqfCxU z8gCAGN6WWzI-qpq?bMn3u*v`R$~QmU z6>bm#D$a@L!(;9aTgcy(%81z-zs6M=$C*zgZn{$1-)=M)nc>{?7iXB6C1-a;laC^x z$Ss)`wO*CQwNh1>u+x)l=4iD^D4V-0V|lzY1LGp>;5@oabKE(v&z2!ZFh??arzAX* zbbdxJ|1#+Nvp2Z2$0l1)D#jQ~dgEf`Fk^=BfI)4GT^p=!TyR>xSo+eJtW41MMmg->h$$bbr|ZboPCJX{?z8E4 zk-~$2+c}&4O@hRzN0jwftLIw8lXWt9B+JXl%I@!tBC0=xd{Qy3&lyBmDLDMJvDo|L z6x-jG5VE+U;J6851w!PY`yeWq?b?qT_e1t$Sv9GO7`g`#K291EtvwUwos4#+U!Ok@ zXZ8sf{!SX3xdoMl!p*I{+UP(5HWskRA%Gc)o^HS@qy^2O>I|AZbHUR-%BY$Ge$?H< z@4RE7(Pkq>ir|4qaF2|&vFqP%2P%N00VOPtRU(EMS;oWvdE40B3myj(+i!|;d^d;b zPM(kjOG%+yZFPB3@r64s+YdxB)qi?}#E#~Dae`dx)AtNG+gez>6@l$pPqH`_*nUTw z0BYM>uv7cHdgoMB9%98>)e8R;01O}M0$4&BIIg>l=_eZD z*(ip3T3+Q*7UccWR5&cuH?^8RxGcyULJXQMN_2Hj9IhSk(*o5iSp5w4w!R$8t!@h@ ztxu?!6HW8D)y*mj`tnB!U<|qHxy@F!Z><5-jO&=EJ|{9c`gaYb>!_%E1|hPP?6N%OO4hiCFd5 zm%9zS_2+KuzHaM@pFUJ9RR1n`{4hU1e}*Ko0AEO0IPCE&M9}okiQ)YQ!<4&s*m>oO z#I~s%FJ%6-vAgY0&0QT~`o-Pn8$HbXA1xVcNfJDle}pGLn3=B@zQh!kv%$<`X@!@e zH12Mx8z}(nPvQPNhq}0t!}2*nM6r`)0zwLQwtFXDOtwcZnHd~(faxN@XWSBB?o0Y% z4$uv!O*f3mrqZ`W1Q`B%A;ci>PPYcK%9&-fe$sT9uU}id{7K{oC%pCPBX*QIN%EiP z+otULpQO*(U5!_KqPlv2cT%DeV+8>3zUK+RK+XJxqgiNE0{|EF$k4AA5~1?MtSNEQ z%s8M~CvTh|V(V;20CB*&q1<>Mo7qA~^}~C3RURe3sSQj5u!Y&nXLi$g(Ozu$lQv&^ zgb>MIP?vV8DOSE&tl^LITf?9WkcIHDJE(u91_5-+>nAyc=LfzKgmfSoNI+VE6SFo4 zys#J@>UWl@EN^_>Pb#WqC?S3#qd z?#?PU^1wmD@>Y%%k=dnw3P?&cw`reo8$b)m32BgPgV(8^5YZ)Ed^)R3*0x)T8wIQc zS(b9LlG6G?{~bMBIC%ZiaOW(nCrdYO0u?EC68dgV)R_4%cZNixRLs7Pr-6m!#-Ss? zM7mvjw)w+xXWBo%J9PB>PcuZS(rrQ$=-zV+kvH{kw3n5>c#TI3(%U5+xG0#hsp6!D zhZl>kdo18ybMxhF?U>mnK5$Dz$~fykY=fI>1#6mP#2$fA=R)=a&As zYP}yUV~vbWEY|Z2L&JUpAq3TwoZx#0C`Yipyv~@)%qjgpM@{Db>Y@RgevMCZ3l3Q~Qn&nE0PGfjYLuQpr;JBeS))-Z#o z_k!xKnHh`7yD7&U*f*^#UuZE^+=6!%pCkpsf1bq2K60c(39nwZ?(R-%1>nqCWCF^v zz?iY&Fj-;-u)hyC+)NYTjMQQJP95hYFpGgPU3Geb?48Vm%Z?RmWIxw%JYdng8LYr9 z>$ozzA9pIgf6pH$escQD?|e;NTb$rW4<5K4*UbIWj#xR;q^Fa?3=L50#BY`zIMAbx zP!xBAWbnsW;S#I&0&tMG2|)R$=rNcLqYS=gvE~%e3>00o^xVuyJzI2_l8(;#us<@` zE-GGX@QqD5$gWwEFJjB|N}#Hp2?e0(xtL-zJ-XhjKpD&0ANKTf%9p%&Zy?z;qv2W*})b?C6uaUI?PSD+qosx8`t&2~QUKuoNsZ+V=)(jUw z&sE}di~zfARXEmGnqs@AtpTcxEbcYcUgvqjzoyM=>gA1pNCYR2<3MD@B8zoi^msX7 zIjT?_cq2%NhQGgmSG=}v@T-r(`;UyhKwN?N^=UudV;qOBT$_mmz6sKR`;Wtgin<7x zn7u^J0wVZs-&09QYz@bsJC0_1Hz`g!QZ!zGHKj4Xtk+pIupcHFQFfqY$_#@t)7nd` zOGOeQ%fbB^qVC3H1p3?47>*5^;vOo|C;#Jix4L-CarrNQz(c<2;wtFmlw;{Y=8(1k zPE-m!Dd#H@j^Eq~`qzPob$90Wa_UR#+dQkERtjr!zbUhRk@H#%Sf?B*y%-HC>?%GW z17QbyK}Lpdm}L%7=hNTH5Ln~aqxpGilZBTMe#U~_=vI>w1?>4mNI4RVaOdSB*>jeKl~Qo z>E=iEwSJY{t!}2x1iH(ab06;w7}J<6ds{dY6PSY=xU(D^tUVGhsd05dZIVQr4Kk27 zy8iLz%K+tp5BToM>>!kp)-+bPb70vY!|drJyiuIvFeY)C!SH$QuVpC`Y%JMg=W^#S z0TeF48)8pCysQI7lW*3_K*%m%hZX7CX$flqoJys{|AOWm_z}`<(KSGURBZq%rGC9j z)$Y0HjhyE-xp_9Duvae~CsK4*2VcPb_h>%JtD@{S>Bhj((gl9#g)%A$2!CKYxHor< z&E&NXlXYSbFd<&jnjmmaEkx?nI}Ks5O^jl2;mpg8a>N~EPDJ$=b@juS9=jde+uJ9G z48cqJ=Q0sg?A~S;s;l%#mwP$4!1q6~X-@mGBtwbKyVJW)U!ty>2vDytapsPvCMT5> zg}n93qaeLOKV@iKw0;eR4jcBBJ%6knDE-q;UirT3neGD1qb8!|k5!|iZ;LG_bOPF7 z0nsn}w0mG}dSc-;xVwV)hKmGfLX?sB!=Sk`HBr;bLv%tJIPVK>&s z1KX7_y>u_V(fnvi)mZVeQ3vdLg~+m{6FcJRTKQOM7dP9u+C3Te^wwnsA5GV{Ic$)^ zGcYkiVl7e^t4+k~B|tTfg=C-4Rj*TBUGmi5ZB;t0-(4!VEUw)wK6(g?GuRKqq~3^fTCh!Agwe zBYWOdd7b~*52xm83DFJ!q-{hB%z%uW7IjejrsVmhCYqWeVC9?5yMyD5iQTO&dn0rH z5*2icO5_=fE**-hCacGjy>ysvRGknRL~APLhPGnGr2+$kzw7qJ<72jOI3@eZ$a z0x~lhm@{_IHyQ!~l=-C|vZ8L=it1wi-rV`@v0FL=6>p`im(Y4!l~7`!Jv=xv%!_Q?OS=ZNlC-bB zxPtk=Nuh88NKyXshwGqkrRx7X!OH<}(b|Xy)ng+?=ml1|pHZex#)~J4tpIwxUOAv( zmiSX}9zv7BdKxwpug=-CYYiJ1{`yUZ_Kmc!yp7jOwd@?GwNxV-Lah(4%FAAc!2(h% zX;i1QDat<4>tiOGt+#2Wj16zI7;qfPT@-^AyS}%07d%t2zWtzVR0SC#0An> z5UJH#felT$6rP24xNdM8v&?EMQ3q!Mn*!_quI?4V^}G6j#RU`viRHIRT60Q!Nb184 z<;ck+wD$sZjSachJC#epUygi#xOWIRUjPb5_S!uxGKZ*`H76Jy+6lADix{1+cgY)W zBrmw^+xWcgD7`&dsMKKkMbnzR>)?2IP9)tbTl70Xq@oeqh+Zb$# zugUJAM>M!2LGePp=f^?xwyFFhL>_Ws-OLBcKH2H}6F zgkDzd$mM}k6R+PBjn)c3R(}eeJ2h@inh{it);dl9EV-O5@hS0?9(Oh#^`D*W`^>qg zL=pt51#e0LL(&Moa9O2O3S0>}L+!SX@L*L|>Ar|0>`2xo5^d_oSbQ<=)?<4~ElZUe zWOy0G^e!C!ghYg{QOi!v5zX4uQ}eb7N%SDHBA(@NzK;;IFqqq)dK19e4&cV&^GD07 z84r^XAJ6nV)ibKC*F{NyUxfEWp+ht3c<%vWFNR%fDWMFgbQn@m$2b-MsrimpN&MTc zbB-ahN!X=^_gjk0CSIZ&;YK;u63L^q?~vSZ9`@@{tEQ1&c10J0k!rHE%V`R-*u^`QogVmY;}!nk#N_pC_J#)q5f*VoB`i`BgJx zbm!tH9Bid0uFo^<1B~SR#a6w!#D`7AV~LISyRbSX1<<%t;&SOkdS`xw`5xCBj|!#U z-!I*#=L5U4>XZkT$OGj|_f11QH~t!BpCllw{(FR8&A8+ARa$ANO6MKhp$7Oul;+0N z!Inbw3o#4ea!EuVnsc#j<9;4;IUX|OdOV}~?vn-r@gwpN{2c0v>E$ofZ_pdT7Gw$y z#6ses*!9`ener>Psq*({0A#UCGW?fe_($RA%!KgB{q*enk&+kVD2eG~m2YTNByMkQxCcAQ((qlzT#7qNj2W?HJ4*0`lchjS?;exu|Sk0|O5hk>hP#Wft z1_9R_$H6B^ghY_oFuIaXCRXu(2IgpyeC!==8KeDL9}`f#!g)C&W12Rb@O3KR!*;B) zP`&z8=4iw~>552Vp2ths=zPlzDoq9khJp2s9`>!a*q66V^wXqKzz4^C>C?_2K9)iO z%7}kiDHrjydj+a z>L{jwb+X_2McI+wlLc*o_^XuQo?s*9pcwFO^$!JzXJ$s^x{)?=lqmH%_&&0a3@s4c z1vg4PHh?Jij}k@ec(wZCfYp*Svf`vQN>VCOfX_d~%M=11MOD6G8H4)}CN6O$<={L3 zJh_Lp0QilDNb-e7m=N8*%T^+EovbCTkQ%oY=f+y)zb_y+Es)2U(lO^U4;h_yg+Vyy z-=w9$AcWFkqMpz3sV>)L#Sc;+VW<4b2_Fcy1tgJl(ed0R<~+1uG|zmj~!Awsy}$()9`Lb-%JLVLpjnD%VV8Spp9_#WeDJ7GsXc9&Qk9FuWR4_lGtD z0Ls1j(x-C%A6IW459QzekCzZl3Teo`O~^GwA$yjwO|q1Xv5$SvzEiS~C1Owrk(6yP zmWVL+HHqx|PWFBKUA^zm{k`w|*B?DR^uVR-yw2;K=Xsvzlk4AeI)enJ)E;nE@NU%o z{&Dv900pnc=0ZOK)u3hHhV4b2y#en6H8HW3ymBR>>f;K6QJ}(#x>yClb5iK>>j;S@ z;(pUNC)DEElgZB_1y$334tO7^IVpVTFE6X`EE|1}WKt|BFjr+RX87@~NU$Q`A*8_* zRHRXd_<*85j#X28<#xu=>-;R(JSk^mZvZ4q@3KImb*e&QE{H*geo7V{hDwfz8NU)# zZo}AK%w|XW5QCk7U>2b?)40ABqvB78M}q{X(S)9#N2Fr7{+fJv>7omSw>0B*({^@=ukozhUPB! z)h;#u8vkbK#{);Rwqk3POI5ds-MgZ|CoRh&=}G)C$;EjO?_%;$CwcrSM;wq$xArWA zz(lX}kVUbZfH6nTI=Yu~+`-4l0Ak4FEP{0bP<%fEel^dpOpI2U=OwTf3}hfQE%$^l zkUND!cAGz;SL*S-xnv#O!-d{Dv>oy_RvNF+TuOtdtX}97oc7I|cG{$@T z2cPs@TXqKjqx;|rfV(k|M!KTHt^8rm`M=RW&w1|Ku`#-#`G0NFiLohtwv`1)y1>Gc zv23%_Ef~t9%@+Y;-*yM|180>3X7@&%l=TgEOui9s>KbhR@vLL&;87I+_U#+n@$Z%Z za743Hd;CWso;2=aJd@PP$)v3ROs7Y7@}~%Gi6}Sf&+M8Z52e5PFS=e&9scT>&}U%M zMDmsPS^^oSEgn{7aBZ!n;_BJVpoWHBgeheQ5V)WCMCFzoG{5%Y`z+@COZA&s7Au`* zl)s*ggq^YCSNWTRM6T+9q%`h~hg)u`#=3x37R4iA=Z++Xg@xsRib3zZh%9S!^Wb45 z{r#)~O8JpTBtpNk`g^tPuS40?dg#X!wM1!!2P2ZDFp`eze&B#cJ-e%uJVO3giOP=w0V3#9(xt8rM_`5Vk0e2GP_V67QH>W4s!>xH z-9Q#9FhU09xt`U*ZbNRi1cip?Sfx`tQS%qpH$*%I+sI^ANqXrCbe`9`J=tOLlw~7Q+uPwDmq#=QN!k8}u6iXu= z@2*6TT(5&TDFmCgru-XN`*#{m7B>LuRl-(XEn{^r3nOs*pw177&Ng>#Hau^n602GF zU)Qg2G<>B{d)w{t*ELp-K4nIhQP)u}8<)9!0*LNgn>!dU zU+a#!WQID~`2OMaI5y^;)K#JO4OFnOqQ!l_OI-ib|I_(LTkz@wZGlOu4A&kxhUd(U zNV}^Sa6*#=WB=^H37YKE@K9x~jN%*|8B(TK-$#U1Zvy}s7$vLja7Tbkm7`;!*2ngX zS&D3+%s@)Un&j_YTCV|_(Q>DqqB_5=3D(sSWiBO)emW~+_jN>Uoi!A<`mV&p$eO4~ z_V{tc(<(R5y#KpQKv~w5b~^0e;PZ~?z2>oy%TBT3o_crIPi{i6`SYqk;GI8IKl{rq z-0bBaIo_Cd{^2P=F>_bDj9+SuTpjGxl{kXwgm!Of^+ZbalquSJnLkn#q}U9W5qq&c zlT1Q$=QbHNbmC2VaJDri*Uk%cW^ddB2dz)PdMAsidnh)a-oHzlN3f389wXu0aRN+P zpi+`90T07@IPP4HuEY~RvT3>#Ia4*uvTrxBNS6d}dQFIPu--g6+>8@qE(5t-eC-=; zoR%gL(K*kL@~N*!G~n>~2$VQ3+2EHl-~oL6#5et(X$5Er59hYLmUetRyOM3q4N52<$CBGhbY3fh)x>2p)A-}B!1WIml@r9wLa{#a3 zY)HLwI@@pW=X7LtO!h<0?0m*Y-9w;4!>Z5K8mJxe^;pm||;IX`~Rh0v=y()3&TMRR|{In6=wE?w2jKuJgYs z4V<(Nv)HSz5&yT>1uGSCP-bE&L>avT85rp_MtbK3*F972MZRO8d?=sO zi#Za;F`7^31hu@#-+X~2(oCRPDlztkrC4ZMS{kT~4~mF^7Aqi~NRGOfcUN0J68;2x$wFp#cmW>25-K(fax=&CQm!FS9;; zXl$M~x-{D$S2D=~fckL^_XqpLs5AOm@sBT!b4bXAJ=dvb$mZL9;~lNlg+2eLPW4{u zO`10H`BxDpEO#L%(vCqYLB*HVc1jhl75`JS?Cv5a!dbF*VJdZ&@Zh4LGAQuJ3wKKa zx1gXjEfV3+KSsLr#k$SfP27WuTf`yA!Y_xl#_z1dPQS$GR7U$Fqy}hVFF)}<*6)3# z43&ejP+g6AfLEz8NC3(N>+D)ff@`;=ib7$m%*{`z<6y~=uq9=2yw@U!MMPruO&Zou zwyH-Im$QVC<`}u?KYSbt%hlp7wC_+R5kH|pfE*pdJff@S2_UyfjDJhd{7U*+P7cZV z4({$FeQTn%YUpEQGiTK)E}Y7d4!jTlh^~P>e=sO$As^P@K8Jqz5yp;{6g1ED=BuD6 zAtvHJeYAL_4!!a+8llRfrN{wN8A6taaj3kA2J`w`Lg1K)51U$|2!nL*eAY9svT!N6 z5W<(BCJ!w#PwZ!3@invkSHbf<;O76eh>0%-j)F!{R|W)ijmCda{>4H}8Pa6~(?Llc zZh^|}Zb{?E@BMPpnmx0)r&+cJ$A=w%(jKR-s&@Qg4yi0>eB4 zL&&zhFoxGW`+uMBZ@d`+oAI0rQ9x4bUvq6xX}YwEu~-|kIo*`LaOgfWd`g$j;a{tJ zc{f$u;Xnnt32JDr7o9B^$!w?eNFA@1s=Ru=>HDaEVj^(1l_rW@Se7?uSugbEJ!hF` z7?XNRpHHX@8B{lMt_$5$eph`@p}{Z2lyG;iIwTL*r>%fC8S|?E#bt$HR(o^=K;I;c zrD?3@gs={;$aP+H?Y;M}LFRe&mByOGi=qWOD-R{xi@~sv=0@hdgQ{%dMXrr9cO>Ad9IHCBmyvk zrp^U^@*U9I&c}1{B0#2iP%n=TlG3QZG- z-JYOeGl7%Lak|C-{13}{h4IMlS0*3O%`JNNJ+)}``0}VTJ@K0!H zC@+5#xDtaP2mO28NlY1@p^UC0OJmQNNN#kq zwvXuE{|HP-AA^f^2FNE*o=8K%HEnPAeJ00M8_*yq<7E~&I(RYnQaO?2S~VdoglD&)rA7_g zZVU>U^2TWFC!2_y6+69PUi2fnT6}9fVi1H-Njck@@wQMQ1;~+@yCq!Rhm$Bs9|FedTJ`9#JWXz+gmGrVU9Mb9rWMh zYX{nYYBkkp0wRE0w1qyY`V~O!j%-I(F5w_92E@FQQgEOsUD%t&NA5 z15mNqwULSs&DzxFDc>6?ZJyt(Jbte@Nf`93I|P03-~kHbcAdUesrIcMse;?JR93GoY;{rS(RW&L zuxk^UjklmxJ@mYbxEOw2WW*(In7KTvGu9BxL~C`&MkANr;`ZnKS&pbukx?ouUL@h6)0jKu>8}B<8STu*ZJleH23z2|eyn zxZ2$p!)eVDMSlNoApXYpN7lZH@*iSoTxFSD^*}spsL^JOpQ;^0Hk9%~+r8YBtl+IK zj_v5zpsG4~W&@>Z_H&Y9{1WaV(`C5YkG&1mbMZPOB=gVcB{dNLRB)R{vvWXBuaB{? z>UCT-!{eyxW99pr8?4@~g zmYp7Hm(23c>Kjn0m>b9{heb4i+#=J2+GcPquSBz;Mh(&wlr&fwKZere)CevH0WfW- ztR!x@l#Op{O1p=HndV4M>8C!Xq_b{`dv2O#+#hHzdSMsXue$RPs={b@%7jasOlXEUq5PP9?bS)R*d8 zU_5X)-HWV|R1ValJntC~{9fgp>V5XyUF=1hLih9JdoZoI_MvCR1(O6ZiNZ#5-*r*L z-)<{ihkd@{-zt*UMUNUR+n7=lVaR7t)i_$$bPk@L3oM_{>IyG^vdIu)xY~qQS>AW| zZx2!WQ0w)Xk&E)v^1`QM{&MFTC2j#tdcoh&5{Hp;Zq=vPvO_DE+G`~X4fi1L$6O}X z`2CCz_d;EahF_QKI&?gdiTrxDH6D2OCh2tfx>L2Se(cB>O@SmG>C)0t@QP_Hyiis& zl8z2IE7fPM^w*?YRFhEjEzFkDDcw0OeP6ShbUrY^U-1n7`%7;>iKGX6I091@$cp75 ztg&6bgfFAVmKs!l)5Wyu*F+(dI?+-!_`sum!P6$TVV@AF z4`OnntAjuJWT}LK3htCuIA4~gLKe{rlX=07H`LkcY34vdK&{m(l zLuJk5%4l*N@Y&;H*Q|i!E$9t_Va!SsN**6hQB)GS2hR$hAydj9J|uzul)#}dHsXR^ z@XZEjLKzjZ4W!kps9dyP^N`q*y6 zHi%vp8QkW>c*$h0w!YR4WPc~;8nr{-7u#3I7u(iZTFDCj{p|+sqh( z0?W!Xk3#*SmnEzgIt!t{SeTx9I--A8Ijf_cj7F-+K=&mWQ?-_i*I@7Y!R{9smx((& z_e4cKwq{iiwLl5PW*X*}xRJu8z>V&kY_(3iM>>7*RcV=Riu1pqCA4&JV&YKwWMtsV<=1kD#o==N%E&tF5%?7Z zqOgQSq)aLPdl0G^Ppa$~G8c1`&1d3HR6Hts7EaqS;GU*G=xJD&EAn<|@eRcohS53>~I>N+#ctH);H+L7FXe;!o zBd*MO^l5DHpYZ-Rdon~%!ke+<+WBt%@?XDGG zdNNpi>CdHIsNsq+Kb^HEF+Lh*=4@osq0qmiK&o9nwK^)Bh*v3(EDPs%iu>vgXcIYi z3qw(#aiJ*TQ{9QrbWchb^AYKZL;1}mPM?2ZuqgArQk;PhZ=bbo+-tl{Z3yE2R{SBn zFfJ`=6?s=M8p=l-Lj6?_72Fh#Aa@u%3o(m38^N1HWPpS0jC43p(VWsFH3-t1154EY z)@(nd=Y-eF=#T!5fp1kovCMIH`2@r~%!yAq8n>F=ld#*FpPsJ%(K3F)<1st48(}mk zG%2%9tPM%d5&XL1d{E-who>{;A%z%{dUTM@ZX(C7@5BA!}k~E0sKiqfnp4PYKPBU;MS_{^pY5 zc1-B_Q3`+PE&nWY*^_h@VDo*x8)gf-vH-t-z2NGCYa5(nTJ={Cc`43)C+fiOkfC35 zp5N5u0t&M$b6Pn+z^1eW0nkO}F}1I;74-jp++gYwpWWrNvw-_Xzoorr&GqJ9i?o+S z%ME9ijg`2IJ0jQ2xf~LTWW_!MO&FTpafN$48es(>H(cpSo8By6zXd+{=*z@|H-uI3 z2d-Huh{xT{@fDTjrIVSd=L9PzGc9joytmGSx~7|Wl~rTo>?S_*@V70TErzR^XTz@8 z(x=O2ZI3<2rv>7R0`C#L(!;9v%1VO8k^R`>svl?|iYQVvhfuBD={Lk4pAU-c86%uDmPt3j; zw0;~SFK1|daO>@#m-=-9r-q(myF)zz9$jxm{^GRH@=~WW zEuNI=>T6s*%&He%#0vNie&fHKbW;})oYuK?8ge!+AE=QjwpP$<=zhqXmL{ib#om&% z`w`~7;=}B6wLru1&9GaXcY^A3q-$%|HilfhbsOXL>6vq-dqw_7SGs2^(c|~!K zs;HM|Ou)qUcz=nDxAXH`M&WWu-`6xNOG>J~N_3cduW9LU3u|x6^)Ab`Ma6-b^OFu; zquN_II-Sd`p}YchiXT&{{z>~aMXZ1Ge|QpCV3>P8#+YE6C?(}pvkJ|yT7S#d{?(lC z7bykhmErP?G}ip5JNDwzL6Wr^J=|~ZZ6bYhuch&RSOC?ctCl1mh#JITSenUUs`f%x z5Ok#}l0WqkH##2Of_=+7>Aw%OVSPVtbpN>L(rF3Y+<7030BD;GDuycW2*Aln@&;%- zh;Ap-f7%qpJGQHN8W^s;>a)&!3g0Ss#dCKl0p3fys<-epIW|CF9i6Hsdt^S@TFTIH zcw5bCN_$Jtn6Q>55#0=a$$iwvnTV8wCh0d}4nSp6*GKhtsjwJzb0h>?;EHdpNzg(9 zpz}dfXE-<@?bPda{pszjn-mqOH!O}6#km>ng~Lv3?xVPIiu?(yiK!JT&QR5FLD*aO zgvHaMG@6o68@tTfVo?K}Tm$1Zk2*vKti1#1EoI;B!Xz=mf)0A4R_7K~&GV%yz#6Jy zHCMamcW$q2`)~7;&Mz~+Z-u1eXCQ$sCs)U%KEYm5%c~rx_)%~)63RI}U6&KdYZP zUS9Xd+!!`x;IwD~n^S!C1qbG;^}U<5PVhSjpBr(H?K0dxkcBI@qG~<6T~>b!^<%2o zpctC6p$1?&XMX#(6$s+`FqUqqT+ejv0L1^P5#p zNgD5evdESPm#6vq+8W}xD(%K6eRGD_oT^vn9ZzFI0qbsVRo+~yw}P_%!?0I~czxiV z(lJ3Sm%dnqC!QfQgv>!da5GOF0)2#}eWg2*Y-=jFK$UkX`z2ZtBS!;aH1<1sbc~;c z7nphTLvP`u5P}adfm~dc6++<_T3on_1XtYZs?&JQVLN|O@CqE=7ym9vFrukBXsD%} zxy;zc!TF5z%riRe z8%$F3kEz4pfU%!{^ zbj64U_Fd0t($@%`u=<>r)QH+E#GWtXAcr$@@YmFb9rw$v?_bPbmEBK)FW#jfF%Nh> zaq{P@skcT_Y(6B7MP?k)R;zi0Km8EL2;uFkV&0dY@WDRgfvWy^0YGKnW)=KBwFVq|-870RX|PQ3T8FX%=kmCDJA|l#=z!$`1Zew!HsLY z;0IgY+`%W(gLCs-sIGiKqxOENZ{vpqJ4mHg7BS;d(hWW@kLGkPvI?&j^_3PLvjlv^ zVyB{?4f^unNkL}`ug6_LS(%OgdST&cl)t zQPF*MU=Z4g;KZxQN!o#`&@|XiFc~8-aru1S5Zi=D0JW(E=U+KF4@&KgIQz=xt!>Wt zYP_0v4d6W;V7KUBdaY@#z;l9`s<4tOGVG zY+Non;n;(%3(Dl+s;u^0a5Xh;-{i`lnzQD<#Eeg6FTRxTnoI=Qmn+DVuU#P zFnF&SEOaOLU(5P2%t_nxMAxv-wMYF@@nqWvmGv5YEg{SPuP6fR%Bk)vqw#FW z?>_>-)vdShc|}dlOT_$pX02WiS9a3I*4_OKlti*X^WP;gb*_s)C@qF{>Sr_HRlHXZ zKa-`Ib?pr4+n!dZUf}h{<|ooa{(#O_NR%vw3f~&83Q*w&M@m!{cpdb(aZTt^w|=!o z_&Fk%EztRqUb*8~WXNjmy3IfKB*G0@6DH}wx*YDg)d{qN0CXwpcZkc22rKeN&L`ixanS+1!(OdoQ9>zVZQBT zk{e7$k1{rX&-wp;S&raN4dxcX+JkAfvnjT$Q{oK`Zq+OSBMLrVm#ObjH)_{Aj@=0C zYkO@@WF4V}RG^h1OUc?!r4tju>Sur&3roA0DT4>yX14qQS%G@y>spP&g_h-d?YD;Y zPkv47`o6iAxJ7&snpnlRti=nq$9Tyd$-Pl9$)QK|0MC;(VQtl z%1z||+ClK$i7!-h&At=MgH;iie|_0s8wuMBJe>Kk{>}aQ_VDAfImuM{$;@jfWzEQ( zX1O-I&(RI{&`cBicQQqlrYtvlYDLew4Bt#QXwS=Mz7WODgD(@jn|_>)g~iq#ht7e` zNhXUs`6q0MICk>b6?zGK9l88j5#1ssOkB??hd_|3n;OOOO1u6*A*#RCfYuMpqE%7Vz0LrbJ(`IDGE5`&LbWT-r1K_%>gx?`9-C?C^`h&pDQ*Wy}Re&5y>~jNKT1*_xiU%I_ zPd5QqLE*ZzQbduxE<*;q61KAgwE2XAL5=Q_Q39N7WTDKj?K-1TFsnG!>=&=9cu=@E zCFxIR4T=)Lbo%WT(EYqy2`(n_F61e*E|m zRMXu&>a$RZ^DdThi@sjBBF{YI0$oR5ugD7z^^cEOus4`)89AHeEkYb zlEHvy%QyakLWS!}Ojz1%f=h8Qx+f=5Ga^m~k!`Pg2TH>@zqk`_F5c2ga zuKCKEhwQu&gj)-la<8)y?rSo_Q6aILHsKcCTNr&PQTPcPmI=RLhc|~WGFNnl<&4qX zTMBP8n1yT9NnJzAfW8|QR~fm?XaH<9BI;f#r6Q_HVC4*Nm!rvRqE%bMP8x-(GEmY7 zc!rZtheDJdVd^8#KjNi+jMsGP-5El;c@RY%hPiR2tU~zKg&cc#&4)WtQ7AYxN`D|I zU(m`l4ps7=K4NZEkDHp#4&b4J8dNag^U0KnE{kjC$FovGCPz+62+YM%lQ**KBUW_) z=%gG6Ud4eCz-OmhTmC3^E7DpHaF1U49mx5Z7VmfRQpDKjYd1+*sftY_=XtJkez9EM zasQn2!e$(|>XGlIosAD{LmNEC;=k_l481*sb&LNeR1S}es-31bo`Xx%IoeC0?NOrI zTv7T1|3loL6@it~isbm}x{fb>XcgL5UukXnwGzrZOt<=xGr28XWpU#dC1D$vqK@S? zvQa{@zR#u}@0l_LZ07w;a#*f)^tD~$_0IdkzJFF!YiLE;M4P)dq~;11Vax#C6>uP$ zH@DR9(m0ow^K|Q-C0?Zr6-BVN`|;b_*(cw&p8RUQuqRaSR1gn>J?(mh^hitM7EbL` z8ow+C_2duWLaj{X#+?&Jdyt0LEm5)nh<71w_C_BH22gk z>m)GUB*nt4ZKNjk58Dz$&x$IiBOAl6w>U>}1#X*vK~YBmZN)(|7&hP+QgK&6@QBTB=OR7|279h0E% zw+N07E1B(Eqd(>=0*@;oA@cFu@DgoEGlQXu_%JJ;_C8=MXoDO_<-js8iWS-Mb4skRiuFrqq1f@i+zRyTvB@J`Hz(I^+yGZ7%e8oC3@AvTG56kot-lpzTR#sw$%*d?c=sRVk6K=! zdR5p@IgIXx!FSbUy&wa7$;Pd~K`)+o-T~f_poQbxkE7OC*f;%qNF(YG4r}`fPbu$? z+<81b^(qX~(&ua3q!p|X^8KfhyW2tK2sA(ejjve@WgC;HIk=;C@|NuM!!v4cRv*zj z1v%T|$aqDr<7=d0G0LV4GZwd{FIy$589jkSx@T%U0e}V!l%+N*S+IzTN=};+cpG(=xM(!>x?o z;dwja-rRIfOGzG_{=+MHiUby^abVeV_0l1V8;fYxE<`tTIrJ|oazpbm^bmj`7Eo#o8aZ%zvE}zU+Cl(~;9a|8mf!4sFhv2YsbQSAUivo$x zF;NFRkKa4vaHX*{c4e(|2^A_^muoKKnOXN@V;>-A!Y$0|e@CfzcR~8NRDhv0ZawTf zf7DyBK>;gm3rxKTsJ2Hb(HYC|U9N`8s?E4f7}GpkIGYN>9(uECP-K9Shk>mbpVybm zKT($Ll%c$4sPqvaM*@h0y>INNkxv%v2=^>PD8vj|H#Z^k+XsRRty_(o7^8!!%Z1YH;od0*EtRYbQmI3B9!h_q5_mQCuEP}KT&9PO^)XTP#Q0(SXcHnnKy zJ*7q-LrF=nL>DO6ytk1g7dhELi9WLIH_Z*K&_@;s2=Jf2mvFyQWP9EsRav~@4{A4H z-_jFXWR*8@?n?RWEY|uTKj+`)R!y+j9`5#aVm&DL zEI61nRFK`xQ(t`$>`NA?X;~(chhU)SDx)X>Xp#h3nSJ}$LQ_sRmH#1Ke z+#X!z;DzLz7@H8P)@i%v?EC!XKQD3|i5m@j@ML--$q$gtS2obS#cCHvbDXD9?X7nb zJ_j74Mr+t{NKr7eKugw#36Ka9=L%{=J@xg1uHA_ zb8xh1fgDiqw^F8f^!RbPQ=GSrb97Zt$50bz>HCPB-9*1VXhe=F@lUO@`26&x^}?9n zuexLe!>+N|I{#16OTj^g5HLbJd2IpoKLd&?4(2})>1bzKn)iQ7D6K7h-%spIPa0_7 zwoufvGqxGolYT|-(;gi6STZ7d;4|&A*tMR?sSRshLFe^HqGk`Zq6q7U)?VqGeK*SN zjfBes`Cb;0t~YFAnzu zS5B>fJ?5TTHbK?C1uK3=u4jeZMc>48mR}2P8-6qY*Llsl2`0$~r)&3Ga&S%~#p5j4 z^suln!oVHIGh#)-kh7{&-mItRQB%;wuO)htp8Xnj%?hKjSfvDO4ey_Gvpsbl%bCi` z#aoh*S=_3iCDWMn%#XyK_XHCH=w6pwU@_~@o*JB|bx1h%C` zm>RMy+uJ}8^kAw56!mHGTI=n7jba3CVq0$uSy6_`Zk~xq3cNyKUUpm$y6?|#Yqxnv z%Qoe08WvVQ3-5+OfnyoagOs?ndHER@fsr$G(i)gn?`jT=LD@p1euI`C#Q2sbPUwwm zX2im=@ykeKPurzsiYp;IV+=Wt)gRdk?uxP+-CVW@yb3z8HGwJga{VeaFF*;t2N&@s z^+zS+px6)aa&Ux&R9KJ}TV%=qi^g{`ZVD`%f_O_h<{ zZldPQ?2=x}={y(iJ-s>nwYM`KSpR~)dpt%}y6$W0uy?*{*GO@B<;;Tk8k3VYM32Sh z3^w=KnNdpNJEMQkK04{;;tD+U5`nJb>uY9<%=0Xa?jA>PYnR|jSuJz-@^&0+KeOQz z8vDT#OTmN4jRR>b^YBmGgUP63K8&|9{^_F+uW4=|J&a0pOTb>vpF>u#n-dR?kxZ8G zP{rUgXVuHKo+B~+v`R{tIB&3$L;Y=9<+kB!t;*aEU>=ybvvr=IRG!0Qxu2g*%{$IG(!Yx#NR4{F2 zQO$tQnr6$sOr_<>kwCSK5n1iRar=I6p~x)7^23`X>k8}o(USEY@pk6O@25+Rcb|5B zcUb`C1lj|lMEKR%d`)(r;SYXI1L?Xtq_qu{#eO}$x>JRFC9{nC$;#wWqHwmr^S2I6 zU%9X3N!!twv0nifrc%l9W#y9&QBhIfOMHrV@W%_FCbXcLmJN-e1m-Mkyn4C*Eg92O zD6adp3@;!Vk#YbbeY@1S z)bGIm3u}#Qh`rWB9@Nl8jD@lSz^bN(7P}>M4t~$AZxz>6fXeU1GZ-0AY5!Aa?K}Di z1YNDu&7qzTxkPQZ_ep!;Y9&5=ZsvMn94e?Y{N<_$?pwTtkx9MCKrI9$4Kv!(9>W>!9XL=c>GR)ab=%$;S zX*O?{i5d-8$*<*-U&>87FnV$0dAd~tL-dY}hnI)#?RtpOkYtW+DnnjABaqT58HMSW z*m&~g{Xi{VmELxUwM;1e$2bY}gHg9$LYw~Vel`?(7=e6A-mwFK>d5OUZnzl%Tq%KD zv@}@jlMalSVrzdVbZ$wvS%*tbpfs3gH*4>tjpm<+9jA}_o7A$?PH0^e8Gm!Voa+bK zZ(aw5D@kT+#}5PXrHw8Ab4Wy8=`20gh~pFP`#|lwjf1AH{F?VNj|^dH{N3e%sfjw8 z7Cdm)JT_5XU0n*zKWRqW0@N*yBc6b75Bw7UWwqiR_gv4U3TPe5x{R9=_)Pop^kg6-gvd5tTuaC1SZ)@mkcBt#PL%GS?Jon1 zR|v$c;3#m6z7D^n(1A1zZ$f{yKf6LY2bAE(tY_wwu4`pNYIlHc}UMW;bzmE2Kp$`zGda=XTBV!ugny73g`d^NP%Fvx$={^tXkPIoQ#y z*0f%O7MMPri^O@qoJ%@uWNHt(h8GT)YftQLtMEYEtv-JpcES4+_3?7O5~Lw+$`*uu z=IAYmF8BE>wL(&Hy2nu7sn|yTD3ci)c zj81Rv<0_pH+V__GU}`kmEhD?_|88?UV9$7+s*yS{e{#6S+ttZQ@W^T1$TNkR9(nz5 zK!;mt{j1zgjrGob_dcbk$hZEyTC9%8+>%mWh521%SK$k7Il1a*clJznGo@hH@3p`P z4NPHHPov*h$tQBrB0uqGc6&^JwRMQQPw!N2l{X82OvB_^T!4C9XMttXx6w5QbmiMoidErSaGd(^|o`py{CI42?e1(QaKKi==pWo;}m$PS2^u?JcWHPe!i_n?ysZG-M95z@C=rySD{?CT~6oxJtxA4 zoQgkv_EeHz0e8Q;e?As%CCzN)mW$SA{=)f-Q+0tqCU^L@5BRWE|kXF)BZb z)K*_0!(D)BiW&bpUy&_Y`|Mx?w6<=7HZ+z+=Kue^<{6qcaZnp8p&GwhD3~`l6zY-A z8+j#!B;CQgM=ED7{i#|L{+YG+gUeJFWnos>_+^d_+JY&m&wyaUdujGJ`4C|^38CtZ3M32MFG@#8y?X!+N7KI6WJ&bNJ=k10@!#~~LntAZi9&@Mp z3%G)^`5YtBJ@%q1xlM4&!ZuKA&|^h9@IUc(5~?|jwi|4|VhKp%oM!*j2y_`1+urSZ z-8-Sb$a^%FCYQIEXy0&IfAsX=C+E=Bc%oN2qrtO>*T1dn?Xv6_p2SUnc=mbOC?nev z*>kC@jZ>f^@VJY+>@%c3@@{4RZ>^o#KU*w0A@I_~vdg2}XCP55$YPi!0O|%C_ zH5o8^$Uu8hXij4oh-msqJb|!Unr-?o&I1vmwF~NkNUJ?b@B!C63r^w!D<^BN=Ht0U zCjkLy(w&P}>V$A9F1AbShP#I0bD-)I!RaU#G{v1b{o`ru{!8b9jEu}#Vv!$0&zv}L zZD`0ip{Xn2x@8?Bq)XJoyIzGt6PkW z@ht3AICljW6_`-(;2m66ntzTqlEDtOx@txw={$=)e=}BHfB+k}-!AMpeIY@QJt4u4 z<8Di$Pjw$^RD`?(EJqoYRxMG5E#X5w9eP~>PW$cG#|c}?=RZb8ZiB!DyTmOaCS)_` z`y|WGVm<_Y`-+^%rXzph-iAEnc-D; z_F-h!8|Z*SNZRxafIiQH^U~5;Og-&(e{nLZa~fV@RC+Zx>%z!fDuUD|j%NX{Vo9Dt zk2mQ6jTGlg!*d5fQi&Jlu+{&IMc&anr&@6#p_ig1(v!lCU;Xf?S3FRH3Kl!pxL?rT z%vmaU3&9BQ=7#DMEH-OmN9%?S+qO|P!{K?Ms8rZYyZ(!>E_NCNoZG@yRhGB9ZEPPc44ib_8_l`0ng14 z{3C+*N8TKWA;-oBhsgiMH_Vol->1ROSK+49d7tN=g6+{wJSg7G%oSAaI##ZLu_;@m z?isGrrtgT;7mWv*Ej$^VI1`Acy*3PoEuTET(!* zH}y6$B~#(7Ps4xYt?a><8S+TQ8{F7BI@2{E)G*2hbvYWI^lq=WFYMQx5R1 z2^Tng*WV5cOhgw)Uo?I%`Yy>5AD;8#`CENqF3Z=w3iD);p;%_|5}Tj5?Qy;69zBV; zIWC>D61w~*r!o}))7A_sOO=G8zAgaC{wY4jN_hmb1zruCOa0YF#K9=M#Rs2&=qXF@sw|IM>|G~e`{({2rWt70tgzKRL$2}yqOWejk z9^@wrvgg>k11$EGM=>F}7$?J-Z;|pakL5nE3+eTaMAGA1>E0I1)exy31xr8fW2I2H zvVGRK-rnox5ae*K8?UtPal&-XZNhJHw0{<|N;2)}J52P#@w>3z$}M(gi1Kbi(#22+&L zp!E&#C7t0g)u1oPKIi|1Xvq-cc??*I^-cden*ho;$9TjtIrkUIN>DyyqZHbSNSroFurc4S9%le)`>D~qRyyUOFOt#n4ygoneCHwLm+JlbIw*Y*W=kQ6w z;JV5@;Pgm`(_g=t^N?+{V5vR4&;cwbX%x;u_~NO&|A@#oTC=wbwZ#?s#xmc+>%QOe z+$PADZUs8BXN8fZDZ?GV{t3hdS)-5YUThaJpY=?5v+zg3uzBkI_(zU^ z#3G<(Sr1E`Q<&d%t7DmABhTE}#>&8xSU>YiwGf}v?^khZEzYa7kZ=+L z5|r5ZT%Yw;&yQ|J`PZ*0t_!0-&ckF&ru6LUr?+?`KjYT&5Lf6#=|Z%_+<=_rw9}Skl+XJ&Yi%b@}dB~wn>POX0hk(O6pm<3&FSwxUR8=BqSeE~qc3y0H1kU%c- z>~#&>OW|aC@QDlv?9`~)QrE`0TgVI8^$4=Ek_$T3s}{td9kp^iJJTz0WJ8P8vYe<@ z1PEF#K{YvtV0E${m}v_t6WPiEIm4?X;Iv?{A&5lN3N$4$pNCluITpE1auf>_vJyK>?#;j{l$@jsRLd;`UgWuwjl9> zx(m7Bn-G;C)N{hQ^{(#l-T49A`3!g+A8vIB>UQ-uo4k|52I7c#KHa`i8jCjexZ6f5 zn#GHO(46=Tsm+GP(jxUqzidxsbOZ(;?veKtU1~{1i~VqVRG;$y(e;*LQATaswuOi& z&CsHRAk2V(w4{K*Agv4of(+duodO0pgdhweDIp>`3@IH$OG$%(ba&^w(EE9xdwaL< z`!kz=M4W3~Yn|&nk7GY#c2&N62y!XIl==hg%(;F5Ek$3z>-~9A`=MXMDG-o4hc5c$ z4UHv_bHv0nnq*vo%8>onSitEP*ayUnAN1dd7Rp|{uW+%f-0v%=C0kKSx~g_c^c(?G z!f!n4oyO|eu0=C!v5#8M)5J>w$SjQU1u3IQ1G(My#e*#b71X_TFR&x`vpl?(I}6h$ zJfM3u2cI^GNZXo)+~e}c*J#c!F5aV3w&2*ozTz%%Mw`027Ts+Pv$LwzRuP1^@lKGKfwF1MzUGv zH{&)VU7<`&D5An#wEW>g*jH?Fbg+DRVgfrKXGhAzYRV)CqT+(joH^(QvKgTjUG42X9anz0TTMrY z#+Az1&8^%K!}`r}dPYLa{?=y+0rE0_p;(CHmj{S2S?BNGRCxL=NZ!?9k)ENU1?Xnt zV-6N7Y;%MM?AjF<9t=RARVyTzuJw-93sB%MVg9TmY#T_DYJ$FKSFH~=Z}kUA@(Gp^ z_hd!aK*pnY^A3vh{w;dhLYDRb#cOxg6zQvs;E~e+-{#0TbuW$jiTy{z^~=?t8C~pj zaU=F0etW$LpNdZ$8_U&OU9MVLt*SEZ>+9Klvun1#2%4KSz2EYN`?an;E3F-h?^S>rW34_E?O*2BaUI>3?tCIVWi8BF`IEg^o%ttd zy3k>3kXLAcpJUSFbW_k;+|JW)ZAUmtnW<3(o#Vap=jd}N;&w1`R4y~0x;fud^co>Z z7l!`c_OHsyyGMl<;~OIX=wV3??~fd0fq>OAMfm0vHli%-<26pLbM*}fF~E9n`yT>b zL0TF4cZi2nv57ICF7Yj@>-eg+;uyQbuv0kC&PhP_?t;CN3sgXNobU)9+q zjb-J&O}GCAnK_^!W^2`TN{Ru27KCV>6^<4p8&6aSLAj)7Zlz?XX}v<{7P~7p&3(&< zi(GM$Ulh&g2su!3H4<-pQsO+i&D7SPt)&cI)gpp#k%K9NBPK09y`1A@tH*JR@JPo9 zBXJbv%v%-)@H+EXv9}*>VvUdB!HO}DJB-z7^xOL*2AJDplc?HqD-O&R%r_xaeudcSk)cRfC4?WLw+}DrkJ2bR1}=kFDj5zlbu&Jt&Q$+Ql62 zUfrr|^`}@|o;;OP?r9BpyZNF_Hj^;msdeFozCw`p9gNp3^bv|Y0%~N~#e&@@NYB+6 zJ9;0;{Tn_CA!aR^&I^}kv22D-Kpk1qB{3IxD^#i1RuDqpTz&`9$pM4i$pBCtWtM#N zL~F`dtSj{Gtmanv%007>pn{ZsKje4D{U2Tp?$G_*A$i>*-$Ecs zzP@KDy?4cGeKss?H692gi{uY=JQES9k&MMvtwq(M!?&nRfjAerR7L0kIi-@Tfx0v@}2+icrO@~4)O4@oD> zL3CKQB4JkEC`lY7Gj#K5K1-2JW$#wt;2U06R~~3&^(EdXFa}}nPB)rc*Ja7uNQb5= zG^mO`>IVGRHWD_6FIdi5uiq8^0Mqq!zD9g-7z&iy#cm222mU9sjOaPZ6=Zs z(MhNaHe0`pqEZxXA0f1S6FX5vTIm*7nVb8}~ zLq$6VB+!3Lug1SagAZFYTB(|u6D0JlEOZpFo{QT}rsbN%@WV%!0Uh}#%8*xKAC6)~a zGfti2@|MkPsuM8Q$kt%PhzKb`g@^NS(*Bow%&FkroK9>ldd{A8`^}c=%o;6}xG73q zVzI{?^e7@L*00gH>9^dJF^CkC#c2nzdo$)=IlfMZn$8iVK>e9`y7HS+i`YXVhm1L* z4kJH%lf?MjxLXvO$oc-HSZd5tHc&r0JK_Q6VBAz|DF$_bcnOnq@DM zPfUFG#O!Vnzt7cXskE=w^vhJO;uqJ8cp|b&|BC`{w=2_#5^rx;jbx~C64mzF<=V*? zDE{JM7wAZpM}GkVyMSoZ#pAAc>bZwX-@m5zN+avQ;I z^CXeTd~KLk|L>tr>Ep?bCT1!3^$9RJ(yRB-$Za=KCDK%f-?$U4Oi+G%c+`6rlx9;j zL%{pqCKPCYv*6+dT@sK?JMF4v-k92CNXvjU&=*7$aC{RDxsUxEOd8w`mkJL2 z3EK)qWKRX?;L?l*lL%fbCrL^mJ+>XwRcOCLq>TMD@D-#JNz!BZc95$qQWw36bZt^39)T&a1Nqv;&FGU&vI< z%9U^F2|n+9e0&Ct?@LJB#P9FB$3eh#ksFCm_dL>8Do0Wq z_BpW|C&OZ9QQJ>B6?9dK*aq+a@k(6F$dgaf$aX|hG2ABpDWJ)&4BMMhqZU)GsIlw( zhOC$c36$U2ReJ<9rV2&+=MCbvQOYi~jy=mi!7jB>y4<;OpV4qEuf+Rk~$#}@tXG5CS_ZrK&(lqtm2 z7nqo`3RS9wXf3sL|>wYC+2olPb_0 zSWg`BcOSUk7OK-Q1YZ~=Z!M6NE+mL_Mi-px-KLNA&z``(9&+uuDH-r!3;*lwAftHu z2bd&FjhjdcNtq?Rc?Mom)U{Ip3nj1s{V=M(`n1ykF3xNJc}cn}vgIgSG4jd+IY8k{ zfQECi)#drS9319mX89+^4i033u9v3Ap90|Nr2Ap> z(n(1WJ5a@Vz>iq(2J^qirf$N>{!Z}s9feO;$A`SbZrDF{aFo7wr(G;7 zG?G$7J^~{?epDmiD@Yyq@ScUSw=uJIAZnRuTr1jqjV|wD^nBw(qJYf4g6*NlOd0QG z^RE%#YCYNPR={$7BoZ}lf&Rus_oFtD$V=l5$O9zwCD!6&(S*^?j!|}(2N^?VYR$eN zdf)|-$+yrLtjXgW5^OFIs$X@JB}Os~@~9GxWsp4J zslFFf{Yd_ib9ov>v!M&kf}czj8P$>~I*+df5pea8 zbkSI&pWp2#0=+9iHU5r7IzV+=*{(=uQqON(ME07|n4&LD<62#i#<IaSK$O=eNqw(S7O%)31@PLoTdYArQ5{a$6dKI_eu7PdMo)Ae^0&I zXZ}7%yP;uWKU~h-#!HWdeU~HsPPJlAvXX{QnSD>+kDsP`3`az|OXWb5Fy{ z-;MGR+t7+QOk5E1VtnYH|7H@%D9hc}B%SBUI@~bjFAlnG&z3oOk7A^7C*xic>C%syN3JEK-cANF&o$4F3sN$Ctu^)NO)=7&=O)%h2LL= zuMhdYLP+LOYQLEQTw4ORasY*DG@`bTF>Ei(JqP^YaEm2*MEj_oQ$j;-0uDIpm*1wO zvv-_BGs?)(H1yb)FC4L-UZNbgQh*cjV^5X5!6ej?8*Q1-2Fo=uMk2nmTjkRtHn$>? z$ac6Ujty?c$JGe8N-=}1Kph3(qpncLQ5MK^!_9$U2HSJV(f{2w(qP5*<5d8I?swXG zCTjPpL*nwei&@lgeYUn&WNBo(1_pqHT zv4IiKsm~oht;PK&wc@Halk5*O{LTuPVs={JmeIBK_C~E8HKxE437W#0r3^B)7ok!< zLm86!5GL6O*Qy^cALZB-V3H1dzvi9Bh_w|G9ME-T6qsDLx2j!zqvrbphN_Kw-02Y9 zAt@)qGu9CZvBJ=Cif@G+<#Z8Vp{KO%_*zQuCfBT+pk-Q7o|c&VXVq4I$Xso z?5L8%XZJ(N+~bsFua(VPem>B$rV3;!qmNv+S~xy*v3zV9@s^Q@^||=t{+O(^Q{Q8E z&JzZ7f9_cY=o+U5$y-@ASdIWKb}o($Dc|SdJX*}IpoG+mLR<-EUol)v^FcE_rMroJ z5ccVV2%Kdn5m_cP*(3JO-dT=AD4~W)_eSDu7SCMw|k3^{d^Y5wEpU*P%{7S7PYS$$;)d(fO>~>kXUMQU&?v!dDc~h>fod@EnzO+LWCY zd!q9yeju_39{Z=067l#R*xQ#oS@!{dd@upD2(cQ2P`6?d!hNgRTW>sF7_Z)@@v~T> z_8|T{ZV@$qtxO#~oZib{RCp|v?)p6)rI|VS)Oe z`B4S~%(3V!US1fPVul%>ef+4WndA65{%mgs%2llD84A(Vug6cA9P}o<|GM3%qA>qrtE# z#m^L5A2L_G#J?Nk#*mmRG3T~7ppM>=n6~}s0LsN;+vUTsa-*_E*1a4j0Pu6Uc^(q^ zkQpvyj(_`K|@=bv(rX$)06Ff@` z-&#sK-(IIzYH>4qDw)NfPH8Z+s^&jj>q}#zJRL22{N$BGxr*A}u9sW2bk8|^Cu%Gn zMSE&zI*Jp+FH%)!Xvb&@a|>o+Ui;X7#!pd3lBB#npRo0}$vaVQ1q!h`L!w>N*IEz4v)|O~7VzG!@n~;G68-hI9-wiD3E>IMQdBW%tufV5O0yjBV{z3VfU{nC1NkkdL8?y$2pceF~tCEK|@+Qf}d5 z<%F9p&Mew8@Ic6q~4&I3kMuWw(p4lVLs6 z;X#8*h!gg{(b9Oq_|wV)lkqnR+KU6xo<^2c#DSAs>8GQ!=KGI|rrqbnxa)Y*eSi8s zFST!RvU_N0ud>NLVsQPGz3Ljye_8wA!Kkn3j$vOczIRacc}`USiLy7z#XE@^b|csu zMQ!U7Gnhg;DuDrvj>k9lw%33cd8E^JE6@myHMh=DOAvDbv zg1m}yGm=fTo?{HaeoT``vI)Fs^Ji+1$|Z*7qv?^aZd>yWA=GWy=`|EZnEf0=mrbOT z+_#<>mtBTPQKG4$Yabw|8O>`ONtcVH=dQ7V`|jUYu7i$aWv#9n?b+h1DuH@QU-7j@ z^PXAs;Uk7R5*PoCY^M0Q=tH0MVjkTN!YIGAUO&z6k6}b5NCJ1I;&HGKR2KRh9a ztaj7N0_)c=(fM<(>dm-s8q@K4zEdFuRA~8LFVdg!51DvuGI#CO>7krEkU)Xz)8+Xg zU9K&?QKBA&7CmhNwsi$Gqm6Mx)vo>#WN)mX{H{tP>T}4a22Fd9sr3NJl-v_&Pe&69 z-0U8XW-aFc0Fkz#=`FBx)wSECm~+xas$t`>A>3J0xS^6tpayA zSW~m6j@ahp83pLsRTH4terfKgW?GVf#!45gTx3sWuE=e5YV-u2J5P%=Z_ZgKx zVJYBVFnnI%!mu>G^iV@z{b7dokgD98rZ3HIs02ci=lFWCPyNkI46$!Lv1 z0Ml=tC}jaZO{k9ETRW<1Rljz8n)m_;!}Bt_#;XEI{d{SL2ZU;N_3rPVP*V8)$}tAE@QKG?NcxP>Hn-;uQ6@O35b7sBMd zz=V+r9EC2%mpbhxT{=JTKcEj*Ny7SE18X^=4>{l%ZsSzVxTwR@BKKIQTux5GHys*0 zHTo=mI+@kRFO|3N309hj)2W{(YPxX>e!;w#Q1)q_%~J&0rVnT;UP26waReW|`|iX> zf!^o%p91PXTgdM2LXJ3FY)n^AHzFYyNX=VYRCLv1J}wLus&ugNuExqH&6k1G%I=UP zERpNo4yJ)K3Q7M??niX77pJDjWmN2E8Gm+P%g){}l%j18q9JodCcjJ-lX?=pAQv&e z#EMj!f@abOIJPhV>;0gpSFEKmfaU%0g_J?^xJ*31B(-r{>zCnk(vS+2clmP-m0X03 zQgSmgE$RKdNht-k^j=o4KFSgM0O_hGhlMJ2;#p4S3RFbkl9=Fyef&TcPD(_i6x7t8 zO(`VcEsc?`?Ebwd-7c1`&CNtB=wP@Jun5P7=qrTjLp9BEb_N z#);92Z#eR&V6(dZ(f%r|KH;y0xLTI!VslmtvCt_E6}(#z=eK=0XBux%&GLm&U1h zzIL;oI|Sv!Og?`5`sluLY5{Czm^0wPbkOHV1?u1kV{8_E#4U(&<9E(XXL$yQZY5A%E1!d% zmt90nxufC;T z`P&OoZtOG9e_@bLi|j0B{+D=t!;zbW42iD;>N?+ZR}bgL)u$3 zhRhf#)czKWUjumID_#bzL~eJ&X55V0q7N<8tDa|$Yr^qj>c4Kg@F89yw)ql5yjzL5JqgPTpy;{KSMNdaZ$ILu;N!7_w zOZ~O}ZNCHttJzNQLYKwYQoO+rBT7aDkjr$Fd$Gx=Lv9N}xMB?}yl> z?N?M}jhtyu_5l(TNK=nafoB)yw*T~M9NoFI%t<8KdB~eMJ;0F5%ya97#zlQPjYBe* z#(-r=2Y;7g5s2WDxUqln2ml6ve!MHxhBo0M71Iu;Ci*-0vLg_hZ3Sai(4-^(pJ&T% zBy|CPEG!t~rm)JRw^mShDW>#d=$lKoxI}XwHV{)upXHDGjojwfKAx=hV|5e$*dR37 zZunjL?@{uhcs-iFAQaxGsiA3=^Mv4;egQL?cr?;nJe>F2nR9e^X|a$9ylJM`AQ$r? ze2~*KW?yRiGqe7Wkq_W}Zt+c;1-A5=Ail34hCM5mgM(vZy@jU9uG*E39?7i^b^jK4 zJ7@z9LWE+CXT z1s;sJra_z|D`Vavx@>d&xC=5fn?4 zmav4H;I*LZMC3OxE{JSmn~6g;_)$ENg$i0aVU+Su%C^^tS%n*WZFxw8Jly~@3@t_l z8sSYE9H5oM?l1R5B^`rBLgx*E0S)ieRD`nRLwybM{DSD{MfqQ{WCyCgqG?<-`Nx=7 zVJYEAa}?2NFYkR`3b-!H5f{$zGY#|H1*1BJB8N{A%tF74q1-R#PRlX;Y7OuxGxG%= zpHEb*fIk^2ckiHLzRV*+`-WyrTjn0VjC^Y}h`=A&6+r)#9&Wqa8S?ljPIr1MG6{&@ z56Ig(+xE3zBR&K@Qc%e?((eRji5Ru?inGYX@<>YSh#{JUpn?HfF+v=*3L2>AdI3|> zJ;;_~pNnDb?%5tp52#Ib#l|qyLSQ_rf4EksvV#7eg5`w@l$Er7 zY_>3H2kw{^l%V%gcLu4K?E+)$Z1I!PImx|XHSfuZ+CX=YqkA+3)pJ%kGkT@O+-Fz) zzLWqNLp!qnuFRvv$hQ&2u&dux_!2X6tJ3Cx(*{_@*U7}$b4Q19 zPRY|AiF}*GpW9q!dYv3@p*wWPUc&nV5-4$MBfJ;Jya04=o>zurp{Vg=@%|r=6PlOKg`VT!e*1%+Q zTDQ#Rxu@=asZk{=D?BfHh&Rw&hM5K$`WD;VeJ=i^*Q5UR(Co5mkX>_$UaK=PhK==| zAh=RZ@*s@`sKuM*amF`R(9kxy(<*fjmC$G6H6c#TZ~f)sl8ei0XonVGcppVQl=Ekj z3Ow-tuFb`S-&UH|>q1gn?NvoG=qp(fjH@lx>@~16wU$^}SWFEe4|anlpb1P&iS~8* zsI{@VVD@IjLsC-eLj{X(cYf+hKVmgsSe6?#q8&zP>zKb9gugjNT%x7AKJ5FUsF|}* zEKe{*({8?tBp^8}ON+x2>ht?zB67^I<`G+F^Uudn+#jomzuT5RBQ0^ssNd3`X7GPB zQVs4uV82o(cm#T+-KV^M-c) zt89Ws$oQz>Jp~hLGG2)J|3IWF--VBRoNU7TGcez{9WWPs`aZ0EO?KEj8u(#VTc0`9 z8!++*4mGzWvO0K?fFDHEbx9k;D91-d??AGT?Cr|z4vKGPvfGJc*!XB0oxXjEI0F z^@chPKi0%t%H<$2_a|{8?}$fid~ni;=pC&0G%NEx2s)qEIJtZ&w;Ti}mz;y5n3<}) z;o%_&z^Hl&=>@PAN8n2Jq2uel$-4WdX%?z6cWH|SqF7YCrRkrZXFw8yXyG7w{ zf$V2P_CiOLzcz&Vj>@wjA(6)!>IpLuf4GZxZJwLM>>7q~z|Q8s1oSG7d?TIq`DQ=q zu@5?vSOGceLy14}K5u^Bwa2r|eE$?@6V9oQZ*LQW!W^yy*+sC8` z*$(l#`*NOyY+?45ke{Uu*UI84EK(c3eJpJFmYx&3MxzYaP-QDswL1(UvZRsszi?4Z zeXos-%&_Sk{&WQ&tWGfn-BiCmj3Np^ZG5-(w6C^z*g-lkKn=9uu)cb4%ph_yK3yG3 z?WRBCH|O>4S#Hn#^9-g`6Jwdp>%A0;0%%L4V66zQXt9$eJLu^C*edlSOH%d0&;Q=B z^8zAXYQM@4V5DqDOErAY_J?t)yf4bOjxB8K6g!`7+W@Bl5j|ozbhEe381WIdls}OB z96b#C1cI8F3J~DHe+MKRuA9z-Jt=j~QQaQMuIe1_mzX(gNH)-;1FkS2bhY+x_Iz6A zscGH$ihVJ!*#ez9KKLGjwo@ zw@@4<5bGhMH#-BgMeL9?s+t+Vuxt(J7|1g;%+&6>MTbtb@Y*$Be0<}2Fg|n;08aDW z*cm{bo&w{yKq;Z^jAXbj$DaH$CeOw0&dEcEfQ-sjc_N{D2VusJ>76k%ELSrfV*%_$ zSLo)Dz2wng{i_5DeiTTvtr6^c0MR!#H;=_)fw=S2aulN2W(X|Y8RbOMzs1+TkJ4x# zXXovt(_enytwufO5=OVA&w(*D;x#-4OGa z`42i@SXsR;tB>|yqB4}3_G*PpnHES0y?l zrCl)l&TB-47(9~mss5MVlf^~lrnsg^w$+8}_o4aTJ3|^EfXLE#qx&%>n&hEvmxUFU zHa_#cl?#2F>92&xYV1lq6H4^pMG@*S9kf+GeGyM^?nCHrM+F+o&KR`I({3>jL!OC%fs2A~DQW&L{jvc)XxC-p~*iWND zGsYJO;jip1*soxd{h+o|&hzSwO(HBnf@niRX>KWjq5#;THGN>KLP)Qnf>St+WvJ-j zACi0kD#nQPQ33($tfV-8ND_(_Eu2IjTV-V2T2({aWflSfZrK`C|y@dQ4t z%jM+O5O@*-5`V%8un&|)2nQDEdTp{ zIT`r7v@2TYyDUA+wrs2)AZ@QWY>cvs(@OpGD4fK&sBrBF!5N-IgLs|eM0K5jEubcx zuK?o-P*VeA`mccq|G3VWwIjgS#7#zvxK31@7k&4LmVX8t_Rf^2_e2DaXa zy$PuJ9;|~Ui3V(So1j*9<#F0&jvTTVMWG_}$#&@}+lJb~llNwswpY|5PJA=7tkC|v zWe@>E5rhtifBo(K{AWK7G6|3$8#t$Bt}ZVhFPlq=i;6BBRk2J@rYB$9g6qE$9~tiC zaM)irT8=3N!O4E7bAG<=?ub2>n|l6bt~a?pB8DWKO)nE-VpkV%#Gj zHZ8Qjw-n}T0j{bWITa;aD=_>hH^iEE$p;`$zq6$NliOb_Yqm@f1-G&0o|%|+AH!kT zYB5jeOEOLOF#9Chk_FiM7?LlBg0u^Y2k5n{0@#HhE@&7Fyf z+a1~X$s}6QsRJPlJSTl3=N6RCnl3IVoBcKDqd&i%W9+y^am61&5`Lx03V;`U>~M$+msH5EL{QxVJsH{;G8{-yrwx(U3*OZ! z2*pb|9<~pKe$sC_P^(0IKwZ*$drXl(EftNg8x=Gw$1e|rA|5{`boIFndC>J`8#+BD z`}6ppPUBy1Nl_Bv-FI*v+PR`*=(E#icv{dJ(RSC-=-myF&rT%EW9K`g<2ys>J3%=6 z8%iE0!uQPw0I4>8q@+jcAI*5&T`!vZ^C{O%nKUZ)NS-5P^8MUXN4i#TN$4~SI;T`670kx>zbDHx&O$qKg}=>9eB{~ksij~$qOM*VNWlg!P{ zO`ks4KYW==JQnv|pJ!@z8{xEabQ&O)K0&g#Z~N6MHiX7hx7t?%6JDPp?FFf@(g2R% z0L1!A%ACgvBKcJ_G9?`c_7lW97fl=M_`@bhdsPTR2$LsKo=>n9M!oL-^hoMi?Hj6# z<*qBp-k_G{5;`~$)OQyj5H!rpx6Jp-6lK*tFgOWA2Z8=s2k0o9kf8V)3k6W*`MT8ze!S?EjQFodGh(7b~WaMn5ueV??UZhGKRGXfR5cgFCBBXQe1foC~^Kt zkeCk_IXJ$#JYl;&QteFLvhkTcx8z#T?Uje>($M?wspJ7KHxk(QHTol`p}WUyO6c2x z&!PLiKQ*rb{AXWGlPx0o1LZO?pHb1pHZ{f@jhKhS|Ae%}1jc`dyv=WJLR5J5if@e2 z2HZwy+aXLg6mqO-;l#w4C&sm4SF%N>2_L7h^73I0s^AYGG;Jx+3)o~=jl!@QD0GvA z96mN_YLWjU`k=i%q#Yo_%5M5avgORl>nWe>v--}4w%9q7p-<{-mw8SyJJLqOWf7w?DV9RMk$i5wZOx6PC}T}d!+oC_j>M^q|@zL zzx9(i=2ByPIzxGJ?owou3SiYvibw*C)!^VKt3b~8peyS;QFCz=V_>}k-Rp<`KjbSB z9tiZ4BslR}^ypDT1-ab;_VgpnSOORTRG2hCtYx63%x8d8HCkbV`~?_Tm)ELa;t9tj zwm&8fZ~q#fgSu=vO*co#<1fJk6Hlfjn|9XY1IhKm6}Pl%5X`)#OG zZ|sam-&hdsZLkRY6eF*T458&QKF~IZJka(`8$^*Bg}gP73eu z{_WVrw9>#H$2eKDAG~2qxj($;Jr4KU^+^rcJpN8tv>RP)8&3w#L={Hshc{SrioU-- z46PS%7kNl;WlRqhp_HJxG*X>Z)jw<1Rp8N*OdA!?UTgW4@jc$cHr~{RqTdX=?*Qwd zu#TU-bN!*5{yb!*@|`B=Y_WZD9~;th2wU^mRUys8i_R!tYEzM~K5W!>Rc0_lES9*x zsbGo`K7ZQhfFk1BpTAy{ZRVVLaogq;SOEYd#J;eKFgZ_r7X6 zp!X>8Tjp~}uNp3Ktk^hqE%UxmqNWzECCP84_fdFQa}RhmK|BYL1oS5o46)^J9syNW z{x^&1DbnmQ$D#Q2a_*vJJ%nA^_wg*Cx&(g@kgGlu_!PcPec<~58a`srw1Fl6be;KaA4YU3%p3QWM1 z4l7Empd!`|D5`fMP_*HgPD9X+s~{S`cb}CXMJmC63=q>@e)S`mtlZkknuF3t$-O{5 z%pC|~xx)G9PhzMgl$N`~#_4X+@yygqFuZw*IbLS{EhB_UI+bkD{Pq*R=!DVBiy#lg z$9)b3TCM>EF|j1?&`=YF9|L-P+&B-*!)#1F4PB+LU%i9{*JGUn#PrtWc~@YgQWQ>0 zN1FGY&2P8wPqn)VEy$k-_7yZ@xa7s|kuB79w=%KAxq*!_mZq%nJ}>_fxF{e_w^*#` zu-)C=Z>_Trhu-12)WMRM{R6OKIn* z@}pMkoPitBlDjpFIZNd|I~!F6_$>*&9)%sn32t54lP`NYjR_N`wGz9u6CE3yX!tFt znn;rCs5PnzWIjK_Sn;o0I&9vVn#9NW?e~xQ2DW!!#O&*(s^|U zSwYMQAq_Q}Z}!JZC79)jptTfN6mEE2FgXxG)!vFefGVc?BO07mcE`fUs_A)SJcu5$ z|MH(iMU;*P-64LBdy(KtCBLQX5RiRTy~_`Lpv5KL(8TLjth>M0bX~@6^Vw&OY_EY_-M&>-N&1_@!@mG z3v*Kikd#Hbp3LFfI;z@KC$NAU;yBgUVg!kNI+6pfO05sfovW-Ifylp_f(&*vmnIQpaT&W zuKlbYFeJw#-PF&SujTNKHAD|uU zYxPHQpjr^w&5!4JK*Ke^J*p_9cf4d^Fz>iY7;ue)Y6HmIK!k>k2NuUVzeJ=gMEd9# zIWE@S7D8-)u8ak4p%`wuo3S)D8ID*4F^arRAIf4?(b(Yh(v!WOC62uSOA8;1WXASm zlJ63@rAsdiXYa?=cFx^3=HDDI!kcG2aNff zURkVWQoIDDp%4tGvhhLe+Q@O0-c`Td@#VkNsuy5X5Qjj{b$aNnvONa+d<4i<75{g$ z>i{g}9q1OkdEgZx)bQ+ZAn^m4P8N0+=Vbuzn`D}u=dor%!vnrKsE$;O^>rfDl`u}D?C0h@%7zD1TcO$`0g()L1FWmb*kb$}VjR1AC zBQl9*;>ZQZTgIdgPr8)LqeyNhh+!aXVDT40$5EL(<9M;R*DgYS+K)$pR24|mhWA#$ z5GgNJjkmYBQ2ynp! zE3btR_oVG+Q70O)iG4A35x~z65CvdV9wf}f;}$yPQI;*lyI&E6H_iQq>zyUoPq8p^ z#9kQ-)!8{44!0?H(j$c`Hg0bJQfrGI{qM#GuyN*9Y_^6miA$axbe1#Gyw=aAqWV*X zB^Jm%ChuKYd#|-aTV{z-_6lOL4Y|Seo_B%#y_hYV%y5_gCM9L_Z@f2e$bVK!Nf}M4Y<#~2f|vUM zU)!1zFBX=A|8dFB0L|mB)Hr!=xnqa4=sTLRG@dCzQA(QVVB51Frck9xYAy7=E51Sy zDcE(1G^`3M#AQ(>=-1s0<37a~)>1Ksb@l=oSKLm|XFAgrm2R}v7PnuYjj3L{V-FV! zKHf7v7&aYmESO?bny%VxCVeGd<>qp=dACbryQjR3<|Ith^Ou|6sKl~{2~l~>;F{mn z80xM^_5-c<)m}5W1&ch%|xV3ehXl3_Yr)X*=GHJHwxG4;`B>gMNUH@0cIJnTm> zL(1e5-g}iS5VdEjpg zFpDLA7PlYU)i0lIFrRId13D0JEKq<2HXsWBMD<`W=nwd#?z zef~m%_=nwtwk255}ruA=c)~9NSWA58$qUBph*E^m?26CJWVE2Hc!@IR z``So}J%}i^HBqcFeM`MnhL9d(2~`1}v%N}CtqtQRXH7wtizI{>aAoI_daul3KyxgN zypMVbda?x|BW;>(Rr%Bc-j<`o`%xeveK=gjvvD%__17(@K6VLy-u%}_oR}Zvm$@j> zUIRnPqd+sqt7B^odbrH|M;oWB*R9`UjnPJa(KXfAjk+7%222WNj#F06p-t05)%_C zIaF&ldlEANCG=5JwBl;`j2_x5zX2PLc<+CYs-hX$Rfd*_@?fNn=%LgIvNn)UWaI%V zO{{ZN13wL%!YWRkWo78?M9lSb7+u99go47O2EewM39s@7&@88;((AA-_;kx0?SEEP zyuG{qQNmr&VX?^h4fe$!f4;7jtRcn*n4H}RN(a1j-i`N>J4f}1SH<*bRxXrNweZqk zQLefc$s6WCZ?)i6oGrCuYkfMAr~2ZKBqpCw=2gN~mdaBwZC$-|xVEqzvGs-WJsu$@ z-h&akK&NGlReAEnNTX`)$Uzit@Am4L7A14m5s*j|mOd>??1c5*9O*y)0*G1wP-eWb zrw^5&fWHzpgPl{g(j-z9{ELXLJWTK9Lh3~qMe$q-<@<= z11Mf?ixptt6`DTKLELx~upN^X$y=GT>&$z3^9I(m#uxzc(ZWfdNmIk0$x+2usQ|r28s(!Q1`w< z=s+>XDiqExz`MhGR|lyDe{9)-%D#G!iS0aruN~h1f5>_Zs3_a6{Tme!MLOp6p=9VT=@JwKhK@m$k`R%Qp^*}#hZbo8>F&<&#_S#|?FA2NT-$MhWu$yif~gl^_Ijg$An>g~#U zJ-AC~ko*kUhi2f&a#kCXooO9IoNnJFOZf;XK2|ko_5ToBR%fdIukcf5{5%eQh0-*o zv%Yw?f}S)G?hXE@3sdA9W2Y=H=;SY@FfcGU_~SmgadE!Erqq9Y3aJ-X1TJltXItVZ zc3#2XG7rwAeeLn}O5>fO4bR`?7~OAOzuL1CUE;SgSkPt=xew$&JR2z=hA3!;^x##p zZ{z?%D~tK8lk3hf2jC0<2l;4?aouPOA7hnr|6Cw>r@-N?U`31wKkcKCKOJ0+Ty zk^t2p5!Y%&8<%pK)b76XpNaXDE8usFWxl}()?T~)|Hsc7W^p}uLn%(MNuk>nzBl4g z`5%5(;m>loMzRbncE3Sahx7+Cb{5wEsTU)63#1?Xj`px2Z2W4vKm(NZdNst%¤ zw3HgJW51LXD-NLAnIS?b6d-JA5tkf=ER_m;BbYT&ip6h-?gKA_>dpa}Tt&P_#`~d+ zKKpxUi^trdQowRTL;F$5m;CHA^0*O)_n?||)%tN>GdKaezSy>=M8`MlZG#wXHKZX{ z=^dX?pT^85ggV@LKZ|6AXQm{^Gd zxe6;$XUBUoGBV?9{}ic*-=C^7P;T3o+nzx-(iRjc_#fY~S))Wt&_jsnt*h)1i`f~d zJ$e1_jPBTNr`um-b4)^|zh_=X`Oi=R`f8o8vBng&+=<;f@YebG09^)_1fsf}mhW8B`OTv*h zp#;aW0m!;%+h@CTJIESB;wNJ^c2$43>moCFG9EyrL^0D!YcOuKTzdF27UR(9TqJ>6 z3n75uubY&rWnG`@a)^;{IAFyDlY8%%g#wG0A~lIHW~_ciEzj9^3Jj`cy2oTI*=)k| z2peVp!{EZH4p;>!!t9$Ew<$rRXrTBtZXlLmI_d1ZRmh7SE~TMRffE;oQ+4=2)JhKJ zvinC4oSsKT%pKG_*6?E1T(FAt;WY%MMPH7|Px?kfn6$4-@NwU}cAV(Rfq(OFh@2xv z&}3=7F@y=T3~Y?#?qk2od7@&}JKDf;iUFa8#0Y{-o?t0Ovd5 z1It+R=&A~=-{mKC9;EOLBi<{kzEYOMo&(@7BLHm`YZKOQ3wFUSGX@ubRoljburSBS zW6ZxBr6NFh+MYj|w}(>FO1yi0+phCcZ+pna&}v@(;rA7&l=tV@tn7RXbCey+(0HK@SZGM9hm#gc%K3s&#mLBr8V71n8YSskCZ7E*%z)>1muXh~_5W<)zm#95 z@KW0ZD}zqVj>ltj>*q-sSuu(+<&RS>=T1NmmV<&qqB?zKTYGHAl@tSPwgQAZ5oh*D z2gap*d{vydG-k(u#X((EDQ)kKw7aSiM_Fge5-ic7u;dmJt%Svv7AvZUB5pRP8s<}P z+(jqfiYmse>CIQnqLk(<@PjlQ9Q?7vfBUZvwD$jL%Fr@_dC{wAl-&)ZtMxq#GKa)( z`1N!Id+NUNCEB#zNaAs$G4GJyfd zw}BXBU^O{rb4 z^Aw1`d<)z&{@>?vx}msq$X~oE?U9n z&nBlWX4u8j{1vk_D6Fct zYPfhBRxz!P0OCFidJ?(llw%NC@QAx7{}k4lVR&H^6;5G`lC(EXEMvJ{;lq?a8vVA5p!D_gIB<9 zd1&N`eh10`?a^obtDAp+I?-lElx7HyePuX|Rl8eh)>S5OJhFHE#qI?n&fxn}YPa6R zP`zyxmbogZZg&TJU55+p@$Gw-0!7@hp%(_LRblx4Gvv|h3ZIcDODzYkf1Jr67GpW4 zzbj&Bi2*`Odk|2zQl$lYzHa;W=)O`xYfSu@QrikXaQ}0>zP?T$D!1+kBI^2Y-Oj(u zQ=g!=)E%_~2+{3&;tcLw9OIh}>tpMStIHo~crB_NT;C7`R3h%SA;L>uhd1xMFh4@ehPkLUn@{h74rD@gCa^mVC=`L3Xq`s#)6E9mA}(1B%Y zxD0#I(s6RBbZIvb=3Sf_JikW_QUsZ&Uac`YH0hV4G zWj>3(Ra{kW5lpm8Y*@$@g>A^H{_^)NdBm}h-G0pvDt9QFU}*R&fr*uM-+cgicVBo` zL1}-eCb=!*Q3q;bv(zpxoF^!L#G>UQh0$eS0s5>z!u_7ZVPV~GoA_ArXvVwd_vczA z%GF_QFehLg{p%JuL(SS92Yv8=cf;y>&wuDO-A*l5g&*dvHS9rGIHUSclb)!vw0e;v zPK~Ffm$`@s;m@Fa##w2eW~c595|Js_JZ|2nDl)lZkb5guSCi_0?V$F z{TTP-2Oghf$Xt73tHi|+o1tzzbU?M9@4WtedKmppRhjPJ5Tv{2+1$M3GkCjD81v|1LZ7XGYSAgZwMm zOjBjK_yCflOg-0o;6s_br*rY(@9Oz#nhRpC>#PND%M_2V>b)A(b3s3Htkcko|2}3^ z)j?&`06fk|X3UR7h{F)p85oH8qYh2$j~W}CxAMRAkfk?mryO+Z24lp~PF(dgFsJT7 zRDE{+)7&w!<3yXsLMV1POk?(uMJPX}vSFG)+2GU73b*~;7jg88urkl1)B~V_hswde z>cTiJIM`jwmcL_5@~$r|n6&rQ2|I(}%tbC24@39$LNx3B`|6kdi4~PCfOIPfmQa`; zOBkK9L5_}o#4Fmezt(gr-KdkKAr#qHjYN&1Jb}dPL9xK|^r+jLA7C9u@}g5HD?#Jd zL?FL*Z@~bG^-rju+7}#YK>za2G)gKaaTcyI`vxp;g7#ZAjBbA`k|` z*0nTw(&#k%c=+Rk4^QZW@j)6(KI#2)+@UG5SIM~QCH*6jRDTktF4N$vI5h^N*-1J zJ?Khzn?1i_C&hA0W?V`}cXoa6iH+`p!HZ&*r0lhhrrA=_vr@pGib@MNiLkixosvlz z!>C<3PE=@7`x-iEViIS4>Xcnil|p+XlQpbNexVHdhXi5-OARY?ItzhXS&6uKJ$>eD z5M;!WM&Eqop#v+Xl>V(r#HevwDNQ|`K3Pt=JLB0~#PbxL5+facqcnOtN@7Ri);=cX zJLnj(PwAz`p|POdNqf#=pvffePMn7cHzXy5OH4owk%Jv0oKHFa-uDI?KE0ILs6Z^=poe<<3rXdi1J<_iAp@efy*D38%ewGK{ zio?9nopt3{#S5icsO0Nk{AOh*0tu&~UM51*VRsU0W1+WWi0as|00Ii^od*Cv%X&kF z^ZZWPL4-1uMFmrP9l2`2X-x=JOlJr2C~_qzi zE%g4zuNLY!?yibD5`^AWJ3r*gaa&8%ftVJy+VIrw_5&am?lW3kxDJ413iK+ZXJJ6S znN{Mk>xoStYuRSogJgMCt`_5vdYh}|c4I|JOg5ea$gCcpqfDN((W-CV{m(CrSle5i z%`@zQ&!^wC0wV;rC-m+`T-yYdSvGg~F|EH>i>vF;in=vY_TDhc>3dI1Zh^MpZ z;TD_f`Z#=y%9&+weA>&B7ZqCab_+Yh_Kv}OdN#Fo&Y2xsYLc5q{--~KD`9c-Z)Q=l z#}3{o%IbnTjskAla3c9?^P&9eVZ%>18kt{Qy0vn|^V6GkXE`rLoMD~1uW&tnv1LtN z@cqivR5-)L$$TzbnuOmptAv<+W@Mgv@&6{LU1}w`X^D7S9u>?Dx+}%D{Ui*J7Limn zGMaS84G#|ktW~x~LqiOfNUn>l95MyHcI{eiZS9fV#R!STHtEU9iPJoAi2;^+u-NN9 zrjMj`d#`RHZ}6{lsKn%5`3n*)p>nAE^bu-Ez1sl#b}-(d5R*c{?&alW+6200Sb@>z zgE7`kif|cscOkEqB2$C=KJS~;$go{p|J{S$Cc7HykY#_^k%I8jND9_D00>wQuoIi3 z?a?~<28p=WRkv^?ffVjip?I@CO%?UEVm7VBgFUtE%LlpE(CaUl9-_8pOXXEEz$lVV zP8t-3hmk0jT9>xj2*|o%7zLePUY$hNc)~RKM-ZhtU(NffPPVEMu~|WKnUeR7vFyo) z4xy;zHzBM+K~4SR6c#Y`bl=Gyz!Pz_=X=}}l5O`z8v}v#j>krN*8=Hdv3?y1u{=-e zWT3>R55zUYG^G^S1CW+o5QvK(}ZRhTFnp8>WK?B~Nv1UR*Gne+6 z+*n?2WCn(R3e_n)P7efcO=(;5bOgRIb_rbYRIvjF+BIn`?yo(eGQpMg2WkgYm7mC`JXu!EDrM1M$o87ueF z@+z#rLb7m=Bjpjc$^M}W%U~U}T{jD6sXHK`L&H7f{}Hpe3R60PXnH3gO2uu5WB=n` z`k$P}VWC_IRzGAzcSubHV5^Kg{t_hLkyFPR`OL(`!~mNudI=vYo|r=98yCk1hR#zz z0)FMFX8KPaJVtl?)qB~H)Xkh(%dQg3Ds?*qDrw_PyMd3LI+b}xTE;+JEHecK(DPOs z=(D#%WOW1^vp{D2ZKys!m`8gIivr+Zk&&YvbO(|%VQv=;|6J9E-V-88I&de& zRX$FVSZ9Xc&CWm!g;^QS=HfR$j?eC~_Z1xdGFNz^%b~0-Ua{*L0}&6O)9$ag?=)gk zPftz(XYW^OgPbPn5!ftO9ab_uJ=>J507aOFP=zciW^^yDB3(;nPy;7Z(Jrezn6Xz? zrYQWC8*(MM9Ofl~7XMf_<Z`}?Gt;wzTZpN>xR^oR~R?18hNHJcrQoQJ1_Il-!Io~jO*)Dhn*<| z1_AO5D5ZSy{GoH*mLepB-C=2Uv(Ga(n)7CEGrw}fHXsx1^=7i5q!>No+S-fK398Ad zVFwf9n?LBd=8r3GGF-JeD)~kx86Qdj3D>Ye+s1{=c+`<|nWJI`*8H~ASRa{V5y)#Vw1LeH(Wh6C!@)u z{JNbQSF%tVH0;-TCjL!20z((HbcF}1JJzy>fyab*T9gtqh@EOGhe@?$#5+K2k|Z$* zn45glv}c{Ql@c<1m_iT3h#3!2f)&g|Q$k)D&U$qN{cqH$O*jF!qE>$+>Zu^+Dr$?; z>e4(CKA+rl6-~#5==EnxZABGB5)MDNC&2W~y8BW0H1eAd684>(spGHrCzY{4hIIdv z{`}9ZHX>iYRo%g?2b?^WuE+;uq5YbOtC0PY-?WlNBl9l@-?<3^rVn!F;F3 z1`Cb;VC~IXkG1J+UbyA!{l*##C@*{#07w|ObKoTAyH`KH+vB%g45Zx&^q=8v$-TSw z+QOvX*&0?wKHJx9`rvnIbfjVgvmm(1i`maS7dbQ+?UU87TC=rr;RLnqGK`R(z?rt4 z=(2J5ld1Zn5u7A}%Bai2v33g46@pK8`hT!M5jpRgBDvKbVRY0ZboMK)()JxF_EBIN zjqr~L?#C0flB-Y!JL5a-`BspgwD{K-8E!$D&>(C)nR8mTc z9K4E;dY&~+N; zOJL2HEf7Y-i&Z?1w2i&aYmP>gR>zt(>BFAKrupVs;wT1TRzHJ-^D1b&@3})Qc33OU z(Lk~BwqC8i_O{=OneD%e>FhYlx~7@Fcn#K(0jHd9n;oTuz2%Z70`*3PvrC5A(dmL@ zll+@U2>&@4lTKSAy_!I7?pQZ_n=)7#ho9)GTM-@GNINGVrn~G)BF#5 z8Aq@$pDZVtXBaaq`yioQ&pSWbAy{eeUwH(%rxNEm;?4~!l?pJ0d04dz_ATFuQ#V+K zKU=|!1u^Adi?okdEm?45lh4SXE5ZG;vu{JC1|Qg48<-QG1vQa1$d3g z!r?JZ8U+Tt-|BdwE3aaRkp}7i4V=L%AYpDiaq<%JnS3DvA~7{1(Bv}&oZUbbC0@=R zn$0)v?0Ru2@_oEvP-d=Jtd#y7haA}dG;10in0!ky=XK!Q8+u^j-dz8e7PT7id(i@P zRLr)=ZD$r^(|xC#ZqT;Ij1?~VZ+3qot93}&4FzqDiZo`KYj-@U)UvRy25iTZ<)3WE zS_(I6*vfo%&%e$M+gxq*xP#{1Z9sz1qZhsDiLa|K)te??sMR+ zbKdP>couV_6KZB^Dl3q&g2u{?{;zOmd}?mE*bMFC02x}ZOk-^^<0twhi@y&!|MH7j zQaOczRc6xt#+O8pY#*!HL(dUy9$Sb9MeRfZk7T z1nPQs3jDrg6;^=;BeR?)AXJEBRqxsqcLjBNR-?DGGEdam_o#jya`p^*7*Bbpot6tQ zlz86?e)kR=*FeQ0cE4A`_xRB$@Syw$!(@cV+=1eQ%)nekxCajE`~~)@LI{M3_aDB* z1t8XIo};AHQ8AX(aArhXpnVA>lwgD{TJtJaaZBHdNM5#zJWqEpgg}N>Q|7;uc*4-J zg1mj;xN*Img$?&LrqeI9v@#eg7fGd;*_I?vU7UVl(-Xm|f({HsRQ1*YYhRc*sbED`Sa`F9ZOyA4 z$X%gua^t$?Sl8s>nK@B}S`L(5!izK08w+{cn6+OIy3ZL*6N zcA395id^~qCVS(%``lFVbl99+jdgl`QT{hP10(lO_1Ap~ANRX-p`vEq0zdafpShP# zzh7GYezLUTZBi{8J4FJ>DQYN+)V4-vesY&cECpZ7V50E8Th&hM>r#z`iY;$THP<6weRb zKaro!V{?~0P@+KZ&@RJ94Oe)FGlq?keb7s0ra>e6HJ;xl&WNrCL~smTPbXqdOXQY7 zqmVhq`$gS+DOYw~leFeH<`@gOH3GsCqGG)g!x1uBuLlM1_9mA%( zoq2bPg$Tv!W;dvaV0CkPahG`{aLQV&pZuQ~d5cdUap7wLdlso54_s0hv((u2y_T{; zDL;-zr|Vso0-pT+^oXy&N0?1ZlDRU!Du#su73zahfGcvEZUWryqH4Ti%ro(kQKVmF!xgdjNF*zO7Ikvy@=fG`gz6Nk#dEF@9J0IZZeL(XM^ zYWLsgMICCTa-rGB_Y3L|y#xyIgV9#d|E_{Wy0^!RyiH9_ot-tvFHIV1A}rAzQ(ZDL zbs>Wbd0xuUdacbc_JED-3r(vvuDhi+B(z&M1K$POJL{%h|)1Ki6l-{V{9Dy%B zB)Yn496fou{@uw_H8ET%6v>!f2Qn(mpxq^ zYpWDg;Bn_RU(GEMQ{j}JCXK&`OJ^@I8rcGodUn_P>c{lTQ;H;%ZTnCCJD0OxL~_fP z=~UH(nd-9A;`99?F7YSTn-mH}S3XR&=Fx+tyQ~JUZ4E*w-T=e9s24Wgk@4+Gk0O3F zX^HcOde^pQ#%(QaE$$-Tip?7`Pu`Vg`D?^HDvB2fv2CBc$(IV8Z~QQ@5xA4>I090p)$NedTUw zcBol-AM-)80|m|_lc21`bY4y#W+9b=HuK?=zmG%of|k;IZbhd3#DKYIHN*#H5rl%h zV`)_ddBYa-Bg1C^<;h!Sc{fyUuxJW45mMivY^K~06Bd{}?=(jagTiHj2?vEjQ z>%$TI)NvD_jpmxb9QO>e9riGn0bp2g&^ko)r*Cl5m3X&x#;mGr-6oBWsDXmHCXxWzBY zk6^u>J$>opLt9U9n&-dw4Y(?l4t|AF`V8tc-UI)yAVKg;gdm{+y>beCJ3jdVG_9~< zXFxk~cf#e@Yuj=e>0qvk{d`*X5u*=sOlJf4Uk7I+za#4ZR^Q?zQ^` zaSDO_>11A$Ly8;S7ZI_^jq6}n%0)LXhD&D?U{=Zx{6I(C|8c^aTE}r$U?m0h)pu?~ zAB3yT5?(|c;g8ep&K+j6$>ATn8xf33d{@y}o?RW6aPvnB1t~1e8V(h~pW&>l^QC;%${&typp~74$3nF%8q4wM4bJ6QDvJiG#QN!opW4LSMRj!& zV66Z11TMcNr3ptG`D`^yp8k}SJqcw?1vMFin%f#`lwwU(E?Z}Y)v}MN&2Z0g` zYZC3u2~@|NvqE1huZ?<8V=}=XX`t@q5wf)_WycQ77x>>$JCXv{S##HwvNgCrKlXN9 zO6P{WqQR#iRx?bI+bn$*^66)LMv3A;K$&F$IkAS_)SRMmjO82gdnB4yays9LcMg1a zrH>8fGO|u``lpgKq43WMT(-D`+C*Q^x@RZLt-^e=-d}Q*Oj2|^RgbVde?_{wWHuAy zknPih+s(ZxCBVTY+9FfXmvED%AfmBrD$Un*8klJ{1!Z>vt5ru>s)XOE@M!(X=9arb zz0cV30EIh2H^t$0Vf?_NAw4VtIg2$z80ly1`YQH1sAcZS8EjqaQO>=V~Ird`c1h% zIGV^}d67)e=3n2!B~M1*vicZSyA|lS7g$SWcr5&{Tx_Mehq<}AwY4>HM!UpG%%RKX z&lG*hFBN9Dr!^Q@tqRms`o3hdaw>)26^|b!yBWmwZMkl5j8Mp)uj5x)>5V{af%Y5d zfEV}QYodwF%wucGU>u@=4P6l3klW<(d4uap_8l8u!W{)$;C9YWdIlef)Fy#EBL-(E=`N+?G11u|9QEeyMO}kXNPq zCN>|)vb#PApc)ExjYfZA!2K?3>u^ByS_~H3{}F|CQR3owB5G^gt+ya=KWpM}A=z+T z`>(%&n32v9C7Q6LW5lJyZrNdX;FTr`jGQj85rBUbwCiY{KJl~mbmGOPYb~QZkLR4Q zQ*IB3AMieUlm#QYLP@p$CF3<>G%6b=@G4>_F#hTYxeU?S*%<|H32Uhi;XnmsfMz2b z>-+c7p!z3;zLAMssPb(1?mxo8gnc8gRT=UyiN&%qNH<$tnXlD!}Xf^`OYcD{$22+*ZjVnPd(1xOYA&(+4nnoUWX%??$QJ*2fv-)PYgv z^UHq6Z$1FDn}2^f`o)#Fz;k{vZZ)4dw$B*%MvtUNw}XDXfhw1B?y|cket%V7dh(LC zwURAKa6a?k8(=@~AWivY#4tZzFhgM&z$vWjoy}Q%#grA{k%j4C zgy|T*S#LFIBs7O|e38nY$m16I<$5R^%ZfX`x%jtLvV05VoAU9Uz6dAkX58!IS8V$y zYK`8B${yzz%^NVRZaJgbWZzTDF3)ob)v<0Y9FY7pAe6A3Ki%(A%XCo$k79QX{S&pt zwS4tS9_Pi2+%OFujL` z5@aB9Tus$_bRI$U(&(dl<-M-M8d`5!nS>*HH+>ndV}s8@PRN)FMRUy%=+u1mgpj4` zjNzpP&4I2LGu?q}_=qGsqq%C(?zud`fiMinPS&q@{5YqC#nM`-w5098{44D;+ie`e zx`E`p?^AxeTM{sZoFD^OK{M)5nDJ3+<;(7sOp zYjoI_m?q-8)KX}}&oXEXmwK4fC-}ZscOC%oQs-iSP&H~xqG|{Gg-@ho-?wmy45*sJ z_;`>u?og8?iJByG9Mb1LHW_*ct#4A+L;O8~>%MP>iy1j_&9-M~h9YP&w%Jj3!(QUG z?>hmuLx9{oa84Dy$c<+=9Vbo8ukm~N-4{ohW_X$QS9qt13n_caKw3V@=oEoKns$R- zf7=cF%Ku&K8s8bqz8{%c~X(^blrhKK|E!brx8vUe*U4EfVY* z3}0w1-^jMtUdAb(#cB+(-%DQEXgrV7_;d!@<`AQMqkOO173Lj(9Ho3Flzm>PA(=OT zfxb60F-}GOvm0;k&&S`s8FY2I$7i0uGPBF!V&7rLIF|L<#h$heoGg3ZKhN;XWq8;G zMTDrcec>k=O2zRR&(11Sl7nwQ5JQ@0#p)ZV?xc$%kv{^^9N*>7s*AK zZ2paa9Fi1sQv^RX0i<-^fZK`59M`fwpS{>AJo~|#dFVnsAg3B?F2tHBujwo^o$#-0 za0+A&@O&W-zDOUqP|fwv94P%$wjEAKThI-iRI_gE-W!Vd`W^XObD4JMO!p!7u|{q27${oY%wQ@;GmTP2NKBc>mLoZVE$Wen@iY%KtE(F*p1B= z>YAIkgIfDRT=7H_j*`lXl{8j@Bc{#=7ogsmd34xb@n?#$Yl(bt4&!F?Y~4KhQOpK_svETrCj;Sv>for-qfMBJ4N z9qbs6OL)O~lnvfV2;s2^9V>eO6!w`m#nZ&7^)HM1UFu9HAKihBHQ@Xd@H=%56G2`W%KQI~UYm_nA5YP56%Mowm-PTQSDu z=RMeAi;V&sN|&tG`ZwqJdaW9JlT&g%uA243Yl8oSKniz&i*c*KgVN18*!tJ{G8W%hHT`&;{wTFeMb-?mwoELnnK{gqEH^B zs;yEkVDA0!k#Vx4xUnJVv>Ivc{P)i(=I6*mi{5L&Sfs&ON zTj|J`=rI=*;1r&(0PD)7?helWR4tbkWUrlDy^_jpU)-dc9-!$SaY0>qYd8eu!G=5{+Pv+!^gRV;3>X=Xb5|nG z=kZpKjyy><|VuFGQB(A1G z7W5Awe&tInWrlFTC&{xjZvI}eOOB;2EYN5kKJIc85&!ijh(owLHLc)e?8Pf5rofYp z`uZH0{)Z>Uvz`;rAdRZcuv(-rdB#atjG>+pESa#xYpqd);yNkqA_sB($=$7zX9t#l z1>{u@*0yKkRLyl;!uCD{@grE#;KH$_H=I)58C}sWh|Ka#ziRqb?7{W*tA->s_r`C& zBr78J2-3+K#_X zF=p_{)J8JM?@X4$j7imosX*WXf0pi--<8eU4`%P3hv`8~`v}i5C&w*D&F(i}Uz@r^ zG*Q(wR1utwrIu0r2(dpt-QwS@Kx1mGVpJP@IHFpo%VXsvViB|Aqp{p2Ssl!|x#>hP z8tqlxm{DGgmL6Y<+|n{cd0S2?Qpd9W_looQ4azNY@r8efqvN4%^fkTL=)RYDBP6bn6<+aw|T`*9`W%Iie)e;uk(M{Nk#- z;CCD6OP_kb3e+B?xaYC>2ED8KG*nc*c{hnhzeF9`dLV_HYS@VXG87K{U1A>P!Wfp^ zZtrK3D_kr?jW+rsWc4r%2XgcC^WRtR#7V}7S>d(^t#YZ1t9$!>A(7`p8$# z{C)LFap|+ZedYO+5$?y@wpDU7ciAleGPu>Xyjp294NZjsbhoIA1={{>0^a+=SuZj8 zrs2a{BqCrCW{^H<1%_h&`q}tzHoSuj5_ibgL*glJ_ONx*6-hU`aQ(fYvw0-KtgO9g znOKbKAZRnjE$ZqS&lJbqmgl#Hv)cl6rxq_1jNYR^UXE$-wW~~THMVe(v==3yU?LhM zQS$QQLG^=&;RQ~vifZ@gwrLcT|euamSZlNHtaAVr3k59sUf zWlhz`du=RHo9gSj7^Y&E*0zEd5%s&r?TM3>Teyj;Gp>o+Gr6JXsjk*@yK&U~H-+P? zbn>>Wwg8HLI_eK1)$e!-f*X)ysemEtcIn3IPYt+`r1at;+={<;lPpp_cl#9dU_wSB z=dmknMs7b_csyIJjP?uHcxue2^EElgD(Fl+r$gDkmp(+7FTzH_DoxBq*l*BW>2>Xe z2@w;lXS>-!GUA^1R#}|I5d0n%>`02uUd7@kt0kTNrTVVMrTRliAdbLPZ`6Ink?#&@ zc4cgpgl5|{H)U|O5U%B-v>u|rQhhUZji`+qLgWSA6LUgaCq9Ri<8C04#fvsiEiQM2 z0}Sa96}(^wu>mn;bB?gWX#;bt=0W#vrw`G`I)w_C^Y!|zFOjTK(@L-X>}0nFUP~lM z9|ReMFNmf^LCqm2jpvjeE6W3%Fir_lTQ08-g}Pzd#y?N)_guex?>}GR6ob%Uzc4Ch zXEGBnuMa9FE@pN|Yc5wj7C4az%hFI zuY|{2k5z-zLFZOqYCNr9;%|LEQPcaNNPkQ$S-0&#RODlNG`~aOq^x+Qj8O}T&-4!8 zb&FtosjeE3;2KzRYr5d&w(xG#sdii|QeRAEItDMPqfvAgrLIfbmDL3sjrCX;Lux_l zTE!?Qmk`(Sc8GQ9A6DF6_i`junRO0suKiWNygYij|K0kDAii*@v7~rO?QwmRW9oT& zFtm=iS?x+HzFV8mjRN-d^)=y#W9L?0Jk^%JgmvC7vXq zrFfAfQlH7?;ak$4ixz7X7|l`7md-1RS+BNcy5Jp5)OyPhDIV0VW$U>oKOT6o|0W?z z-}%ioB@U;Foi6+34E2qNMkJ)~#Xg)ZNp76&_>Zy4?3BPhzJEV;qYNi9w0bskXHEp^ z1?X#~>E90uc*xOX57jDqn|BgxX8aaNkwwvjvbeO~?Qbfe)wcb!Srs}D;y8N{aP9gb zbHA^H=N6=$8AForzPTAj8ChxRvcS_f7x%rn&sCtrLo3q^qkC@ElhzD_d5ndTrvzclA*4`-JiXK2;OsDwbp36y z1T*ux2lq@c=FNxLy`!=q-B-=RP;=8Fd*cF2W5{R4ECX)pt%<&jv7m*aKQ-JLUS64U z4F_nbPAAz=$)R#SVj2Teh^lR2C60mFaRFk13IyBaW~KEMrop?9zWP2zvZax%$IS|f zG&rXIwbox@dH;)EmZc_+>+@)~3xLLa!0_alRqFDVN9HuP!Zf*Fg!A9|o=fF${}G%e z!p*8H;~TarXf^7>Y9s9oXV@J-bznADZU+>AbcMV}>kKXtxo)|;Y+9SB%sK1d+&jcf zenyeKv2yIOHn#%L?Irv#R~d>a!Kuh*0;QjvyUcr6#5eN#K9l>VMiRL$<|DGom7!qMO;xH9Um26j3T|VO2ITYN3>9miu`PZsm@7gzVP> zP{+9hsyN9Ey#LH&ntZ)>tH&PQlAi+!wksgg0}!Dhx8vZuJyOOT3VHTV!VHqc52YE=o{huUX@<=M(?el}i;{XQvLJ)b=b<>Iar6AwP_R>eHDg>1RC29tf z6p9cDF(a5y>|;1xac{B1qy&;Xd#+jUXdxDAkLbKQ!kUOMbU(pR8VwZ$Iar#CSS&{H zj8nk3v5DGG^|DZ%6k>0y!3=PLLo=sQmXR9#~sgKP) z%SR|#kjK!ve|_)6C5Ct}H~+9r0P_&-@KLTjo9k$=La2^MgSUHS@#SB4qhfux3CGjA z!_QFTuzd*IBxRvJ)1B{!>biHVD8XuFQi~<`s9%=j^eKLO-JZZ+qMTv|ktX%q}QG!y%=k6iF6w8k(&fTCJn%F3TpF70=tlXE+T@OU!roWx5?i~O^ zr;(Wck*W+0 z%suOR!{U93D=^(Zv4_C~B*X{35W;pJZ?tKZjG3poQ37TV_D5H`MjIoiPKtDV#l+aU z8}kVNbb;<&ukzK~Is1V>k&XZEKA-43@tgVaYwikPt7PU@P_3gG4q#5g=e|mjek%(v zV+D1$UFnHH>c#rvbUV*=?jM{KH*2epu^x>nPoR+HXHRYf{mpE=azX5aU-@`&!AxC? z(dgzWSBTR2B{QA;^ztv%?#DbR*Z9Y zeI2Qc(Fob@k@Lvb6MA@0?JYA>riIkUl8%QN6=`m`fu^DJ;WuT-XM|4ym=j1Sik6_X z5nWDyeKaIquW-}V+ATEAvcubZgP|%_vrWuzvc&W%halumj|BajKaJrPR+;V&=Cuet z+tog(2eG~Ryq0EWna<`6bo&wgGhA8e(`UA{JiqwF z5!U9Pq|41Q;QjAaj|$!6cfB%9yB|B5D*p`}yzwxD6JM+!&NEq?&sbOyLi5LX0?EdP=&*MuSGK}dh z3@7}<;DLH6BFli&shP}xm-AIM9UR6Sd_2U09;~A*dAi#YrxA4 z@jGj7vTV#qdl9$pFyB#kmNaBm`@tl|hP05+5qzdzB;}WNK1dHKd1l zn>JXcIz0Bwm)zGT6yI&G8B#n}PwX=old?cYj^``>7#Ony#3xCp79 zr*7#{DTeS28q0DPt+qnL=3 zc$Q>htF~0%sbTX)ows+Qu6>AZtZet~gDFGh!S4P}XYlW}2fI7ZH@Jz%|A6dm4HKRb?r^<{8A zU=~?#ZxoSK0YOF+vtn{NL^i0{r@2~GR~VXJ&@5Dpx0T%5wLRC-=wOBp!bye9O_#hY ztoMOgB{sXZO(*M{j5_x`J}B*C<_a5sHFu~1QGZo_XsNV3ndmU;I!|Ch+P^)Zsd{$c ze^H^|zH;+&q37S^o7#DOW2!6f7p0rB_|BUj1wVSOI>>G%-$=f8%KY$V4T;Syh(Cpg zz~(3-nfI>hRiB6ZA-?>M_Z}AC^ff+cUT?Dj&s*xoKL@#gj#psx& zF$C!b>F)0L^1h$v_uTJ4`|moAee09wd4A}A8?D|s_xpjwPuqK<_>G(0;r9B?)^kNx z3Ps?j-EXX9UV!c38*jH7<-I>&4@mkTB#>L3XYi{`hyy}bTxNHD2$>*677f}j28k9l z1jdzt;8)?Zg>i-7!4TZ}@GkIu@S`{j&rQ2Ia4Vxa)WB+Ehn4{THnUCxIry|-hnr}2 z2-9Vh_(IMwA3yoeOWWYMv3C0Muu=0O=><#n?7Jh)7nK*XnsuG*w@fbxxEc_)sNUz* zImQ=NUSIm_kMq+|S}Ov-4H9GPJOwHutwN}kiQO!LgYCoC`=X-nw($!1zumvWnQ^&w~*7wK5^VL*B-c+kE zwC%o?!P;;73zzfuqzdVQ(*p{ZahC7f-B9HFXnN+U#x}4+pkt?gZputyfg?Lm@VLfT zW%-^%=sasBzweAjOw^3;Jp}~~Oxs)AmO_1`aba_5A$SfCu4an;fCJ}3w$RHbQ~?}K z@g=dkp7a;rN3=0LqJ-;uy@AYqT+uM{4_W!SLGCne-Aq zO?T88rM?Rku~tDj2SwgGdjlyk8q+eEg)#4x8^*sVinr zIBp;&{!8RSkE)E1`zi8)b-%|>Odf0h=_zLxIORU&OBEhj`GyoDyWis{hZ>uKBe)p$ z!WplFnHfuulBe6F=)DB_dt>?y?)tcKz?!O(9>?xY%sLBR=TbDug59*lsQh5GZGkzR zLJeHDO7nP4Pd>(jFBLFp45sLKV>;4v^Jh@n&!PMn?Z5WvYltG|K+ps(!z(nycqlN_ zyt%Z_gIY#`=55_i6(RUO_YQ^doLd7ezrp6G*M;=6A9@%Shf zG3gUnR!i|9m($Q1T>M=FlKC9EHa6I}iL}O2%M`02s|;4lYzK@1nWG3;Ci*cCUM{NF zJFX9Pza^zrudr=kMT(BRSc<%fuRuY+H1-)>HM*Ds!ff!r!2~rr@|o3IU1s|T^pS`v zotX;C?wkLdDo<#B;RRowrz2}iOBKL0u=S=pgW4`TCeef2bN$Gpl2?4HuYu=9yPw6% zg$z>!$Hc~#atize^S)l1Vjg3%N@9<}PbxFpKo`l+M#7q)LHvU5nszjqAcR&DA=u~9Br{JmB)>r9vlBcrv=w* z>sYG8I|trA0H;GBbmm(Qc>@=|QFHpqRemPW=5s{tX|sYh7ewhul?>OOY*yGaY@vFv zxzTeUon}ZClGocNaIb9Xxv^~c@X3a$Arq|36q%M+<~V$pB+RsNUy05x?&sPdE0~ z4o4Lg<{)L%BL*rTDcOik$8xa7SBPIEPWKGm&Su(4nBib-6}tah5~bKz0-gJyxC{ofBm_ zFqN=Iv==h6T>sgxsVVM(oeH#8+rZ@Hi&{l(k+|d>(xAteC)*@d`9} z!<5Dkc1RjRZ@N>hZ=M}-e^j|L5MG2nJ9YcXAya4Fcn&zshRve8e|Jcg)bz3mB-XRb z1{_Up&lu{4!Iy|v9{BDxarrMBpOVqU-tit=r?)Y2)Fni#VCAZs*WYIVn^OCb+FH0L zMNsMIA-i)WgXaLD?`aZB;dt7Oh5F(nWo%fzR|!Y1!85dCF^8X9Mk@c?DKmX?MrfvMY_#dOB`Q^c}*!3OyXiXB*+@Vvl z`oet0ckWVBQuGtP3oF;pSdWNA8DAUn>z2jWE%z`}_a#UyEGgC)p9ThGnhzyd?px;O zhKT`&xg7D1+z9s=4JKZJT$+K*aI+`GHR7xv|B?kZRdbB@wnK~7ClTLu#Z^)KB=ZjH z9pYG81Jpfe)|#~z2fRO^Dl7w__`EcF++Q|2S&2A3?*2K6MOo~Gpd<<3X)(9;wco&t zDCy@15hoebbROiFoSJo75WyWlBY~dU0QUMQ6S91PhLGY zX>&_V9RB{VF|+e<_ZK(Vh@^EIzS~Xz!m$DSq0L0BChjJ8v%#?ANxH2m{U|!_d&e8G zXb$vZz4_R&dz!qj6JD=qgeg|Y9VRJ`^u45;!hEWiv#9Pc^1RT4;|smx7fI6OM?zw4 zMiIWtnL81^AIZ=0($ddQHj3Bbu39$}+CuiY#|^B!4 zvtov>^Nq1{5SCeLGGDu>jLdCNu~{uH`ld);RYm@E$gA`r2Th4?y-o-Sg1do#55Mdc z7>bjA&CgQM!^o!tj zL9q&@S|!b?8^g%svv`PWTFUn^?)lhwh+8e+0k>@VeuH~f*((K&?(&&F%{HB015`$@ z+R>Mg3I2wZp=mQ6Ys_@lx6yJY&B{ANZ4|+%<7iqU+fkA*(Cqj~-A4&A(wRWkvX&O3rm>8Bz_PEB{>TApEj)o;7>i3tILhnem6^T6GLn2CIjAitJa1C z7~<{D)v+pe#q)do zkw4w&ovJ=QUsCY$Wo?~VBA9hyMvBg}aNrYI9qelCIXvKFT0l!(M-iQF6yzdZ{8$!4 zxdM*C);}W_ZR;F0kw`~JBEzi)*_vj=mHX@%t-`xLL}TnK$nceAKnjxcNApDV?Y-{P z{oztPWb^zD?qnqaYNkusF!b5){e5L)@NNgWVIqs$ATZ}y`u5ZUEfsD}z0 znQ$*_d8{)IyX)AFI!jAB(l0$~kkmge4+o{EeEGtFm{jjICKVpWkz+mbzlSvz7kn?Y z^sy+;ZwMS?Y(p%SKPD8hD!Nf&`Znh0S#=eo?vRF1%KY$y>%$Fk2FfNGzkiBK-s6H5 zJa)^6_T|Ap&1r3YaVq%S8z+Ulh8z($Ti@7t6j2{9f1K$6E z+x$6%H{5@CVu8&h0u8S8W)==lh zfPv29qsm-vD|qwBcz^NoD)G85@?6d{=%lCZ@crNrzWSaJGvh@ns)AG#6O;QSJojIA z9I9u(-jV^2Q&pUBm|(1QKauCN5O~Y>OWB(rZlqTczfN1Epb?ffHkai1l`uX_xGD0} zWW-w$%VSEGI2b!Q8gb>-^kzsL><1QLLa-q%#*{FEQD7@OfsUNyhP0&cnL7H{y^!zv zJk-};2%EEL-p!eduU>Cv`Qs-TsXFYn+P8PS|HFPPRN*f(*Y`~4Q%_pF z2}ldg6keTz;#pohc0`Kc^-=$j>ZAJedBmDL^k1sS(agSg5MCu@7>q#)&;gV~P6E0W zy`$Wmemj9a>ro$tvz)=m;W#p93@Ysc72P@KbBO|J8)mum*?m zyhGNmsv=PZQ_jYBC$~SqJB zqAndmSIA_i#^nQx97gz3`G~8#4c4`8RDA_)q{vnm1>h!aI z@I974%qCR*VM^2l*ASnwvfnHGn%pM8*RhCcLW!aVd4@ckg->YTser zuJN=vJv+0WE3qk{zexPiCCT#G+~%MyIZ1A$JGxfuu^z41?f}J=RrB$P4%i*%%Hn^$ zK`DhdG|QkLc3>jYrLT6s?d}7Crk=d0y+BWS8)BFi4T~HqV9%l4fiOsh|%u1&p z)xdk@`F4D-`e-)ENOvJCtQT?|{Y6{p;JVP9nXEoakWxOV@ixZ)VysL{ zr92Qs7=86x>(}HLD{-(bg?>r@R6#v_slW$Yy4)+fi+hr#$ccE2X?zEci@>4|-<9jE z45Vw{oNKOpPkQ~%_#{$+RmSuCPhgDq|2daw-`q>Y+zde~9^1sz-&BeS1mc+R?Wirdn-9nd`&NZdxtW$lE?s9tb?CX7}@Ob%ft$4%NOs~2D_6oT!oHE+ZvKX68fnsd{G45#zl07Kw)=56)qqyJZ;>Gh#1uCEU{CNsT zNbh6#*ykjb*fYR|t1nk&yL7phj6bhTPHz4tI%h_v4lWeg+7%blIc~;8UEs>-`s-MQ zLNLIfq^HyBv}=LY3+K;-uSRBd25Da}G=JoWU11|hxiWbc*f`G4 zLZ28P3-#*hSGh3EVJIPmccHXvS1}!p34S26m*Q&{Et?pzqPKFVkM)ZJTzOhd3d}Y< zFTSG%V>1ohLN&yI-KKyWm6%9&1)MGuH!_4XEdpJGE?Xb6iG6i_7%=Qvkoge~%J`nd z|EMti?Kjn?d*5()5MK8R2FFy~hOpgPB3j&PqlET4+(yQ@;E-`S@<+$(zqzyE?qs1X zHr*oAg?r|t3q+5i&k{=n3qZ>2yztq13HKmRPeV5m-N;sJ&1%x77SsjC3AVQ;4+Oa7vYk;{0?B#3aq@ZznLjA* zTG{SY!K|{Io3+g#M2p6KT`JtnOz%b$`m<9)L5G4tR=PAdRediD+}ALejT&5DW$9|` zyS?w-vpTnFovhLI__ok^A#!Z{RV_|&SNJ4%swM&u5c#iLj+;A>s@{k>IodO>^yy@E zKf$AZ8-5)DKTwOiIexlZnnO_h7$5fRMG7*fy`zK79U=@(6BHLw7%Md|Tzq0vHN2vh zPxxF@gC2P)OOtf#Zd8hb|88`2G^*U=vYghC!Mlgv#U=p-g882CHRAow(L(RFF%TJL zjd|SCsRbS8NI1^g&HRTp{r6j1ZP}K@EXnatwy9tvQ`J=69+q^TJA$te%MNSOUVve{gjYQiA4f67aR7`I@RGpM=Exa)2jBvALr%!NB z25!M$9|%QYNS;+JM-*?8bp~Q{gm9}2TU7+Khr33UlOWU>atl4z>*97d#AEG3kLE@T zA|2%PYk(ml%B$XN>)@bqCp_rIR5Of3-`}V|l#6M(Q-x%V?=bvmd@{C&NtW$Ug3I9B zab_@C{lCCPEKn$V&%f_Qota-z+WUnqTqOn;*V2)k%!xqUzg40}3R?=EsF>>-O_2f* zE{M%toSl8VdPT3eBYo;9T?(V0moD%mi7g@N=N1i-HPsJL9M;dB$i)$MrW>{dvaCDU z5ZP@BW5N7uErsPsxsBzm-sj)mMASJ^>P8m_u9lRSFP^FJB>8h_GF9#5IP2)0BPHY;JHb0%m2;@5sy1;B z2*0HLi-4r15^no;sh4eJJGSmpLJKewuFdh&Tu>O<^X@wT?nRT>b4C;xhqn37U~X`6 zXuMFGamnY_3zA|EExg3v1kr-ct?-;1x#S`f)u?Gvaq&f2 z1W{S|>wm82n}GUI)FMxt^=;(8x$Y-i+2a5H={JF@EGoC5*+}Uypxv6;>(Bg_l~q7>@ur1Yiw4d%TP@ME#DoU(c5AbI znwXgvH1G21s~yc)93B#k=mL}PO1BHnbrnLZL#f@A9n3mcAhnC$C2CM#(?_GH-|e_& z#uz<|(=>hO&TZE-YkUPXRWL4yXqj`_E$3Sel8i!<^OwAUN0#!#RdqbU0kk8ZSQSX(9cah298_rOI~Yb4={H$3v_HEoJnaQ z>T(ZRfI9h~|9b;2f=%1REUB>;+s@L>+DP$2>dH!7t*o|Eo)?q6@|*WXtyb&P3<@GB z&dJV9LTp>&oSX_wp}e=>&O$)GGNc7NY)}VCYWWtfc+XQrxS2O)J8Cu#2RUHQ-)B$< zRq(_6*{Dfveg)#Xnci^ow(Ph3)WBGFd7qkXi;Rwk2UJjlR^qmet$rdG`0K_UTUsS$ z65`*))P*R*Zq-`g8bD->Ic<3>kk@e}a~XICW}H_pFkk-q?Hl?4k3NWT4&aNTLAmSi z2VH7a4mbej%A)0}k4D#W^YThZA$Uu+s4Gd*u9JX73>*%3Q}T`$k>2v9vhy$r{r-~f zQfw$-o@d4&0vz8b-pu)OG!1FCBZ0nJmCFQ0(4Awk$6$k>Frd`ciUSJ7bczEw@P5Xd z>JC6GmbQdR!I)l8;cq+G_r-|!?+5HbrG4H!KK|LApV8Dcsh>G6I<6b?<6gig$b2%ZP)oYSxg7_|qJ%;i zvLG~TT-2NtBOGoN(dgVJXwWJ)du`1LyAC?Y&8~I@nZt2+S!%+0c0kWrJc|eJvUDe6 z@;Anw9$PNB-!|9;!CiDB1PPC#9+=o)qVPKi{0^*bn+~04bcFC^uJsQ0{HLzfJU(4T z<#T`6yLv0BVzr$5M5=OvmXu%wrZ{8Aq1?6KgQyc3WQIDZT|!UQ%;-$5m80!kZbb2o8bgMp`&`qC`>?v` z?V0!H9XawFBX*zW1eJ=*$|9~)^YQTkLVVhsKO`?ZFsgNn7grv{Ppws=-SQPlzfS^R zrD!3Fb=1Me$3v7K`^;oqe*eIMC$bl(-K~g zLIF(qy0xACyVu%@`Z*W|moR%deQL=eTh7253F?101 zhZZS?=}oAf8GW}9Vy{oUE<4CxvZ#zXG6^PS)#j9lLHITE1A(O3pgL3rxy6grDm@$p z_Zfxp@8QUa1y{hGVX!J?Q1NvfU6ykNVl#|iG(Nl6jEo~UHwH?zN){oUYcIDdOA~+D z{vM-#MVVvszlB`lF(d*F{BH3R<5S@?e60Lt^Ir8{m3#*?4-ir0vS$;jdyz-4M=H6R zHgrzK*v$ikE;J3h0|UZ~xsL{#s(~>}BOcuv6S{YOc_c6I<7=h}Z@GQCd)7_Thx8mE z-?crM9kY+_Aa_}nv4>RL!?9vDM+1{U(l=QD6gox7%F5DYGVP|k;t{GC`%VL)uP@`j z>yV>+t?|_GeCaZ`-x>Qim9WZm)^UAa!D3yXQN`o^Q}p)6`9B#}H`;G?{do?E%@}1? z8}g6t{~R;8Tn*SKo1BX6^!TSZYt z(A6f3A(YrWgyV*}AddfrFq;FR|8S3)Ry9?ZU#N+rkIVrvHzy8^qGSmIjqqV1T z7FJfbqIhR+kK=_-)}?v+nXtUa?hEv^1EQ{5Kc%MhD(}2>yOLKOxJ|qF`XtMkxS^2u zA$sK6Kq8WxK`AxH{3L2v)X`BxB82bT(`3@vU)#p62BrrM zRNgg5r-hW~7D3yFGMGvJGYopa5WTm=j&q-D&&kWfLj+Sh?KX(Y8dKpQ{Oi@u;Ek%8 zF#}a&bjLuGVm?{_odrXvPZf-ZvvL}JN^i959JE6kb{lD$?JwD{ zR$O!%Q22d#LghuzHKO3MMf)&e6k{%tEsc* zY_(vo+H_H1oLF>k78)Hkj|UmAdh;Zmui(F^8A7qa=j=!@u}G$jh5!Qt+~-zTdaLBF zG>&mboGKM`-?o@mV8?~{UvwIgi?|Ox8$a`zQyn)%Jaas6{?*owT@5;b&_b*Z&4T6b z!oH+mUHLv2+&AaeJy!c+mv+p{<w)^Q{+^lQS5yw_!I$4cq_}NBqJ7BR;Vj zxb#f;I&iaj!&iR*;DAo`q)>4o-VV&0@TPvPqEAeka0d;fciQ|nw_mOJ9e=zbhR>cb zd4polRMFp0L!w!fnt`{NDUTUL?JA+)u=)@zf%r9R6Dwad;vf=7p2dmpcln1z-()Gi z%IW*{HeNhD{Zh;K7A<>c{WTLTUy@b!ZIh!y1Dug&DLq|- zi4lD~!&b07M6mbqK^R{9Uo8LUP6MOmJ?wuc2$9GX#4tn~A`jCxZ_vOV|X|+>pPi;(YaB)Pa zUYx>yX)T%X8FsOB%XYTQcJ`}u_Di9!U^-oWI=)_b@{q(ja)RENghl)^E4uJ{`D5mv zUI_WXJT-o!^9qW!Hs&IxEQR-?d4tWDAM_zM&MjLUpm&xpC?S$?CS1#6Y?Y%NV=eqv ziO#Rf;CMgi2_ptI;XvmPQ9k=_iu{Yn?yJVTquD%_qds2ox7 zOBB&znUBRF>QG)4L!AC!kIrhF_Qt(F=fBXhjO1YG!@uF{s_E+ex2!c#Ywko-$gY@=FSM-B0_~ zWpRp|4PBA$OIjz)9f5kU#fp|95dra+v#t_!sbys-I2VqlvX-noA;v}!Gg}G&?R__I zpsQ$s?X*)s7QTvK?i9d1kpu(81zI@dQBEj;kjX*nqHf?HHqR{gS+&t)f^0G(Q!Mm7 zh!K?jtd%oVvBHNR_8-CnuS#WmSi~&8qLghL=u)S{WK(~#bO)5C%V!3(67?f>sY$l& zjc7LH=NFfvX5s@}2Xn{=E`|+-2^P0JvFxt|4f@n^qyS#5d?l$4r9`fO3brIN!#|)b z#GP%W%5hH85N z<^4(R{037-M?_6u-xAwxE=ZThqsk533POn{n!3kFuEdCg#$~y1me-0kQP_eh`=i~J znQ>>HMHnyysaZl>BiQCY>D>ex?P&U#^D{;C!+*5JLVvIE4uCg4?N!c61x-mkLn(0? z=-hI9#qdH0#G17Tsrwv%^<6RSJ8hb1z2YhHWM1G=FfYxYFyTq0xQ6TWXx@il3ZCn1 z%1qF|hR6j#hViw9k%;mhSq0zTMim(TYD1432dP?cGq`B#P$|b!)p;nyB4n06*qZ)bq`0?knf#>88 zh&tKJqUJfE+a?rn*IDDhxfEj-c`0k4i{?fIVNDGkfoFA$rHh$B7py+aoiXN5dm9re>w=e_1z*DCwnnz6_D( ziIRA|J)s7p-))M}>`A;o6Y3avcBtpv@FHHFQi5$gL413BGjn6&28mNTbP%@3GM(+sa;G}Bo0&Md0Kf5TS(M-rFFt2SDf5a8uOeSJI zBTrf`rTYD2>e9D7ug!bjt>aQ=Nms!z*&O1JNw){@AksxcEIjKEdB2h}1@Q&m{%7bT z|I+WeZt0@jrty(Et2Wc!_W!K!k9F|4-@|MVaS{arpm4WZnQX|bPKII>;j zEwZ&HGe$9IOM)>A>E)E1h`w@zn=A#*MO&lK*Q@x~EFM5vX5Uh8!Jr*fL~#Z1S>!E@ z_WSR16tFxTlWTzt%d+XbElIi44(r)sqK|5w#pjFXh~1hhMe4dMKa=ClmjF)zRZ9q%t_SCoH*Ogg0u+X`pu&rm5Dj}tK2PZG#=S|Tu(QMs9sS3^YNG=SdtBuk7EDd?yE!2c_fB1n1(7%yy>o@LnX4P}q@y`EEar=`K7U)w*iKn9H z_cz}UCNADjG#I4$oxBFkk!K!b(R#B_s>i>3xQYv-d|HU7YE$$z1Hy_;3UHr6^;o`% zOTm4BLN8=+m7iL+c?Rp73?B^MrPNm!3q!f!iHLRO1c-q}dBdbVokz)MKHOBtp2?#+ z6a|pjIaO|`ylaj~ng9C1NlC+mLuPlmmAat$fj-{(;!#MVQ}(O)>Ii_>fkO7pY;b`IT;NNC^*4wnq}qNR_Gj&WRC z%F-6nBs|^QgPrd!V`Q0{^L^bH|Lqr6_YG-2b&mAr-1#C7T!|A4oT)M2VOVmgpT+$6 z^bQk4=40(U8Xz^S?oEb_UleKP*@`2H61T3R9|i+{ADoMWJ%=K7cvqP2^9;>0ddbIW zFf~0)O*J=9?X`m~!XLlZd1gkT(i^II#}iv|7wW*!wf4djWzdoN_Z9ln+s}9kME>a+ zqgPy5D&!M6117SH$|Sg9^j9~J_eoo`v=sDyc)v>#DO$DZ9=lqy?zd&6!oMfU)&y;i z94@>cn&VD5ST)B?CM6~+Epdwp<7)PIIaWPMsgn$=k*AyxEtMYz?M8xNfkcSfIZ*Lc zQ?Z8_{x<$>3e6IfVArGe3e=O1>}2_x*SlNBA5O-w<&=9TD7rLzCgLuO z$NFEVzIqN1z+x=jTPzsm_V&KJh63%mNwUUAsPMnjEhSMbzBSF|p=;_WSOlF|U&zeMPhi1^FW;c*_Ao$b6o>0oRG5N@ zjWYlkCre=5;{#}|M9H-K<-F-3BK2huB|$l#Z7Q}}p6>(V?&<1i1wZ}?!2`gays6oc zW$d4PtNLGnu8r!qseUu)vH$kYWxy3_W%WKuk|mUs^zD>>5DxooFQ;aF5Tfto&aFc1 zBe@!T%#EJpopwf^rxGc5$Xe%J_{~i~na5-`|d;xKC<4U<;757K*=8eZ1){d@sNu!@sxhCZW-Ah!8+q;M8YW zQEoKCdAjm&YaCtaBeQzDDX>keNC^xKv=}7V>v1&gZvyy9MZZb`^7XoySY1h(Y)ON= zv+)Jlb7Pd$lK@UrasDHWuMS81)( zTx(>QM9}Z5hMeC}9j|&WF(5I@4SO|GXBIC3&2~F~h&4#|JHMRr8OuO5e%)s@w8}Ze2BfWEi5->>Ow_7ZuhJX^u)FAV zWM^vq#=Of605g0_h$8}qltLJuW_V9B6BO#h${RMiYvD$gO`WH2|W54QOncG+SbS9917LySZp zc(yPU@=ipzEMh3%?ox@Gzvh$!(yYH^b*R9Bfq{bJJnU{ijOC^GRvtFW0M1lY}r9FEHzLq!|7TTC?Hz)w)OG@s9OwSHu#)?fIt=O4V(h>UZmg#9-feE zg^A{#i-!;+8j%@NUg3pvzuBclwn-H2KE0KX>&F9w%g=R4bd?SQCg)ZHmsd z{WDZAIEnFW3Vj?qe!4P#N=!bI>18u^;CU;#eBoqdz{UJNVP^FrECyXU0&fIRLXz{(kXvb$HxVKtxWJj|--J#_?CcxXV>g%VV z$2n+Sg_G>9KIRnP2~dlrXU^9r_p*DqGp==zFBkSxe9!t9#9Avu+lBo^LuxeCx?_qg z@X0`7bGvYnZKV4cuy>Szi=oa|O;){!Bn+&7fSCYLW}4I>^zEGC*SrkLKUA!Y;Cjnj0YhMiVQv z#7DbI0v)wx%dDl%oQGS0hc6=yA@enqatp{MCV3I1zom2z)NlQNS;(Emp->m}2M$01 z&vORA=nV+F&Lw#VZN5$Zn3NR%4IjU;cc_XjzSW+pHY{C=tk)_=8t4?e2tC{P3_4x* z^>=EY_D!^u);^Zj-P>8fuW;8Hdw(Sz@#egE#VclOWgfkTbZvxX@p4AzU8NiLG5wUJ z=&6$Qsbve?u~kUf$hPh#BlpuW@x8Q?KvcQ@g#sInJpRFhYu|bzi}WvIYNaOC*t0Tw zzau*zS(!$9EO|WW|2ZiUN1cLeSJ(>J>3I)^=SWDWYjqZAhMa7S3bVUDeQ_;iJswzN z?tdXkfCy7igLyPId{9-><8XTcj)x|FjOl1IiXK_mzf0xF-v@x;=YKP7>N|DTPK~)9 z6%wv=yuepXcuU_^`!qLs#h~D~>8>kBGEnpi3Oen1wZHsI=3rIfC8hZ!@R4pQ3KiOz z;t)LI3BjqSPeSey&%g}GMF^!Sz@ zewAR+4`kCv{+^>HigzHo<45!WWU$#?=SOy?BBXXHFoFs3>$3aC6docV++a-sm<3cz z*{I@A2Wfywo_*#T!zjFq&_=F6FE#!13i)7LrE%`Bx(CEtJ5 z4_<3cwskj;(eZt~Mlb`ni|A+bM2USMH3E{WSj+}9Nw|%&58xxLK>7rug^3N#{M`lx zH*Kw`;bRtqHP-7H*RmYl7c4r*%szmn&*OG(_OjOGBZ~7aSUWSb{uQVP&k^+QFpnHo zmXzF*5)7f@Do-mH6%_@-rrnj{@Tb$oeWV19jwZ3$C0zRQCfH7FJ=A}sJaF)j3JDkF znL}@I)CGWIWeF!{=jA!~{z3nYK@cZ7$h+pOXe+CWd5b5`&ShOLQ%8W({<|rm@g+|~ zm-;|qqRFudslMgD)p|pN8!I#0_;1syzfSXY??F2Y1y5Zin!zOvvuy*TndL- zHHTUITakkd< z#2dUZ`fP`r&zbQ1g1Lj!l~_mn&MOl^Pn0)+dQm9RMki8kHkc&}M!F1+C~S;^RlmB= z6$4=erPeWj4xt0a6#V!2QEb_%c=zM?TC0D>zHiDobLH6cnX2%lp`rOKK?+T^RUKe) zsTX(pKyn;3ApHKaX$c?XkDw$fYi^rOPg>JRB|5hROBMt3o?D68xw%GRFxeSqVe9_2 zfyHQ^Ky=VS(MWS=p*X$(I)d+)(i8L=9fk3xcmJ8-(j znIfTC!t)FbeujKV1zM8r7FVlVVksDyk04b)69lR}D zC>bOF{*uyBsf|;qCxJj>eYSs%>U5!l+h=X*n-kG={r9H_M0)m8QEPp#$%aTkoGoAw zGXspq1IXAMT<|qW9?^Z+z*u3U8ud88I--1g5kS>NPzsN9 zmEXWi_78kGmgp;olF4L)M3L+pRy0}TvgUb!(d#yhn$ z-xpzqzM=e;%}9<#`QMTo)GSa|a|h8Qpy%V+|Fgcg+Qvd~HA^|(w8TjKR-tStk5z2t8mO4C zafQNCW7u*1V?;>Qwx8L0;SAxJ+BoS12zGwN$pDxl*UV`Bi=dG=E0D4iKZi65^87PY z#t-I+bRSn5vf+w5*5KgV*RMD6P#lIuIEu0~E;hCVc?VlMpGdZ}l{gwXUu1lYRA6aK zK(rE@=TgcvIDoqBT|D*yV*B^~M)Y44ANIxf`@^K70|<|AK06NfNhNF0PNm;f?{gcy;@UM3~&BB}obRbHKdu zUnXFFFH_&2N%y@Qk;;PmE!?M@BRMhkCA95$_mBb||>MtgC^S_^uCVMRbY3`tHCmePh@822i_{ zki0iEXPtdIM(_4A-KRJ44-IACKD!bM!8wYW*ZLcG`Hqg7%XT^KV0@3JggXLO&%HwB z8&jl=R(O{pa{sCQXa8sPL+iNjFl9gwDyz4=5w{1+=lpO&zR$Cn^8gS6Go5scQJ)ni&c!#Qbn8YYp$-jjw{=jeV6wl{q zZL6O44&K76`s?;BG5KKOUY(2osRIFzrPgp$P*6ln%sd+46rC*Wt(M!anV@POUeAdt zR{5OD$8Su+#(nsJ-b|7^ZGXDR9rN%!$}3)^+^A<96rU9Pf1de z`r=nH)Z6i;#|^{YpWT8H>)NNQpm$+c$qMbkcntp)_Xjoa$l>F}sVe7$P2&BY(O_R8 zurT{Uh7*XBPtq;&-tlWcXyF4&;p&(N4(bsvi}pNtzqe}F0>fKntKHFc zB6&qMzWthU=Os2h?!`I)n?RR`z%VHm4`wb9C#wCSWh~q?$`&Mb5OX`icLz-℘$l zxi;w}$?YX20MK{irvgE8Lhl$%tApV9UKVOy<6ZNSKytI{7(pzoG5t5>$5RsyiJz>w z76r}mV4_Fq4HiZ74N^3rT7)5p^vs^OE&V7u5;i7$kL6KQxS$#SHR6qQ)RX3~bYLjy zb_eVKc9JufV z_mir>NOv4{rlW2qsAtD?-pbW8R}=lHFMk5pCltrA+XLxx+I4xq0Jhj#`*&&iT5lfk z=l_WMLXFpH+|LxLCN%ClLhL0%+;MuQn&F>D@;_F+Sx(5#{1J>|w4D6jYjz&fxW5AN ztv7o}em{5}`~X@QQfKfhiZaK}zQxe;a@G~H-%r7;S-hC}aw#3;`>n_BmX{%ry@M+0 ze>{F_GyKs4TfHz{=+(OM;$RV#*B-WnKIxU?gROnB%TCH9tkj6yZu`-0Tmq>X{3^Bt`*QSIZY}z>1}#b!mA|B@(G9ex>FDV(Fb|-8 z;GH~`CklHt;7=OcNNib%tggNDslix&2c54NM#%^F!AR(;`c>&7PEVV5YgVcw(Oc-C zAp@_KpIf?6mUWL|9&nL1AU7rB3IE=Hmc&;gl^!I5^(ME_;S zy!Qk5G!ZJ{!v>QG)5Yk~{NvQ8%jhP1fis=@V9AdnOFydiN8Q*WU=#i65toE@k(mga zoj*P??-0+Ap?FET6imx3z3G=twioz+WW9Gh)&Kwh|4K zdzsSKWmUA;(vYYbaD|uMID*JpK{FJCwh_e?2cgk+}5$S_q$1X=~ETT^SmdAd!yCs*TY)TF}2Bs8)k; z$2z4FX6$iBOL|7w8H8_UB~{YAdC-+m$m@!o6=1`w-V;}!(ym9< zGe)97pvx*HKSyCB$&3G?U7}?*Q>`1%kB{v!0~OCdKF6(HY%xJz`?Ved^0bGA-YcLQ zUmv_DowmBAotJ)M@OMQp^>ls>h_t+}S(eOaxl@sF1DT;&z@kh5$WI^t8<`rU7Nk;aguZ%Vn22jt7JpiIt5gLJ+RS0ER047dw| z^pV6eLnGj}hIf%rkC44NmUS;zVe-8%NvsV`Jto)zwX^^CQLKC3-Wo2pQ3p=bsd3Mhy>AkG01J_yr>!=w`G^2VPpn z6#3faVDV&SYQk;>6oqZNVM%Of+pK1j*3|bmOn&ZJToS4AIX)1-MgL5h6s9^pH*e=-7Aax;tv-kNvv`n8+ zp;=HZ4b9-*_^J`yY;ciprW5bG*5 zGZr=0B_<5yd+Q4eu`_dj5RAvv9wTu9L(XN3SFq!zfvKowy5jqPLf{5R%yLc^p`Kwm5^t7Y>IhG&l1IN zv9B%{-(WJUR_A@jz!G?(dvYAAd(ssqaoqkvEca3uvDt1sBxJ0vi4-qd_7lF7^y;WU zF?73*{W{ftcHI}i&Jhv>zqpRYg}0sjnVQ;2IB{(7ZlgA+3mKjCb}MwAmOnhZF)M;B zRz=%Fg7ZhUHpk6#?=>!M*rMs?IqMNl&CD*)N5Yp6zBu{bMZpT;qT|a-QP8;o zYFGqueN4oDuK`R?IyL4vPdLW>N+PY)9$UQe9E$Uu1w~TeXvSnMg8y7?aUNJ6~9lOsqIGy-km^oT{nrs37sWXy;=abz1vo z{EXfVcOdoRl9R1*7-Eppq36F#8!??Zh$dxtvM@%^+u zG+zn(wr37|Yb8#L+66xrB;Ky;?Ug0kXublOFe&lHf3smN3$fMZ%N!0!9*@f*40+W1p2untf^O5W1V9(an$!5}RuFcK=IQ4ahBv7@a%d$Z41&WgPM z5$a-d=6KGN(EUJq*`)ZW!hKdp^eDKbi@aaP)5-nP=X7m2tLH*!CnSd$3&o@rWy&}f z9L`pbBGcf_s_5;6yn@R~tHwCb?f3hOmCmJkHAn!sArxDuP;zOeapxk^UhdQ_L~zJI zq`&+W(`RXolQavJ`&<=_LJzat_Hq7K)#55B6N~Tngr!2Zx{iN!O%or4UT4dJN_sLR z59>28-}v;WZ_V{fqA_+%NH7}tMYqR(x3;iNPWa-hccE<<^#xq$IIG@0s?n18zu`8p z(rc$()P;qJ2c5Fdo~;Kk9;yZ;qg*E*&oBtKD)QG{YqW;l0_}RI+p;d{SLd!LITu2W z@i>5`@j8sISILY8UL+g*$#4E(^_8&hK~{yKPWAy7J?@3Vikfhu-`>_A>SA0=%5@3~ z6#TLF^aV(wagQ84mKXUVS^LDNHXbl5dRfcSYPYO7D0F{ZfAPK(59u)vI#ninEF%_x zJ(vHuu~FKTkvZ$fER6|c2Ei|#maRg2T?@J1@JU9mI9j+hz2FwT;g}&~9@S1+nW{+9 z56%jldV%||qe}5rCxH zS&bF!OU2^q7$Cl7zJ5kL%pmnZz-x~q-8Qsl$td#-#o{UQu+DSFSoV_c)RpU&A6W8k zqF3*F{roHKq-;vUkFJ2)1VEGLYHzjBn1NgQk=33QCiTy5Ly8#zRZ6$tcoSRO^%&2k z81d~)r8$?$y*p!{UR%7K)e1OG9yy4X5u@06YTA_`2?GqDMWA~w)@xyXdW2G*PA20| zsKHc*PF{)U^6cp68AOtW04bcaLMtNmN<$enEHNp!1Sf_cAMpOD@AG0Lf`o!}zBWZa z9FI(I2qrhro+t@va85 zZ)ag^|H`s^nBtbR;0)Z>9gi;jus+9Z=+1bvXTm@M@?Z3g&B#MFBRGc&QBEl`bfJXmy$=KW!WYr z|qV&sSPTi_H(6_9s-O)7p!${5cY>BSX#h;^7zTSLawX?+XiGm!Uc4 zj`+%beCT6EC2#)PYpr}!X7~WD8&{{Ljm&AI41bm&^C+~W#E-M1Dm{bn7qOxF5~awF z{#mJ;&8AKE! zkG+6vz#LF3{B>ACf4)HPa6Tj`Hqm@tlm{Cfv$L7c_@6`1;#3(U!S+kb4)BKMJ(M-n z4HQ{^PwGbB-M9D~X=5>E9@1@>_9ksV3Oq86KjGD~*UasMm%7sq)a}#iOHkshV1=6v zb96wn6x|T)5)RMV8=acV6mXt>4(he?<$&c;;oD#M>p0RTxeU8U1uHh=i;N3Kl#HBg z=9$*^t`*4NlI9ktuXW{$XnsJY8uS7J4LL+f1M#IsIw$9bli-dAGFcb4ppv_MY@RK1 zUz?q=cG4P|6+L|`x!ETA#*JXlqr1DGZ=CIHetse!VF^wZ0|FgXISs5EuBVj#VdFG5 zj4V)l8cJ(JT^*f{KPYHk@RM+a4D`kp5S4EX4cmCWxg8_)Jh!9}-jdoirxK*rq{)uE zHL6uyhD^-yX7p)V@K(7P%dg9EM)NJDy&VnGH$rB4Fe!+^M$xR%dl|q&afkoDaj^aj$QE)F5jT-hPcURH5miDF?N6tHg9}FmsJtoRu)KvU7fa%&Lm24j}QFnRm;$#xT zRJKK(el4!7NU^R0sfu#V%_HDLYr7NhB3?-NWzO{vuKlpfSqAt@5z4^R>=t){>e*-QMg=i>zLr*9A+Bh+2KY9)bmpb~*o-CA1(e|Gr1?0I00^ zyx(IzHo0V*<43om-q>GUBHCq7D@>6Z8`oPhRKmTMtLT(oUI^efJ_X*i;%bs!Noroq zKAc&u)aLOR*a&L<{FBD0BymaWeyB(&se^wgg}mBEu7cY;!8pv*IM0l^yGQm*SEq1Ha>`T3T(Tu2J$GO-{E)+VG~99k9< z6879GUp4D7^02~kK!uShrE$60E=6<-vn;qXW5Wk^Np@~+B869T+7wDFi}61U;eE&h zE#1EHYFTzn2Yo3D>QY4h6DFr`?W-sCl17+xm*)lmfL2Z|3 z>sKe&(m+1XTQ^i-CI2 z3f#N*0}5C<$c6{NPtpVuJwB+BLkOx<9$s)ODQ=Wr&rX5qk%BTw^u zHhS*ucj(8OsitqIJRJ{|sK<8+2DQFS&r8t{!uMO9ON*oxfFtC1(EXw5Sp=P$zjYO` zY8Rc&cd;s|)qQb6$HQKFh~bVg+g&5^Nh)8u$^(@XcaG%-k^d+jE>4X*FFZBY;uLJKmei+H7*PpfLSwhdZQEo^Qn$Bd7#gT--A>sdh(R*dlKRu!Ut?hXVg~)?VAq1V)tX`^A7?-qon;quVq7Xr7|%eE7U}r)|7`Qtb%pb-h~-<`?NujEKL%&Oha9czp6_M39S-Uqr-zlrrP? z`%v@qvOuZkBQa6u-Fvn6$gij%BQH>f&S3AvGmkXV=*>)Ngz1mJN-SeZIspK+=xJ)5 zmXPhBTQz&8`Yz?!p=_-;7+5z(t+v!CCjlF+@gPInmd2LSD=RZwDpt<=E@5WhH zVl?F2@enJUjgIW+$orwU1ZGCr6(bB4F7rBmi;pi=Ahzmz1hG0&6Y0M;XB+T8S2}V& z9W|8zr8SG-5l-!AHg~Tdt~an9k1_ffFn51g{3rMXO&48&#!>x_e45{4l%P^3`(^B2 zVOM&#O#MP(W>Z$ZKwiI#W)p;UjYUZiV zlhy8DbEBhm`qyCVr*gp6u7g4)#>G9fpAC#6s|jUGOU-kZa~X>q9A&L_3WoyePqoFd z93N8lK@|V9{b9X#-&4$AJ02|NWggdjfD@?Ccjl6P>&#E7d@1EfKKJp`MPMq*s4gfh zR7uuWMGu$Ru(Fs86hLq5xd=o1j_iKf+d;;_qwLJ?0lD|+=kMMdK=Z{Pe>m|-x~39n z3qT8vr}^{U7@7i5(9q9(@E(F$HNNN&9(QqRZ7o3N_zWWm39_OUW*wCCIzo7$3xi!< z`h3lf8N5WgYs zeb_PMd1v_0c?h!$W%vAadQ;N3+8qD$L!HT8g{VrJ^~+Q$Na)Mt2fdD%@qrLJfnb|y zE^`Z-Vi90%8~6O(rIubOAR6#TID)%74`xpt9#4BK62*ae4l@&X_H;5o#4xySOmpHc z2%sZM?)r1Ka2C_aKGKFKKNQ8UI`Cw|+WEd_hTotZ&Ano8#uiFf04SGBf^BpZ2uR4v z-2@3cbNBVIfws-*Uin3!3tTrugMWp6@}2v+mtiT z87Qn!&wjk~_9TRNc^qF-V)%#A0isqY$5hhQl$VodaxR5d)&5G{K6%9U&zQ_ zUu%Rh7@%A%MGs#VFQ_^#8^YctLpJ6(!h1(g)GLx3AhxzoDyZf}bJf0Yap3u|#&xlUV)J$xQZ2#FoE z#7JS1A11bKJRmio+ro=%MZUY||pYP|Jq>Qf+Lnd?H}FMM@?A5tu+UHM;SU2cBo zo}rz`H|fL?E&)5bB{}Qpodizb>Eks)B{9b4@YW(B!3VO|37sL^WkxXocSET$`^MhF zQ;%OumZt!KagtmPW0AJvgf9C; z7qUR3K9bj>RIfGHx3;1JIXKi8`K?pc#JEwVhR|I)kcMCN;aq9;hH-YKJWzY=HdvoJ zZl)z7N_qzZU3NfvHr4VOgidD!y>%{}!lce2mqx}NRbQqo)Nlyc_T>2_dnoh^-7 z%i@?xoXxk&x7Msu%)iPY`W?{%@2Y7`ccP{0#@9Qw8baxuVYqP!dTB$FvLPP;>23kgLCKW>t&8V__ ztwZ2ce$7LgBKZy{clCVu`<(trl(m?c`KC{Z9T^z`iT`R}%5kwh;C|SU2Fq#&<_<#% z7U!O_51gWj|2fo8{|%I7XdY_$y!h~f=Dbz>fartYw;fHsf*BJDl~=UT70AO_+V`Bi znuXR73jixorQn@iY+#jcf)OcL}(SZ*ne8J#K8oy+Xe6!{T&fCwg|XX z^*Qht8+%S=$gvLE;BEt464Z0st%DqGJ;5GCLT&!W3lZAmWw~4`yO5{8%tNi9LL(_y z(X62G1)8{szoX;-ywGXfAjt4E$P+Q&UG!Na)*??C_ zf>cLsYaGEb-siM>l~>J<2Hy>@u*=mQ_-_=GHO~g5EzUVs1Xdw+wspsN#-Jbm^VoZ< zHA0(*Zg{JTMW$%ssW!_A(xA<~3(bIyrVYz{6)1E5Ju$YM{f>oxt83{kGRoJSN6`Br zu9R1~!-U%&ebjTsV>ycCmtifbiI}2ucthO52%4U;C~}ToPzLF)Y=+a zMl2wYm zx5a99#|%a_^J&*RD8N5g5;JHy5jTsK&DayWO-cl7n4K)}$@5rywm}YP4a$o!$PzZf>hM|q2PoU;1OSr=>(q?3b_qm$D1XL#MV?5K$nvQsYex&`xU?NQkY#K;G*+(f4;OLa4uq8~9d zzQ00~?0~*{A775QXnA{>Yckkm` zNWHGgvIuT^TuwSQ46{g4CQp}!!eW=`@V@ln}JG!2uNuKTOToHE!mH>AH8m!$meIQG66}{s2KXOc5iotBTjBVX^O9_ zxagJ$4rwFb;QWzTHvig<)M~V+J>TCS^>3(2Fss4G>;n zJ5d6TfWgmXptb`dzze)`sC+0Ko_dsjvRzvP_)||dK6NH=`bXVRH}7wX#mLk5!M~yu z%VVK_H(8zeA&nyRbDj@EgR7X?j=C9K8)#g^Iwc$yBQ7{_n+U!Buzr&f*3Q|UVM*N_ zRmGDPR8BM6Oo<=OmD1V%&+e2XRc#8s?Ku;E+sU*U%yR7J;Vhy5(DH{pM{TqHSj)gX zQ=S$-F*P`QA$1YiSm7R2lNcAj&7qq;_n_uAF-*L2^VgE_z%62qFaISrY%#-Bx!p3h z9>b-{F?;S!Vrt-RB|Zv(_xKvvsC`KNt2PJGG`-d!GFb>lgRJcJn0TWewV$4FD!g;- zmmb=0#bHqjg7dHvW1w~aTr|lv&kliJ8f{LoDv_(QMeL&NUjYtCsi1mf+%ERVxwXyg zDf^J1RLc#Y7OfdM+X4(ZBCI8>ILFgtLR8Z`_>p#+oLnq1e4f!^2EpYERa^sb3W0{O zvMOFC$bI*Zh+CKPk*pmO@2pB=(Oo5Zh_{Xd4)Sdf)(E*+OOmG$F?+99VW;{w=IsSoWIz zqY84tQapJsC8I2~Bv;#()5aM0y8jFL>e(sYxlIEk%W}uGE-f+*rk(bxhEO#}`ZEEQ z&n6El)-rT^#;z@i`t)anuj|8ULHW?(-)~Ps%usWu@tP8;gO>ERo4)T3hsuz+Z;1dX zT7FUZu{&{Bd?RRMV*^kW9^2h?o`h*Q_N*CvZ+aQPKxJ?%@R)_&JvvzA*B7zEs;sh& zZ1Gt+k{08u;Lk&q3OyK^)I{aG7-^Scae8GU`+XT|=_~&zHe2TOPO0FVQvOcTr%(hS z1{Z%!ba4LWXiT&H=&U-MIiSX_$iGaw)!JhhPA`kf$x9e0aVN*c^X1P6gz_alD1(#N zY`7%ZCnoDC74BbN*=GMsosE|2wQo_mepBIZSZ`iKgj6w#t1vzKu;=b2jQhO@A|mQ# z?KuZy&A{GHy4!bKnnSjcT~m(vVyg@^0#impb>5089sptmZxjc!bobOp5dj`)@MI|u zn2-vBgPjIiP~nFxv+S#F@zPFq+aC(aopHdhsFTd>xD^))xgUR#$5?Jk)4Q&6feh>=w5?6loZO@r zDy4L%_=^T_lq>ED4KhdfN(x3=59hU!D}rrK*7|K3KDW+ZX$D_BZ1SOxo*^*VG)`p{ z7#TPqXwzoE)T6X$#slJ-6a-q{I22x~II9ROo=>4kCYH~8C8MA+F6W>jIf!WuR?Vn9eq2;OuG^puqDT)H z)QtM$a4|JKL(YZZ?u+;3ZV8t674(`%g;}3u1Eox?6aY5}@%yJG1 zX|&JPD3?oac`wv`Ir<+4g4yN!VdPzPyZk?t1wuU3-#1&T%6@eIA{O*7L(FnDK$g-x zi-0epYCt`cR(H+v;qhVCvSK_rgpZa|E3S2P9(%XcP`>fHmNc87$Qn`M6P*;D%%a}6 zGod%#tmoR0Dt|h9mv6@$A0O9mT2f=vS|e^9k~tRW)ixSwM|69eYSA<0ArSDeT|<6m z=;DD{@h~^An*t*16KTEhnY?JfYZ%Mu4Xk-dg)o8`eN#0N>3jqPsN57guJTriFaEdX zfOlUAbtC-@kT_aWnsOY{nL3=m|3^$?h!4!QVH?t54kCJ3jbFHx3oprf!@=WKR*7%8 zruN)6O>rc>G8ruzY+PXzvmAx!${S~06W21E4Bp~nTIFKhTHXFzwMw!n(hfL%Hff7h z#J;rh?14QhRE}5Hmi_>Y!U6&Z#;w}*ff45_r_Jxb&umd-(TqND%J1c2kW@2Z1}Xrd zXV01$FgBc-{OUhl)~7@(-fhwt)KzcV-8^V+2e!y7M}XTf&h(n!^G}WBR?&L~tMpXL zn7#`J?riuT0&=v1RwT(b)hxm%|-K|Tjrgd!jK_=OK))8!0TY01;6Of&XFp0=xQZ<@r~JQg@v z+~|OLu9s|Ayns@(Xe}Dnb@UA%D3^&n^2(qfg2JUk@roZ&b1=cau7KI$p%CBwK;50- z*6Pi-Pdw>~_gR$($a*`?iFT=o~zRN@8B?7Lv90Ob5E+b~hpC3Q#*+nlEydrbs zh&t=jP*_tFT9ZRGh9snYeFbdqs8cdexqIAOWWoNTC1=d{>CLC`Y>RmS%VN0#<%;+L z`x*Q>n1E-2Hnps{#1gYm=(^>Z#|-oAm9ZQ#Hr9{nm!vKc!NK~%N#T2M1Z8O8T)le* zCq^-bi{p5U$zk)^N7Pfwy!)yJ8`wz=U1&sj4iR8Wq6b)+m@2miwdejnhUzzGSj9Zo zeOSfZN%wXTKdwD>)RB^tq4`Z)iA@owmFc-2AHbOjRnBs|x{Gp@to=dZG`wl5F*)6g zj~KSET|nhzL&G!f2;5xS*ZR`ttMsJm#(%a(Q}GNS4SsE3|1FmZT|c9L`BEZ4?!GrK zab51`9`88@Vp1@046r%pQux|$=?32%x+^po*da38Rb zK7nC53&xiwBg*061F8>3Uu9tbqBJ)e zw{Ot99mAE#ABHqvdIry4X=3rmbdr_YOkIgd;a}9N%UuNn=h_RYWD|`R!JF=8U9`zW z{}^iW#|MIsFP;9jQA%(Z`JV1TsWEVx&E8U*E@n^+bftznE z4D1|Z^AQWBb2qf}87*(nV04exZ}{AhJ&X=k;4T>dQy6aG-rAIl;I!6>5fT*t61iZZ zl#HxqXlEd7;s468dt8h()M?8On>8Z1LxPGDAL+VH??q!#^=%>^-f8ClX1|=*vaaN zdZy~8n2qRH{;vU|Z}T6mJBJ88PY3ZR9UF(*@=03%2`cmC_jE0uln+04xO&1Jc=C4c zi`cO+qqyIsL*4lC6JcCNKRyqa^ZH-Pc{%W5?`Xb1@#flZGeV4#SefhWlF@+RDY?Mo zi0n5OOx?I|h+gsgrO&0k&fq47SNJUs*alb_;5`HUQofBvowF1X9RFeB4s);;@~O*E z3)vJ+yd@%rF){@>YwhvBfVYHq#jVL`h++>kK3m#+BRe+q}D z$hxG;6AdM{!2v5e1N{;SZ#04T!<=i|HK$D%=%71?DE6*s2|?|K+~K#Y=}qdGDCmV0 z{Vk$Uz~eUNju-*0go)fc?2#*Wh?6ppvQR*Y!(&t7u~w*cd3 zA}D{SHB0vMXDkS~Da-1^J$3YOf(2=%VrZm?W{ka`wq0xRsRaw78FP<5j{nX0GBJ2$ zbGd;X%;%Xq>Mf97D1e6-jSHZVJT!TRrXFy!Kf&9(yBKl_^Ky0pPt%b%+Zz@86>@OO zOx$v>0T1L?^Y=9Ut1cS;njm&#Gu+x?Z@2^WSj6OzGW%`BbCu0wH40FQ=LOfSQ z@@nscFd%%+!?82?QjwrTi_d?SfV9Q;L9w*2KK6vzKK+Al&0_QXr(xO&safJf%Vf2i z-^aeUI1s`9DsA?m{=Y!B4*KUF6+ivn`p}<5FB*%m9MoFt zVt3G|f`KB`?g~YLp6(&KIrKBxGdDLkTFS|=xijW<9B)nJ87RMo4UI*JK@6c*?~P9C zUWJlJ_D5=)0~%sz^u-LvWOsgQ*Bh5;EJq6GqO>Gjpri1=QkHA>O>+F5B;)*mv(*=? z%99RZ!g%tou}&lhLnNUUIh-yl=#X>jkJ%u|2ooyaLcO4-h<;>B7{Vh>y*C^LLG3l$0UwBis(@xtRY8PdDyoK4w|1G1^p1r>jTKiXp@Rh zQ<%&}F})rqMi~URKhoU7LoBBL;AqSrA}BqQ<^n}O7#MW+pjx14XELZeuxLTTV;USa zA8bIvz#tpx%aEbSnZN){`gsIT^i!yL=461*$`@{>R(oK`7qW|9!%#!tzHm{%f(n=! zw0tLZJr87%iRaHj{(J8Po^iRfEOkV1B1)~sM4W%4HtrEjADghDpy1M=DJ_KqV2uUO zllm$CZ`1M4UBoRNz{uc{ckd`F5{j|Ub~f7|+T`MFOQgoq^Wvr&@S<*qdsg6XHTr|y`? zEX3u#+?H6A%*W`!8}FmEA;s+I?b4k1p$cQkl_uWqeIsmDk)9;kK5`Y(5xc{0qIm|P z-`02%V+0I}4F+*j73Z-?XnCkM5L5@hX=Zj_+%-!4-<&XziAau2HcK3DfKeOA=`pWe zdt~VKtN3e>PYL`SoQ)<`>RMcy1k1G6ncRZb@ez}hB!zU^-)m~MN2=zQnrqkghlEWA zKocl=^!BDWTe5k|13NONmY*Qw$1(m0H3$zCHW2(RzW6n&th~r{*My zFOR^hxCwhRbbLX3B=GW`$LRD%5Ya09Amx2Sjf<}2_$!Xm+3P>LPPeJgL-q99k19js zBL2FbnWiVR>pk!DUze?{-2Y8r`EvxJ!(VB5+3Y@kG{M*)8QW9?D&~u_cb(9i9tiX$ zEa9o4S<8%uPt-+Q!Z}y;EYk4e6&6NPo1I`IGMdB~0u+$=XBed%8e!jUJYx7uibsQmuRk@h z!;v7;Y*MOFPG#&fcNVLd!LLFFW;|(@l?-F>aH9=HlklSeiW;Y*Je$T*a$NaAWnkMr zgFh?Lz^oW26gu3zUu!=BZ?ymM{YdC!WIT+rnh?TQsN`AMn&3W*KVOp!!En;1yt6!R)6ocsq;}9Tk@Ihy0Q#* z-H#O#LH`9CO?NTRogY8hu{rV2b$ETUKZO2;b0v_9T@&?U$({!Dzxwtf$>kA0FQI*- zF-t95#B%tZpGS;~SpB9P<+1Ce%R;VBWodP_&hozoEAomxW8{m3 zH#~BFJv5_5{F0f-ONzEzNM*96)%Km|U}Cq`ef?Ci-~Jc-9zTA3`SRtwAAhCA{t02# zS1AdECiE40Dr=i)-$~&QAxA2TGiiP*f}pRf7%wfgyjW&7t|KTHl$Y~pRg4Zqd@y*= zIcH$U%k}Xbu5vR*FK##~X*|JeN4qSO+@x_D3Wu~0X%Ov^kTU1e^d$03#J95+{N*m1 zgw*PjvwJDLck*@n^C07waBrNQV>Is--7MA`1C%~q9T=?evq9_Ks{I! zo>FYBoKR%?{JiRhqepw0B~rk&&RG|hxBWT8bgzqeHwN&R< znLvzWr79*JNqenj<2WMluq#@*Qf#JU%+~9$;nG4;=Oao+DQH%=Lw%3s=~-ODMp>&^?XL@0a@*gz z(y_kn33fP0T_VOZRlEF|C$apA)eW6kadbT6G_Cu%*0I|_np_G}O($> ziCcx<3FK}=1B4_*qi*3ros)=A^->xPs4U%%-LIRBn)!Zt4qbjt5Wz^TMK;6mHVR`1z>m?LG_7LuPn`%_viV%_7F0d z!F^;=K_R&pkG3K^rK0zFTM z5oxFV`(j^^Z(X{~252DrA9OdqGkl>p`mrR(;6FfI^u@NR-Pl5T@o1zlDBarOSd+JB zVRG~Ny8$oC*dN}&?k4kTk*2l(Hd**J_5+#F4`Qh0`gd{?bn06L{QadOcimQ-ler>j zFB)!*Sgchkr6D*pQj*T>1{zw@g|ILERAyj2053&$4A45)b)5*oJEt?2BpeUg&|!z} zgF^Se7Mi_kiBlXk6zuuBwqsjKlnuBjy?abe_Rw9Zg2|kw>O@BHcxf&{WWrwVes1&R z3A?vTZ|s#kY?ELD&i`}S?F3?c>HHfJW2nS>yjr8$ zdi;a5hNvK_z|@18{5kCH<`3pU1}-CCL!@vID8KrM6649Os*@OzS_!Ghmv`$lvj}7e zE$K`6b&uPI?OG^k!6%*io%uI+t_jWZm?)xY!n@BM4fgiLm*Ub`a9=5LmKBcOy#oVk z#+pK37>kA@ktk?q?_@+F7LM$O7r6hV)J5V9ngG!K&1&Or?a7f!=B&V=j~460Ynp8b z!>xmL9Z7RmP;hK;%yOoI&0)n{iX<;v!-?2pmg95xJ|CEaC! zxIT{);5@!rr^AG1sjqAX3*(_ag~BHLWk;rs5pMg&D^YJ0svj7CF@1UqZ4RXx=Zt`G z4^y-Do8pijMf^k#GyJmy2wq(lN)e=za`uRS3Jx7G*Vb`JUn=t~ z#gz+ehN#oLX1!+}5}p#|{&aR`Taz27J4?Yn6jarvwOj`emk6vv%syjk8a7C1DU+Gx z+0=2(gaCLzM#`uJx)7)Dzj+#OF?by%e1) z!5O~Dg-0(&w^19Or@W!J>wNU^j^fJKZ2bWN?|3pnCDT7F15U+1b7K85WI^=pOu?|v?O(*`s@Zqz~_%EOc%)HavY5QpUvnowa)#UD-6nkd;92H_td*S=31YzTf` zrB(ePL#s`8o9o~uC%WMK)hI9RXNAKO3f$_(jV)D~A*0O&R8ls;Vr+P5`*QXhJ72*U zxv4tkl%J)nAKYKema!{ER@kb}vWQOah=*4N^NVwCnpYBjFgm>~u-0@5g4n9AYz?)vm%Ugkpg3%YnWxvdOd{ zzgQ*kA^Rv|{Q1-?ST@V{zVAi3m%Bc~oG<>)R#f)0^P`42HaWu`eyN)l$t2&l_iKSN z3SSAjc@_UUZR**s$pOdyia`7?nh`GhG7tEk2UAnZFBipi%5dkvLj}X|mgi2@jS_+F zA0^wlxVP{U)>q}v7-L_j8nH!ecDclBN4Yo*GSa#$Kd`_sTRG}g+6pLK1 ze=7cHQ!|qIETPS$k1#0DF#i9@`tGnMwykfD^(ZO=8mgc`s0m0Bq$`3Vp-2yeq6xkC zUPMJoD25U`C=xkzL+>Cafl#IQD!un!zESVJ&v~D3|B+0XnUL9Q?bY^LzqM@`sb$e{ z)BKybh=c{ZN1f3l-+haXP?)#uM%xNp>vb&sD|%!@v0sL#X3`5^wlwsj)bva8yFulb zP*Pcj!`URL`nq`ubHGg0n3@k?;l!z}t!=xIyOkz8MDMNi{)3xvA)dGF6*vyYmipMZ z9lv9yVW3$8+$@1kPY!-noDQaeHoK;4CGKMK2o-Sgd(z{ZTESpe9$u4cbN91mHep_} zmQag0EEZIb#NG_(G3yM|3wcP%SvU?fvLVF-7PR)!z_Df9*K)USCoPbNnY?=Id@nxT z0UY#e4Y%W1I%NQh{evJK+BQz>o;l-IJF*$d^X_fY^MqIU_(|Vu#ODTT{4E2=S#2u8 zV7hE@T$WYHs;mVMmT;|u9nY}_S+o={3fi-RVMxrjG{DlaUNsDJ2Fw6;C z0aLceksXFKF!!H^Kw+cQqV1gErz~AJ-*7z#k{Zp=wlig=f1!~7BTM-wSYeWBShmi0 zWU-^>#j-L*)wsNCRafMGTEu-boDp0#{ZsNSD@*w!5=GN-$?i2j+sGO>=NjqHhx5C( zY;|FG1V9I2O`p`YJRbXMPwQa(fbSHtYgT$$iVv2`<&(rq^3|*62rQ}>KYJdk@Xh$I ze8=)74RxhXW5eD{ju+VMijIK}w=ZXlgI&tZ9pLA0)QGpION?u5Ly-!C;rcfNi(E?d z(5ms+M5yDF3FKgnx4RUmjJ>w%fXu|J4cT?T#1P*M9`J+IVb6IHp{Y2LbnxE<;+qvS zRkK{^=c^?H?08~JJW!eUdWr^7YV$4oN*g>9tpHrhjtFg^0_r#q<4IExjc+tFFC5gX zaO^8zrW^G+?5NGZO+xa$-jDOQzv&Z*ycnc#`_bC6UNxKseiJ<)CaK=nHpo)DAQIi-4}OwpZqFBiMk2w9xhW5&jQj7jXku6=B8X1Ydv ze96#vDLf*ne{*#RYik;sK`$SQyzxYpg<{ljN45VitE(0wukV>dZXBGAdabZr`{MU- z?$&>L2mmTAm0{oS?9znPCqE$0r9Hm6Mu z)s+6)dg=mp8L*SX?$2U7O(o|kfKktr&Xa9kW{G|yM9Go*#VZvdrC?F}x-aYI>1*s? z3#ONtn;6r7qK_ZANI#LsDJ-WUct1p&As*Q>Qc%2}2^ZxK8u)k}rx9X~--?`thx|1- zRr7fwsqLq4q||#Ucg{L4*})3RJPwp8A>?m|5% zqGi}{nikehpHamL@*mS^+8Foh+x$tD?>|0zn^LW%6tpFhhS=2o_6B;#Gji*PZA9IK z;ky6kryVhyRm+zcxD#orUq83?G}0Ve_@vH684?RGwO_PjhJAxAHu%pFrh4_I8mIce z<_1ytRsOR^7I@uv`~dU}$8D=$9iy<=HTW&_=>=bD@q8Hu54Izqp_yqIp7?G#q4MV0 z?Kw#Il&L-kNR`n%>{|8ffVr7rc&nl)!xoS3!LU`VCdksS8M(xU55@s;-ck;zdDOD^ zhynUTY11bLJJLYcL+o&=Gs%acwc;)rz?Nt({`zKvUeaS1`oqxvs6?p5hcKo6Pwb*XFia&@m)U*)ZK%<4;j6)yl4b0_$IxvMx)9Jij zOzFw@ul}Ooudy#WxtJ8~xkLEHOcX|tjikDRq_m@vIisz_{%cfJw0|zsg@#&0Fcu|& zg3>K5Q;nsFE~GB>=m@r#j*!x8yCc#GfikjYUWy4(g&6&v*1>(^d5(g@;d*@#$GQ}% zR>8jI{O%z0Bb;ePp!spdX4{iT53eVb6SECzh6P(;QlkvSz0X~H# zQrdpt6qvOgc~0_@PQ>=kPW0R$7dns;k^G&{rNn=cXr$>C1vzHdrpAnxjZi#O$CICg126$Xi4r0NR(whUM$4je#VKx*>4poroC?*itHjish z0|I)jB_yhH6_AclQEV|-G^G(a+1E6se*b>?8)%?hP>CW8=ziXC6OmEoh0ZSW_!j!< zRXbe9SkYA3To2C1mgU_n=L#C9djDRx5Zs8}75;)dbaNR@WkS5UD^_gv?wJ#RoR|Qq zcCVz`c+47mpXj(uU;~j-?_dfEBmTsO(OIX!Pn{3W=RDQpQZHYa+WpQ7=R++6I8rlC z3HfdS)d=!u!+K>C&~N6ia_J|=u=_ttF+*cgRqjoNhY)45`72IK6zt=V*`K15tik+{ zw)}gZ<`;=wzvaR&qNBkSeR8I0XCERIcocX5Q$CVKx)Lb+!eB6>M`}L>7#2>ucZn;W zpQJPNMs(++{Hjm-opBM)zZs^ZnDyFFvTR*6?>=mO#a7-WW|piTh#*wazw5GHq-;(p zZVhhTc`$p_S5(ZQ=wxJG`#$v}F~FNvYVJ_K=#8l=X=`)To(7OIqUC#Ugw|D<8-buR zIz2ep$iL;0jCq9QI?vxyh6jAvNe}avmA%@+H#}G*NB8;H`lxoVQ&|fq4YG{X_g`MU z1Abc_l~lGfeJ=87&)2SZVY%0GMoFyH;n~TP?=Ihg9fz@Dv9EG4`&4)_KCB#@RLTi* zPNl&A!}y>vXEfC{g}8O36aHiO@*Bgo32g?NhwfbA+Ek+9fwOV`CVC=b9b4XgxwsY9 z8*VjuIXR64Bn@XJClBoAg*%9{&K=e@j~ymS2?^8MD)M_Syp)HrEhGwW1<41iCYIdSMtA+Cb};UE z-f)lHu3MMbPv1n#f#t*|m%LCR#TP5^HQ&Da4Jx@%spdNB#nf?HAoW z)T$+ol5S#tx=XX1k-fj{iU-rmzC}mnPAV6}UDD@f#Zz*S*oT0Qd~wfBj&bgwoHgYu zfEL>8lu;kk?w*Pkvo&WYKErZ`Hv3QEwQj-Qeo^4OUy$q>esI@PSP*@tr>%I~NG%3Y zeOjR>|LxxKvvkd;i_jqV%fFe9BK17J5V+h?Eow5Zkwm}Kx>fd`NNS~{q4Ry=|UNHO}vBA}ZF0qdy3bW+ZgllWg z5WdUd3P{XP%JL8}2p!(gsh|YLzJ?m96==AE+G>0!@)qD1LKM<1tR~G{L2U*F;T8ET zV1Y1yFhewa)eS|at>|7IE|L#5Giwv6-tjSb%G}Y2gxVSE=peI1u2i(s;2`(hC5WKY z;gSlUAgQ|csP^~_h-qg&*a`YdSyNa(Wg6(49tg)FEw$Sl^ zEVmGe$7&gJB*y@4wQtejaY0c#Fe6*YhzW;Sd%RUV{^4y{MkrCJlS940^XJj+DmF(3 z^eKiaADn*wnq%Pw3JL?tefgY}$eJD+pU@aCuU?IO!Iy_2EF6#1;i?0sm++QyK~lAf z)nlCF>dfq3ZAgF6Y(vV~cyK<~AFjxcEx0s)`vL_7OEK_CcuDIop$t~#GjW0F`Nc&m ze?!Bh{JxI5bBc`~U}sBf=AzG+e%)4nX^(3_dD~!-X%fidM+ex~@<~MxX{_kzi(HkD z%&7es!=3NolkUIZ6Tm0+*oCPxU*Tl8&o7`w*KYZQq7$p2?Gs6pJ98u5R{pJvHt>ay zGC%UpI04NV}(_0p<3laTmEjHRTQ(X^rnLOh|GWcRb5zjUJ z*GCOkJjgsuJm8_@-~-ucf#uBZGykEzlZ3%^I0wixaUPQUp;GH|q-}P9g57|SZt`eR zq^fLon!i~oJW7!)P9)|OpoK{p{H3M{GqbtS4yk9EEa7fzJfN0M#Fr?O*z$LW7@H*; z@`LV%{;Y+;O<}bz@-vvg@*L)FU2ONg4DKFo(2ZiVu!OJ&cx7ePXC2b2T&G|6rzV9E zF%iU0iyM4YNW;Kux-(=z^-$P-&9vojGk?|Ul`i%?tt+qMloefhLZ$$aLRZXR6~KH! zyQ1kHmZCQ>R7CipY_J5Kt2AlvpZ8+4zEKvp4cmV45d}r-Q$SLzjnxR$Y!> z1vFhXmgmi^t2KV{6~HWsg-Nbwm)5Go;I-&gun;PKTUtUFz#~d z|3IwejlbQ{Qt&B5XPuC4yIN{I@i=0C=jn!Yx@5?hmCo1w;`r)`+?aW>l3EP#)do55 zR;4W6|9V|DP+zLpb{ocJB;|BiF($FD6MRg}Ng^%n!gjRso(~t}zqP=%hq&8^;L_ahR7s|V0 zwTiHcao^*E`p9#8sZw6m@N0Rad45cw-e#I`LwfU;ke^&IFuqutl->vO)aMBUV6xH( zPK(M3w4?(Uh*Ex{K77gyq(=a7^7ZmtfQo8y@2o|0M8??{kR;7R7&DP9Es!kffA1E| z)^JMnsnbBS1_T?K_Rtl%=9hmX(h3o`NERMZVlEt>vhv_zb*>BXB8`H>P9-fmK0mrlJ^c7GsVVDTL>Qb zZiS@EI|`^L%*(Jv=9~SYZ@I%{!&ZmvS=wp0KQ9Qa#N&ngZDPH+wDO1{gU;KqU0C`_ zpLDs?-QU;0I9pk4Y`bvMpQwFZ(h{=~TuL*lvRx2jWLx{__@2JWx%3rzDjI2<+O^et zl?hndH8JqKnBJjax(u8Bm0Jc=XL7~grt6|X4CB?CV(|jyvewxnwk$DjuE2BF3-_$V zbf}2>QmvRB;6q!(4Jybr-glqi>DxiDSM<;DQO~lw6UoXgeG$b|+MxtC!vvX>9A6IG zkQi%B%|SShQ{+Za5=z|_8!D!XXqH+V*GJBcPzZC?ae_j)T4=sN*m%)66X=5w?LJH> z7+Xn?zWz-=JtpuxPbluBQUp&3hrF_Zd;%a2ceN`(-dxxw{CYSlD|-nt^TN+G364}4 z3db>aG(gmefUr4Ml)!G&3)8f7h&3YZH9*dvl}dm=M2p~-(zV*A((l{ZVD9tb--Y08 zSh5PxRv!d!aM+n%F@%Xvy=vvR#sp6r^4wNyoFXLIhFC+$_iw~jXWx(2W(rkxELmj& zEQf(S=ahq6%bN0@&YQC}ur0lTpw_k&Gno_i;-(8`c!GIbK9@}AbiP8tVPrz&@TqX8ank8!3(VxbZ5hqL4(gL+aacw)H+;FHp*TRp`C3(-WiZowAUg~H)57{?ys*v&kAk8qyIf#t8VpKJ91?11{Uo@y>k@fj~M3l=QX~0{+YoErQw#z!i@^3J5eY(S3sPc zFq=7qoP@e=D&Q}W`(5oXcm)FAIl+|Z!}w)6@k086@BFAUO)>~v=jsoZZQjymUTU&Y zFDSQs5AhLTR56K!e885zvxRH1MbX(mpa~SgXB?^_rX;dLkw<)Bd{gnV3xu+WkN`?~ zv{~nhn{*olk>NWc=X=>ewMy3GG&*OY_EXt`j*uY|jXn^s_cr{BW9AV9xm|68s%ye> zT_7iX_;r<0q4)B4#jPzuxTG|o7i^!T@EI_^1VZt-0M9%>)bdh|FiW*sES7-?>{5Z$5sYYHhS@;@$_GVFXiMakCFsmk{CrEBM7gsnu-_ zlV9p}@?yDbJRaq%*ck3?BQWY;KkfDGh}Tk{`-o#>{SZQ8`dY(lnI>FWSj^%cyGuAwq5W9=2y1DZf<{7KoXD@CY~J22*cQaVp)5men8 zO`u7lv&X|!y72Op#WBs<@O=1C7})l?yPdsBKsbShfszT8d8n>zXNZhYIE+lvZzxtU z8*rYxl?j^us=#B%fGvko2G#G0f&?qEaBU!7l-a`|L$Pgw){ z%JqhO7aJH_Ec<>_afUNjbx&aU^R<0lv(xQwC}%Cx@yP@)SVqS8uUTLlppSq-3kHJD zFM8(+I_SkAGQKyLkZ8U@E8E%jlJQRjIz&6*IDhNs`UtGUH@u=VG~MDA9$)R@Gqx$G zW7wb!i!aSsYQUmw5e;V8ua<@eEwvZ*<@#y#Tfh+}k`xVra2rE?edW24NbAlxYw_y8 zLF8=TXsj}e8*4Jw-Zm&G2yiL?H$JG`ys%kQ&v%6a4*Bb~y+s9!YJCLf|4swaXp;+- zBxa92I=D0SGlQ(Ug}X0~{wOjoBFnZn`*ir332)Kzju9lQLc?jMbZ&hcL+h*qZ9L}? ztujNTNz4yZG}j9yhmW8G*XE3e$Jm9hL!BC4m&CMWw`+(LjFciPJRuQ8vsO}ilul|H zcjFWZ2^|@M!>Nk`>8^Ao!@z9zs{W2B5@rTHK=Ydp^Kd*K=w<%q;^ zf<9H?EFe0aUk@$OS{$~Hi^BsNF_p#YClA{rh*@Zt*!gS#l`#YLyk8;F+VPYSF?UgK zdrS+mdZezHs^KY&K5bIb@^YYodfa4D8J=lv)T7181##U}Q zB$K%eas4nSyL*B*X`0*ek>1~2F1q}MTVdYC$j)j~$GX!;1<@WBD~x=u*XsKd-Vmyg zKkk!Ga+-&i;zr?C5So^8|Fv@rR|C%(Q!(3GcCMHx+u1-OrPb2}X%h7^_$useCpj6m zqzbC4j+`JkFPQHRu}cW+GzeF2Da}}912AZBqT9l_r@w(fP}hoE=-{Eke_*8#C+CZC zjBiF9tcQ_wip5_CvMsAPgND;iPxOGi`I^ei%%FUS|2_JzgI^Ec{G)v_zeQY6j!B56 zLg_!JC(cBEd5P7xYMuJeE%M<3jsBYXC3O{SX@IFffj2@K{LX^vle)HzvWdo}l_E0vj z)%xO+^}bD{xMO}3D52QUo~K`LpI7D39hs2B&6)Yx{Dw&I%=93#BAFVdrw7B+piNrw zw+vxY!gSK^4u|tugoYf-+?flAhFmy@a0yn6l<{cG6$7_|s@2@ri_nKFfxQKOe!`nt ziB9F@wfy+;ehRBeTkUW`u@3 ziHr)i=h5(p3hWnr(~?U=NJ^)vGhFk8hY6O=Z(~W1&MTLWVYkhy_Omm)rlu^(K8RN& zAr)dzaX5&^IRHs944E+VDA$xTae{=UV~oUeV|#fXfEIX7)k{DRH1nF|X<#0&*u0J_ zt{ADv%L6S!b9C}HuLnF{mA?GTEXcPN2{5fQhyEc6Ok%v(&;2I-`uNy{RXp_{yWv07 zqF6_U)Yi(>dOEFfn10B;%-x?tx*O?`vkVr{t>8&Ks`K;-yCxK?7eP0$HPw0!vYY(Q z2}NmqwkUawiq+$ z^_&iTu_d+o5HhJ`08VINSXy4TX_;bXP4yt#~GM}&gWlkg4uI`4b8TjZeWij8cr7g0$9(r&7?mrKrq|10VX-!)L>om>B%BH;bwq}`GfIo@12dUCiUqGfEQ5LTm1h%;OHUUP>*IOL;5VCNPGvOkN9cGd$OAQCoN-j8&F2C2v4W_+N*w{?9&tdx5K zx>aC*O*A(L$k9}<*~cGb0BCe0p?g^KT{TDhk!h{V{X*Z>Z-GIb02f2a_ltVxxC@bvjq%BUv0)kT zCIq2&+o&yUIVp2M!^R+P2u{#Q63qI0t_|-XOzqe)LTCsIRfNzetW47MMS0aJRuY5| z_LJ~(M{N0-GhOo>Kh~W!ISQU}mYT}Kg^J!RTY%>(MCl;nERej@T|hsS{no(ELCVS1 zCl4-X^f2?|?KQljXM2bx+_e&C4G!oGeyP_TYVXWxVFw{Kv_TPVG}Nq--}%tReW~Bn z0tx_eJaPG8RD`1bbDu?bzQ`YXwQH1nwOf}Q`~@hre^HQvVmxbI3zaGgMbxE9>84+6 zfX6+tY#;o)%c`tv?#SQEY{c$mM@mtky~*2y^UusX!eWPu%1;pJ(lLLZLu5)|rm1l# z(Ul?4`atIaDB++Dl!_ed?0hVL+1Sn!GiG&U|FZLJzlYe;3MUWl)Zqh{HeFO8$VoUs zPRh>MB{ z)K%(%4~5_iO3E7r285p~-A3oee8mI$QhJAYfzO(L1n%(w4c}!kD#vNiEk#wEB8GBn zr8&Xg9CR&j#OHQni=-oNoKbdVXNN za!!qB<%kRz%4{ccuFj* zNbcZAJeT4l>%{?&d!$*L(B)wggGe8wdJyEoaBgWJx>LkwQ_t zi)*PQi34TY9-q~+x2x>*a8(go38!oXx}M=3%4SdG9={ZtRnMhy#V0eO20`ud)y9== zRYGZHYby5^MhI++1e&MM<%@{%OF}XXn+YsFet`&Iyu+?Z*vXziO7)iZTSPzEyUx*& z12lJngcwEfoo-BNZ7&C8jgr`0pGV>a{I^CT+N6;ScKUP-D0x+qQYh4?n!LBCTI*A3 zk$z);oFD&pl=L2TMI7J1xZ~qN^|#7u#`jMZQgu}ZxfNz!bi``eqRm4$mXm*Jqy%C+-_^ccJ$7@QVAB<#_n~e9 zcIVQ#pWAW8+dQa3w{y5DzvZ~6-Eo%hirx*85{uGScNyK>d9y(cWr$kotI5w?snS2} zNCY~tA;d5^%eY~d%pR)( zwOTXRdG~gFj1m~BOq$LO+s#R1LD5h~BAC!?M>crZ$@BamI}E&>n0!@_rxU0`@dOz% zpcL#v{(%2R4?5&#DGd%hD+2ONm`=B|35|H8C+XeI9_VsBSgf`!8_}SjPDF{jC5=)*kaiU+f^yJCVC<+F#5+(U4voBUJ89M6yK$#)@1IY9{TI;(N;?6UQ0pRzYdOjvA- zX^3fm1fffP-E_^L9G~aGjG#2OhKxWv1m?mvT6bIwyFeigaFeyOL&(9*Cs&jBT8PwqsfYsWgHBO)*l4wE{LKL#?QJBiV)1xaD zAwF!E5q33WTH|nuO&XZ5;fSEyrh(;IX99kMz~(v`OQUh4jGviWcU->?Q>DGAb!2_@BG@5_3N@tpWDrr z3u>iHeKp;QT_kVg{Kk%$8!SmR6Z%$-^l3uhVyA)u3<2G6oOgeO7KyRixH!x_tA+BJ zS$k60h8`G*BuvT1T zJ+PbvBWAiF0O za}6pqgg8$!g|VgO_zN}+ydFjppvs2~%`MnNA)n~6Dp-4rgScCJnd_iuN(i_S6piNq z`L43{D;UOyG3v-llcssu#idEP;0_Q2s;{f~(C(J#BQccCBs?(^?<_@1UThI3BPUfy z0N-%|J}}kaC^tQbVg3TiomebV$WAM5nxwK3cU_FZU&u_X-OCGHl9K7IZ|I+Oos8Vb z0STCP>Y>7*K3^_#sVp`ambm-f_%-SEe6K}s{-Ff`SKY4cAp1Sedtt?DYB7ZJmtzQE z69xe=4K0#dP>cWLAiv)0oRgmQ)Yt?da)?J{z0EQC4dNj|)&{Qx-HKVMnO2j@*}&tlOQ_ z{~yCnD2L=Ya!FD8hwS`#LUl3=K=jSYo*i7wjrkx$_n+-|sdE$=^+sO6PRhlTx5>V@ zJ$QxHEM&ZQbCYlXXg9YW`Y||YS!ERhCy_`XtI3cBCzLGIz<|=Y8{af;mePr7nHg|8 zJw6B|HJ~-7NvWI|(~8!x3Vc)e1OCv!e)^son~opT&ZGJH{6;Uo{-|_-I0^WJ)&E|o zzI_eAi!Q%_9?973_6Q3x4S6ag%a325x-0`!ynt8|q)7U;njG+uKv>0H$^vR7#B?GH zswF9+@K-o`2_DkleNX9u%wNe6tt#oM3D zfWX>2rwX6VX)^n>h+M;}zIIgY&)siT#x+wZ_AGvTDSZCBKa>1Uqm#x?zf3NPy4V{H zgN+r|wPv|PJ=DC$PE!1Bx}CP?)nyR%`m0{O69}WCDMR;MpAJLdPTC}yqbwDBe|ALW zBBYw@WPjh|2n*CuhLqvTu#%ei;29?*z|pr596*A{n#b1tpe2#Ib6_E(dx72S9fVj)nSvK+WHVmg;p&SfDXgV}tOfHS&2cIOhX+m@#kqE1UMTgZnAJz8dX{ciIL}30Zkao6%M{()xe!=AKFTodY-I0# z^MaAg`u<@h;*w9AlIaXaOf#%*JG{vFAZQC{qw|WMY<@~uJp+QMeVS#lcO$lDpo6Ewu0m>6ESJuq0H1699;gTAqzq@^Kj4yxI% zsv##&qv89Da2tq-rdD6WRaI)%mn~|p0FZNH>3Z@`fKdcd7)yxFX@iTKpv9!=ssNMM zdXjYsLPTQb;>23%5tR}ruWuh;mZ@3A`i<`mu;DYHwQJ_Rfn1-fTqntUoS?e6&mY1V z&%B=NXiXi?W{(?}HwGim(5IZlnH|^wPP(b== zbaXT(fKI>3TQ*6n1|Zb&OLtLXT@8gnz?R@2Dz?W>PzAtnG_{eJ`bU5b^ocalKPUdY zcI?Xncqwap1tqm7?`x^*P_F!Ot(-tk7D1OZHw$C0pgPxlaV%&|^iY$kAkOxuCsw?m ze1gg90xRYEW{W_};u}QSo{Z0#1^-vjLg^UIK0!?pvKMx||MoT|pU24~T1tC4f1rJM z>GDwL-V=LcTWG*qFG)@mRA+^OdxV@@Ywk#Qs!$G}5FhVz8r~fXTKx%EK1&t(og;-j zAP4b++UWr=rs1-ZmXKQwfKJAVqCwB0n>erE7w_bD_XL_%1rVNpa@|1oLFX!)L zOF^jXKnguRroeLpg+b*Y0Pdic@8Ckb8)T%87B(Jqa1ymONYm4Y!w}0DqPM__h!Hp; ziWa?{97?R+W36_Np-TB+?|iUQU!Vhl{yPBB)aWk2)Sea>ZckBeMW(J_#Lrah2Nc*o zozun~4VnMPK!2TX{VRG|KZ+QQlF@wQFXcRYO)YbFbS7k8rR;k3%Fg#ECl&b-uRCbD zr)%2Zq;(wmL{pX@m@!IUtj!cTU}=kund@wN@#@54PQdr{#VrK@G2_N}2N##(va)_( zK`H+ff8u!a%}yq}J045cI=Kew^St{&dhKem>p^u~$Ai*V5G|#w|96YVg5zPjyuiKq zwS@%?Fd6OzbS+GSn?s*s`8I79R#YJ=cl=~@Ljon^vIc6`EOFA~e6h4GL)v$kblp!H z&elFMQ6iSFToKwzf=c1WNQG7k0kpl{cW$*>QZXyuTT6m3LKV1Bb;sUY3``6R7&zcl zWk8wb(n4^2;u}wdW-kj>NL>k4j1HeMmnq#y?Z5FHNVbbWA$(IY_RuK2Hs5AS6g~#X z(#?}DKpyn7jy4sn(8>A-U-Nl*rJ!=MYoPLLL|xF&{zvb{mYF?TtaZcU;a+pXv#=f9 z#X(R=V1XUUI;o`9Eb25F1OKI4nNcv@P*LN=k~I zp-C7y^ltx@S(vL025u7Y7xhLUbh@+du!&SwUCD_;TBhP--yVoAX_%p-1ta8;dR1;v zM7gu|GR={>hE2c7dF&h}jL{c}(%?v5jW1`VhfP`A%Jy(l!-H- zju|N*gb}xFNkUNO6yd1Bu10LV{!lP+ZdUW=j~x5uv+%S5ukJpU(sgPO09jVv^JioG zj~M;&jytsWbf=(2>B`{Hdy0B8&BS88boe)6gF98@oy>fQPeH|F33sp60lLAgz)eaM^uL4UaWgbFu{FfE9hVo z-WXb#yZL&W|H&8DGusfbxbkaYbA2=xe)Tr2JJr-`6-_x3`CEExpmk@Q^ zIDrj*gI~afNoPsFy`(=}MKST<8eky!eBa6#_ZXfyCfrFmmOVfCbjTpXvbIlM{KrJU zpATQc+-9+jxY0`_Qcg7=E*?K;IT&lZNc@~~1NWe$N$+~?+R0+1EgqEGz#qM74Hczd zcww%$A5=^v2-#24(gTLmy7(2OXIt9|O9i$SKE0=h2O5&~0jY!dYcNRIGa7}bB>IYA z!8??L@N#GI!biYP;*uT1heyk4!(k!yUfo!iomh>a8+WD*Hl+Qj8eu9PyLCN8_ItO{ z9z(^)1IP3*Vgoin$#DDl%=%>~6hbv7Hq_OS7v&`eawZqgCss;1tOe)QmNYSCCJG9C zm&;ek*U_MB`Mwu9n zT7RDE!{leylX(Cf+XGgyTlBAe+4|mh8qG%CX+>n9mbpGiY)oRH|Bj10I4|e>+VcIR z<~iRYR)5oOcgu=;s&ln8#^=Y`h3Ase1jI%TY}9?X4Rid@mNGpT&Z))i`KECxqqj@% z`1&-Q-y82Hhkh*j0GAMgh_BXJO=jXl3sSj2ys>l8k+UB^ZgxDNYgrN7-oxX%*H&-B zeyFcs6;DGrqr(H&Omt4RZMHkz^G{Fe6d^#bqsKRU2n`jB*9cvhGWERg1RW>72foi(e48@OY#jsK_*NNKkF`Thp4yV4Qit&w*&S7!?XKnbYB|ZTgvXhyAS!9WGA(M`Fv)>wP=+IXylu9kv7Z29JUIz>`1$pL-EMw?_>3wnV%yQgFd2 z98B+dPY41{p-uyh_b;A)c^9YlpWwys6?*q4{L1OIaQnXeMYvek?!ED5OF9sK=>H(9&N3E1r;@Nhbj4LaPAha-~M(mImfKFm10=vnll zQ~`&==%}0%$6*9XL9nJ*kpGCOUvIA=Z|)A%`W{ufE&*G)JbY{vzbXZc7-9mh4SlHH zyZ-p5M`~ON{LNs6bLR0Usq4RQeXV=7OCzuT_JoReLyyn9^dj6P)rn;ySK(QeBgeuy5LMrs`%8`z2JA<8|@c8bJ3q` zOZTsWX3j+>tTd^hY5z@s#?lGGP|E-P~sthsS6RrYPpEOq#j(r zOzDcRIN}6?Hb*%^Q!P!JCCfv zU+UZ2p|Z#>n}<-U4})l6_V#D>hu3Rre6`VTs6qU52-%8(3xx0K#|;$?b4P?&cZ%I_ z!mg$oBC$rwi*zy(Lq@N*XJ=s@3b@c5=Hg)MO2?)P;@3z>GksD(C5?lS}+0twi-XuU>tUS57vd_-A3yxT`PRPg)2Et&-i_Q&98ZOF56Su1R@^R3} z{j#zC@7C9p?UCeG_=IDQ{y(t_&RZuRQ9qv!9phj2BP6RT_oL|Cco?lDlre5_37~$KvKvHS|EpxJLTuCwQ`K8Z{_-8|Lv<6``H+dehe={ zA8YtV34XB>BEcy&@fHdPJ^^-v&y!@k@z!w(aRn=iswNDmup|Ofg2Vci2I##<_=VAZ zt5TOy7w4PPi$bKGyrK~ZNHQwxlfvo>B1%HC%CeDZu*>(vjpfRwP%_*jte3>L*1Sk9 z*rhho9ObjcsqbZ$K=8#h78-?d$2GDQ(4gTi*ud)ATE8JL0oxP#y~FFN zTm|9p>XXekX{l`Qo=@X-KHhiq{vywa2Ncq4@acO-E>((&|0uVX&Eg9M(hg7Ae#>A_ zr-~6^Cvp6s-Q8~iW~^Ui)>dCn@o#HMLtb4(T3Y43EBhTE?X9`{fao0>+%{x+uFuh* zk(Dqgp01Z3+cR8HOqak_HAi3FVRI}1#2@ZHZMo%ECF$2o)32{ZqMr>X}0HUzA|WtwIbb#Y+G2@OmGt@V#fy);Llc@x&ayhzvpXvsE~~3B9FKh-<=M z0E}A?UX+iP+>nN4uhR=>7(Fjz8XGV5^^H!}<5o9_NoF?ewmt$`dH=DN8H}HMeQP+3 zsIS!wR9~5vh8c=rZ~J{HDEZJ#kJ7J#QF5DN%zkR%oa9k-!E(*lz5MQC`+DgTiER6y46xyd1`_|M`I9dvzClK#5ZxMls=LMX5iam0xxfCiw$X~=JA7BZ7xEG zdS>i0`QLhGp-UWSVP+6aVgi&VFRSG#`L}$KuZGJx%MsN z4f`C>`^6?lQZ}BO41Z4)1AU|XS!CWG;o=jh7#@N2>*(Kr1Hln#0#|w^;sJa3yyk z*2fwB45#5SxsLg?9%*4_W#y#^axy8!3s()u~K(-#$`z#9qJhWEnqZ3ymYKw*QY@jZokx(N@TC) zT#Bnq^~^WlHnCjx!S~cpsb8OU-qs@RGpgURsKYC$sdTtVZOHF6e=nMAk5y6+$Eh1S zX`?kpY#?or%??Gwg)XT2c`fUA*2mW`!|9+MGxv4llX@t8Xa;3LaaU*%{=d;L^ zA$P!Y;|-lI+u~B^#xW>OZht0#0n@By*bilX4i z4J4%FpiELYAjsGV-AE~Eky4QyAvGEVK_vu6m!QC?0h8|TZfW@49M5^4^ZdSlZ18f- z?Y_TvUDxORx#D7C%nWabq#z3K<#LL!_SPP5BLSj1h|NRh@<{zTLO3To;n2rthXsd>YoRUs>5MrydlrKAutZ*m7n4^BO`vapOs+5D3ii4Vts*-RhO-e>srmBColj+M10iL z>kB~MD+;fg+3!IHO*Zw~P2Lr_P{*1~&Z)QC-b|E|al{@a*-i7k2!uYR@sjWsj8%f0 zP*`ME#=P+3%>L%;TGU}uwJ|yi3Y>(h_Ro}?GTW@$9C26T3{TVtTm5%q2^hbiEczVW zKqm{XD~+bK@rva2-)(Ao@g6jn6*sgmoH*esJfoF#y4N(3(b8DVhxm(aac>}; zWvAk^l$DlZU`RNx8Rhf$t?;&iXUyhnoc<1zS3R$BDRL;S($?G$v6(zMSe498nAo}L z6|xq}gK65g;CMli(>7OEU+C14RD(ZZC;Y5UwuFb|y7ZJ0^Ygc{t1&u~98m8vCBpz( z)jo)vcrG#DgrC?Gkm{{;k05G9<%(OqV`v`oDICS^(3<7-cn0m7C|L*5^Y+RX21Dgl zKm&xK8*;XB>mc3BZYg#Ht(=LSM5pjh=Aaq6HNuEqDEmx08I(21IBm8QdeB%L|NJvo zcB7 zfjnDDQm|VwGT!&oF5)*>`YWGzV+}&hTT5@?E!TVp@`I3c15sym?mORs;PcNC8m$>1 z$~~WqMjfagLlreS^^DLH(nbwIuyR9uGm6X)Ehu~!Y3;{gYLji#&!z(}{E)1yQx#6C z@aQjk7qZw`P&~vAjpc95bT6QMxrD#;^OprJZ?7Hhzv~w0^wQivzKiItsontxVKwQU zJ4c1OyavD0LF()HdToogh*_`CJsJH&)))LP>9bMUmj3Fh9AlaiKHiV4if7gO)*4~b z7#L5vk%2NJJ>n20q8Lw|LO8^_k(K!6PF5qHqmFGh6vbNyj&P;eh;%Zn2GWg6;k4QuFXjzT_v5r@ zUs^A)#OJ-MJw#|%3KJR?x|ZJhbZ~nK!>#m0IlGhdZ-HofVL?ljL}+z~LWQd`UB5vZ zxe&}mg36ODVSW5lA&=eqpSch?HD;YMBwK_XjYgSr+IJ$rWHUm`VtDp{^^8Byx+XZL zo&pvWul@Y|fN8JP(f+!}8ixnO`}TjE5&D+!;NrDR&cBw}+MXv|6?f?u8Qju?cbafV zUu^E?Y){UG+ls$y%om;J7A2TIgTmtPHe*BH$D*pp!A7%)ULqh4b80nIwG5tIGei%Z zxd(961|-0=w}RlA)I z#rnnSG_Ltx56@ddie3A=^ZtGK{+Z|ciSRcXratVkp*JNQ7lIFGf{T4vc9U4f_ReJb zU}}HA@~*Od&0w^_x*BKjnMr$}s3U!E6}Nv+VIKO4A8DTrKd;^4wLhE zxN$FeO@lj15^+0`V^>1yCpedk^nJ+4AP;$XP)>J3o_tD~PeF2h)=hnBtY8z|B-C>*bmsqp$0Qmf_--Z^mA|*7>Mwj32>0ppM~W1^>wdDcR z5}uPDgMcQc%S%F+nY?ODRPb3u-I)uRD=G{(l52SM6=sikCJ0X8m;+%rIHcBcZms1{ zUwK4!imR@!KK?3bEMIGI>^y|uNSJ+xwRIhQd76VaJMaZ{w7YBKjG)|}8I>4v!`k;k z{yW#m8JTF55aQnyVo6B}@P(4pBim7=L<9vN;LjWbHaXl@wzi?!u9?Sv%i`kVIaUjO zzneOC=76S^4|4Fv438JKd^?jTClbTPp5G1)abF*U`5V1?RJG+RjodJ3!ba>v483=< zh^`4UT*+xL4A&1r|D!{4zL4RPeZ>ZNyOoQxQr#lfL-4I%@6J_>vP(2aRv9k;3bjn) zrifVH?AX5rO5YlrkwRm5vpA$LIG50U;(kvkmb2A%qsZ;HkAkZtmmn0iU21z@_Fsx8gDe6R2AOu_j#@8j-(N zjs(O-3)X|wt*Q6xrd14((+PqXIwEY1$fM);h{c~H&j%u&J-|1|?s1e#<2pG9_@6YO zKw8M9k#$S8c7vL)nORJS7N74=dKaFh+&31me%7Hk@>;`eK*Tkp%;sX+w|Z@E-pClYyG9`{Pnw`5Btg45zi(l=7ja%cGRCMy zjX+Oj=_hc!s!yzD68nWF z4lCuFI$vqk4WZVra;Yp6z3IvX{@3tQO{u>Ae&yfYuX_-1br4sfH)vV$QTIX@%|W3~sEr_k zUjEVfi}C>e`dVUZtp7l$FdQ?;uhyoqDxP<9ypk3vcjNdzjd@d9%gD$$68qU8>Tlra zZrImFO*6ev(#2e%s**;##+J1cCGO*U3=MyA(rv$5nd~*WqN48q6CKw(;g<@(0ARCt zuYQrlOw`(rqydl$N(nw`DOB(=Q^unzcI4uXvXW9=oe6b7Grh0|pADD|_rjT(wNmHb zSp+I`*^2PF+1b%pAedJ)H4e#|kgh)Nz+>@cz_(n2ZAo;hkacVA*b@W3rm>1C?VjW| zg0(0#&0T_!i{nbg^0O}TGVH8Z%5V@`Th*D2L5pP3Sn(&ank5_P=4$;>=lig^f!-ru z$Vd6K5JlcpXAPZ~U})OlxcStI?G-(Oeps;ELv;hL&hgJu$Q$CaR5E?^%VV$dVEAbH z$mux=_^jKw_nnj3mOXiF+>>MKvoWqi?vVaP433v}+pXAJS_jFTzpvumX!bdN^NWXP z5Yh=|<8nT}hXJN6M>F}zly28Q+&Ef~WXY!}W-`c)+hK7LYxR)g;$jnD_wX;)4OL=) zZm={Jx*dN5Zpp}w9Y}fqc{PDTALX9GnQD|>So~BobkD}jJ^LWaL*-X+kxS>gCuw4J z&T&~WHX$%U>aN>{W{58U3(uZAw|I7aQo-vJF(kIF=Bw^3f?!qRfg5Evkzo92RzTP; zIn`dLstqqMC`YL#@UXv;`^`wHoNxP#50%g-LT`Hu>qiIbww^roS)?R*a>z~hf+03!uDcugRBHo}b6A90G%8L|g;|-aot1cJIV5F0W#$-`(d+|dX;Q;eQRaYo zn$isAq$SnZciM8_ARE&0fQe@oHKjoqD@WRr-n^i$W3O746mkEaxiPc6Y*6rAt1BA9 zdpr=hljSyOtd!Sj{H&!tN+M?{D*Yv3AjiXA#m!_490}~h7d&VV1e5Cs?1D}6eupBh z)pBLN_tB8zqweS{QU)JLa_wusNAn4%ilw*Gn0YI&<-KeLy5pOsxUYWF7HHowdB&H9 z|4ANnpZ+Gd%(1&AXKt3pc$cG%g=040a|1IAFUsDxU*`LE{&Q-ubT~z75f4?tx>&0Vblr>j@WpAz#`H{$AjWYYT z`&QEIC+H$7AEiVcY@~=N+@**RdvI4%&UHilS@qlwiUQLs_nw;L--QK{+{kp*wS<-y z)do~7L15SfZQoZlA323M$4AnD;P+AMd;zjJE3VWpG(CLa&ql8W9hI6g5ErYQtaQ<=65RW|jkL``H4dZ`!#fsqdB}#?lDi=mPx+ugpVMQ6 z7@!x4{(i%IAO>I@A+KK~KlU03C@qQ-Gxm(k&c=qz1v-xIduzVLPZ;6Y`i^ zRCyo(nJ!~;W$Zow``kOtfykQ-0IveLtVTstu0pK_TS*~rvVsnK^B$=nATW{=>{E6{ zRdF+QX-UETc_M1U=rcCNo}LtXtsz3!%cQo^gg1Q0_oDeIe^+~ZSPP06p1)h_i_A(3 zunE(R|Mot=6jg)8De4>_t8m7Qi8pv`MAa6eCGFv9)JN2{=EQCGgKXVvU>$zpuv!Z{ zgj=NUd}xd;e5VcF%`YJS;_C+?4M=RG6BKC>xFEIJ546+ z?CgXwA#cRjk>HOuL8p(yr2kxz0Zv++x$yeR%8l${5p7^u1pTqaDcKptAw)jA{<$TB z)AMfE%^#l4|0VMO^Cfg1B<`4cjS?9S^AS$KNe8g8qPlORqNxdaRuD$N`RZ$I^vo zjF1!Bd}3(t6LDOvD>tvp>N)>@^>TWD!*`CHn&=-F_0T{XbK%5`ho-^60cBni9L@em<5aLph zwlEu;*U|=oqz04@*CSW|D!@TWPolQ_YTAsjToVUq{1|n{DcYbKNL`GF5j-aNv@>@3 z4$CdTtikw>qPdwQ+;)X%4gwo`x;8)Y5(8m+kt$@BP-4U9fXN@{SemBSZC_KJa{%RC zn5A7`4p+DxjgvWsH3L)2Y~Zf(MZTI^g0*eY*!_cP^K^fej1tZ~;KT%U-%Zt&jw#z9JAj2s5OQzB`RIt#}%}p=HL0dI+upZ`fVCvUk!ad4ZcBydwi8jV7!pFl}1oWNFnFV_kRb`FApIp@20srUvB{Q8!uIadZI2 z(l#H3XVjC=b1 zA5D+dDYCjD!)j2yGJ1+~)3lxSpve4K%tuLtl8X{=cq~12A!vL;c7?qt(jmIeM?WE& z7Jjj>HRdMxeP*VngjNdSyEcjS%@?mvkJUM;tpvCdUnFLEc}$FVPYZUH^7cZ5NT}i? zpfnFW%~Wg`l&Z^1TTL*j0XNazHl%v716NFd6edmC!=o~me|W1Gn{gDZ7EIP*YQ}MO zX$^B0AM_38Afg=|wFdxhBxtZjBBln)uV9oW^kht7939{YB)m z<51tf*LyDu)3tV)gLcdLfkq~O0V%J1qK-Z}@sqP@dUPR}B* zCk*Iv(gm@|=){_ba9Y zC!Eg;Q<@4{##RF}4M*C~f^flO?g+3qmBMHiEi1r*L{--gd;6gZoOs})J{H5nm5?AU zENwmN+=C?o;r&8yp2cWyza;-b*CGU;sQU>1=ABh8P2Ku|PwhSJgrb$MJ&Vzu;kJ?* z$mu_1qR5jqYs?s>IbmW7NE*~ADZ{5?iv1yEx%y}#lbw^PF$l8mi9k7^mU8g44C=_x z?z_HT(~;yp$m~FtVGa{dB-ui7&ejvj2&WZHFHPt!nQ;4_m)h1n>uWF;D^6ELN~jd&{f#G|-2$$(xyImAX;Loba45J~pbt1b63Y)3Ci#kvO(9I?k|4iS_<@RLzrb4~d zE&z2G@tgeK>J`YZnyqP|k2q3>Is7;1nco141=l4ySL_Wg*Q!ox^B(Jc;@E#Y<@>_J z_;*Wum~H%f?;!dpd1nV=%a>TW+HgwtYMiLe*cb_4M>+So#o+yALzz9@k-*Cg+fz*_ zG5>pfdYnGHRfhE*E;a(JtkSV>gXvHO&*|0h+DhsdoZoLnnNTnD%ScPRFSx$QeGbqp z;zW7tZCuG;L4mM02-BqZ1*{7102WaJo`rOr&(5p2yF<98 zAn?gg)ISErOnt73;3&ZEpja15?aF~u0tc+N+r#~r3uIYs5xhDMt>S6!;f8Ry&s>#Z zN<@VyeQ&8y0CE8k$#W)k$*H@uC=i57*&U$5ED-4-UIhwzxd_JqBeaEHasL$Yg&sGX z^TOM&?xno5b9r8MKydjZpH!<6O9TPYWFeUPJ4L;hk_J(}5VB_9Scl%OQ!V3BV>7A| zJIog|%r_gb3RrC+=Sl?%G>&ie!pRfgMM_Sb`0){#%^Y8^oeR0PbDj*%-`VpNXlgz4 z|FQZb>E2uB)89s&m3IFRC{{*_Bu_fbcda@h7F|87hU@4q0{E+It(k+ba6bbutsGA; zUb<9Z7J`D1?G15e?Nvk&B<$_Ch_>iwWx`RbX)q|0OLOjHqjjIcbr}*;hK%7rJEFU4 zafl`M917f&&h`wx2I^8AX_#18Sy?49jlbosuc8Dbn-LtBf}hOIGW5X;b< z4YP~3%V@xf@%FNQYZyjHUf)dBnXq>5DqfVc%5^*$R;mkJZM4=`Z>=boo~EXdBPZ^f zMeZwQ5su-o+80zz?cVl-?G!#nz=h@f46sRWS1%^^4AoSPuA5O&=dMJJmZsEN?jE)w zTIn6z&z83xIH>h0hQ1@kJ&~`e|Bg?jUu_Y&Qn}X>A+zWANam;ka9!go z4%bVCvlqjc)n9Vk(ILw*lFNrfEvmf0y_v(Xa-&VzweZjQ$s5+!+`Dh^cuWD3Y>Aeh zOmNV{o0bUPAjkH!xrsqrdRjlq4+acwrvE4^HzrAd)r+~_L`I8fp^w3dx$lcEH&)(K z7AH8Bi#7CsHR9pr=|hpr*5joqZ~$~+%|7qO5o1vL-^RXXN1&bqYu8_ZXY?rhusrlP z6IK97B85#$c>FA?kGX+EHEx7yCzNQfHxM$A!y9Q)vaS_a2T&(3R>|7FV6XW$PH+&S z_V*eVm<8Td2OD+5#F-%xkYX7wFng2=92GERSlw9AguPzolqq+5e>p5@Ff-09)8mPJ-z+eew;D_>D6BxX0!3h{v=j4S{YEXaV=wI-$bUMBwK=W z;vgaGR^s}rGS6EpwiR{V-Gc%ndz#!l!R26Unra<)&?pl(-Owx9D;_i+!K1zQI1es4 z3tD>J{Rlhi*XlM{a{tFM#YJ8Iealu$SuB&NqNe8a>`VByn>US>#l_7>#d@<+D>>?j z8(XJKYR39eLpgTe*QIbtvtosDdut*TBFvvP2np9AHnp_$q3m~RQ}8fgKpIT1^o&hP(4ka})0{jklai#DxTy`5^_^L6`pg`Q8xD14PjJ z#Bj<%teSNpGze(uP?Di@pK&%a9Y%PQr)hh)#8$FJp$SYfrf@eYS?QHmrKC{9g-wZR z#N)iyNEV5$P7jNC{+)NxKFQ5dCJzO=rTkJ|hN@;8{f(YK_pf8bEHEk`FLSkq>Vc?~ zU3Q$iQ)D74K%o{zr0dpMU<|u_X5JRehy$qYZ)S)J3N#3&br6nxrHT>7trO*@OLhk; z4dH3-Cb!<)A;j+KXsZZ3w1XL8qjP}}7h~Z!57(6rLPF1L4Mnst&d(~rOFl?L9gnw_ z2W>bZF)=2lm;Av6hDZ?B`uF;-)$n%u=h#!B*T6X7zt>Y)Qcq70p0A>Q?_m8P!)j)4 zrC*z@X+6x*F6qtZ$`)MjcJ->v;sfjJ2WdWCm*Hd<0o^~Vxb>TOb z3Xgp3YD$QZx=@bf0Kse8b$#``8U8e6#X%aXb~7YxeLw%)knkEsx?GK@F>T6&XM2xfL+5w|hI5$WC0jMpeYy zqVP)>sCBHFq11_lpKVp$0D2%Jpw{jIC4@auoH0|=m=33cRwBjZDm6o7SXa=bV^)Rv z>cB$_nrv{&`h~C+dKWO^v&`}p4$D2&BTQA}H~GUwe&;8Zj<{{dE$DyS^90yHJdG@# z{I>f@*jGcTS3a(efoVa)!QpoR;`pVn)u?wuHpZ2>q%~eo^RLSpvc6i+`cd@F-86@< zTT7wE8H~8B%QA^u)XsbiFV^ikwa&@aM3#iENnT^(&NLX@QBIVht6Pm0G^x7FeB%bN z=`TnuX|OO$U}$Oo={EyJv*nxjc%Ec&=A;(6424qsQgiL!Akb!%Ev3mC0dd`)yL~%& z@D@lK%yuIISnCjbv{=erzM+Qd3Eh{!>V}9An0gimwPh=WqZ|Z+;q?Uz&i-f0Lyx^Sq>X;Mz@AW+_>I$>y zEgqP@+v6j!{DlZgRA}F}dp1E(aDV?~kY0La_Sf~@Lvr?DzT4xXOw@6WESIViGF9!9 zMykKQ_PZ>XyS+yYNG3jqzm=y?Z54+u|GK_+IG?QzmprxS#i0KsZzXFz$jA$IQA<75 zW#>rli63eGTMgu8c6tFQf=ek_nLBx%dO5_SJHw*(OWT*{G>^G~7w2ydEW~n@9**sG zc7x&msAFaIws;0szS?7_9Ms$#D=Y2=}$%u^X}e#QQ^YfhjQu8XC;YfP)1N;na-87RJQtzXFlDtpni3@zSN{+waLU zQ6o$W0~f#mTB{5`XLG~V{hckciHr`;FPW2U+nqsT_0ae8$`xb>`st&o_Sh0$3-B4U zyjViEl(}&U1&kVOy|rT~_f}N6hK2Lt&a@slaq+;c?y-s8g?@T&b`?LM9QHs=-wk(^ zeYD*bTlg!-OWVkGt8Ca|{-1>HKmD_vANL1}E!8~fA&7B^1~HJ4AguAfSN@NoqIV|w zEE0|?T(G^y%Jt@ISLlzq(W>;MlPuWpWtHp3zp6cVQZ7w+hnl-jo{))>d}beosoQOB z+5C6|)9nNndxvU5!qM8ih}23UO<8=o31@_oNGSL*e~~3z_)^Ws!v}-FS+SKsEZ;zlNGW+*tdRF3;T>s=2-zT6Vpkw zO2Mu7Wg+HEYpMkEEa8SD(UY!no+y1M7-J`##Gr0NMF^KNBzE%8`AwcJ z+<$nAy4#B*o>I5Ad;7^9rVM=Q?(U9Fg+CIjBhyBFmJdLKf#TH9yf|j%uc;btvv&36 z+qc^Ryym@Y2?q?k(c_}#9+rbvmeurtp6{iV+xW_-As9DR(s^wU1*Ka=-&XY6{%OD= z7F+iJbQtu`x>9b`>2cT@g9?8mI0fjeTGp0}mFNnk+9#!iAJ@pG>X+pOy1pl0>S869 zKN2Wx`^DGEfYesT{)A^<1rEg+37qGV0NMlnliOOl%Dm%*h<} zJrc39WTqbO2?)Gn{k(AED^i>R?<^Nnqk(g#3}&S4{+gkmK41kJUkOp@V>fdff!f(I z;czwhg9gFwK>M{a+xD0&gn60tOG-V1v=iB~f3K#>vr*7j`Fgmg>Tzn~dx4Mq37?mL z-yE+qE?A;!OkO1vSs1gAXHvZ;K~6~i>cJf=bw7Rj^o9O^Z=n+>^!4tFi8Y8wa_s<` z_?4q@gz8};yHX6H)~QooVQKygbL`59+s8E*>4MiBhGg|qu7xLtSHhRTmhDeyMpRKx zki!GK)bo+sxDdB_BXig8s`lLG$9g~vty%u0vwqE7rsAGu$Yaq^l-11_tTbK)ce|>D z{7AHTQ1}PzYP;5AV)q^~C&=AS)`X9lLCJhaGXxcU2gx*rO$18wA_I>EN5k+}t0aaJ zkBaHXqA!_FP|S;!V1Cs?kHEw?1IDi=sTzkFhdS1Kb zq41jDhyJ=wxH2f%CJx0ZVTyYXW4pX=mOJH_fD9n+w#d71FM)KvWhJq^Dl|ZP%i2yi zi$ZJtNH<(dcQNXJZHD{lNxU)&SQWTP_2$0^{Szl_^D|F~!m9O#yCwiL@xZm(`_lg8 z5}-Iq2KtwQTV&-wBxrxW-rrm29-T&gBadCtpur5urJDvT-k5VPrEjg;OU3tFE?0gW zVOVpQAL5z#=GsCz?dfc4XCxKc~Xd8fwEt{474B&otWYydY&gJa@GyEZ-Zh% z$)5#hCQuh-<$v%@?7!U@uF?2X)D+QCH}q|n+90Dy0WKARI;j|mGZTb1Fg8QSgTI+? zGE}&~0tGY#r<@ZC1`0oBQ);T5!LW=Epuga1_MZRnYUkELUx3YE264h1+prp;C;JJR z&PRwYLBS+T0|1T`V)av%Z&_ z(Nd)zm8>ue(2!z}@iiecUPT6sWUwB(mEvYASlM^9Qdd`Er|*+z*3M3KXZ}BvF97&V zWPa!_NV^S3x@?tZ<{9ezqWJ@uX1xAB?C-XUH*f_L|M1?>))?mfed5m0&?({<)cjXdJ{#UYk;|A^l>H{fEncy`efapV)U&Awp5T7HlxAh8oS}c9; z$0N%KwGN}D7;2t}KGdZpz@j?3lVMC$+I4&7m`s!nLdBshWT581wUFQu-M{k@Q4y7YtBKl)h0%6nldGv+(^gXTAR3RJiZN zeX1!Bx8T@#YRj9eQU<@Kw!Xa;vrh&r<=n-Wk-Ld6O%KiumHPX>Oczo!EILP>b6;*> zd%!iZSnEqqKsE7Y1%oDh>bzI^GJ5EUP*X+C_!3N-_V z-Si^?Q1QCgz)5%oYF``=hR(=mA`-j$l|-_eO2d;(lt)mZr>>TAGtp9;G=0U#-F{#A zvH(g!OPZ%;OXJ=5e{4z!JJHfy$pNy-2FCsZsWjz#(C20$w|j0uABR^YFxTBb%Y;Ll zcVjas2`YH74fbR|#>|q2SeeFqkFX_{E{SoAPag_Q?$?ary)fRe7g+vjj+cI^VF<t7(ZR&#+dOSwxN$-g|Q8PL+K)BL=wuB zks^7fiw;{GzpMuaDzQ=JXQ9!%+2KkU`#tE|tKHo_5zAQ?UD*U}H}oja){88R9pQySfynMUtc&9{qE|f&GxOYVZb5do4AHkr?EIeu!x|g7 ze559}l?&gP|6*Oz!}O)r5y28vQ;Jcb%bNV=l&xgcRM0bFf*PwihPCQB>)JqtGW%2H zy&mA^2$w^jO_+_IxYxgz4?Azm)0H_{YVYVsBpIvFp@EmOee*LuGwL*PW!_5c;_hKH z2E;z+;jEz~q%dwREBw#C{FU(?*SZVt%2s`GeD)~(4cxJ=C77QLg3pyQL5aS5(~Q{_ zwrZKA_PZZrw_g|R`T{|NRIl+-Rsek2f0y{bwSHw^Bi~+Y?d^5mm}v!$@<9OsKk5JH z1i7%V2Lhre`fdwzrY3W~+L?^pQIgB9G`iJWAT>St8{qPv`y~4}z%@SX;&$Mfzw<4B zd~_%xL(VW*b7bCgE2#9y<4tVg=8I`CvaW};)^E(PLs=_*817o^-x}Ob8lr!&7OG1= zwH4HXD*P4Ie*4Q1r97t8F*< zCt`VKc9s^evTtQt(u=YX-H$?PJ_hEAC6}(74RVynZ`nIIth05EIV;K>Q{ZU43eMMS~4teV|m=b+XS8!5=nlL#sTGYO?mcr6%F{vyU=ihkKx#b^%l8mb@o7eB{OxZx*zOD;BdVIwiuv;~@V>MJRwwJ|5!u^iPg$kS6mU!)d z2jvJ8uSrmr@YAJ@h?D)Nl2Yy$KE9k1JheWZHCI=>0x4V&6Xid6+ILW(n8pXicT- z)B&}$42+CO_pzV?NpTmeNG&8#O$+W7^aOex-?W@K>}de|=0|!sin^c5r|L_hFl>u0 zg7Y2K8w?x%QaW?3kfSVImX`(CD1`f7>-NGut4YRS8foIC3_$NTj8BPsRDIvmU>cYI ziY%Z}_CtK8Kmv)Rbx%>fNHn=o){hjw!S{`(sD7hK+l(HUqLli+C4s&4PxnZ9**lnKl8Y@wh!tPTr55OZzWKv7a7Y?yp&S>Ea;Y`={>x z+X=_*{1E>^>y~*}O?MaJ_WlT3%9W(?o z(2j@1M8z%jt}{9~sl|(FUBCs~XXeZQGCa}U;IYJXPs=z%ejv|AD~pcEW4YQvTJ^iP zcSyM4)gWk+jEYueq@Wlfe%}x7#&Clyw7wlRlcaIEcLQ>x<8q+T@eN)}}P&ccop{Hhj0H>Ac3r z!_+0MM^#gJv+(q5MV$_8116+U$xtIM`RSk=2J}a1yz~G^!{OA?ZG_z@bZr!ht`~(y zD^0#wSZN&{VF-r>{6VDU4+$$n#n1lopK=f2;-xHM3 ze(C6RwBpyhN=?$3K{rK6I_ExScqm|;kqGL5>~P^t;N<~HD>Y%?9`LCeFpgh~4$*a9 zCjY@UpioBi?MQRKqwW6|j-RrLI68E4+1*mrW5)SuA4H_7&1l zo1rx5mTAZ+m3Bd+Bd?m47F_ z-W8g5gTpnD$Xnw(TH_159ZA-6qrSgAb5S55DCqK~OEksat7gt8UkkrHTMFb1|8sqp z{*>@zhuAiO@_UalL}#+vv1yyp6p5OxHQ9=B6RPiO{Q4o9C5iZE;7-C$Y4{ko73`2KzOn#mZ~?@AEw2?bYXxFld`Mvh*(oF`CcA?q-hnpVxVfk^PR`g&wtu{N@WJl zenQaOH>jOht5IT5EfX#Y5M#0Z(wGEqx&@q=m0GfMh=!$?gi0wIW2x9GLZFIlM6^+RZSKASF<%TLBt7v(Y2Pt zEGQ5OCi8ZPKkRumr06={Z8g%&4--ht(SkqgV@)mut_B0?rH+Vw6`}$z1~qU-nF}vz z>&z4;Er=)`VtroWq#acs%fO*5^w0GC_xH3c-t59O+&+J@w3LyBMMVA_2dGo=sxw{d zG$5sP*ivY{tTm3C)z! z_baw-3(7WmQgL>SC&y8Yz%02kH3NJw?FhumWX!;O2!8Xb;&`Q{6_q)>^cg%FEUG9A zjz!Ga#B;d6rv`g6n#%71){KmeZH|heM0I$5Q-#;wO8Q(a#vnUUi(pWu02+R%#!qQzT8Lt$q@) zl=hC9w*%6LnxHJwtphtEvq%f7M|yV%UTD^CNMWH|uL-p&!q2iA(xnskw4V{D{v7Rb zO1Yzn)&J!vAxBHEF)0ggltfqwg@>SDDc3N46h=%{cp-0cVdCuu-eG?mkNo~Te4ScY*fw)x&Rn^)5XG=NWSKIS7S4_!pC(y|F6hqEdnb10SOU4 z-K}agg|UqJpt<|{Z5MQho=54~T2;*q8ViHE1pR?bAA<1SfnG0b=#fIS5H{IHTUZ)RM49cQ?KTKa$Px- zi?GRP(-(T-$B@Eo7`tpLqN537f~vBw6~HNK%Lp@-3E?F|m5u1@tn_MfzYuE_adBHf zvtetDUli-dYAZ$A(kc5t;EbsiQNM?Ct(R84>v9I1Fc)7-ZT=_-aGE^m{s(sl6j-q2 zTD`pVT8LBm_>Iafm&ziW@!Ab6m5b5?!}FJH9(TZ!`ad0n!Ct1;fZ}W_-r!tgTMo1d zeGiWQymcJ){GThb<)~pu$4Vq9AJa1`bm_6v6^d)q%JfQ!e@Q}#Z*`MObyLT{8}Gl? zyTeuLgDig)QDcmf_Ig zFo+zd@u+D3mq*phKoY9LvJAZD*fuRbdW!P``uOW$3Q8??sfJ44(#mXmy@e?EYoGOJvs?NXD?7* z*C}`7+r%GMZ-!wBTzSR&7yG6VH+PrV&zK+Z=~=gv_UYkGcmKp&?~0HpLa$H*9aT;y zye5c0{E2e>N-Yp44Azcx7-cEukyhkI(@PXxNa?`Vy?yh%?8|7CucdB2T$UY*7Ojs! zWEsuYyrn5?rKjFH+e3^>Q`zI!BZhD@rV$ONVG?_?S0gY@BNFUT9RCmFhfSCApkZvV z#l#0)#Nt8V;Y#xVvgl3*S?cQqFjuJ&cXm?xeY`AH+{k`0i!VOXCx~LEy_3rx|75J^ zk4m0cS+fQ{^XdHL0Y#?2hvHvfNWglmeY{4iLr=6 zoW?+x;HveEG1c#u{=2!~T^)OK?&kNfQ$p;<*X2KVo9iqbKtjr#i(Nkd2rVob8_0t$ z<+*RwaPI-%dRZxtf_q}!^_czUo2E(p#1Cp62N)|p7Z}vh2$M_v(A?r=^~^^{SrLA5 zKYsiMd1l7ckJO*$wdwK%9s!TL)*`)^eU)nuVoAjI0L%Q?;4d&xupsSCg6{_gy>v5YNxZN%}n3 z?rp8$|J@Q}eU9M9+h}(M?J5Qnn9j7Lmq=iVnt%i`^zOiti@nEQv9tZ5wsGZ#NDV!d z17Ug2QvYHY?XWs}v_p4%4slLuxi`#rL#LYU^>2oVj zg3I!^En?lxk4D(SrE?^x>ZQI|wkZ^pkc_&!$4+=Gc*!vc^6(yAKQ{16VEzX~6OVQ* zmVb*8vH3xQ?HppD_Gdfx!YgC!yFkaBq4QnWWZl@ld#7f^=2aSr4S%RwzDZO)`h=kr z=EPsr%($^iF0P=-wA}WCiR>}+%S;@;iz9tCdXHd&$DP$~!V$;YQHUK3-1R zIp{5QLid5%r>^32r*t-#%a$wNgeTD%g>5^s{&O#au4@YIz5y@W)EJjzO)LrZW28-s*rDsIdEkEPm>e;wYB;CP$s4x8RY(a0hal6@yyuB^jXOfQE z*8sh*gp1C8zWQ^ia3!^*j`P*%H`vl?mz5vqww8wtX#Zz&xO$&%T(o6j0mRxlc=gK} zk?O`YM>0q2GBSG$c@`dewo3bT9{Y7br?wsCd9G%EjG^*77k7d6-TSdHxlKKJgX|`% zUoD6mO5Fc6ssYQ{=LW*}&nLw}JX1$b^>Dq}9Nu5y2%B$y;@jp}l&g66%AaJauj4CW zl$=)6vzx}YR#J`6*|>P-57$bIo?PJ_HvOoUSzFuYu{UzmE_kWG%4kwjf`t#W_@bRY z^o!o&|AlHG5}sJk7U`P&Mp{mr<~nw}pl9Ec*}+6@$9|;UonLAH?yr;B-xJq+hf#yWNdqv; zzxV%R@$N*Bo(0Et`q@iTkoU{DltG{!j<;w9Gmm(6l#PF5(_|&8}=^T}w z_KIsH;z+KWr~!Q_r7%3GXGi%_M;Ug<6ia@40Lc#s3|#ENP8Wb$&C7clv}|%ES4}!!3^^k^e{4TgNrI|L@}-1r$L= zgb^YrA+>>YgGe(331N=j=#WkcMMYqQAdV7HQY1%rkC5)}?q@$RIk2?>Buv-yeDkdR;8taUZW0Kb&@#UUXjY~W&LWp) zF2)Qs7}UXdt&UYIEja`sDVRP{?m??QXax1$x}<4gWjzy2X2WPPGf~K15=tHqduV!# zEbk%ceBYB@&2|I{{tFTZE8s(R?6>dloS)~ho4)ha;Qz(a6n7U1o&s@$LPvvLjs^rC zkQMUvA`m}_F_NcGker3H%q^q`0jOeDng=4m>3ugHX)ifD8t)>#-|3gVb_2`QZDa|8 zWE}X4G@w0qZ9lOKTVBRlCeb~3@Bm0C@IO8=o&n3tzLM6!y7)JYoeW~_dmQWu*KJ79 z$Ac&oHgt4G+T+^6J`rTW9QXwW_Wrg~s!-aMk1Qk|I~R=r274~CGscf1bhpVZ zL>`}1oh;cgb?lf3y3T)&L~*m-4m`F4eGKZ+06%AM?idp9SG6+{i4MlrehI@)B2VwK zoI04ZqX!FzO~7>kIKPR)g8y^rL{GPsc&EZuZ9YAJH)^{5^D(w8iuysxcJ zJEHBuV%$~@P)W?JOLPSLNX9Z0qFFdTq4H+CP}Gzglao9yMTXC8b7~Z(x{VwwWRUcv zu&oVS+MR1Ee?}H{N3HwF5`z@uukrJKjN}Y5e*=|=Qa=0jGy%gP3w{ZnXrUZHgvEB; z-H7)+WD0y#8Wa1a<_RKiBgL@2@vaL$hP8>f!)1rZ$*7>`I>v-ay{}sB<+m91ORk+Q^ir&H%Qj9s`E?WUu-*UrN>2;89P#eAkWmw7iQ(yC0KZCvetLP z%`hkXwM1V}Z57i_c-ZaucuL9-LbH98tZoxw1>62!Q!A00u+s3C%T|`)Aaf_DKA7Ky z6g;pWR@!|LA%Q9yfK_wwkvJjtQX&Rmy%5AZV$A4@rqhuOIMn?eReyr6)#L?y;7UN;REL+FEApCj5~oA@6w#4PUhhdp;wKRyBV z#1m$~l|_2--+bR5;VAgRo2qUB{v4R`Y(&#k@_Yy!@IciEH z_9XA1(f2L{A7G@A@5dy>!Zkl?x;N+Xy1(ju1hz1`Qc5iwR*8&TkV1!HKRiQKd@_t+ zS?L|ZQp}&%C?qwSPETIE)7v3Ty7Gs$1=3KZQn`WP6}%iqllD$ zD0`KhvPd~N?I#0A^7$B2*j3n5=*=nc+E%!&8CWG(^pH8*G{3m z^7%@T@?t?yf=5OZPCYU4S=XU!>h=17Q7j&rH8e4yT_^TZ3N^L;OB{bE!frysb22!6 z?jV4}ZYSFui?Hp3IYU@5Erq^26yQ_LCNi*+tQ**8-)ub9bXgHzQk#uhk++?(N1D73?4k+CafKq7f zww}e*oiFwH9Tz2E9A^HfV5HC@4@I`DUYd8H*I+i}Ab(S(I;xBnc{=V|WR4F75iM7k zcR^)!TD=FRnN(41!;`S}=DNrhgH`)}egqR1Xd9Y@orB3pHj+!0+Jg5*Y%wN|V#94C z!q)YEdXS0Z`hI_R%h0bNzNrcS}dalTherV0o0YD9mz3FQvU0nKVXv}+pa>dk@|?_ zof43K1S-+gc^LEE%PDLuStrKWufor0|G(bR#P`dDLmh#z<6p<&zI69f&gm61!r76s z#@@+71evKtFqBUH8@=t}iZhjh0zY(fs!DIAxMuCS13>Z7_ci@LIZuV4O8&2;y70S6 z@h0GX0N3)l(tD?Gw!Uwnmfd9Qcl#*%s{eG3`zC|5?(Ni*wmoMywI{Rp^QHRkhukPs zG%>pb*7{!rPxrcD(AEPP#IkRX_5p#&lAWLatD{c7>>G*@MzHAKllA;&DR!=}Po(|0 za^Po*kXWa`$Vg_I04Wy7hpd5`_)l#xaooihIk0&6ynHW32G5uBWQy^44>rujQMN20Q&|BxP9jO`zxbtba~|D*%iB^*mTTRlVr z?VKmLG`3(6Bf)2+X`>BJ+@v8=~ zLg}w<-veyPF)--xio%;Z1C?-`?!2hjm`5d65H!K^kQ*Hc(ywZSsZLkN1z|Ca6Zs-5)R4V4a6aY+ETh`S+3 z#u>L(ywvq)1&h7ZdIo%gg2jNyIS_LZ^UZ(CF{iUnNtU0q-VT^mu4)ZN(RgR#|ZioE?_H+O&ixqNYoEsHt()#s4MfpAhiZOyzt^1 z9*ZH98?85Sw5#MDv$GEaGs|omcK0wvvo8UT9N5*ma$+3N39U1Y3CzC% zBRk z)aTXz^B@$@HoHav%-(DZ@AkcE?~Po5o~*Y-ne~1SJOJ-$DN;VeBfhYmJTyXWvk@71Z&`+@hKSG8KDX4lY{LEpp0ZAHpk5o+`0s0A5$!CL^yMt*jY5qC1D}n3_ z*Z)N4-3!yl zH-)-Y^+?sxp)C&+thw)9LJaQ9&9${e(pWxN9UTA=irepX4G|46?C3@bS~>6(02Nn^!S5yh?r7AtuC3ku0Ji`}-^0G5ld+Vr2x~4trbCZQ>f=Df z3iW)4{HG_TFZ}&4N9rz)(xEZy8leBAFUn2@F9raO6M&?(#BuJKMEGg<{fxThuL9F2 zzg{`iB9D3fJ=ZK{3J;IUy1fbZMQF$-<+VWmjeb=avbOC23rLm${sK@EBaN`kS-M>^ zX;gAPa);;R>a@Ov5$31uT0r-Kb%ozqwy`D++0|E=a($$1iOpD^bibnlIQ7$x_#BZMn`2&IlXhNzWqopV3#jSWITn%y99e#S@-j0ZnewXE zy_ve!k;-8cqyS02=wmp1jMwTL<>{n%GW}f9b_vHJy zjt#b_9}7D;>%HJQwb(dKB6{aBAT+QW66tJUc<9S<*21DxdrC<4>Ft(S2r@kRTrv%=2Xr)2fp69zxVG|qp$y3-=0EoJ=sYx6xihHyro zoE80Wa{%fgyjJRF{_4rOH$cSiuj(Omv)qJKl9wAK$=Aqn5D1$WRc{T5oLPenreLDa zy-}Xmnld3TeHWVkcZdzzbAY6 z0EPYKhQ5K|yQitPGXhu3pHoSEjIPfv9bNN_y!f%&p!BBp=)?+Ty<-cuEcX1Gn%uNv zu4UrQggKcq^m}Ove*UHo=u~KB)dw_F38MwQ!_pyVUa~v)KVl4|s2zrjW68-|XFLzv z%G7oi4iNfkNEKYIpOGtb2n}OX=tpa9dVO;7OsoNvsTa8aqN9midp_H{&HHy@RYos8@;T(B89UW?E8_x!K^(?FY+=wkQn`SLkN}#8c6@Tj^GY{k<`5qU*tdMv~^k$j~dafPIN+D00nKMmPF+*{D$$R_abWd zt@o|hT_V$-sol{h#+MuZKUjK~W5Mren6a%Ly-|RP-S{;AAMf0#1cpuCfT}$Zb0)%% z7>g}QImAZD_RBu3-HBu7NLuk(Tl?R*e|S$d_P480oSSEM*@HXDkcX5P8oxU^*4>HY<^qq z;7fnJT?O{lj_9l2Y}+~{Wr18(AE5xNfE5o4!9TD2nytJbTV7n$cMQu~@@_>mI-zdK z+ktng-|*}UP+?Yu0wKpEdEd_KYlcAFrzJL0?bdv@ePEDP@i$lwaZLm)AgVho>*Flv zvN9K_I2PW!`BN$1?7x1qTO6#UZK4pxszTo~`KO#?680IKLvl*{HJoNq$t2EO3Y;{1 zE#*4++Un`W&}L{PU)17ic2@i^R{ZB^{N`f()?%ayYZ?HY<8t3p`XKJ_6dOOe;)iwg z2;=o#gZ>F^t`*FaveeFxfK)t+*34iIUpr+nH#FN!`tPk&v{{x`*;)XGMz>LtVfUJ- zszm0~9-FR0;|X#yhbD3&Kf$l3OTbc%)6I>j&G2m}<*2o7b{@C!%@?jUKBPXpA(TBh zHFc6Wi6Y;=^KO67-TL9F_n+=C<>_z%bL~U`S5#@z*Vj+6HV!SzOK=|v6R_;D+OTP* zKV^f7OZepQ{LA_1(Pkif|F)Wv;AwO$mL)Ki6Rb+;McWRLr==k`X*jW zp<)8#5)%Z@FY5XQsqen8#%{7oKj^4_wKW{@i-HXN9H5^hGr@w?76e0KO&o-kuat_MSK5(bZ?v0=)>E2KR;l;)3ta_IxGZaYN1% zB`-TR*IKjyS-(E+u`pst>7kHFw+`8_XW$q^_qY-(a2xCUZhCu6$v|(Ti^clNQYS>0 zr!@eCpVcZJ%@+rS5wDc%6%HWiQO8hHO_P;S5NlQWN=95V{)_!jrXur#n)wj!%BrfV zWV_0IgSHt-U``jB&;IW`!$XynuI`kuc_GHb&q(wxf!lL$9y?;_@xXn2eEhJ=eItDQ zh@5VxV2S0s<4ax{Pj4-*ug$%EeHfq9{o~_f)pW{MC%NC|41KxBRL3%>?HU(dY znTJf+73o5|q5kz<^UyHG#Mgm;8R{7+E#~WsorZ6OVR7XAm67znK$^%c22!7$v+RuX zshylx_F&rQ;ezuO=r!@(@dIqhsxD4mL>+8%nlJ+|;+hCp+A{4UC-sew(I~-RYnt6y|C(=zU-JOw;76hefN*h z?+zYTrbfOyzaEmJoP79Drscsn;xTCExWp|kMX@AyAij8%jJNu8xB_s;B{j)+Q89&9 z@31XV4p|$7r;=T@DS`213OH=bYVt+3&v6p~sPBZmRbc^);AO9K}hTn6r=>u{jza?acF0U;>|33+m+i428Du`wV z)kOK@@5SU-_-HY-o@5;@e$g0*{io)5q@AG_XW172X?EnZx8uMGK2YfaBcG(5=g$^g z{2mkMg%s8UwU8II#dCjAcDP>gr~u;3Om@%@lMW zo)i(yeQOKQZarKP`u9bv6}S<_z7C*x)&g3NRfI=-M2peitIy?x|-#c3;gnPiR-R${v{?E@8EW*M`)gV&^J||aJpciR7wbP zWkJsv9Ry$2dKFPhw+q(W=gspHm&oJACeYali?G_=8Sie}tNuniDCpsya<7 z8J$i(KufFuOSnaJpsg5y7I3vm*tXA>yh0)e+dMDps@Rb;X9L!*Txm=hiG|yNDYBNn z2BnW93W$m_8W7UF>C8Y+W&BY46fI$Sxw*&syHX9X^(zN+V3g3C}h7Cg~mgyS_ybjx&z*@g}m|rle&VVlMQ$t_u!HG5kQzEBTMH02Qg1SnGkLMNzfY zoc0L!E#rK~SyAi$!OBrq zeY~BD&;WauN-6@7`mhJyV^=r%SuCyG+euxNSvKX`B`6lA{{s?CKoc70hrm0P9!Y*o z*T#f`|4P!B{Sgj-@_Fi8yk#GYHOf0wfzflzfZ%rk%S&2TL`je-PQr?Dd@72_zK;4Zg?@~QEo57GiZ^J<61@V?@H$I6T*|}ljdxUJ zVGox443Mut_83JdGX(Bq(0+V?fV|$xkNZVw>y-UmKW#c?YxYeN{E*%jQDG5({C(J= zj1DxldhzoaeyMWki-J5m)Jl%?|H_g-zN6=}bWr3OFkDFt3?!BDRCFxA@`=aPQGY0} z2jEcO_GA)duxh#R{v6*_TacUkoX08lRRD$ITyU_(zn;fzzQIk2NAd%O#g|@t@2(?` z5Lc#!PuT7qyc51QxD&jLJZqaOSX zbWam{cp=h#iO9tPDirJR47Fb^{ZpC%zd&^csQKmo2H3BLnDapnF<~B_XB=kR38dFs zHhs%B7Fol_mJRot7;pc=9!n!+75!jDv9Jtve#o$4fWkEl#_A?Y05FR;Lv90tAfRII zILg39`lNO=Bjm%-zc|cg97ITSBIFtOl zSN10zeX{dG>dPq`57)`ykWtO?2|#SdM!YR0eKPw#>aW+{NVU3z)S;=2t(6PT0q??a z;}0@Sj#U%4?SNFXZ6u61*zOr=6>{Q9);oodwYwjAtqizzbIQN>ITil@vx$tay+1n1 zR$L8)%bN0*nOZ5?RSXDB7YCg&Pk-Tu?B^2zQIDA~L_wB%sd|zcn^zB<7?6v_L7jCbx_T6B|2se-WqeoEl4s_C`HFZ3+Hd|)fNIvC1apOqan zLb-5hNLB#CpYS&EXWI{^FwsHWKzG92$LELi4@-nWty(-WQ?SWJMyDJI$>IA~ZBgOG z$*RpM)@*iQ`ttkXwg9~R>HJ#vPc6JcJ|B2p*kQUF;9K}#A|@tMzx|(Tn$l<<#@Yj%U5sZq+f&gm zRW676u~tE4>?GPNGqh6r7%h?(@?mYdo#E&ZAA1 zp;C|d!n#^{F^=b`<*g-oVafMZZcc74D;=_Hzr%8qYKt%gtx_PO83lx-x`Zsir8r+w zp9usf3gkjcl2PNxud1Xk6#4O(jOPlBC=JnfNTw{?3-TPlQR}aZRyRO;p@r{3+hZuH z7(+&FHo)VYLa6qh7nX6~?5)etPXnT{^Dv6S28Z$%p98N~;K15i=@Eo;o98H6bsWKw zVg^@Dk0!y|D3bw=Z@ak=qFPTPu*ujbe zNts@OBets%MZ1@DV3j1cyAJ))oZ5Oh-^AbKdDcn^$YL;}=(un;>xOw?$l<&G`=z#J zx4QldUEYn?LFUq6dJBH)UW6;fW4TxxZfs)x*?Gf~8C=&N>yI#hlV zbd92hAmkzl>OAj*^@9e{4ts?DP-3#X9ck^_lcmJ;9s0(GmMX0&Okv89${qAi?}&ze%Jn_#Un*}Aud1{M)7K8CenCxwxJ@EQF|(d; zlvZ4QSoLx?S67QcBA`TrG>q9RguY84v5Zm1LX$H#r1bdqORJvjtJH)+Uor(&a=B1s zuj9WF_U~{FD0IGd`{}5!pCEBBwW!GD;{241$Mkb&X-$ox4Uz1Vt|v9LU&w!&t`BB) zpdnQg->Hp6MPCIt>b|NlxHvAWBgFWh#^7-~t=IaT#51*dc>ekEy%*&zjGVXiMD!K| z00)0gnzIm#+n%}~_~_W7)*}8@$rM?q&3157*0uPlzEc&g30Yalbei>m*_{4T2u>|t zK#3bCbw`NEV(T1N?U(cw@#cv7i(2>1Z*Q4{Wj`rp6SLXh-K(_dj3(ZR{)*E`64RcE zN(`S1uEx80fxZ#_Lbt)9)S%ZhR65_3<@ilRTMrB|3s(j5?%3GuVe^ybo3Em@U7DoV zxgfBIE;GD(HBSAD?SOhx>Gkd0qMQnZmJkJ1b$_d@_EQ5(6?(|KGOOUu)6WKk@$GFD z@xK(2njJv)H(}BT8b}GD4N-#z%wK;8t~0Rk*BPD;zI$-SHG!}?y>6s$S#h=>k3B>= zlR&@e9ANX|kRqAo{HluFT)7?*(0g87Q&b4C0;GMlOkQ8@(;B-Q=!Gu@2X|iNn9R${ zZIaDw1-t^X;xb7G%!vvkhC%0H;}a5Qr$_uN3+dVUd*@p2;1IaZ50H+h1=P|q23(=C z>{pE(vYENV%nrJD8+;I78Vf(9RDI=YTt`-&x2;mR`;vbrH8I9Gyetn5((g2(eov#gNoTBnRgx0dHLuUWgMoH{=YQL?r?o6?H1j8=2G~a-y{a3x7^vQ zLtdYE$ZJ`w(`dCSpWpU6QdxD&^X2${c$GE?t7{9L!P3YXB?BDd;6D zpw@1i#_;<>u7&v}RIZM;V?qlAuuIy~F=n+T5nASDQ_;+rDBBc zKj*oA5H(BRfnuX9X|_gje&yKSVTz8-Wq!l9w;(^5LUT!nXLCme3qV$5v}*{I4tK>K z&bOw%%YIf&xjV1}<6x$K|G)n5H)H^-Y5doB0*&WsDi0Aj+xTla?}?j=cFFI@k_ zCV@XYYi^L?{s0g-ReUab6uEH@0Dqzo@Bfk+-*q@GM@4Rk|9uOeQK8LLe+MWOSGiKMYS-PydO%r{QYn zn#%mUn3Y{UDMVP3Ri9DPYxPFjaLUf`Dg(-YoRS{OruOl3p-$t;D(2qa!OYjL8EL0O zSOw)vh163HA_)@A_uRu687X#ZR7uc%`uNq|$khGDy5D5L-snlYDqEle`_G?jidhlF zj4$q|<;^v7+(NfuX1kcAJz>I9v<^Oti|x`{S6a3&E_sJGzcz)uq>(eK TMii4yH81O5h=V+H+K;85&;(BK zj-hF_`F|^wZGG-CesI<<@cw<1Ce;Lo>&6iK=L13?tP$3UeUCtDDu|;!t*jPLmLUb? zIWwYy26?q27htwb>^JY?G;k&I zG4z}FvY6MLZOugKf@&|UIJdi(_ZH?u9LUbe@aW8t;p?f&k(zBck4dLbqMn?Kl1@gynAs|H z9>w1MvBuKhDuW;E@mrN+^2Tx-VXkn_^8O2g{3kaNXOJO}s@DkMAZ={MA(=dbcT`q` zSK{6+pd)`b$SL_S>_>@)NcE7Vu8V2rGy$R@f~NMXbxc^()dp%srz^oTgOqpf#N1(! zj4rhzjJAxSpES*3g?5QNbZsS!`o@Qi3fy_S8RRygs_aP?lixuc`mPVF_u z&*gD!Mc5a!`-JtU`qYem7&B+lNQORmvZuB`w02IcSCm&_4!W`PcL{HyXJG@C9$`;xbWx1}0;yb&F zs;SRO|0d6_aWqGl1~0}I;@LX1wjvFnp8IAF0N1v1iCAfE6>*a3 zf0hZ+FKttJYNxCf^oYOw`aqhI!hcef_9}-AI`S8kMec7DV*He{)UPQ2!ZK$0W)WMW zJNlG?`Y9o(ep9E2N$@tG5&qv9S71O%8Hx#M$yRTm!4f< z`bhhq2=pc_wDAgAH)m>62r@VaTk%8-RDILfroCX)7VP9bQxl5mD*ccN2nA$d*S%-L z6pZsQtKlWhVj$ovn@Atj^0t*tgD%7z+2=9|8sHXFf18@+%f({bw_GSIRPrH@Z3=&u z<;pf3^^>g_{j-A26}(NHwbC4EMboN6)l4wFKp^zC-zG}UAy65i%JYA(a=!WSt*)K&!z}xF!t`Or z7{CPAW{mjX3;jUhtUIX4ioB0(eegL~Vu)qigrJO@;@w*H3I38+fqf9kBvd4Sil)`) z(4k_Fvc(A841wFt=CQRGexL(M1teYtq#h}0LfGsIKD+|q^X7FS)U8?=^ub*yn>}eR zkmR&N~^tu>a6-F)=2o5Z5ILwJSPd$tSoE@*Rf%RfSOJ6 zJT3hnU;l6LQRV?89p22oyZ*X*PmyoZ|B^6}sX_Cpp+T0eq^sMhD_&DmQ?eAHF(uoG_q2d2h)Unc2<~t|W1$n64(1U5dj-}%;D$8D z<(MF~n>QflRnGoq*VSwrWTmtw`rdO?rn=C&N{C;T4o6~4Wf6h&!d!Rt<>mb_c%Ax6#Bw#}1F6(R3(xS+h4YSKqm?*~)VjPWV7!zL&4T zD(TY!Qn&+3gg?G9vSWS9xBbns+1?0MC?!sXQNS|atMDQVdOdYG2ibf`>Uz~9BAMFfA1+u znKr#OIy1t`+WDE)J#e$vM(s#_vTI@n;Xc5xei9vs5-j=91$iED z3#Bi(I1E6e(%tPVf}=Q@)qsL;-M^8vB>rdol4M~XI$t5q{?qogW-iy5BS6I|H2RZ3zo~% zfL4X3p593Ed3*BtdC%o}D4jq7?`;4rbzj(SwAQyOl;#G2A?o({rrdlx_`Tr5V3xM= z>2JMVZM^T!n;Brf@qfSA)}iQa$_V^_-aEk!F7+|BJ4%|YBt?$3oWb8mg*LlZ*USB| zxN?JraBVJ?F}v&;tREX=R;){bwmP#;CT)k+#Z9@*?%yv^33ET*Dtvm|v;=UHr#gZ$ zEeItf4MvCBTivXMu%OH!(vJPn?8HU<32lH9E^JA`WP0crlgnFfK75$XLg6-DB@U^hMdrIzf(Ac`Ta|Y2nzz+F|2n zM5dXEzbET3*%e}mVSZ83Hlfi!MzCMF(9U)f_|P~>_4J0JC{Ya<#@s#%tthDjPq*J;tp=rYZ|%lTKBLNh!lvwU_-&QGh~1K;Yc6So?RF6046Y=_MeS z$M<8$cqNXP^aVrY%K#xnFAR*#h69AEiLw_BL#xIP;7JiG+?apeB*-Hs4}%m-^2t8Kw8=6S8axWeUgBzl`$66r z?3v|r0-WT^^NcwdkTlj|Q(VEoykZ2=s6r1eHHH_CexqG4B&39)OJft8#iC#_6W!y8 zH9t*M%Y1D!Jg^7??}Rc>`9GpY>DOtw^C0zKzE`MoMbhP!(t?9q3J1d2bfE;H3`{5$ zaMLBL&{9DIWQh+iJqnQV;6!c3M=RjAzJ>;XCMxo$=M4-)d{wkN9240}F|iIp5eh{w zVKJVJsulh53K}iulA;WE$Q20h`?M3(*UTd5{`7mq4nl3K+i8Ku1S_ATo7%Gz&WFHr z6rGOx97A^J+g2kpw_aW~e!EJlY0O+l6gQIeCJ`G(6V-XQ4|xl)$P1`H&<;^eXTC=! zIfGRT#sR<#psuk%sS^W;#*(X2d6eJPO za($yxQiOh{2js$w_tW~c81+%Z4ZpN$0K`2zhg`Bl`8Jh+iqNX+U==R357cg^ zV1kzzlC-j<|N9l%x!a$!RubC(i+E{{iOECXZetq( z$_3WgQwt!&-eCCGZJJe@`zW|Gk~0RS-z^RD{d5Y_7l8LCw(T8#dL!SABb*+rY?!;N z0G(X3k3VHrzR*Qc(x0pZ%E?q*vNaz`GtUr?qTyysHJeioe zINn=mZS@6bF^w@@?0$-15ZfOgsRj7>{|WhK^8(C;`ew;(m01OD(vSgu+`6oA2xNV zhqpe|a1_|BO(d=pEXxi*+NiW5AZJNoz+y6tEahp$hs?94FNCk!zKAeSPB5GKnv^{$lB&eYW7T{aZlcu3q7J@61dyrdpgwlt&E?+^VaGI4 zK!jbtdjs66{_?`5NhNWO&ux7W=+}4#*4KZd{6N7!r?)7@Mu`G5EmSG{^X?nc=`-Fv zO=)wb^FROC_FBN$+zRZVbA)1u#>`vOEfpBR|MqyVIBy6fq&vi0Z|h3(?si{~3MlY3 zN&<4!W+$J`QOpx^OkKC*(pSCTCz(225aU{g4P{d$9@2jjjWr?j_igzhcF}xu^|ZVt zpx|n=>2rPgq%Te_5%RimapX8Fxv;+??n7A%mCatXe7F;G9@oY+m@)JB#Ya%_{N^{^ zlcp!x>2w-_{(*&UjHd@ES1BtULCZL$Qj1&U<1;Bf1O`!jcJz4OP1?`ozmGthJsDaj&4b4g%I=u!QX%1vjY=rle?rwpd14M!~OUMI`CH= zuzL7ihRz+D&glBY6@ZI8sXayINk1Bxorf)*ZV`Yw0Ulw?X$w|YCoQq68(sN0T)0P$ zPHWJbT2~+E2gdj2W4e<-vb5S=uq_HYRDOgycCJytmDo6n zzWI4%(0Oj#Ot5Qv?C#34(a?Q)i{QhK*xj3{<$8;nk%b29|AZ+@qK0y&Rt?}FJF1Vu z<<5%l`0c)DI_v%PIm{Hm11;EEywq)r88s97CnH=AvK!>L(2${tkE7jawUZ{H>gc?- zUE=&Gs0SzRArc(j74JP@ruLNJ|5|m1))Ku+HTM1Hvm0?HyGf?rU2eqJ`LwU5#$k7p z@2lS;SLCQ1u1$!O9RQ13Q*^q!9uaP2FQhW;B?ZPe%OnZ_Rwi1c<>+aw0kkuXb`3akRX);<9*ki zrqz}JqP=aQjEWnA_ny_TQKR5CgaF6zmm9peZ$BBtG^Y!4HSokPdcC@%l^|dHGkQ6~ zFn?^}VLWWmdC~KN^FMbW?3VPQPRr>If)LCLxXvP+Rlk}Aa5StTFLFS^= zC_f|bMBu`v_sL2#2K61SA4rMOcaVf(51~j@&1jmj;6TtR!;jI3V87k_`s681t-n7- z#P}CxdElpQ>Soz#EqqK@qTpS?!fKmeq;01 zHqC8Wz%SFthySK^Zd7X#6|*?t^8@c24bVvaZ4JvGP5ek3vnzY8%p#slkN~j&MJI`_ zw=sL}Z}%vdXgHF-%$E0`6}iSvN?hER2%-xxOpg8^adA zi6lvAx(!`!FV8n%i1hTC3b;Jqj3-xPLz8H{BVDGjQDlk(@gYp;dd&v3bxsU zzBZFrFh%%Y0KSU-2CQ|N8iHTT=P9IXycYdB#;X9y0=eYz5lp1dzTCT2;l#rUcuz15 zseDG*SQx9ZS;?zHL`cO0VUTMGdC;Wg^yN;6=z>KNVa9?u#V`1td7>wnywMt&LlF_q|dPz(ff$R$2Lu?#N;DBx!Q4ktt%5U zo>YztdN+Ih4&xxq$c=EgM3#+K)icot?@oc_z(X-f;cOED72IdjpN;BECIdkN7*~&R zU_QeLF7fN*?VI}?9$E@J)ZqdFo@Wd;IDd?qK-6x<1cJCljxVm=k$hX#>z)4Sr^I$S zFs*$6>|_s5GnKds?f90IkHA86BW%ejWlR5pC1qg)eq4@@g9cz1Tb}@IDl7>LsAy68 z_&d^~iAe8#zJAS%GKbjI22QeRTjzrduJ*%#-h^3$sau^>MCARV!Ya^pmo4uk9K-0K zF~R8&5m2N!G!(`Uw&Jrr{dE1#s2@hpxdG;QEA@RZVx#PM?E^PHYp@5kMKjW$c-;)Bk8h*@a%#FAJM}Z(jw&gXT0(vr0q$7ziTXP`;OU<+JixsZ zW$otG8&%=YhCB&$*?d&pxOIFkZBC10u_Fag(fz~2?f`nV=8~|J3@mYUN5|66#%=%E z&uV4zKaW&m94ofgrc(IVWQo`*;y4TC%}!xl%R%6w%uh(Us9uAKO_TvooTCYT8W@ZWm;ZM`$7!7LDRPh;PZeM*#t9*VYg&5oE0knlD=9m^sb`j|R;X71RjrM6u5n-@jG@CLNwgAU z@v6`)*wzWZw5JQOj{-;oi#+1wLlRU=3L(WyCIp9q3x3-fZVd=!v$R(E#mOHy6rf9= zRoB8OFcRC&USu=GMbI(&(@}~OJKnJGyjx+=^10oj3f98b(dix-`baNgulbsROm+(r z|9?CqrWT|YU)lh%R|)@ze4#P42P+ z2E>$>Im_s@(xfE+?yY+fPDRZ$X-hp*^JT>?DrdaXe`40+IYQ6K1GgotLdjrI?a2p% zHEao)*<;N}Lp5vNkEp7&YOBuPFu$A^Z74Me?kcU65j99`a@^D*#>12u7pnP;pF!N4 zC2u!6pX|;>Mn>M!$Meyic_Xc};j{g?Wl~2l%hIoON?jb^2YT&?CJk>|tk#MZT9;Td z-@%`FSJ8L;;#AKg4>JU7reRoHwA@S`OIxm@!W8cResJk44uUBnN?eO=!C~3^pEQxE zTQRAZ2L9s#H*>Kq0jHFC#Hs!H`ciPdk#93(4OR+gz+enAF~zn!B0v+%4otl;{sxB3+VI7_mIR9i zK>))VJA^JC)^_poo$cA4REI|28$dKoxZfFvO~xq*1J<%=_ErJ;s!R*={4Bj3fS$Qe z+LD77k*_M!@Z&GN!>mzDt^DH%nQ_mX61Onrpb5lq)J3%*imlHNK&K}A=7K6zfn@pv z{_>|Jw}{XI^d3+QLJ?L%*8`G$m*vwBd|G2;qaHhr55%~nzj+2G9`~D*A^uakdx^QI zrj^pMmQW_7NFu|F}Qy!mUaat3tpg#$!=eKP+9mY|%_XDSHJ*K~|fM&dtS1xBT8v zBUNyrNgH?|$Evzf<4=UK6SdawJa#x!9R@Xd5?q3@r9QxWXPQuE4=Vk1HUu9Rqs&|7HaL)CXEo(Cc~B zA{UnK%MJ^oXsVi;8s6&N0NUxx3*6=Q&c$}md1uc*PvntVz&$7#tMJZ;DT{^nlluF- zzM8IEXudWr*kraP<+I0(|BtEj4yXE!|9=T3WTaz;=j8k z2+}6y-`{ohpRVM1zwi4sp3ld#98^edMM}|@k1vHO zjDVm(KoQ#6A-(7sahUwt=DEs_41Sh%$AJ(}L9+w&gqW4wjHrhdLM; z>>xsULc(=XXDfN6z^W6tEIs#;bEg07)0&L~A3wN24>!?rBNU0i75$>$4<_+ysW>^m z1*z;WZY^nerKWgRKK-A=*fBA2Ny_e%jF(u@-V@EK!-~P@rFh&ov(fgkv38RRz2{l! zcd$2u)1yH@f+5RiFs?>X*Jv!Z7A-BW)3Cdk;IITj^j2bhJ|`r>fY6hpRS>s>sYSy& z+R%M+uxoe;c*ZsB#tTbxzNN$ZLlD#=A;4J`1D%H~&ds$UpT(!EB307S6=rYmeOw<%tf^5Ymw zjo56yA23~NXR3*o)o!41$Enzi6y;+rcrY1uX@n6kfvXQ02@QVb>WZ!<`%|5%#af3B zzdEZ6d>{oC=*74bADgVctm*^V;ogpA_VWgi|-#b8>uw%gz$i`!f z=Pk_rMvy*ZK>@Sz{4xzH&v^S_0z#S!H;2EMb{RQS!$WM~5ai|BfRT5p5JbCgwO0+V zN7FPDJNuoJCF&2PYy8p%ckBUZ4u|7b(wbtaQDX`UPVa`)Fua`rAJ*057wfHvbS+K9 zy00bzp_8W~3V2mNcY^P(^j;$dcb3`oCAyjX>nfOvF2e zWJcH35xBt3v$3OYKp$S_)>)_(Tpe*PJD6G{P_gf$PN_Od!2+nQjp)^PRbJfT@g=7u3~cT6v)`MgB+hZPmHAVzxoH8sZWpACMjZgNl8*7g8G(*Rpkfh-P-s)nui@WmRUM#jbjlA#Hm9Db(or|(5w$Tjc7;U2aJG*70 z!ygMwstnfsm41Fn={0q(U3qwix{5EnYKHd&6S+gq%8hrdVHS2C+qcd4DqguJ+T(zk z!EK2(EcLsBJTMe{^P%N1FRna#4*P*s3viqi!}lTe3OVHnpWqq9KfL`uFT3(U6id<@ zP1^FyH#dNkoVL!$?@Rs^Bf^>Lt2dC z=8iJtrTsBl_M=q1ZUHeA*~S-+tC|S+<N0~t?^ zAi+dT<-^?EoP^1e$?&Crv+qD|@*A_CB*YT}?M;?UvoBrvLn3Qa9b zMLEQG#=G@K3Ht%U)()Gu+{n_SWwRP- zNCeiTZ5?!_nm2z(IfeCZ(>y*i-HLNah5FC9doTs%TeMyYc(AB~BENVMmpBL}%2zd3 z_J_c~lR|=_L7=kk!3Op0OU>g~F?!_hCLN@mrV>US3KTEfRM$J;6{mS&+B{^ramez9 z;qwau`{CFM|GDZq&y(%-?_`t2ue=X;^b)^o7Nf+m!0<8l*#g$7f>E8nBN}ezE|1E# z-p7W3@|vjE@!1G?kG*$pA~Mwih$$TgAeO$9KoYe&Yzuo-dspxqPDC&7*LhY9J`U+! z@C-HP;`R)#@r_s*7fxme74;t7rHWjLb+rkZl(7307)$~*f<;E;L1=xGTw{W_Wt^xD zwl=y`z#THejWvfq|5Y_{0|NXwD)1fZS=9Znphf!xd7}njnN`R!#eW`-Jo$sSJa)yb z*bE40f5+{4hTp)JLayfc@j9VYyo|~?7qvrlwOo4R@O{7-N&bWu(fa27w!d;Z+C&NU z6p%u>&ZWe@hb7#D&Q-NSOg;s=zWIZ+*OmHx;L+ZCqOm1FQ^S>OTtNzpvwY$A2b}(l zhu-_Wi|_{lTAXzO;#W4Mr)F7ITPg~%i|cs_ECl9NvHLl@--F$v!t2f!C5k2bSV)L! zdm_ENV?xG9K{Ndamu?VZL#~WdMJiw*KlSjJDa~A5T>gJhXjIUsW*kjq%IM5WwZ&q(hS3OVr#^h1=CJ*FR2LV^a{#i`k7)!#BUM8)pQ+28Epr5rJmhI7b zpWC}ON>S$D$qbB!HdcC@S${{Xx^E_^=&BgTNPdR>i{U6R(+yijT-w8G$$`3&JKVAJpSxMH^*}7J5HgK_lV?N5) zE67EUnCF1E`+4u157I|}@CqIGewM#;r^0F~>Ur~o9I9P5|I~Jjd$7n8NIN2|;;@~Z zu);}kf&89{iw9lFaq0Z-khJqmSK+TK9Jl`he1*=Fww~t(H!B%F@0rh)kXA4%gct|_ zqRkGG^4{qQ>&3zqc4_aum+4y73#&jn`aD)o@D?i<)ptk~a0HbteiR0Q6|2^}nQ_t- zZPjQ7^T>k!bsvEcb<|9Yt&vF1CI`E;9pE&u1JewC3}w|gWsfXZLn_~QRpIg@1ob*N=GdNw&_=Tb89!4{6@?somaWeu0Yi(q-5^DK16gnf3S}p4Ea2()GUf z2?nlTOpDzTHAgMkho@hVgvQsUro>9njb0^?Gy*~f#jj6BF0gv6Excm2>==!*E!?35 zzCCMLANDS~9dfw83qQNdj%rW)+G#NfqZc;6E{VDh;yYI=tY)&UZei__8;8WgzUW>F zoH6JFQ)CZ3l#1f;#kgWP_L5!`YZf87K2x@sA?IKy#r6?H+?fwWCmY#5JiL4&f;f!< zCD8qGxZY;pDKy#CEWJE9Ux}NMJ73=E4zslOPH~k%zDSdR&`3V@Sqa6RbgWWT{KXBd zU!VIKgsEi3(Z{FOQH-ag2ZmKPfhE-cU0x3_)rva|7OGk(mrs1>V>0+T`B6q)MM#Qd z>$Z?l+#_}-gD0|UGE-mo{CvFo7t)7IpC5w~b%^Q$Qipx9dT}Yh-opaBxxEeiR|rL-Z~K8i|0^T$$KzI&oH|vfN8Pt|?ldei zf@;9{{60h-t_Iwm4nO5!TmkReG#PGCyk;6BcE7#Z*Pcz{HY8}$HSrY*>icp{3~=pL zc0h!W^T2*5@t@)M0^YrcOA?Z3VzNI71VC`mcs;}dpoyM0GR6~glIe<{6P?i$vl~eJ zpcFGqjxUCjdpn3g_}b8OJ}Sa(U>KcE_9Rl{&(8gpa$&pk{a_E+>hmhg*HG{06vnz{nWo}jas$mqe?XPRLkZVFR>|o3XS{a zd<4)a^cs$AgFgf4mXR3-?~M)iz3k&9y&g-^-&9G`U$A6thPAgFB4DqnE|jj6@m26t z%*3vl_H2pKeHt)07#!8ztTXD{Y#o(Keg7hNr!v^suo@t0yEgucY72$>j5O`Ew4B?& zeQ!Xz8U7ifil*Ibh6`tYls9$KS?jID&!|`A&Kj}bPsQ}y)=fF!nhJ}Ovc{#Wfr zrqR%*s7bXcxhbyA*DA~masZ8^K$MARZ8qVa{^{G5-ojjLOzSW@seP7m0AyCK)JQOI z6~}tq!UjNIX~!+ZrW~#&h_ABjf&IGc;?E+0E_f~42oisgG3M*7l-aCY!<4C1#d6)!JgO4kR5z~PmTvUs zZ*Ot%YEDc!8D{KpSnlP!3dom?QAbDgp35bNKyySU*Q#?oUl}p{lPERX&mA2rYGCV> z9C2I8I^mWTwAUiqM=(k54{QDrJwaGsngVln*PT2Mqnql?P_0>x1)G05xe8_5+aHxt zDAp^=;fmY@$KiPTuG5;~krDQ~bsz(CiMc8Njnqw6gNC7x?m~rpkh+H?XIf5wTl(2;@%HlK{+WariSw!FM#RfLw1j;D4t~Z)S@Dt|2?Z7YiW~R3AKek7qejF z5ZhL97YmWTlUE%Wc6?O0(CqL*BH}QA{)c~5j1O6rk+&yN#_SnhCH){L( z2bSbuS6BI?>dbmil@L#uW!dySo9W$U}VT^mtFce-q-Y{sk}sY+kEK`N_oxKO=nt9tsH zSnYgzq2$>T$INkmOru$Y8FDJFeq|}|N8x4)mz09qUqU7mbbiqY~kX!f@fdsFn} zex20!67Nz$CWnkBP9!09>s3_`Qr?{KSzN8*mqxxAZ7a83?;g0gUgf&!`py^ z+rEw1=-soLuL=0D9kF8;Yfxxh9Uu{bGgglpzXdcqK&MA|b%`#7T8+1~qc`7pUdST1toAib`M0kdMsA78y$UIJv!kNGfLP~IB4F#;2oyN2~yZ|5rUua$QQMau$)h#emS!D$?zS0p~4DFRd--ew0y>0l} zhViGutVL;WU)sVf9qz&TC{{!=nZWv@7e|&@SHQ)TV3PNnFX(Evb<`A&i^JB}-#rAQ zD|9qM0&9J&if(VEgmJic9tn7t0kVf0>bZK-kR5CuEPs=dAG~(0y@t^tDmktG%=caK zS2#WVaY%c~H(;FQO(|Hu1KJOxE+_xTzZt3tfMPGXn@FG~m8%i(+8G1$G)6EuuS8|4 ze9~Hb$Nrp&Sa}~+Xlu1i<1C|Hq)RtG%0kK&WXClcbMNzzfYU=$3315`2Uo8Ae6=aV zsD{Y}!;en-gsWM>P0g3IO~BGFx1KM`DStqkPdPC@CXZ%2vtk-?lX%Tk+C21M56BdB zW*_Y27|OpKP<7|W`)eF)Q;Li}=U)7LD*xAfF>}Lh+_YRe!lWzY=ZI_W?t>+VZ4gr+ zW7H|VR``WhD~#}ZL{30atYY=+qRg8_hnJH+-pw*qvlH!4IDP|0Kk1q;3y|=;xqnwBkuS~AW%Ld&NpC~9sG*QV_VqYh;Z)ZVzH-I}$cOMih~!_fyrEqr z#IxD==@R_lZwwjD^A`>FLhYATna`Bx3t%hTkxl#~Sb+7g7MdNP&4!-Gar@rD_yh;> z3aXOOykAdKMNtuFXeGQ5S{ChKvoj#Tg5Vl}sp@6(HxzNBaaf56R+zJe2vVc`F=guJ zy55mr5?R`z0ABy6%e<$Z+>@C{Q)E`){Z%*GOFA5|dx`m=z;!(P4Bj`BKGCVYIN{oGu}{K5mUV>is_rLVdcLX}u@8>3-vYgMGd{ ze@0AmlrM9-{vAe-KW}f|(>fh$_pJALl38}iF&a@{{Q7L*oNN$oee{O6Wu>fD_Vj4= z^kj9mh(3j%stFR_yFLILD#q;pnz`{@W-#ou0QDB2!G-w zB2|J9`&DLS-5<>@gr2v|hY;w!Hw-Yod0D%}Sn_uCM`g100mviHLZWx4G6WxNv)<+- z$M*n_)4`+ zwiT@Y11A?Xgtw~$;?7&~F8am#0?d(ZTqPXvV;X=?X7aJ4*6o^9_>A{Xt0jdsLqMcWd}Bv4?QLG8400J zlkF{JPQKgzD&J5}ntj=0oI%i}hQ7}>Fy0e3Sz){Yi;#x19Pt}Ovmhw3y3QH;`L2JLB)ME5%VXULZAf@} zF_gY_)1oPfrm>4Tzs=LrJSISBuB zdD&&UunMeFU5H1-VhSNs2~<6;l0T-pC|=NSODr7Jwo zF%0*=zQ0`9@dE$C?ELd=q~@L2-KGAU@BoF+XL9pOaT*pt_K=P^N#zcV+X|Z7jl4;NPEo6ICsLID-#1cH1f-g?1mcee8}R6e6|Z-zsX?y z>uiWKtfMQs3*}wOjkK~|cxTp}w5Oxh>IUZ81w@h7H_;~TMb}B~oQTSwHZ)5>#HZ_Z zI|q}j3eeB1|oJcDUJCslQ>P64~#mqeOPdpG-#52ud>)8xg z6)w29TU2Rgh)ekX5bnt7>34`Dy5tn^tPNRaWDtT3(plpUGyTd{;-z)XhxmkL+i>m_ zhM?J=VHS8`2R+qZHH49yV*4unDo>CXLf(XlgD3N&2?$I(c>G_TsV=HyK>Iw#P z(9J4_25*zx7Zf|1HabZ!AUO%X?|URce(cw_<}Z}-tnp$URqw_LRbET`%~jze5P;c)W|#{HkSx&>W?cXHEECLt0LOLpZNmqin{3hyWv&xW26y1k-p=H`-#=R#Z4WOM z3I1k7sZh1a77w|UZlh)~E4Z}VjBXt+Po7-7g&Q4vO|fhl8KnMh_3)#z8CzHhH1GrT zlAIU??B-vy`~S`NOQx6`4nCaUrOjzN_jN5(J>|~!*q)#yie)9M86o7gV@s7&ZcNRt z5XB@oLAsN%$|FN=2FQqKrU6kztvt{Q{SjniVxq12BYC~Awj)l3(_a5+h2F#A)Ii74 z5N$4$yjrkPC_P1UgJX;(^xJYp*$i?rk$IWq@e?ejOv5K4o&NEgI<;V1`uS_J!6x`Q zO3f(l(lDRj3h(qyetev*OT|XrtdlnsM68fYRM(>6^GI67GplIG6S$e>mFsjKhNcgs zIWBf$i>?I|pQ7^RT_7<|k}5kKBG_tqV>%n)?Sr$BD8GSb7lp;#&hyHte;hUb9UyI6 z6dQ7buhZr%e|Uj&q<$Y`HjAje8_n(8XQ_1ez^q`-Y9FFs`{>clJhvx!BLB36KNk+0 z0T+|%rH_w)gqNuGuYMs}j`s`?4|H6*h948uKzt{5fhf?E6FJEWUDFRSw}TaOrixcK zqtj3-aGV~Ol{uYFR-mJUQRUWGZ86G<*HBrA&G{a*?1>d+=zQ!49xt;g-6+O%`gv4d z3hXE8V2W>@8JCt&Jpp{mFW*e8l&#jLq$bby%bH(1n)iH0?s|#RS1=-s`Wu@SEz60u z+Nf=HLJW%|8%Ugu(pQwcAR>_wAN&Z&TSm4Hs0=OQgiM0E{sTXO25xNc$_4T^uVisZ zr|{9HKPtf|1tcR*J25-k$i`Cc6OE3D2@VzgBL_W$V{xTxXY^X4+dp*VLe2^Q-I5nU z!sPL#ixu13+vAt_1x}|cy;r2y>r84mB#->ZPfhk@YEDhu2M0%PiAMgWl{*%H*Xnn& zX-Ntb=DAY-duQVTSi#c@yme?h&K|YO9pUj!h@zzVPlKRu_M$07Rq1lf6)W=R?ZwN5 zgDZmN{J>JaetC%fqvuO*r(o)kFN*IMeV0H*8(cF%#PoI}ZIGp}vXWNpuab)u7_u}# z8)~mNIQj^$VRLQ6m?FbS{EX2TQ7}p2^AHZMz{nuK5JB$7J4vGP%hj7roaRZF{C@(6 zEo$k(%j?bF-`$M&<~iyqX_ANhXpJT~gRiy=yNKkQZM7$7ntc5cs@x|}mk#4m+li1q zwA?r)?-7RVa0O7UM$2c81N0?WCwI%yYRek&cPYN9MGj*H(2mD8_UGFzwK)@2FyW4- zX-@9DBjD@gDW2BG#)6^Ny-1j6z>VR<0RflZmoavLc)`|>qs01Kq_DEFvXMS|6Va zJiZ$$(Z(whI49!|%Yzp`Gwp7&*LYpu z3YPjin^u$M%xQ4JH~bYx%Y-UgsW(h0UT4i zVzHNp6O~N9_lcSJx3i>H%dc`-Jr30J^IQJ&NLu@>2XXRUr&_5{ur@9^RuB~tO;1~M zLO{;av)858z-Y#`Q&s%;;qYqh=OcAi-+sCGV<^aOSxVM=h`Kk)`@2HH9H`efR+)Mn zRwt}|DWn_X&ExKm$6;01-Ek5FKZ`~@x4U%)N9tDlMvrF1Q`{#gj-I`J_p!d{2%qCa z{X|gi7|aB!FWc-;+@wD~ZXP|NR+ADKhus_1pUG{@t$G0n1~%4v`zf(oChHS9TxSRQ ze=kd*{;QXGrlHZ0$vrSq9&w{SO`ZUtc?YKAv$E;yllRI(VC%4Tvj*_up=8xb`UOp! zqK1ONUQ;*Y|4fi&?2kT8y7?FvZZX67+T$VVYiDwzw)VbK7q>rc%$)zG2bQ6gW3FD?ZiwXJ-6ShRg}hK6I()>>{5j^E8;ji>=stAc5nO9 zJI^cZ_rm0sHBC)4$wEbnESvc-*a9*osw?c$By>)<3K%f(W*Eqmp%Llwe{<$S3(Am^ z38?%GRpDobh^H!d-z`6_8V5f_Y~y$dDwV3SYK#_E7m)(fNgYt&Rl_J%5bbX>Lt>Pn z3mi-YGS?$Qma;Q~B!1g>$e1D@_M$sL7aBZ0m34nh+1(W~tbWZ#?sn3`vh2$-!D!jf z+e5w$4mf25)+w0x3Y&CCuWaxKloc-Mwxo98>cq`}5Uq-go}Qy?AL`~UXW)Kj6X$<9`wA~F5jEL*gq6L!uf4Qr_~u(4wZXs8udtc z-iqk1Dqx0*y{M~w5y`Rg#n#o@=#{cU5%y8JBPET|-TV z<-sDF%6BIC6DR^(-tqG5c`3;uBu#YTJk{XY_1lMTJKdOWbRiez`-k@-BPI#>*B)(v z9Apb6G zm+Zqv8@|LIB!HynnH4i(s#Y}Q9X>bQ3}xD zcYhWaL-MSTmIdzKn2h^;y*!>sKtJ{`gJkJ86#ku-Y!b#OS~M_dD^cuuf_2$qU6H1f4=9_!5NpgW)lj+hcOxy{;t@rA7kA{1HN>Iw7PaKzMnwPxCO3CaMX2R>Jmpk5e zN{2B+G6CzZAa!XsJ!mAas`;uUDmqNc^52tZnpscRU?MRY%S-jQ?yjAVp$By56cnyx z4NyU3<@oMB;>x01r#h=p@F@t3Jxld9SgKq!SS>Mce^ge_D4Y*5y0+$2Or^6^20 z?7>&rKc)`Uq?^!_)zjlj_aGZq+D~iiOB>4$er2vhRaLL0j7S7}l^7(n)+CL4+;xUI zZ1Uj!1`WV|_2J@bsfls$9W{0MW%IvIELXVU1gMI_oNb>OwF`ghdp zn~sSuLg=r3YM@dg3$?bg*Nn2sVxrucBt?C5f(fN+=s;C;%V)3>YDW{;mtCpbI)Iwr zgKEMBZbRsn!hR}ralM82!=Gmr#k4fj*S&?`F!UWj=Lj{F*JdkBEZL~=9EsrSKf%Yz z3i@vEv%!`A($`5;zC{kTnrP%J7DCltR)C89YiH>iUk%RsnMNZ4Y>_4;>^)!3G<}Lb z4@n}b1PM~D$8IxGJ2SJf5enWpmFRn?OCJfHfRAu+vmD_X@@VT4xw(=|{b}SWf7$zt z&SPi)e{XHzi@x4oi_R~ZDKECaBz9lg2FpDoU;x%+0EiAB*^~A6QMwOXusXjNo~hs8 z=gv?v=BPQq;TJJc&#T`IsQVpsx>f|LDU9U4xGGxm^wrh3=aPqqcP- zNBt?s{QzDOSP+cW+YP2xMT>e@1#e z`j^zS;EvDw4{qPMxt>k=B~tRNl`$3VriqQ@cb%!1a#)&cY3o8V^ex>HI6Zm(7pWdh zf3H1FCY5XEvdASkcGCyta%(n|7#P5`EGW3j@DMLwm=YGMNoja3Gsvt?49hJ98KrSq zD>66XHEoByAr>Ns+Rz!k!xVU8?oZwF7^u?aZ3OhY=Mb``2VG&wP8pWvD`|mX6DLHA z5YP!Z2R}88DFF5BtD-Jgj?r6JP65}vU3xCj4yOWGE4o`On;npbg1{*7^c;hEM=De3 zEr>vGfRC)&0y+fzQH32GI9<|Q^3vk-_$Isd10vfSkZ)qdx$*rHuMRzJ4@kCXT~Rrk zgUqw6@mNQ5Q~Padl$NLG{IDXQ+T8CoUQIFU!nM*p3VI9(MM5* z_hQ|G!#MV~2XBqmyb3-(+%-8M^+nXd7=<{Oy*u~mD>rUeIsvQNI@@-f=UDQC+(Imy0IQM^*4C_9p8430e*`Ey=vaz$*_H33P4Uu`OU(KBN zguh^#nC?@)KFoDnfuAcufxe6(-26rr5KQ8IWdE4 zTszk>I&El^_GhP)!g?>M31l$CO(dES(7caNJAk%?LzP1H0)+K069RrRUW_0jbT?42 zQThy+VJ8ypeK>SLw6RypR_FqO3F25bM6?KCNn=S>DJTo+_wNZk;sBa0J({koOaMp} z+X%{A)y$XPGoLJShivaT5^88O zl}+zu`G6}@ig#=jnX4o*5cr>sB01VIuIfLvU{hrRs>_$h@n>`+Mqq%hJRYoUD3M#U z5z7!#i5Hp2qU=A(`uVnaQ#3u@mpz?5bx(HN@e%iZ5LX;6PSV9T9B!Sfco;_0^0sc4~A9Xd*u zLGsqd{l%Y8`QyUANhGf!?7HQM(nFfQ(|f{R%?KZ2v_0E(IN8H&60>MNx3Ppf}IlyohlTM;T7)#lB_Y${$#geGW_Uf5xkd? z=#U%V?OihDT`fc;( ztMuy6Guz8lo>ioxrnZXZYgF*n1k;GqkEQ7@li}j%HSC?8FFC5G&w;B6n7xL3_nC4* z8F}=k>+08U!N8uJe*Q+ecIYcRMyHs`;+Ih%JCl77RIp!#Mz=D=U)+%Xt@o;e^osBC zqEX$4YQ)cGx|uJJ-mTS9rUa^;3l<2BM1Y6+tfO%^>5@go_wdj^#ay_nlla~L;y4H? zL*mdx(B{9@_x=P0O0{u3g-2Owsi305El4130EfNnX%?fWwiU;O6B$$pdgq;EdO*Oj zeC6AlE>hjcge9J9GIdkVeKo z*r6J#Fb!R8HCsd9ON=(dp|tgIpN%f^6ooj{PQilRSNJIfT%R$JN63Jhi`s*Gd zJvUvkG7Z)zo|+1GeT?Z@4K84}!F7w(YPE!zSvVpR^X8)Rmtv(6b9zHIBg$8|?T1Ek zDyINj9QE%9D7zfT7bQ$TJ)wSEPEdP-(Qlp6qA9L@v2AoTM;Loeo$y4`&kYyAncGYC zuj`Y<6pS1GB+b~v3-B_V`5Fr`PZ zgXjZbzXmt~r#?XaEz1F}OBSyn=vU&J)8I^BD?UvRHWEE3Fo3pZzJuyzhAY7#Hhc_- z5;hAI{j6d>-u{Na7y;u}R(%!}=83?PR*=M0QNZ?KRQiS>0M zq>KQp#NG$px)1Z!uM^>On6o6fGa#-(Iry~C|!utVQ=(_oowBejZ?lb&Aad4 z|F;8^eiRjURZ^W|^wx%9lzOoD$W-j6{J;arHrA@bhq>xF18w4G{;}76RI1c2fN$M$6r%D_=Me9GTJ__|({k>Z_ zX#auY;*CJ##~imdUd)y-9{Lun$E5MTSL0{8ULPT_9Myi;Q{$rFqNJ;!=LX1U43^9M zZ8s=f>}!*f_RTVB8ivS*{1mqHNGm2wZwX*&ih%sE4<^d@(l+k=e#2Ur)PPPfE7;(+ zYv)~Rm`4I}^sL_2w6&5GtjEk`T^clVHWK;iwuO9{mZwd);*YVca8C^{BX~F*8=+7o zsrxc_|05M;Z89XEy9B~8hz?2e>-er<)21HUU)v1tOSU;<`lQT4ZpTvUsh!5;P8+eW zXf_`0Zb$+^5W2YJoH(u#qBRsB$uew?qEq_sR~rUrqKxqRq7*&WYrF&#Z4#bKf|{k* zvqUX6Ed@X05)UbVJY^p>-(u`p&Q^32m^?+?R`k=#2(-?0)%pD5u>uSFPA3oOy~+on zQ`zxqa(?|0g~oR`WluL{GdB_C+dmytTVvP2b<}7k3Q5<93c#c_ele|5EBf-|+zvF< z$1WW6D`c78WEn(n`e6uOYFAy}Y8%5F!k0)A^ht6)3i~_v{hVZcSR5bkQ=}Jd45fot^DAEk712D_D}vgvQ3uxcGIU6#&G2@>}fohIy^JK zT>1dnVPoszL0)=t_566Ea$J~5epM8=Z&>hmECC1t^Gy7q1-N1?FH4f6|M5;?S_|5Q zuLQT3n`Xky6rj+BHmN4PP{6dayGx~>qQ`GRAmQqytBnrykIhRvFk7AXb%YCNnCa0X zP=NrQA#Iea6ny|06i*{Gk*;BA{Wa7*SkcRDmv{q0@#cvx>{Go4$_X)tuX$ z+V(SJrMitJjL+h8wOTS`w9*z(7XFT21e{I(S!PO42zJC58U4X${7NUf(5PTHrN5)7 z(469H0T~A`2li6z^S@lFxWvN5h1R@20O&x&&~OTpurF=5`*U_E?A&v%$D1WxN zJxUfMb}83vAPtrGq*Al~Yzek^4{L))X+r>Gb&qQ_nqdY@G;kYEcN2VNb83)(xKr#U z->MWX|9;BCQdR3PIWpgzt$-aooPYM|cEv&c_& ziG>`L`$@3Tcl^w&2@-Fe7HZ^>)bIJ5v(GL3J-3d8#-uAwCuU8YDD8v$R|+?w6(C86 z;0Q*=mAbP`b15cZ>)d-5%Hdk*%%I>dd6N8xEHWbX1;?jN?K%Ory{k0BMW|y+hA-2< zExf!Z4r5vgxvgu`UkoqX)wCPXYWMlsV;fE^9NG1aSz**S zDS;d+S=m>sC6o0ctC1SED~zm3HaMxmT|2tKuwl0bE0m{{qjXEezy5dNCdvXKATZ2b$Tudh zjhZYn%KjL1oz2#T`NZG2)fdh3K z?%)AdYeCm{DQ@0j^|4mD1cc6aXI{#bV=~TonBbd8M@AOfz|0sVDTKZ)N{`s*qD*`;vU<%UDbYMrk=My=$J&RH0=MZK5pwiZaqgEVT1Th= zo`D)V@|lWyl1S8v(dFW}x^5$S>MwTk{n?LKvJlA@{4tlJJ+A>P{C}%iCt8-FinPMk@(LUyv)}_EnrF$0QF!Av#uUhMsQ>gTT`tCv}caB)D(H5Cx7LJp^qUTvOrNt;9l3A*n26S2Q=z zcN|qFymalfIRdJ*aF7mH$%Ao)|IPuaHU28QmLjGOb=nrd7?L6C#;pbeTeTi+9^u>Q zF8_-#f%a7;7;E8<86jX~wbMpLU~{L~5~ie&kGcJahdT5odI;Xc0z-P0DGi-oY@h}tE_Sh%LGxm*~fuswmX4i`)`dKYH=&$0tJpr#H!bd8$*6R;JDIqI=F2R?R>bbG-iEZ|Ql( z!>MO2T2aY>Ptd(&5*mw>HJA!kd|w~%^vcEI5%`9J)zr?Q!xN*=ZbMY`lKaphXZklQ znIZV?TFy*TCGPi>qXTEJTD1?wZypK&ALe=^a#QfD?Vt*uB+>bnf#PLUzE1^&v>F-a zK#1Bjv}oU~18ysBrL``4gag}sZwcATz>_=ShyDO=%;9S5O97_Vtz4Sj3VrqqGP}J_ zegC`#|GR|iEX)i&vOeY*a0?xB_I_|7J{w{?DXCA8c#J5$~I041zo0?FfY<=A%(=WR~Ge@uViwCcq- zoSIcl@bU$jo6&MipQOpZ>XNBs85LAyOJy95^?z_Z??sjWhD@q7>==MCXs+L8EC@ql z_+}bS_X?&1eHN_X;43`ZZ`;x>N{!Js1lEkD#5TcQQ=Y+rBGcJ|j+G{P4bOn1~O$hAF>7(#-QnL`G(wx{}cxdhr|i4={A^WrVz zV^XnsKnD`dBc7Od933&e1QWBWT?@Vy8_aRsK#{=u&I&9?Rc@c>W~7>^PTAbE3e&x4 zbkGqSDfiHifW z(=oP;V#0%uOzeU_uM%(w4CTv5Gosn4Cb z4M-V{q7wyY(bA||GGPPGg{rZ__w2p3*_j5WE_y$?$%|$(Y*H9Op{=TN-NpaK)oCY> z)01N`PI*val1?6r6!@W6Ds{m|E~%F5k@=u;$cIksN%dS7qneCCKBr`m zP4x%Y+t6$k1{fvx-6`Nl`3CuLT#Q@u#z60VyNvhdC!t%xtoOkr&T*6olQ z(MWsT;4g(rOW6IwWjo(D&~JL)#ViMA?rFGP5PNdIjGXmVoNdULL;&-8yjr>7X(zON zyd?_B%)zyp3No>UihQj~r?sS95m_OSPD6T2AH#CUsD2HPcfgZtZ%Oh%rnr(e`1cFoHwQ$Jyo&D0Z?o$shhgh>g`i@h6jmF^bF`Lah!D6KW; zAM4rW!!A{Idsw1O|CB6d(7h?p5hYMUd%qbex2Wih_>lw-y|hmC)T#;xJtS%yJh+ot z&f^S%2_^ccB(RKM^MBCE0ein^H&#d?NdYDxi81=@3C_RcF6r5Ihw0nUJWnYWufG1` z$T|g&UxRxOKQJpF(gEh!{S7FOp8LR}!b8*ltt|nfQ0h-ES-AS2+8WbOqG7<7%JUZ7 zx;>K;v8v{xVh$4tB(AOqb|2V*Me&SXqn{T*;*POf0hG7QtX@%*N2+1~?U|RWC-fES3C{|97hlFy>Pe0w`VC^ev6<$iR><9A5kaY^gnXtxC z^+PG^Q=89!w1;X$pefcmejmG#`ik`HoPTd%x%b&E_+b~KJBVyK%=O(&5pAG(AoCqn zKP*A-VH&ksyk6!4B*;i4>u$(YOvP!*6_0I|^jPh$4~S)5pFd?K`|g-gT7oWXWGzBs zw`#mf&O`Ik77%07whI%7{)uiMALURD*X4Y+ajnaGm21oT_hYN>o=~v)tQD&@AYs>U ztX|qo?7e>y1t;&Gm=Uev-e0Q)C_amnf)Bhe7YG2m9^v$Bye znk4;?cS=W^s#znsCDIBwrr`y3IP%H0v;AK|tdB+XL*wf1)ungEJNqgZ<>-`O?G!Z= z1EI|-9Q9*%&(P&@98*erzj+zBMYNplylJXij98ue5P@IM%PnzQjepbRm;TYpgG13T z%V*SqycLPC=PFg1-dk^Fc5Y>{AKTZdz{}lwJ8c9Ac?0F>T(!BPqoX4N#Z;U#{<$C9 zjBzsiEYhAOU5DP*Ri@qtIB6?%EeCdG2ycu8d-i1QnY-!?_R5DHyQS*49PO*(uA*neSD%458Pk z=`}%m;Uny3xjpWnA6Ux)v~dto1XzID00RgTNt#}EoNZe! z(3KaFbm10PVKIH<1JugMSsmI6l?xKA;Q0}ic(Ugti>aE69LP)F_$~&H1L`l*cpjs{ zZ;i$4HtxvOO7$C00C&^zzHeLi9me)tWro~%W*D6LAfuRsCj7L2XI@s-@4YAa`sx(t=+b3dl3%QmrB;7B)7+> zfJZpMjkY_?=>eMK@~Vzv^Xl2#>-%i2Hx}~Nb!2)`4qUSwHXUmbaf(f0XNq89`{_k) zIJ2ZKTl6xkK{J^O%3j=_12$d4bML5|qb__!3?R#k1=c$*wmPrM-1p&%9Zi<$6}(KU z_SF*pQLlD3G-rqJq2&>SROa8b{LN32V*jcD8)q$6wVA7*y2PXL-0DYPj|1m6hqV>) zz5T$(`+>!sq!|aDL(Ql9^g*vG+`sPkI zxt9DJxekVef`mKo6!)EFad{ad+fqmkz z^Q1HKFDpKISmcq6h&1c$MJ*-J2N+4U{teKcBfJLo*=($NNy0hA+y;=^YPcqXwm?QR zK5NuP9#YNJy1c`2S(CaBdB$k`Q)MO+bDSW=L~qaTwx@OWEZK>Cd%BJc)m;y7(9v|x zFJAgKZ-PaK?X89cTQImUdl6u-0#X=djAA6-lV_r=Ps_A#T=N5m516cgcjV!)P_Pn7 zeCB$+p0FDScxDW-(*0^jlfJvZodA3;8aLC43GZxO2ifXrUoyN-adw@p0Zc3ZeNCNr zME{E7-`C*hlmbq4r;5OIQ3oziv-p}vhwEVe2k9vo;0%zLhQsqDc}KiTPO<)P?b$kQ zt@JOs;)(4bc)X0cPx`q+oGX3aY4UpsLp?&~u(RN^kWzc+xR%^0cUdJt$Q#;^5oKca z^Ct88k*_vu$K5Wj#=;LTLMaKiNp+a2pD=Eer)pF3XV23I(09>?No`o$Z%z<}G`|{u zhO5vN=N)kW<7c^R8RiI8UFzlJ3Y7`gJeB*LzcdfO<3c#txU#2#;I1y1;p&Zu4r-3P z*@`6AvQKBT9|~_6YC8V@VjGQ0zy;N_=hPzki!C>y^8SZ$sE!MzZqUzH9)ftpcm@@L z*k9wi0F}@``WJGSp|8ZqNN51Z_j|V>queZf_!C=)G~v(Vb^0znui9*mjS1xegj*~8 z|HReG(N!vsG^iXW*!fb2N%BZo@xE%G04~;)f(A9+KSNs8a9;#VvlT)X)x*{s5E@20 z&NFc02=IZR0d>)qBQb`q|ZY?^mPN&U|O!3w`_M0BzvDsb{mtz|_kN{!}EVrOj>K z%+8i=!}_pG{qF)lpzsa0ubK)c5TNq`S7-pz4b`k3B{uSY5MH3e-M^RYi`)bZ!hZs~ zYx&!gzT#kqwgMn3U0hrhX`kFkvn4wFmv^X;owd4XiPeDvqp~f+WU5ALtIQ zmLLC#Tq30I{(b^Rq${##jTP3qNA>STqREtL>_oIv7{%RLb@c$*ZypV^)6{!E}?s3`+|4DtQ z?c?K|S039!>u#i1PYZ>esV8q%AelNfugG;Gb~(E`Xx|$&8_Ct2w+XX*}nc;XrKxC z0W$3k*Qs})QifyqDw@sZ26q{elap^X0Pl@riN9*+!TR`Ta+0PP5wj8`jk$2Fqpj3Q zT=jCMx^xb9^s)q&?#Bp9l}F$^30E~Wy_E&YRkB?dFP(W#MI&%#i5PlZ9M{&k3YRXS z2aqX-Na+S|dvVXeIeUM!z|4=d8Do79u6th`ZEOa7iim#jaryoDxUNtZo$${a;v*u9 zFs$dSK{z9TtrT9gp)dUPT&*FjjdQQU6y)i){NP@TUV#I_+Ufs*{#p_}CnE=EHaY>P zRcKkkT+tWeC_6E3DBge|0=|CqvqRbrTASB^%E+s_k$S)6|^+3^=mV;9MHEli1@WVmRKhit18UT2$2l?1z$ps#?XGPEMl9_rEt=qC2NAP|Of%}_^8 zB8S_!_Yg8u^s!wjKTT#<-yHjqio_9|FU*j=zEI{Bj1blaoSHOiCO_FT)9j3roGoOb zM|58-cDWiE$4E9CT+cw$G}M!AOf2MJ)9;Pfuq@aE;S*Y>dd{uD!d>oPkZHFy9FsWt z&2(M<%0-^btUro-M40%8+BIQrBAJjID-D4|wZ*UGa1J8k9AJF;)`YEakRA(e#0<~) z+2Lni8TXPR*=2;GTWAs`98xP5WpWd&(dCj9-KVDT39nYHoq z!ym}ho9A)fA{bgV`W}zz^oF2bC|4i2uz&5K>ImNYCyc&Ibe2f^ z4uN~|cheS^{j0(e<*uD+H{@_Q-YJg9eccwft?_IN)9~{Vp?>)Kg13mpR5VBfmpTCF zNAky~2SGTpI?Xwtba;~h@ZDpbcWb5qKA{$OO0x~l4CrLS9-N{^2^@yQv+hx`8*a`j-NQ{?vfX#bY(|tIT3Ej_TO@>J-QQJ-km=pkqSRXhRO=fo;AjfpY~^_4q~tB#5hdt< z#2#@@IwmSaY&gJJ-U+n{p^3x6Xjv{6@$Gah_`*j|ES`RzR{CFzYT_sfK@zo;ktcK1 zU8*@hs)Zr_G;q@PMrWf)MVrl0gciQ2yXLRYH8x+*I5vWal?IH( zNJNdQJOgQ5)H=q;0Fi-C*sx&Z&796ez%3}RXm7TjLl!gzpAQ5!rzRi;%4Nbno)hQ= zR}g-Ek*j>$S~lritSYcOi0or;c=6|gGw+ci5##<}lg~vR-F{uyEVlGjlJ`+_!=_9( zM~eJMAAfv2dZuNK$eV?0T)WUD{7T`s)ELVV^EToV?nN5$ZvsAD$2h0Dc3qCz3(sCc z8#`2u5h#T`{QQp7)#ymd?X3|(;TwSeNG2%;hfT%1my83bF%-mmvkj4+Awhe!RstWx zuLJw&bKX<};m>r4k-c||K~j#Lnj-lu(SEiP{SxnBtr_Zc@?BHVTw%Rvr)4C^Ps8Yp zZO{Z!6$->8=jc6Lng>A2?xmkb^HC>mEY1lp9Xp%>92yqpTs{X(Yx<3?=MnE^yy9?@ ztPF7`KFuzwxwn7P(+8VfA(G+7nnYhTNtax+Gst2zjr>DDOe^pIlpSrPJNBJB`jdXw zzm+jK50PL{{x5`478rfSku3|M35@c{P?+6!pGA#|E*x^qhOIVtn&tr;V9)aNuh4+isKo zX74 z2rL)tA`w09%}8yoBhQHO7!BQTT%Vy^&-)H9gz4@{(Ywi4?F(pjBULkavO1APc@sUv zyW}hQBK5c5H!qi-#;A+{-u4Nr0-lVu2N@k4>r_H+PVG;7E{rhU@+wRcE}XInOB(t^ zUcvGaZ1vHQ^N0}H^u_xv+*X_l!77E(w|_g$RhL!K3Tc_LC5mFNA#V8QVW!s*?!H?j zPyM@~Op_T@V(lQ*N*ucm^HNmAy!SpqVP&5-7!_nb819?|GYY%VMmDO3S}f6HSGIcjc*wBt*x%b4nqL$9b!5xhK&_@a8a2)dy!_-eiJ zs`j{02^lc~_8w`ZW|H$138F8^-WX(5j8u#zK8O+|!sepwG>CD3GDM}KN zXfY78)|h)|!BSK|N%I?lvh0H@OLwsoi4-=n`zWE85O2nuXCO4`*aT^u<8rOT0cz<; zq;y2s1kouhIeGpzqul36r_;cInl!iVivm)GteFfM1S25IIW#NG{E9}tSJf_}iAfNL zLMPR-GS0gAG(xuN4V<>W5qVYH4aER+aT}O0kkW6B6A?V4dix20&#X)>M*vdMcYm?O zr^PLrF|Mr@cct7rw5bakBVA69bHi?LSVrPFA73?fCjO~JUf>vwW$R*JMH&%kZx=o4TXLBeTN8tgcXI_ z;ppbZK_0?9bW|Y83SZ6D$$;1B1AAr{Pd<@I5p*EtxA%2U3wda6^p@Fw6~=CpHcB_E z`OO{C_lOxQH0#B~sm?Kdk#2_R@@0>I&bP}Y9-M7x4vDxN&8n8KHtvY5R;?U|%78o} z=Z+{>DvNS!y+l}lpYw;)CV>MFBE08t|F3u@baE%nE>bv(ZgNAXWR~;q=yop>;LNUavUHUWe&M)-+w1WlCj^}?gSj@y(qFJoNxmYQf>4eN^HSq<8J70I-@x>7!vi$4^ zyTAW*9wQov&c(@#crdp-zdi%0S~IL#ds_=#7!86p^Gh-}hyViW@ZP=kI@j~xJ(M4AY$9VCHB|;KFeSssfqp!$LAgi7@XLNk!U|}75Be>#X|wjsHi`+ zhUi2ZKxWJ&P82_ppozaxlskGt-X}>L7`IlK$ojvUmO5c>7~QOSZkYVH%4fB-bPT?d zr^AqFmd;sNrBp?`|0kc|2WK-9E^HB7SsoRe+$jCgr!Cu=bNlb3w$2Z#~Py)+-rN zM}jn|KLk8FEMJL}{c?C$lip4Rf87>NpZU$(zB;}5yxh7+O=vwqmRq<@N?N+-Z2PyN z$1-}e@7`wDSPCFJh1dFOL9=j^=Un+kpb{+@9UD&jsm{A>`KA8#Q<@OmD6elS?aADY zC#5mPC4)IVK@TB^0+%g??U6F~#ET5iaWWEABJIIM>E?Rg7k-QBK~HZD=(l&Y-5FJkDun_*GO&sPc(#OC$rGs4f*%jO6B4!bYduyj%3gyQ z+OPF;uKtK0|Ii3zH(&|!+3{-{=nm!1*E%m}|AL(-ayN(C-_?$+q_ajI72Vx?f}S5} zouy#bSIn%HENL0b=sC%VmJGoM!gm%X#$B&H}sOj*jg@XgJqgI{$-)^GOqI;EE4nsCX zFhFMkq<9Frt|xzMemQsG@b?CZV8n4-LgG-@jDykoq!F#V-|Y#ZQzT`bK+UDP>!pMk zeAy85SwAzoIwvzSuy`q*a@-7yxj@Qz3-iruRc$w|*a#lXRqL6;_fiHtEwOmrJXXMYwXw<}OGpsy}dUu|6X(4wm(6Td#sc1cu zPTB`tTKBZ1%GJ&O62ibPI{NSaAQqCOhIKc*I>r$HU00`1%kr;=6-T(U=P9N|W+Sh` zPSXH=(}|wKPpt3L0XRV)F7t2=j+~sUy;Hd^5IPF z4howu^}W&7IrO0ooh3TR!$%mXHGG!9XWD904nKQmFA1E^71)pncv}pJp_+@i3OEnE zLsz4#qo4sN+mt62)7%m~v(gG#jr4zt8A-t(X~|iIAf8oVvaF=TzZEraOQXe_$G0<) z8K5#4OybMmtF?wT8%|djmJz7FuT{l*5B<_0z(+^Z1Jv%+ybYK%LrBka8}67eq_*`>iIIa5r3*N6uln!m#CYId~BbV1o~>fiSejL&1(Ro$-` z;_Erw_K%K9dO8h9#Ia~4L%fN^N|wU!8Z}C;!o7cgKmnCULuO1T@qSw1#xD|dblQF- zmPw?38e7`%JF|~fV?CiBVGcrqOZsGzs7ngAyrfFfYh`F_j3iV-7$Yvj#~5!G9*n-%$_pdl9e|{2tU%8f z_@VDe^upcqR!9GEnb+&{qaBiJ`m;5lR2Nbr!JUxO%tMqelE2Fd9ft$frUQ0z~%n9uLSj#$pF;)@cn>8>3y$*qh@eLs0(jvRgFnGnCFOrELNqDasCq{fv z@hqpZNgke&P43shdmT%&1<*{xdBo=%HWqh4AH9TtNQ?y^6$tf+Th1RY?K( zBrXeg+O7Dv-JiLGhMc1xDjJqSVpP#me)po3m>+yxgIKv1d>E5(5U~9-M1Nr&IN{ou=&vJ{$ z)zm@xnAcRFBgI|zB&y}nXgY8OoR->w7*sV)$Vjv6wMrEtle50Q{$aPm5vYTrC>8Wq z8L0YdUA!({J$7FjOrQ&FwKVgnlht`G>0cMZw4;R2L`-C<+Wcv#WZy43D`SL_rw~g) z)z^$HFWet%*B=UOkM*AFwO18)GlxXke}P$qvt$V66&sF7q_P;osM*4GQ`_J$Xq9~m zedI4lR0rZX&{9uR(gjtFz5*56db!E=c&Ac0@Ta(y*B+9pBQc8_Cr6@Zqnj-SU0{Gy zoi0ACZukkWUt-6#`rKCcIh7}Bc0}HZ4wz1W)U>ngsz#0UYD05EXY>y;V)6BCAU=pV z5+Sk2m8ruAYi>K^xP=z4QDlaFbn4rl zebY8vy;vMn?kSSO+-Xz-uLg zpDOS@_{jFMs35(Xbx_rxjf~U-?=sQ87|nhR($C(xdJ@JFaet-d142rB;pN~X>LS84 znJbNP5u(-FnX_y6cG7X7c~Fz%A>@%xK#S-3${0V?Lmwwj0Zr40XF8q-)TdmZS1oKp zxO{&eGlIB2OJmV;;DpAqrA{j?{w(cWg-_<&AHP?xrCOu`oHgfKdky_xE}r6vt{#7I?dxiC}@BrTyZpBF)q{* z7ZK)rDEk|L3WDvY<>US)DoS}IeE8^DvFqUHb-eTTdD1)IkR?Wn$>pRz;F7*&yec8i z7zc=unRD$NXU{13GS&3;g@M{T)jHWx8Qb>`tIg8p0iero9m%=y?HOmws&95Szat51 zYHBjFz@9}0VBS+Jr43ewh^CIQ4^X5L{8jknSed+4O!>O;O>%EbmX+{o&$lm&S&0># zemUrq1C3OrBGR(5pla;f5Qm}9>_a)_eFa8}TjA8`o1JHN+Du?C$0z#1KvDFRM}Q;dsF^t-iaiP0RsaHL*b^O#Fp(w z7{q|$RNZ7S7XC>DK)oJKYqzBBL>+5?IM<1Rgv7`_K?p-dT`Vp8 zosJwt7-1U#+f6Us4vl{ZR}h_-hMSz$A4}CpegJ$vGPJ*|k3q0Fu{2QPv$E}%iEP5+ zppAE_qFC`u`Y-!sWAop*cn3Ab3T2rsCc*kA>)(71pCY*vnpKBF16!O+)iqv9SE8XD z$ewpnVZfMvggygJMMFC{gbFjicaU&=kjB;)M|@6#wq6|@(=@vl?KT0jZxlRMKv2nYkxCwtwKA=SNp2%N71)u#gBkv02%UKUZ=NWHCs1wOC~s!>&EbU+tY`! zW?*@&A~b!pK(*~sN7{YR{X@GcYXn9Z0b=lW_~5=S!*O&K6?951l;uvxK1po~WWA&V zF4R&J&!MJ`Y~RVnRZK;rMsoiOZ>tQT%&14frl;)dpqam-m8NK0J?djFuX7{#zz5Xu3a}RclPDtf_1j$yPvH9ZelAP~>JCDV)!qob1}D0FWIm#xOy=0`h@eL zTI!ACw&Y@?6y>b**3tAMpUNU(# za%JBX$t-f()J{G)o!M&zxsmjbMS05zO3xs#${Z!alT6is)NT`oH2(;xq21)(4OeG?7L^j)*gD9)A zUwzX=nKMEi5U6e}sVzNG3TGvD3k^-P8Dx%OIp50h)1-S6r?$S;hAC`OxaBpJ5JnF1 zee8y8y#yINJ=34mO5$!Dr%b4>exqru$H_hoopPjuIHBr#gl>)t*4T&&`n9VZ%!Uph zWAg!{6uXR%`T%(HX>47sn=;+|XhG0O8TxF4oAdk}m z!gX%TR1xPT{<>ls94{~chp34(EJQTdC7O}}2#RRp?W9@{^uG+ltEjtwq6Dt;wV`2c zxNY5CgJ(#CHwsy>h*;_VR|>&tS-%4#Ni53>2~0&w7MXCeDxf?bvY>B7i^SeMO+gnY zi0rB*@?NofGzbzn`@j+2@N=c{Dr3DV*Y{N|Y=64gxY4Yn>vkV`dK;rX7t_bQcU_2F zm_YX_#yxv&F?pDJsZGr9-SZ_h0yh)2-vlK2Doo+MdXP4HU7k`U98$pO{;S;k3=tz`vRu2o4GXi-}}EHBwQ0%@Rvr!=8yY9%cWKuAR_F0QKPXr41Ss#=s8l~dY;1G zQQ;eB@No(7yxpIy$Y`vvKVUAnJJ}T5q&{J5dsydiy^b?n`fZqbcV{Ukd3}uVJu6c2 z9e1XD(_Z_>^5M4auxT~&$6=FVg5#Wzd#{Os%Ve5+_EJdw{6|HAm&+VCxHr=?-gGi>^qwM}erlLh@%tbz-fMQim3ByF`I%ev zxGDhteX}G;HSQ9%C_O&X*{gZ2=`?^!c{$wIq-TawJ>z!bLYL!4DMTJ2#Spnlsr<~p z`-K1>^=6-+$-@^#ZS>qpWCamh@Z0ZvpvO#~ z)P~0*7L3-*p@mfXrzz-l3Ov!!Dj(2+VHT|P3!Cx_sk?%AOhi>tv6&71K+%?9S#ACT zdPk~3_EV>)+9-fyIRf>lJpCQNeXZsK`YmBvMmNo-rGVTqjPz z7jTx7R|VsMUR)#s9CZ>6?NZwgX~J-v60%iP7o$P!Qh3Ck?cdUlkF+x}-iYZ^lSrY; z>cXk~P;13yV?+e?ct9}0iSbN!G^o90k4q>ev`4x~3e;dQ+X>;sgyeF<@{RPh(LbwE zhGkgIel9UOQyWmAZ|H+VVswIBnwj)Q0aMV-+#+p-p5Alx&(ocd9gHu1SR+7+O*SnS zC`Bcli+WzM- zMuz(i?Kav+Rqasy2X*8NS-dF!Lyt~`vLN^=kJ-Wjfaa|MY`?%)9+reTi(0Q$H(X}z$Q?fq!vm$jfma`E} z@%!8x`^3r~9MR=YZm2%|RCn>Nm;X}-B?Auolivj@1<)wd(;ti1%A=+;jcG-prF;w zDpppzzKOzN1i^z=v;*cU_(~IdBf;ZrOqT0+`DN=z-w;KPmRM4nUmn<$Jw$gUkOJAa zVsP3HqW{Caf#03Q6D5yV1!B)A-hKk)YqZfmGUs8}4y49`E`@Z^oo?NkwmmxF-!UZrz*EW!BxvNZSy7r=14S|Io zW^oBx@ydzXd{)8xQsKM5YVoedq%i_0p$(So`Jo?lU?1LEf1JjC$~G%sgDzcC$u^%Dc={hZNiHl2@y7z~m0 z%Kco*A-qwgP>!5JYD^!Z8Rl7X$eomR0u!Fz_L49EjIfaepI^d=rlF~F>+KzR8U+bj zlOATkU;(Qy(Md0G09OV{xnSx@Wae#^P$%TU@}SFSY!HEF&xX zJo;5ngPU^{)SM9~$HWSZ@0r=zCmiFY-1LfF)afRn$EDQZJoA`>Smi{h_FMoJE;<`L zQuJow;g0P&m!S7k;3iUPogK_ms8t9H`L|>5#FiS=VAL2(V&JC>n)bT4-OdLA3mH3b z^he*lDge9GfJ}MtP=`|#;0E-z`#=4?@tJ@`z+#AO$TWAT*GX_iFy85--`~%hX_tS9 zRg9?dP9=mXE^=t@p41p`=>LVHzfLf+c3LR%Yx7-=QQ}nm5@Mlt^yj@R3^dKBCfkrEe5F7B2PX!0E7G=gn<7Md|68Jp@(5AJQf640{98o$uL)!gI4}!K zpxO!lUnvu9MbA>fq3>~8R{wWml5r%~wMjoDdCjq>G)5)T?TLUhiF80?ajjSw&^e4b zz>1)dO1o4|rD9tf)zQMj(pq~V0cK68c7KmIcn+h+@|T2L5C9!mo@(>N=5WK&m5k{W zMrAOkzp+4+46P44^7br=<&32DFR$AJ@O^jFy(BKm8$*vy)r6&gq+${`S7&F#f2SMK zFdh(}W;D4O$O1@dpIs&unl1NKcR+HmMP$X%$X9pPzSpzW!t`wox%_%LSvC_JG_b>< zJaee8=y_YV?BPOg{t2ssMQ-J`kL4xb)3x4b93hm$ul=)m`lqPvi#>GFwZDhrKw5$^ z^fgxw6B((p+Zlfw`YMxva7m*Ij6g_qaAx+~lJb1&!@LgCI8A6Z&TOae+8s#Oe6NxS z6T(+QhI|zpn()3S-=L+)O7xjXMQ&~E{2=5A`)z85#b70o2zx`jMrG)x5zB2(bk>IO>TrJ@D!?rIJ9f!nZz<`9WWkWoK9|! zL(wX>uYF`lFx(lKbYoe8+6fs@;;c~4U&;n)>8$pyvXHdlY0A%-6c##%R0g7t+oR|P zfu`SiqvRyZLqFwl+tlt004-#AU(m9UU{Y0}{bx%MqBJ|(1d^dFB1-o1O)RTW`jM(| zSN!0}z9a@2Y1ztDH^0rhpxIK?%0hh!5ev2LTU-o0sRGJ`&cZp4i-HO=Ih-}G4h3$% zQvW4>rLRDJ)->6~DGEr3C{v+Pqm8`#B~~CMyPlwZwvkfrd*JfzIh9RHONdMW$J1l# zMEk;`a+z%%jezkIOO+RQ!7h|c?*c8AUyMEJ=tG!obgz97Rvf`iIucg;4nfBe3R5Wt z!7Q+cY@JhRWCa4*qcWki&!k2CCJ5UNhQ3Pk%9#22|cnqR!a z_!e%_jT<{0^4~qGrhat|PK+Gp=%75kBa)M9{Lidfd>$5esJpe zS!1CV-FCn4=sxe`uA7VY8ck?ci3u5J^iiXY@82U}vi>x>513^LIHasf>i4j2_GE~gICz4@1SHCuv8_`C4UP>p z#w~eOUDRzl>qgKbQ`;BRM`R5#AVH{M=n<8|zh-4CDB8}=HwSHjvVHPHDMZ;lOPbuE z5+!7suRtk!CbbR>W2o6r?>akSp46Jl*)S$(kG+jU9fPuddF zUzk1XT%T1H#8-Xyw z0~Sw$GC70~w%%hFJ+D8ex3S@JaD5D!!`?x(UZT;5G6P-4vVhR<+Sb-|;x|T&K9(uZ z6lXu4^-?(M`>jTJUF^|G>*&1PAa=TWSd)+OSl9^vts=Hx`}5rX(5IG=K_FGh&N6B8tn7&ua4!fB#~PzOJVj@e*8%3P;B*~M6Ojynj3-o^$R%!`tE=x* zohqBU|7(pRdCMWxDCN&=Y-~cqLjRV2P{jDByYh^G{%qgtu!rvRt7bj@k->|4$qIuO zhlU4F9(`9Ra$mr=?148?uwzA5LcVajxTK;9r$?h{&N6UUE^y-4f_4?|XQIu8tn~7w zG7G!3faJ%CqsEJU*%xybVgkjzF8?wW1_L-Me5J{@;{M>WmGthmeEuPVP=ntBJ(3Er6UK-J6Nkx0*tZvO!(7kZ}T>q&F z=gWZqQ`d`K4yl~T3L<{kjPmiM0N)S)`mCDJ>i&wc*T^1aE&07!_e{@aZjbNhuHTMI zc|iD4MG~c*v&YXs<;)IVZtuVrjXy5;%6wPl=_^`WBlpcg3)jCAsRs?w-~8JI(W(8U5GswqILYo=Do;n11S42?K?QXZIGk-=#azRc(zKR_lcE}ROl%vpX40?VsdjBKR zzMyF8Yv=^|Y@@j?Y(A&z@8911{04F#4e&2V<#DpehTsmO08)6J7Bo{<;+R`ca>-;c@#hZ#g7GTjisl0~DJ+S3@XV6- zv9Rs&A4)T6ZrJDi^%;f5Eb{Zq`hYabpKwQm$I$6Y>Ykp&XWWn0W7*RD3*M(dvrbxs z&-wGn|FVrHNF&u+53YH%DfpVW^>p9yR9}ieF=lxhH0!G7^|MM6`OOy8Y(7wBzfT9kOGxur37L0o zl=$D>vzzU;>+dIIV2VS>CDHf0KcD9X#%{FgE4%IsNqo}UYHH4XlWn5Da}CNK7$#2Dh8iDLOU-SJ0+fR9D(<-JpG0 zbbl$)Y>oS3`3JA$WIZL&hq-Wwv!rz0bz>8} zQpW8#b3cQVm%;+52Tj5fa&XE!=Dm(oMHb>BB7XJunB}V<>;Jd(+7a(=5HEcv=K98N zFd3l6065=tn+}nZpYYjH zm#qdMtkGe% z8IT7LZslm}1}(CNFgbvR-(CQt^dYg!CFIFquO)sEsWr6jm_$`0mC!z=o6~U1Hh7NoP<@O&`)Dt3*3O0vcmd$f??~!R|-y3iFtH!tdQ75 zZp-JcnohB}m{XbY;x7O&JJRMwT*s51u)GYE!y81Q$y(ZyF8_==K?A#ax3}g2gsc3V zK^`=MtL9v%c@iR6)V)}zK%Z%n9MTD4x-%N4HjUGEfK(|#1ZSf+%zOhWl3?)FPUNR% zoJPSZI5nQEv(|oor^KF3{BH=CBs!Rrz3I`NIw8?IOfv)%CShmo2f8rZ7!yN{({2ha z;rP2PbR}E(uk9XLLQE_F@C#Z6%K$Poth#4y8TWSX0~~Z%Q^#(%39YeQ>MOOsl^Oo; zN@lUpUV|(1jQgYLf_F3L2+@AB(#i3qjsQ^Za>nX4hTRuC>}Bsnim2bs6g z*Z(!bl+waEe+%|K%XdxU*G%FJO#r>iaY#A|ln~JkOPCo00sqtq( zNXPnF91E@q+$DSrgpg<@(R<(FVd&q^YqNjg45e~ff< zh~RR5aRar2dXR>8;fze0S`ZixNo5pw-BPn1*gmlf%gXlLsCi^iRuB59cAVLXe8Qua z5^456kt|HSM_H{(TiWn2niMMjXia_U?w`Ylx!Vs5cQ!_Rc7|cvi-Rl?S<1!QC?Jj! zw%B~s@m4ZM`>aUy<64{!(-73eoS3}8k}EMXU|6WRDf&zuw(_9YYoV8F2k9o#?P=~4 zC_pPZiVjD5ltFT^-fq6#SSvK~#1kVD)(}sDg}Z~B0Z3Lc_N07B z9z6)AKl{;6Zt2ZC+C&C`m$iI#?bi2f1$ZZ~z=df8$i;-xMs@FJIG^P0ycZ|D1)H;SqS^;+#%{{*W# zQiYUyDGp*^hSR`r#S5f1=bP;{gQ@h`(ux*Gg}K#c^9mfWKqz7UMh&`J-GLN zGbg)my&tCfX{5}#o;Tk3%d1fs&#o31qwwk+yCMNAC^p48WO+ zA6r6eBkLRW02#A0ph}bB^H=AkWtYjHmxTY<%D!p~9PZ-ySI9)&5m80%Hf>zHeNGGQ zO9B(THlDozl3<7qvPh!$ z-0mWmP4aIzKU9Q|rP%#ysn>}$0Q_k-rv6jZKT?Lv>#9`&?XSy7(eZ^-)(0+!Yit_3 z*}7FTJ*2(4sIDk{2K;Gz>Om~?^e>t31;6Ce+OfEJ<%XYkp!7bmlX9zBq$z<3D6Nqm z6SSAt+m?+9_;$?b2KlYoPxG;Ud{g9+1heZRxwGZdd&dW2`B(N!SVP#8s1<9#>2g{j z1;yHxU{cT^j+#GP_yrj|Zn4KS)b1l|7YTL3m%dTu`XJfG>cun#VGReANHoqvu5jGY zXLKnaHOHs};xPrhG^o`iH;vzp>>o}U_-(k6nO*{c4u1ABBS(|_M7i0Uw^^J` zC%>WuX2)I~Db|%5=;)j;r{A3f5gXU7O}#Ci8YDRdyfhm0ftnD2P&DMbH;$`Mb$tNkx(My>Zm|`17w>|fPas#q`KlZ(%Uhw$N z{(YuU=_Dmpuh7M5ZB>y&ZCYjko>nhE2Zxr^L1JNBo+Z=_ z)!9(3&2I4ylXj0uJg#M9y>y8T(j{6lf34s6$9L&h&FPI%XXR$<015 z^q2RqxqaPX*DVSb#c|CdP{cg+sfzJzmjm~Aobk2f!q}3U_)E6$>NbH#%#L-8_#u+@ zr8qor{j0n%$JYLom3EnHe!oCWqyej<3>ml;5 zqc0bEXC3*y6pKxgpi$I6%!rzTsn@A4y4Q%lBE6TlpZF{NN{|&%fo_p__*9XVV@NJY zQ4?JuV4C$Y#LzH7Z6coJL#T&GK?Y?ho^@Ofdm)5bPpbik@TShzB3z+u^{%S0e0Vfp zdm!VXBfP7tex_l!$a|-bNc9#9secVUJozZHHzG+d$WhV;PlOD9*Jmwer*Lfv0&K6^ z@jv;6bsWT!X8O>ONoa$Xfo>4BxX9HT2is%>96^XHL_L` zZ-GN{O`R_s8Pe(*sWw4$H*6M1B$dmjLr8Vo;+fu^YS*g>0;vz0`T2ihD!=pAM6_HC zm!jBFheA8$lzHKF7o_sDfbk!Q*r|SzJf;~a9$+WBSY;+7BNLiHGOM@DcmkWy_=dS% zQe~FNcWT{E<$IGj5d0%8AARo(h5Ew=$X=1;(pVZ2-V@xPah~_!S0enUDXJ%`gfJ|> zWs#hseK<~s8`&{V4T0Z*C~_9puY5ot>85ua^0GAN4X7R?$fatKP1Q z*Ur74HgcPfx~wdX)kIWEei8SAHSwni7Sjdz+z+Q)P<3_xE`#DNW1|nB5HFH{cqCU& z^+i&j(uXJ(Cp0{&sgN+NNjIu9v0syFe6P41%jZf!6Q3VmNT{V(^~3RSYX|b(4Dww+ zmrpCmt~W0r7TP&jlttwsTc{hKYd2X_%cmu?-)z0jQ{ZqfVc?{rp6WRXHMENmlGV@6 z$pQ4;Jwt(p=W#^sXxe~6Y?;NU)X8Uu>Wd(!i9>Y2e9RT-H<%ho6;H4OQA1n0RP8x%{`F z3CLHNxIDRP#al_}A>ll{IToP$d4ngIyju&FR9{p@Ys@>*woabvrh4z5jtegZir@@O z()I4&AB04H#+z?CpEFfKRXrSy@p^4*9hLC%sipwd0~K(nsS<+%xwax7B|^YUZ-&u3 z^yjy4t>RZk#NxsTt^FZA?ws3|r**u2DWwx&ed2$(OuD%{025GEQNyR~{8J zh)AlV65%aElm}=?(Q?x z-7o-NjuzuHLUi&QK)iV#7`NFJB{A6)Mdx;AacQESTlNhlZIdzqkRs>rOXTKr?la=X z;uM{b4~FiR>YlLC@E7qTLP~AW0Qf>v5!fo$Pb9N~qf{b7pjuvr2-$Jg%!STRGnd4g zMzlc>GT=cq8c@7K$SZ@S-`%TfQa5T+OQuFQ-=TWoXto7S>%kmv9Y^6~)}R3hbA#vV zd13@R_)CB32UFAI)4QKXe=I`;e?7iz#W{~-_r;O|g?yI#kYx$~MY~)|e#?2dp;h}q z(ye>gX!gfLy!(gv#$q_XmvI2~`r9ct{vCnlTRY+;Oz=326LaKP_^;Q;h#kqp<-^d2 zggKXC6A$a>$SSi^$iFXy-W1ymi{9T1*3LK`=mMqb88ArkIMYLGA)oC60W0c)TQr`=^G)6?_~7BV z7_|3s-WZ{^6$jKYxYh1de%gmVS0kk^p2T5y^ORC^xL%>2H-6g=x1x$0gj9B z=Jmk%aZ*=~22Wgn9Z}d;!7*b+`2Oo*HWhJy<$;kK0MGgO`1W(!yq{>*9cKXQk}3MU zg(CNr2Ou&p-c9C$j~4jYm$U=f;8)I#gSxDz5uxd{rc&hLp%-*iMk>C&s?&l(SKpzd zT|;alv{9Q(s?qMA^|cbIHgD=8y9S^8@W?-oLP?(;gj^KOSXL?lyt4;JvYwDAz$w+x zk!^ofyl$jHpLburL!r{Ge2u!#Vau83L3C_3+zZnM8-(_7apVPMt3=G= z;^OS=Aqx<;wBCHt865nC=Oq!qFmJcl)7{brg8!=~u_lr@47!p%*u8-`<~r`M6hfMF z8}WY!X9>Zq6g-4-0UOYQO*T0%NwDP`eduLubq{-Rne9rppYwHDX0!!n@Dd;1$Yp=y z<=gkYzZPeppcK21Ai!Mf5p*^Flwj<08OD@8u&pICW9s$N!r7VkuNyXnNF5Ncf>r`H zRlT`eJAXIi*5uqCC2%(k%!jh6?=P6Znz{_cH0=BAdzv&aM;qAx+~oy6-qd#+a^fzl zaqDTmK5Hp>^LJ-6nkp4i_iaf)!(4GSt$hapf;%UL34{Y0I>v*jAOcQKv5}F)my3^Q zg?JyYKW~Y_yb|<+j%Po=$}RQhL-(>>uvLETBNv-J{HSoa4n32s1w8x-5}N0m`*heLKV#nEth1* ziFi>IbLO9C@V%*Vv`l5;DGhFi@7QfCmtDiKl}rlM#fU3&pUFteCT$b@;c zeHh?OpaWsAyJ4MgskbxPvK=JK>zBAETWRoa_TDXX z6NP6fad@OdL6;D3vt^R7K4lcL_z|Fr3KH(FAU}JDrT+2t4g>HapE0B1n^E(9j6H* z6HA>Ug(=aqzkM(E#DCY3K%&Z-qsi<5!Lqtr?UzWGevZ3^3}v&Vk4|2USh&+?DsMZ* z5sRnVW`uT%({&}L2EXR7OS0_Vye4e6iFrdfZ=~koec4)*Odj?$-8A&#NMyJV0RXQX zC+^{;cLFTK!INlcEtiayor)>I*7z7Cxom-DPe;C(>ur?4++8lG_j2<5&8Vu+(NB;i zh9Z82t8&u4)6q=jxf2zH4$!xc9+6X1`a1$`O&+g9T72j!Z9WUjTjTPO2b;Xs0iHQ1 zgw#BW-Si8AvtX(LlLcP%rC^^BV|o7Wz1aOF#%DZ}>!~1O!%yun-Ek0H`fwY{F`Pi_ zy^?H#h;Nt>FyfA?`dKkq2+zV&=llQ5Ly{E!s22k}#H*#4y}`p4JsDZ5o#SDW?lFC! zeha*-4$8*DHS1%WHW#NO^11#w|J|@g0Y$|0=c7s~Hp9AuORzDxIqbgonfGqK8?<+6 zY4`PA;~n?DXxIJId{Wsz=R7L2KAh|}ceze~u^8ZSd_e!6f#%Bm0n_!nUIgUATfi4d z#`C%Pl1>xT@fcg|VntJxUAKGzL_bb7d3);rLfzSv&glRYvCY)-2b$xC%eLr*?ZA4a z1?TD6Ec@3WcS%bU`8AG%h@tkD8b_tO2>ZS9W_tIiklL#33M*&&030VZM@_Bj_|M^s zodVb!iJ}Duug<)5@3xeqgr%StJzm;o__}RM=q;xKotqFF8-w?2F!W+1(XLfwpvC1H zfxis0Lp{_Ts11tX9MAiex5`%>T-X+EZg2!BzeHdUA&$%9 za`GDgxxCat;0oNW4YQf}ksNi>}1xry4Jr0wmo6~WV?&=AE$O2B!uDxK#;zP_OCHN)UsqY*> zAdvLQw#hx2oRFc{X72uv3v(r#j1;$4;rSM{40JfZd(E--`2c6UQ_kTst zZ%#n5`whk;;2bA@d-A)i;c9D%QBfP%-ubjY$thoWiLR6kY~}=~VI=%aW_g`N(J!P= zdgx;U2ZL|#&J)wJvOAlpeQ%ua&wWYh894;+y}n`M|J$Mi5QfGDLdW2;?W#PdX(^WV zc6P(*0QOWhXhqd0xZP83f%(58@1)>PJ1_rZDBc7yBvgIb{IS2cXsyvcuqM2BvMl;5^d{K6JMZ(xoEkbrw)@nG!z+xx}#}l-t;bq zQLs4fH|7s~qxX&b0+a^Uw=R`-!Z~Z%lRyhL>a!9gYCTXu_N$p>Hw%%xW?9$A?waqT z6@&RA?#-9&4{$q1H3Mx$R-YpWlAE?#?8Oo9J!;R@OTL5F8{o4jeI2HAHk76%1oJDy zV?BbRWx=&uSCxyR1w)`B!^FzW>^oo14BOPt1@*-W+PWu}ZOp2veLePBG$A2r3&kA~ z6g4ji%R5zGcEV|q2(hDdDd0FIe#|`LYD@?C4JFuWA|hBxQg)iVqU= z9aa_Oiz|iP{QB~(-)2Ruxd|f~FdvbSoL;JLa(RofEGY=TuUQS5bHDziEkRjrIrO^V zH5~c&ctf}lZW<$ehpLA~6TW;;Tvqh)cj(4ZKPM+Mb4wOYI+rLwBVD)u(nb+_!gQOc zK8D*BIv#%dfe7g_&9HN%2stl)11$7^&HVs>K6BiXq=84|KKE^tLna>270Q+#qxXp( z(D@R&N6Iy$Xn7fE?b^f<81&Hh=ef_+BGb1~c}9p50Zz`*e!`@M0^^tk3?28dE@RDc zvaAa^Q;inl-aL?IC^SQIYxDJ|0;xAi=oE$bSt5E2DP)IRe%o!e)ad8P-JsO;VnsXr zAT_0ZBil`|>PM%}qH5wGqycGpuGZefCdljWqT?m}+0%d<VbDX4)^8KmUV$%py!$_w?+|ETp!?Y`CK;MJ#&4{_hsoO6~GTiU}g-4(Y;-+Y95R zKzx;#I&bt_;s1yo|9v7r$EvCMD;p(G{0TNy3V;9E3GeWX)Ao13M9PXrI%e~|>o?&i z%Op#zleqJD9uiB&03ujmZ<)3CsN16UF~wF3>&f8YU}Akyaj~$&!XvLBJL{Ba3jlHh z*Tl|>P)=YT15}J*%NX~-&J+}Y=7$@3xeU4`;G`?5bOEIMxvA~&bO(g{oXrWMe} zzW~}e3Ns*P6syrbhFK|l=2R4-3cQlCpkJFhP&oJy=^hr1tm!^~(IsF-pD(Q=3%*Od zM=&;Z^gb;G-sQmd^}L}TalKin!du?+2#ICL;^&D!})Jh%yz*GjzBiYgKCRAz^Or+zd&(-y z8DPTp1e5r_Io3LO5hm?@ucyTUC<^w>;zOY_R*@hKbrmGlb)XWz9WR}2@ZkMLLzB=6 z)SjPYh^F@r5i^2_e@EjBicm@$Q46kv|25_e)wec99MGOgc~6L*>t5A1-&5}8VyzuA zrPb{^r!TiS@oFp;o7^2WpmPAbkAL0_fY$%xC^8h8yMb5s8iD5CDF^C9|BGf%1Yj)}jh-_renAXN9I>En|2E;S_;j}~1%xv0x$L%;mc zI=GYxBWf60ohxi3$QHV_k@@cntr_ZM?fp-%j0lo@G-{*>)ESGmQblMcuK4rOWfgja zSi1=WXq^3MYrf48w&FeYm&&2`8C)#z+)+;xsgE39*5UI_uZWZ(!**31fd1^eAtO&R z(fi;q-%9eLTjJ<~(x2op-LHJ(!?ZVnuT8T_e4@)vnM5bT)lG z#3+3CJ=Tr1E3`AVm}sN=n0=6amRJ~jqWkSAF;}#Ut~B5F zOn2rtL~zshPhM~%iWecpSs6IEs8bqhrunJ2`=7PVOdK%{^#8)%1$MivuwOlg9^|60 zBiK)r`xBoLm7Upr6WK}?C5lJ}NGA(e)lqi!!f9a8X&%Sdh49>#o|~2qd?bCn+|E@; z54%a)=U^xR`@o5-7;^G+k{EPJ)w7?`EcM3HIH|h@v|k)YSwDSci$H0q>-p(&;`iQ4*sI1oCmu2jv)V@Sl^yRpQ1Gt85>3 zK2xpSJ?g>xD^*s5lD38_I>%u5mkfMC^xy3O)m?ma%PrMpsWCLceZjxl9W^EI{kC1L_wn9Oj|AiE z0OaO}O!dU*OonXPXp!Xs-ce>w*6RfnF`(VKRT{1`ojiRAPXlZBXm?Z}?o=eoT|e!B z#bZRwi-ngdi{}Hp!@BV`mi_U7)ML8Wi{bw0hAm<983J}Z1naXh!K--0Yyzk63b>>C zS+!wTc$joaN?K7U>XGPK(r&oyOmro))V*d9BgUvoutPcY1KX{4t@g4v;T>x^P;zqm zXg(ilmesDk+wa4iFIsL-v=`h0*F7W%@AAPIzVO@x=G85G0~`jNbo9zsGWJj+lr|vl zejMxE@|vUqBG?AyI%(INxg&DELB#|sg+~fS?6i;zrh$Ewb-nw?ap~{@bC!cr``8vbH{CS!LNtmlYL+HA=VtfypS{ zvW^>?8)`fTpVR$8JM$wVI~qX{+JMb>{Tj5>2Vb5DJoO-VF7u^ov)m{8E=4JLVEW{V zEr~^FqgNF@)p~yL9ToU6O%@&diyU4oucv$NZRV$|P(H#k_`#={)1lLJW4UAXgD<0ZkOJV%Nb3m&%$)h}S9<|?c9@$mK!3~eV%bCc?o0J#_7WyrZ*WI3C zyPIOWv5!f@Em%in>(K>6rwV|%yH*kgj9J?icf80USrK7ew(==Qih_A?ALXG$Rzz4I zPm~=lW2>TsP^|dX$VQF_!^Mw>cW))KnBrLR;K@~ZI9j)3`Ch<58~e{x%AeFT%kZ$%dW?6sE}+XKb=_6L-$C9hI(xB{Su;lJg-;G+^*O@-pPq7tUu z`T`E;ch3|`&$G#R%L2e?{7DXR#NH$}?YooW)^44O)gFbHH%>y&j`$`7_9wKT$G%hC zDG#r`S4)AGQ=>yRkSMdT(lGNxyC4QP(Fyu*0tZq%Zd_yfmLD&Fo+Y0m)?Z_o8PZ|z?eSfE;7>o50N^q7|Ko6ekG zsGLE$t|q>P*oAK3uM(ggM@+%e9g}4ASmKKF`92P z&1EpTngr7#xC+61Q(qlPTd5RDZ-EA~#;;pfruqEiISG$z%f!M@C$D$=#050SD6;9@ zjCIC-@8#iJSPzWB78K!UujjmJ0P`=zhT-#<0T)zr=~4*!pPXs;EY`5D!naG(L~?Q@ z{`l;MJRty?`Z!eY_J!?T`&X=BV5*U1VsgfsRbjdybDG;HhT)1x@ zKW&PNmL$0OZH`a0%|X8y7(}{*Ii*8Pk8Be}mXqW+K$Ywz= zWb2s3d&i_(N7^g3|JDF^|GP}ojF>SVnVQh2 zVbS>Ujpb|cruZs_J@@8YoxvZDdV!9>gJ@4a`LW;e>R#m3#}hMi1FwRCpIl9fG?P2DVZbq#M$hg zUC@Xkm)Rt>;!QjOb~opPDMDWaz978r9Y?_ajz&r5&-6au4~2?GD`grXksF&CPPr;| zC3u8@Y*z|RkqUeZ5FkB6VdlEGXZ!P~W17twT36@Pd^RH&Hq~k&FUQ6(W}1Dw>p^C6 zCdufnv~$=KjXB-IUAnA(EfrLzo2zAL+N*c z>ye$vB?0?*6Ibck;XWMH?PbHU*y1vCjubnEQ^1R*38I_OrdfGg{KmCTAr!|GBZ|U= z5W|-kQb(eSF%)X`JBaGHIIi zg0_zV#9i6x{oZZMv1Mqs@Sy3%eeLf7juLIP4O*s(2S%i^hmRqlvORB4lnH08FTy_5 zk+>Z_c=*&J*8*|iXBb}GzCECHYpg`74x`J;Jz^^FH{%>#4?~;VEeT95NoUlTv(t)? z_gUDf>c$|Ie9{PEP1ma{|0D0{xB2~QZ7srjXh##eN-HZln4B4%t<4x5Fv<02?a7w* zO^;paVYWKnOboZ<$jz|7_LZBp<8XyVnZpsiK~gZ@B0ezb zrbB*4>wDiVK9nY!Oz*?zARI$xi$OSSeUxG?{dxEH^yIhdJQ(HQe8!Xic?bY#mid(b ziBAC;bGPBaaynJcCoJQG9NqsX@^>FoF})wL-1pvp&|H9w;-um@RT|^A%7^^a=mf4s z^!Vmm{=ewBmWzTznBykOf zvDNO(HU1;2sE`iV%-5cRLk(@RsYG)+;5NNUA0lkPa1u409QKqOyWp@98Ks5(hKHC? zKCmD~u)3qd=Flvz3v)V2WVk)hCa*x2}|*YhG+}e-E&J6XylCv{{l`e+ybg)i{mN3H2L) zIN}$t*rOMpY>#96487ne-tIjTg*$rU7eDHDJemqb$-KM0{#lwVAv0?s!cok9rN#|w z-B`ClA7YyO>1N-zA=O#=fnd^-@w2~o_}6f8j=C?4+zk+Krgn=T46j>Cg(H2E`dGH8 zj-elNFG)vagWdiCYbnKg5^o5?Cqow zr42&y=!g(ASNr8dmfNk4q5r2~$qbHVQx&YS7B6PwUmvkWUmN^wk@%W*5ic2kEiqF0E}`y})t}XG(?x$Al(iAye?BJg+>{Y}y~;dmWpX{O-Ae(;g^b+~ zWt0*e0;SpZzNk6$p}&0M?(ij`9?k#bR-MBLA~A1{#JIAu>)XE#D$>hcso~Vc#i|Sa zE{g}K&;dUbN#zw+m-j)sC63#FR{;sltUXW7FDVH>7&93To8;{kf1)m~0rVCApFo{(B!9=KWpYtM`NHi&=`Z(Y`NM8ciR zXxW`5Iuk~7*0@7Lxbk;y?BU|K@`;cOh2Nks7a;Bag48J$&$yp1IOS^0JvPBAi8V*L zm7_FS%|RuMx2vhXf{zJYL9oTwi%kbnP0|li(Gs4B5`iue(mw^;RENpYWWv6QMces@ z{}~wrH|j$l#w_OT@o-0fc3^s(EcygEHcAkJ z{#UYM7I@I*G~_4;*-5N(g>>isV6;3LZJwmHnDc}w_SsF=lLOVXL(CfknjEOPQc}Z0+2%27;y`Y}=-8LvqJ{OM#Pr4{I>0sJI-y;T z-BnrhEE!Pa27l?9t{UTRBWX3V9Tjn;53PuHiB>oz9|uz0my9gg^qX@42u4F+*0I-N z>?h1XlTNQ6wCF#I3xt1AfY5=9Ta6BYR468QlO-EzBZMaS;YdEyeF$_g$CIq2$(kKq z&wu|(W-S}5hAHKJ3X9-=UE?$=dicRapv_H6!%| zzh4?1T{Lt{-v#DxHUa&SHos%H*5v(WE)v+rKQuCdD)E=f0FsMdMuNV0-eL5xrT?$N z0o%xFw?S5ehK>l}wr~`Hyr};BC!rC?0s`jHfoU*@LyA;}$~AXeOa{J>wrwnm-;~Zw z&0B9rMyx-FgyR0LeP{H;_x`=; zk+knKvR7KtspKgKKG6Q~Fv_qd&Do9V7{vYAK(RUz3B{wB)J_B~Onn%6}ZLh-rKF+oOv9O!aDzQ`q59+J?Yi$e@f>Ke{5 zKrN0iSL2bAvucjMSHY_s zqi1D?`j-ySZl&%oi(UrobA#Ee^Mpk9Ue4EoaGoxw|EanJMT8IsbG>R$MOG6q{Sf7+ zd4s;U@@aIw)}DHa`$%IEz+u%L4NOEkmVh)kf4vCVsgR$}&7@1$bWrKUQ2Y=~`p4B&)o|sX3MO0!a zw1+`GS4Z5PC+fD7@tt znzHEc5_>r=%za)I)kRl=Eu*$@UU?_QPx5@OzpMdF{D?ju^m96hn-78>X!T=01S1u4 z{~Wz;#{qlX#K8sBFB~C2Q{j*k`mZhAhM4?LYUwei+cGQT-ztm$j%mpVbr}64HR|4T zvz4InL%h^eEg$3hpxl?%?hB#F-2(?L>X@{A;f{?K!2YU250SzwI7G}l_|M;WNnDGO zS6AMQjBy^=ALJ^1@1rrviM~k4$dqmVcJz|Rl~X{Hpy&)^8v3wXgHoZdj3Fv_f;Xx+ z_KqPkNpv62`E~zd>+z3i^6$Tfkc_Jid$>VWpiLB}%dxt+@P+lr<{*{T416>680!54 zT^(JLOgY`Nj%S9HXREW4Rk)-fi9MQg7VU@Y{{bGpo@b7bDx&{Ujvje*O z5-UtE#vv2zn3+~Ji#sb}gw{%BTTrOqP`}obk4utFg#qT*`dAVipAVpdF%tV*h&%Up zyY16@$kVkM0sD$mbOkiLva*CjvHrYAwEk^CHF4Sl59P%;DP$oTE87^yzJlmh{sIit zQ1;d#d*eY3$e+fdESaDlNCu2WL1%GrextQAmTDU+SdhM70VVeafeMtz5`+_Nkg5zG zslt|czi^8$RK)H|seRb&Thmnzrt?|zB4fZ8b)@_-f@Bw{ZGKKnTJ%70v_}0=`haz> z`+&~n%=!3Mfl)^>P4A<~rBOMH_F&ALY&ddup)57zy_r8ynJ`-#W;jisk7rSzk-%6W z5VYtfssvtZt@DzOx`NSjUY(c7$PhzaMoYshGeajG?(ST*C`C}Ex8!>^j_Xc@N&-sV z4Ko6UYS3mvlN;;|Gc;!3Gqn@xBE{Jx)7rW5bOnuF2X!-c0EbBrVBbg!p_1sdwN-h! z>MQS z*~k{NkrKqPg>{1-QXeq>rGBALk=VkTHwrTxn|ZgdmnbFe%T$!juR_7|dN1eI*RTK^ zm$rk&3B*$$4R#0JTu;zpJmWVp9EE>yNBfY~-iD zJ3Mpn=(Ea;&m%!n&kO|^&4O@ETCts?%#HK#%^eogMDy@xdsvA z`erEtW6h(lzyB4^3vVA(k?mF#>gUUhpE{sR0P6sFhaNVd;s5gx>^)jfxabzY4?CtU zXy^JZ?2v)DP#0uV{iqd#dAhdD{@uIh=>apRgoKTse~Xds;w+NIZ0z8?Sn$6VK%|N$ z4gG3kXUD-(xTTehT5f!EwT*4T@-4Q-=y%>AD{FD48UQJ3J&u3bO>5&zkz|YGDnBdA z#L7&2c!Ktj`ME(mmgGjRN^KCmfjC!IlF=UIcU5+Un{hP7ap0z|Dq2x;9uhKhTO3u) z&qv3B_zLn&DRDtC+IUSubu@ahaH0=N+u2p3M*m;C02o6G=3~=+@qICmKQuNNAvs$RjV!Bkf6iH3(SK0+y!yZ-^@NMFx{xo4sjJ0yT?eSr+s7}Mt_!= zY0er|0(rB{leeQ|Lgsm1cIz1_YBd#*@|f!rV3bmvkz`+6fA?cACnhYuIXbJ@sc_R8 zT}Fg4X6zSo5l-t|b`p2{EZ4FC|GW(f2nm^Hr&(OP2UjSxPS$MuBy|8H!XbX$mS|rH ztU7#}%lo>b$fseXaZ43$YMCXF(1;e+5HuKS!2%VluxpaNV#i4$;Q`5ZWw#%h_v?ns zC8prp+b|{uE!e+x`%5K9WHf23d#Mw_RQ-`PafKO=eUS?_0QW3UCQB zdG#Fza|!uS)C*jQ%)Ze`4%O6U&c8?16ahBMNpNM*w&`7>xhn9d4{Sq)=oh{8i$rsC3!XxH)R^ z*AQ$d(kU~Jw{)HO#`+J2{xo1=R2@ta4f~b-K1aXPm!AGPcpCPQISKKBMG$^J}K9%{+%w%@J2n3_BO+5Zi|28#UcD{QKpueREz6(wT_;`p_vK z-{WBH^kDR_f7O@eYfNGJXqR(vyVY<)PVfRTjPO5iR~0nV!h#c|yDz28{;aKr^W#b> zhEmbjR~qpuc4#&BG+es>CwaSGa z2KADF8piJdx2xW7(aaQcGc~k&Ae)=Wp;NFzNDPkptIuUev*MR<2Ob2FI#SJE@+WPXv&$a#?#U@z#~+4 zPe(a9O&aRcG?y@_#YArKRh<+b?w=J`=j%N*2*Z@z^Mc3k`C;@|`AOp=0~EsVj|$XJ zR0N}sKSyvj-CB#c$9rpJ91bU#qzS*988d6=GWq*TWB!bpSup;aMopllkaqZ2;wzN? zBD-m0y_zkW_a8_xwx`c;0c?|oqO%=I1a?`mVQlZI1j}D9%Zfh7p;FRP9#a^L)$fKL zj`6+2s;VD1^4uk)jMr?-wut-(1@)>VeDHj0FW4sa*^mPzX=b+OxzrW2Y@7%5tV<`IBJ>Vu2ze*|L5+DE^s!BSVZ z*{87rNhrw%Nj(!HBWvORf|E0oj&6^EEQe~v9W`X*T-she_UI_-@>m?~?3nxf)wA=W zNS%NE%H>p#4Gw;sEWo+{+uFv`lKKVW%6`r4Pl5fJAJG^%H9QtwGC~~I^d;s83#ee` zm&ND=32{lk5m0#UH2%P&E#`d}9t|xN78YifJ~;3AQC?2;N6XG91x$W{Ov5!iRx*z& zM5@&ALW= z&FTy%m2_VQC-?Lv$|!9Pxhg&3vk{Z4rY+E^+BY+b+1NHQ=frkt*;3a{R7^yXWTBY$@g5|*^`=!ham*5v9)$3(Wk8gro9U+{$6_|{2*u1C zkz{z1vZ6O!4Xt)`g!dbc<#7Vv0W}*Q8xT7gs>9uDB-ams_WfV7VE!xX(lSNAt& z;Uivp(S`0<^Qq8EF)zN;66N@_8*=le7t08MJ5uBcWJ|z+=Uc^aw%Pw&(cHx-zrZjB zrFC$O3_VeD(BlbZV;M-7Gn|07sryFjlIT@f_>AXFI9r)e5EX-?8z1reOYJ z_pt4-l=m-=OQAuN9bxgBu~H#ew@V4l4ZHCM%qWJ#&YL6;7y6(isdVrMA6vmj2V&JT zC|y5-hSUl3`*8GI-iyzAbYwE`5EQAqhJ%Ke*QY8xAhDkm5isY%jK>o%Mv%SlPbO4O zVoZp1b6UgcilA~yXiay7A>^hU*-iZNbiB! zxta`Vta1>@ePZR@IS-L@D-XBSD}<2X!jbWqiJ}+fdNn)W+9=$NgTLz{(H{Luj^tyZ zhDHf=0-&f0iJ+hJvgYHbrtz@r#WK){S?4#@GfxuvB; z6bY{sa^*f3BBByl23Rb{qpSP(78qfJFQTn7(<_|=&5PvF*-vmWh<(F4LD!R8OhA+q zqiEsWCmQUI+9)ZmHyz+v@^U&0%JrfI4>)l57izK!Fn~a;F{EmCk_4(IGzIOrP>qUd zScN8ZO{MU)K?WjgM!>7<9Co!<(I@$DVk!cohV)po(O$^?$)2!ZtTD4068mw5f2?}3 z={-&3KMgxrXr27$!FZZVDqii>9?Ym1uNGSy8eild7A9?cy(*=f8*BfetN!xa@4P4y zE5g!Xxu^L}ebA}HuL%(|5}VbrIalzx!K zFS;ZCIIU==m}cSj469PVu)&ZJw0&62##;D;c>{zVm}-MNi8+^)G(+LJ`e-eI|FZ~tboR~U^Il^@m|pCr~L6;|#@8jZVEV}WGjPx9Eh;CYS zs$?uc1lb2Z%41sUjGaW|_N!JAxZ{D25-LyFob#sJZXHmIRxHr9cqXzqhe{+%5QPXd zJNdMfs)4ECzCshT@>7RlJ*`MYd5em^p;Y0|j!E^;K<```^z;WM&av#PF3s!TSt_v; zQg#@7*oE-ucGA<2~c zP5(h7XeO~CeZxZfcUV)3<$FGe@SAAGhv{@uKJ4qJJcqi5hNN`QGX-Fbex$gN#()D9 zr4tr0X5F0Jkme50x#Kj@?~q_3$~H)gP%%ktoPqVMDGQHS0F8Wy^b$Rkvz{TgjuIni ziOe1C9TUcY?;xWtq7o3D0%cIwDVO++;(v3%h>Ck_dLzRa?L?8FY*Y%O359d`0mL9!<~ARueC-$aRF>9v~f#N*x< zM~%*4BcQM893W&U?Mr8yLEov7>u2+9^!yKkm!>@6DGdv4mjF7;mZ`|&K2q>)TQw8y z@KZE{eiyl4z5CmNrb6$RG@M^c@VaKVVm(V@`uz?fjw^*+>Lj&H<h zIT8OInuV*~iXO<`hsDZnOj85@sz9st%g%qKdmX#(qPiV!N-qp5HZq}!BtXRrA=*XZ zK{92M+7;Nv1lJILmBEm14$*cUiARsM+!vn3Ks52>^-QN?zo2z7;&H=RTr!Rh&oN0v z>rkfgwEXQe0|2z$dE(2~#+Yb#X6JYS_*htIF?SoZO=$1R0oT0M0)enkkugh4$>3A= z0{*dH&;^y^Gp_@vyNzy8H?kz0(>jwM%9a~It^{%cZGbY?^hDWUgq;gxMAn9Inj z%>0ePg-S4*h-`}*Anqu1WPmjsxu66yi0+Yw>^=UQ(Zr0DxCd+}>ltN{=jna0~^qvluy7M-O~%jmL_cBRg-ygVs^WSutN{P;WRU5a z^x?gH>&<04IhSeVvh)%8DHS18njpCu*H~A-^suI90Qsh~^kB}$WEIoe4g*EwHlVKM z#I=Z7Jij_+BN@r>p;yf}UpT%Sm3IgaLn31ioN_%y*4ERL>HS)mOE0^akRXOVC&jHY z*p2PA=cz1H&50+*fZd=oP7WMUZ4KW*wY1`tl8yPj0+*$~Knnh`8(yVY1?e;tre!Xu zNDsQ|l}RX{sG`*X8#&JyoZgFZ8c_*&j(NZI(Ix~|zdL=#-X8`;e!v!J`rjK0{E7Ed zz%2HA9^+y5U_5*#oZ0=VO5r-)R8PP2aS4yD{HqZQ_Y}oa$om}gmJBMUL5}TdZ1F@0 z+w%_&sAa>HBJKx9#S<#k<{MlEU(dI8KgTJ9?6IfOigX{*GNrSSSLtOhA%FNtp(;v1 zC$y5mKI5SlgkDUek_8*6i~V91r=#T|y|!_Djcg|V4YUM*P|xF)kzfr?yj6PG(E++tK+%PKsY$qQ$+~(6Q~$1uh@GbQ$$p^1CX0ZywW8- z;5D4fYZb4QYHVnj#qqmPJ`^hE^u||vvcdvI_&e(Zo$zFLIspT%Ky*^|#4SsfSHxnX zTyMF1{g&=6i0cxtf4M*R8b^^KO|O28esQ+k<9yHVLa`%*2JeUK-OcFZC(^Lwqs*+F z*Joi&bQr<04MkXys2cK{;Df<`0L|Bs+MjEzXfKc8a7B$Zp|fZ}vc-FF0Ep%>M){({ zh7f(U#7_onA5hoqdV-UAjs2vV-#xl@cP|Z#MDXx>(re^4%Lj68x*b136o;61-T#Fz zkqqJh51*Mj%JGR-~h`f58S z@eLzeKNYw6)Y@SGWviD&s7$j@c0rU?oS``}C9c(6EJ6{%7rG@ux%D!uOZ3uNFn+8t zaks-gj;)OOz{EvIRxw6<_}U;|ZiRU6tCt{0fL0X0K0o=o0S#TKt++V! zHJ6=*%Z8U}#Mcyi~Xm#eWcwxPX;%?s}VKyJZ>NXDW@ zEYzmti$S)OUPUENe<^>!vWfeNVrM?q?LRODlnN zTW9Z|8~%z)arH_4r&m(VR_-8UcHR%y*l2PCoak;)d%`^jX(lYsaJQ0jv}K*2+`tbP z_-F#;TUxZ(c(F1zulI+e1ld0Td`w-$FI&osIqOKeA0LD{%#aL7h^-fKO1m2ptmKv8 zu}%!W6{&Q6iGPP+Qq9W(Us(;_q`{M6{+S?evjhPHR8?U1Gfn_UdRhF;seTLRPD{e{ zhZELuw{KXoGBIsmAAZg^Ijffegn`X-Aa{%=;&Cv_5i+a(x&*oA|E`jaRJkX3@o;!9 z(LK7&W_x$mz-_;ac)8OHtSll1xpeh!;VVO)4Eb_ucy^at11R$UCxF3+2?>DPAlONv z=xZ5a_5V`?7-N9V{KqYP`=0YnTE6>S&e4(mck)(GV%V8~*f!3}Q7f$$x5t$w+^Fqh zT?sJu5{Q5fQ272^=KEt$uSZ$%Y9!jAYWsj7B$~J&Lf3A%e5`Q}9703FoTRlC;4kL2 z`Q)U9+B$yHhU1+H+c_46v5DK?mAdJK2m2208Sj=d9V23~-?#j?R}2v+4-f5{an8!O z`uK7?5!!N!0Rzck&)Lcqt_pZ?DVP1~^}_hev7-0Cs$X{f7ZW<9!Y^edt83#|w>dsb&>7Vx120co(Xm6 z&6a}bNgj!e^_1)d7|~Gyo^b0pGKGnAm7)vTXzL!Rqq-Wi86lVmb;ad)JCr$+GI)d} z2zR6+tTGkHWus0xV4EVxSC@{^+HA;rr#NP-CyyZm?E?1-42k9Tl5196*GW_zUvX0gd*d z4+rar{J^y|UO>J>EbyWlgY@ZI@94h=;qp{|Z+*7NqbVWFy^WCp9h1Eat| zJT=`_3E#qH|MKYj6#H7AVo*v)idHw<|KzYGenlg{t?B-}Lbs-(_ex_& zOG&-{SDUxvXY@7@gj}u~qlozn?M1N3*H-`?{FhTC89nEU~ctkKWF%f6S zGP$tezB@`t8I(yCKp`)MEyr85;)>KACzS4Mb8Z+0z>rQC>rs6lojl96gZ}T1lXT`J z70=14P_j@B^GlDsop@)(RrbrZd+^MjsW%qrUf@|Bo0SJ7EU~=2>}&-iIjJx+%{kGB z$)eKIqMut$!Kl{2(UNiVN3Kdcs|5v(5>==UsQvpketESFEh7`32buLk$E>MkpW#>BVss@1Y315;2p ziE9EtUjpPvOF}}V>G%y}$-G%fvJ>Tgfn9z4MZh;oy(YTs+ciiom%Hm`dtDBD=lf<+ zI{RVwdwuPQ=Xo-Z-=Nb?r{cM*R#K0ag&j-zLGtt_HJmj5APEKvdoAGKl3-cK!+(eg zS&w2CWBpr0)5HmjuJZI8CPYVJ3(|Z_KJo(bB(2M_$>*pkII;seHpYH``keJCl2INx zWlXWBLiz`-7~-nv8!@{8q%@FhLe zHW@u39Ye2wC5y-KjGDUO+@x}gLmpTnjjW8AxWRaw=^IQd!i1)d@*i|RI5xBo7XK~0 z6ISI`1DF(iUtosO!Sse7#DRt{&*l_AQ>OXrQ3@RslU%^f!P)tWrG+O9dDZ)S@!Pfn zuF;7JC0A=6{B>feET|bM7?er$Gi#{1mO+l!E=1vl>1mV>?s36ee0O+}J2LOh?CdNenVZo_GT4X*AhV3Hc95V1{}?Jr z2o0jNazLR%lZ9EaZ%B|~$9FHn{PxM{|L&bCOi+;cHd{IHn{S#4YEIw<)sJSI7U9g> zPx-9zw4IZbR57Wrvk?M$sTmLw*L;wt$+vF>OmKrolR-Y)(DrtT>Z6B842<#l<`-Rv z0Q8R0!BjswG1-mW4j2(CriY{lO!#^!Z+P%#N?T;_&R2AT=7o?CGN#+$ciSLnU0|Xk zm0Ph$zghI$k4pG>}Fdlam;P#63;x}n|gO=bG|&O$aF`Y z6Sro*pw$Ttn$KiGn6*+yljshSaU|b~+1UWCH(5@z-k`WNAkIkhyJz}(cib)$>8_^A&2>x~-d@AAu z+F2E}$M5m`9_g4MIy$3Dz%;$>O$T4(Rwt-K+90fhJ=3&aC!{%fwl}*0ITZW+`A=UY zeiua$kMlm(%}!S||H)<+R(FRg;rdCy|M@!OAgqxT*4TlqxIT5i1gH$?{J0cxsL-yT zrKKLHtN1BkUF0t&r>iL%l}|`m-5VRLtM6Q4Qz=41t6W{%Jzkzp6MtNNn~x#QDKFK5 z`jTJx)8F`zS!|CJk;e!eIMt6s>#wc>Meh_eB-QXPf z?-55|vG~2~)c%Vb=%t}z#6td+mhRmiY1h~gCWhmayBApXp-@Bx_56BxI6`0(MMJ}U zy_m0|-W!)M+@GmdJXvnaEkzmby-7|s=ioF3eqykZO<^yCpK#JMNyT-&^;|OdN2vcy zGFs2FdBn8*(NcpV(#9#Pvc5k0e|s1n*u!gE(kXr%`vQ%$6Vuamp0_8?lsY^l{U+h$ zFK40R;^GMj3GC#K;@w6K32-ercB-2Quag&|v0DWD*>#64YtJVg_uQ`tnlsn0#1407 z8)IW*FE2h`bjv`o>HoglV6oADru68L2oK5^dEFjr8MPWFfDqvhT7*PkwqmKq>Ti#d zQ1!#+`G9ajEn0sP)9LHJ^s6ibaug;*UuWlnzyF80&*I{$)`vI0vp>`yAA2$};fsVQ z_;DMtD7OY~F6-jCWm6im04DLn`#I!nX+Mg(ND)RTn>E<@lLVtvHAw8#(RnsS;dAmz zY-}1A##D$Pi@W?H{5y!I-=neHZIy+#8U%Q~N6=2-emHYYKGc@@fz4zSc3MJra2>vX zgYxnw5;wy^m{q*(q@_q0ZP{{wlusn7aiLzJEg}>Lt5D>q$Ezra&?bKOZu$qmNjCf~ z@D^DY6LEd zvY*{*%zBQQ>uL+Pgq#)tC7$XXEW#I~=r;G`v$P?*xnvI*5>P`4!^?<-kRHwnw_3eR#4K;WyZRZsi)R1b_tp1#GPXda^A1a8vz`rY zu&AWn$66jWF?KN+^|r1-Q&S^g0NL+51#1elYg**5Tl3c=uggP2dt2M!7WDs?=gG?< z0@`g#^)*h$**mNrhZ?vZKo;e9O$|2G(N=FSkli7+10)mEf$*kRVLv9#N@iUMb2VN+ zV5tGb-M#SZ77$kh&F#8?%#;fW;tA+~zQz2uQvY@}<2r@kPuUN{Pa2AmGSv_|6FOEh z@*kP^RbhI1pOVH&(=T{0n}rKCZ|`?(LX1pht|wm25LaHaT94}(EoPW6JJjS0jbGJ? z%^aY7;2dDz?p;KoveVI&X}81*zrecReWSym*@6|8VfPrvYkm_#Z&xFIrb{p7pU3`9 zg(7rjn#?l3Ik!(pdZ%X43-npK+>(Xr(ZIc z$&E?w=$JW1j@9pf({|3K)fdQpCNjYumN)>tw&MPg+)37zIm`!P+fZ648PCQJ33}XzK2{%K z`t&991t){s9^owoF;DjVd^b0ro4ATErWo0ItE#Mg-U*9YuHOP`k@cgDmuUqg4-DUE z9gGmp-UNn255^6?Gq_1~W4zB9v+!)v zt%3shhVC*Ibpj|T@+1`_C6qc>b{k*hLOt2!rCW%t<-pRI4U#6(BY1gMHt#rVO;&m< zuT$K8pusY$iO{%5 zPP2V1`YNH(cS+?=yg70Mx>kW4i2hMH1e#3;ihkd)RR8=)gdyDE$!+G8-@v`W(+THT zU1lwS1Ks^2J^iIiR9cRnXP2S{D}=0Ek!j0rq9} zsT;rDkMuci3H8WM6Z;VSwo4@aC|$MYU#Xl$aJ$ml^raC zK#c#Slgg)525|&luC|*0ksjJ%vyGq~yOem_W2i&V;sav}B3!%eW}XRxA^lh-4sFB! zYHs7~!~_R&2rcm*&Yr?yfdj!WvV&4`$E0flaygO+x<_MmI~+BctOEFc65Ti zeE{*=MlN|)D6!nZ@iSOOs&0nee`7GAY*LC`f$&FaFHbR_Br=aBI-MINK?a{d#to_{ zEy`XuRxDHC6|q_jk{TzUNWr2#AUu%6h=@(4ZYy~YTIR~%1YH)(^CVPsOJPT*;8wH6vM;4wxW@wbVJ#2(B?T)iP&Qvc-M%qQka81uZ8`F@S z934RSOD{Vr+*~)s!E>c|j^QvlqK$mMjKJfcEzg_l_Ca?*KKWnJO;BXn23IL8L`*tG z5E4n-$XD&g9d5D@Y{V8!Y#&XSP;_auQ=%9mzS=HoQzir(s`!My!9k?W!#%LzWZA(dC(8F~+<@16L7BMNZH`rV`u zv52c)r;Q)&KO;d9lC~H5@jdiSg7Bus(c<-$;O$4)MkTx1@&!QM{Y3a>;B{lO&qaji z`^ook34&cvC98QxWhLyn8yph9tJk-!e!<(7IWBS3gmS~z^{K+>IAg5!P$-O1K4)IX zNO^j1MI~~{Hy?2KPxTVr+1J{-Y$cg-rI-@$2H#a>-%REGAC!|4TVt*%%6(IF+7}6x zfds~E8Np4`sb}s@BX$t+a8P~Nbo>e?7^CJ+&$XkzR~7WcaovsjJo$3C018(|i2MWJ z@iBRbBoevmGSHR1=xYt}Y(Ols^p2KVTpuNCju^|Xye^C=*sM3e={#nA(ewwKXRGOA z^;D<(IT1YEo)|a=FT6F`?cnl9w)epGDuEzReH?ZILyGq|0ZW5#W5%dDY@{ZRm%4h* z@5oJe_jYXT>x%n^w4CGm(Cg;0YeD5#^mbkN56t0DAU@Wcxjy%`wDON3S@=KXt&*K- ze()tvCpdDZ$@JAY8SAP{0SURGAtu!QgN&9RV5T*j!3Xz!4GcPmo#I_ld7ot7bqB3z zK>dPR^+VI5J|FGDT=N|lWP`QQt~H;Vt;q4-L@rN<>dvdR_!$m23bN};RkfwfKj*;` zs&U#ofk2{fR{(i%=*wNfYMVQrdM|Enq;+%~G}Xa= zY0!AY+$a43go9^voyu!j2n}g&0x`#MikUqAg)gUstF$ESnS3sCa@v(6UVz>BWNNyl z;)FU`f*OCTpy-Dwz4$nN{AcaP&PA7JgO7{E>3hrV%GJ-dzWd{MTSmo|l?YIJ<1f$h z*k_cZ?9ZT3o!0kQk>2kgqD{4vv;DQc^MV`SiFderF@k>4M3VAxn4IWZvZo0CO@^UP zb}r&Iv43C={HZ`0$(`40QgBo4T<&!lkPM_s84Ij^VsdnuMyM{I1@SWixS53_N!fK7 zMf818;Wn^PXYQH#2J_c$nCEFbBq9^6Cndr5pBFYk4R_{y$KSM%eC+#=mkYP>?a>zM z+fLhVR{^bfXyCD`(w$ZHNF$w^2jp+Oxodg~;g9rhKP2=m!fa^&R;g%_o ze!Dn7g~$448lXqgCUgio!q~lAbTK|*$3@9HI)?AQSX^wgwO!KD0ja5XjVg7R4T%$T zO%zduLMe1+q5tm%;#Q>axSdhFQYIPi!hX;dq-FlAofD`Rx@ggfZghcWwBd_aY1k1H z%clCjj3EluDY0R{;%sJyQ@7zHMry#q&V^U6thva1vIo=jG6F=Q*XChvw!OG~$dLE= zs2JSSV>W)YPA2@q#6ZetNB+G3At_0nt*6|et+1wsvn6x4r698iCYM}gf9d+(!_pEd zgWRO=1t5&DcwP~(03^Eg`^!DwYbFvY?WfD@(GMwawXU8~)PS3m>hCpMIqFAMtc4s* zy?^WP6S^xwIVb*pu>_3SD3=uy<|_|cVv;5V92^WSp84d=l`{XRsp=bUW}wz6hj_SU_wPzGithSJ{-^>w>5QPC4X^SYXq81%?vA|!UatS zG!@{F+{#H`T`?y(1{;6FPL-eQ8}#EgA&eZemMs8}IZH+9RARm-Ir!5)9uPl{bNf4& zIwUzE`^){s4j2q}HLydYC3$bpLQpV{Kqy}OS0}$8C;KC|`Y#rQ(Gi!rZF2SuF;|ww zk>F9GtP~2=(j>Yp6%=hXNBQZo_VI6&KTaOV_5O;WJAYf~G z!2J1zSEy1q)HlQD`Ff5O0Kd-1{&TxTuXJ`e-|TY}5PBr<)PH9T1%IaNN8{Idwt`}) zs{g#X+IC%E&-P(HpiPpKQ}HofGqc^}`eC1bluG3gh+}MDz?s&9w0eGqWc<4_$YgiQ z+Y2!gwt2HA{}BmMg?gmyllALBI2(X!hj&1> zL!6hv!v7T|^)nQcoMjQ_{O)`Um~ds)G!_7MSfHN8cf%QTHRLW*_#01-6|~q<&9(qhum59tpB} zP@didR@X;qG<$Z|p-ptj18Q>%@+!6l2n5p5U`i@KJf+#YnSmcI3YP5%-d1tGncSSf z7Eh@+Qw;JB@HHsjaaOF00!0N%55O>|T#5I>#Xd5+umw)46yTMh_8*ApXef8Ls}iT5LnzNW@eIPXx3fX zkQj)d6~rSb{ZgPw1}7$GZzdsJsqSY*uN_xUmw0%1>y$|zJNuK3TkHKtYScldHB92- zhHD+KYrcE@Y$;)MI2M%#ePS3CbpWSxsZ^cK6ix9{>)KjJQOOYe{NL4>FCW%{N;PO1 z{(olZQ@jT{J{7!tW%=cH?9=>wXuZxte? z(O#ZCky?Itoo;SHY?l@n7bljMm%Y|Va`W<_2cS`YoBv4Oj zRpWXLi6;IIV{CKuu+bw7Y>lhs1J=nEZ->{HDwppa?e=Ra7JD7K=Wb?3>qqg_!Y=xs zzsi@Ad7TAo^NXja&#w5snh#Py`Jk~uox%HU#ldv6K$&L&DdXk}-nkn|hCCG1Y}@Nj z$5YB{=|&ad%aq}RJSi#Z6$JLFwLI|~`csE9;NOLVTVy8$i~JmrS5xd?1^Jdqe;?j1 zC2bvpCtcgzpT2R_2erxxb_tmjfIKwgWjWcc_}C;=BZp%{`{v>7!kD;)Yz(V`S(C?9 z10yoSFk{Ua{Nh3Ta1%Gs60xzfm=RhGZ=mVWq*8Jr0N-FSwKv$`*))RFanAihLn9@o zu=s7py3fyg{wHnL$j~JhzV-PI&bT!@DZwWeN(;A9LNfd<<1~m7$nrdv;7=c*>ufHu z7`={7{D+9WHJ+4-wwU&-!C?-*r&qdsHSIQ9q15O>J3$SoH9vALSvd&brY!{RBYsC8 zB(@sl^wb!UN{8dx+dsMx+{5|tq}6vwtMvvx6*~*xv)E7XQwGeqq*Hvn)@+zD3&H8F zgrh+*Jh>AyWCn=KzScKui!Nl8 z;V%T>t<9?)W>mp}W){FuU*VwgcA3p*n<_u5GT240ryY^-6SqH!j(W|P^p#>(a6bPr zPm^930@AXxe+Bmr$WUxTLOwggcxPGwJkra|_Z=$4k;agj$)~ zXr~$1`zQ)OlZ0fyD9#)l90+-rGMZ@8ya|9rsp^OI_xHaEr31ht-f!D7wzl9Oh9~ni zrWT)E33H@J6HHV zK^PEx%fvk<`kxv#7DlO>hmYV{jpgKZU?6O*xjN3|?jOa`RAu(nEgoVnFD72zBs7H_ zAsx+zou_-Q#8i=a5ko^(7_PIDrx!{*0j%7{fN`f!l8ztOd>*;2o_KxR>wj)dOOv;8 z@yshC6c)}jHL21Y3^n~m)oX-PQQFhhi6NB6^iIyj~jlD4OShIrduE2 z>vZ~CvydFi=aTM4Rp@dl%lqv;lv^aU;D~F z`Sh-IpXQ;JLM0e?z6rAPTdg`b@Arjt%@-)LNMK%qGa;EZXy1Cy_7&W_-NgunVzXc78&TksP%NKy5z1fb6dGUKdw~RX7R|IA2 zG?%lFqz_lYVXVz!Z!J}gg4}xx>sFj%)Mo{$QUONcr(S#fB&?GY6MimFwFv?rzBzBX zP<1$Zdp`f5-ASb)XU)Bf_B@ddK15SeF#hiCE&ZK4`h!6%BKdk*!%9d5`W&mCmW~?k zX=9j((cq~xVKfktO#j_)a>Gty!Qkd57jWFH#}pe)~I>tmp+@RiUS-n@y7~S{(-RkO{psaI*7%nbum5$3m zfvl>$_i#HlHcdr3r)KBbN>@!{e3+gn2l*c{fT z(tmUjtoQdkILR~9t=LGG_N@}m)RP@J&+jIEu`8%9dM`N$l(8CP#XSMZv0{hf)2)fx zR%nwu;fHX@r)Bp#(Ua?eb@1mJKU46ZL-Ot+|=PQs5jqN{~KLT9k zepGZHGj}iU3QoY6hqoGxK)}x?6e5-;IJLqeG6)?lHzYq!YEgEF#UOP+@+^2-^KH~EGa}9VEn70m7=nUc zB&A$4cu4qpXValcN6k|tKFIrLiO~yp1a%GAI4MsC58?A)&{BUg^wRG*Az!URYc2TQ zsIT(!@{t-0ktV1;5D_tA9yTPr`OUM`N!G9gxJhgM9iimpj|aovT8z+57Bcq_uUGPnN$U)y>b|2@doCEY_`5#>A)Aw?9ubV>* zCvy&gvvYHR=!Q(Sgh1CP3{nPw1oVA0N4Nv1iMF?ssS{0fLM3QFW{2G=CT36U*zf+y zXfXdn)GDNqP@QE=X4gO-Iu83`MUimMx&T{p24fnH3KsYL?y=+5(`mewwp;T}`~U5# z^l`;*v(muPYI{(Skjq_}n$ps4;^5^4)6#-50(qQvnM=!-3QMKnL_LkxO)U2MMA6%*A9D?tE5q|Oi;>N9InlkUMKI78YhZjbY+Xy^bw0dS8-3+OIFz(hl zdmnLGxy`}(mdo++dj=We$t?-4Nwj>N{BIG|joLkeq|$QBK99%SP+ez@s#2uLAB2a2 zymn+{?W9N!pzaZLf{=2WJK65eCy-0W7~NaCeM?wPCLK0%A+-$KC)a4GvSb54@* zH_dYg`Px<;Y-=B-rKM?WYo}_*yb~&OxX+!P)%cXV2x)kikc~gq6okT%h+;#T``Fh8_W3su zS~MwG1Z=MXXWt`L#jnz6Gz@yBsRQ$I?ANb5V9_LIc$==t5y*OefUSSCr>;##6dOY1 z;|`}=xv5B5ZaN&=G+EEX)xlpSQS78k!DZG;K*gOSre>ef(&4n@)_Cv!q)QU7(uPv} zOXKY`^e^xc`_%|i?D4_TiQ^%Atzjl4_plzAPl_*BS6VGNuc$J z#fFBHr*Pd=^W*a8~w(G2?E;;tRwca&vv}@ z?pRjjFV4NOtPCOVhjQ&&rHi8c{O&RlCHy&&P9h^_F+_R5H|2Yj*e;!O!&NELzc;Px z(>uK6C>l9htY@OqGEv$PLW(8Ed1jz_u_O;275UHQeS(8=Z0i(~zM@yg52j~G)71AS zwTNe8&J34M(~I*rBouyl@JL#DVdwe89x_Q_ksB;s0kEU2nZ59L#UJ-4iE>yOu28tU z;|U;wRI@Oso|yYr%iA%@$vp!x$1XJ1%sa%HJPFy^AHJXb%i`zWH0FkPSHw$c%or_woRKn)yEe1I`eVLrQf2d{t3wT%m+5$zs3{jh#LIYhk^)cOP^9_M^~gv=${WTuZ00irkjZ=fT8VmGvKu2z)U9 z85UCQYdyF;AZ;OaDzxcHNi-=C)fi8=M8bS$VA`$Tx5FTZXGPQ3D+q<-xfaZ>#+IUA zmg<5A6Av*W{asjdd(>1t0K{iCcuM{QxdDj!lWI2dhVEj)ot^9Z5D@@jBP8!sT0Nlh zqkg#f83(B>6L~TJQpKqN(RF0bm4GJagN1^rDRu0c)FD0?CZrou4YFx!Y}+MiLHc{X z!5#y4TnsQ}?lzTe*J4~|#ZLmiSG+x5CfD#E;8BqBHN2Av0ePZLisG|8;ExTlJ-}OE zct~k(TssyYp_c8tzm{(vrL={1lbJFZDdWZlKf(_H(($VnvFGto2x>-=2Q{maz--I@ zFs1^YP`}B-rkX#PU|y3^{DHvfe#KtsZ$m{NCLGqTo%AnK`ELXq-LKZx?gp3$hmJ7aA~@N}l$eMi zac5^ybM08>({LfIGI^1dG&EXNW0x*^8f_ECIL*-(jHZvpN9zA;p>F&)FL4DOEP@?g zZ!MgWo&6bibT0z04_4+^rMA=e@81WA?FA%FX=D6B0>h>yT1e}nK;x5}ZF22IJl@Zl z`m=us_E8P6BfkM9;d1JC1fSI8WrsS`ak{P!l0JWaRLHzb4YB=2d11`L1{L)|i-2)gFxJ&K5967CP<(Geho#woZu zH8Ivp2LQ^P6A&KhrUej*kLjhBzPRGbWNyTXx6lt$&(TAF@WD0)0gf?hyT|0W?k=FL zXI@P5H3-F~>BwgiA_7n5RBEZ~;o*Tn9y-w92P$4SbTcbcW1%R3V>GRX7wQ^{h&2Nq zzHz4A3^uF(6a3zI&YUR=AlTd0gdYw=oeyY}ER44UUGd27?KUM0r;qe#D5XB;E6wE+ z)1-2r71}-jq+hPAWVoK%S#&TcO{`B0C8%CrQZovmouzLPQZWh`P5NVbc#_d%ZXEFlt1ofXk@1v^dQFx>mN6^Rq|DdFx9nN8w{*6BwR}I#* zK!=k*>wiWe|CS7c$GY)hq6=qN7G-HGzQA_rha>r+WfJY3BKo*3%oEG%C~q^Oy&+x< zUO`b%xP%h`Y6rNlVt>Aq=VB!#F^!Dizo*wt%LyCHwtZ34Pu;-iR)j<7C$cnV5@_8o z#SIMf&dRDV^J65x+^rZHX3T|)PfXPtV754MivG7F+C8 z0frI^?xDk)$cuz9m|x>Jm>BS5b+^=^f)U8;t&5I6N`0T`OiMo&ec5Wj`suVwxT-cZ zJlu^iXtp*v>6rh=sr0x!+BWw`j#?Zdo_q;_9+ROsW)~_IDm)~)Sv1oSrSnvkTnY$Z z)Pd){&|P|b)b1nS-$yCi-rEz0Cns*1dRuta17}E#1voca#s(9n{!mMsvAgVmfRwqb z*V7Ql3a=+Q%%>)I6LW&FaB7j=j}Ps5uLl4q+H_46kM&mhy4P#Cx^j7r=l$3}mf-ixtWRshznx=kqZc1_f^EA9SOpMxfgE8A2g(bk_5dw^gmzk}5Vl~FDC)@3>r(pNpA1<>}8Oxq0m?_Gfd;jk2upp2Kc zH;So4cgJb_qtdUza@M>m=*_^;fJ~Z)^FhZiwqhm$Hh(PVq=b|--nQIMMYCAl=wJd*d3iYo`!Tv4y%i5|Z`?7j%<9E0Ewjf!S&{ucU4St@ypv2s3V%U{{y(pP8zYe3tv-Min9 zG#V~pPe~P~_G&Pl)C z&=o44+c=EXUw}yWMBNA}_QQAQVD+%df`MEZaV>aA<1N8%)s{4g`0@$)^#(Xq*Y|8) zRHgOS_4(h+G*1Ncz60wCGkBoL>7 zgPwzk6#iVQ0GJlK%VoKSMx1JV;*6*Ia`5M5jY1Nq)c*qCUP+^$6aUx@09c*vIK8{9 zpED5OUkpJfK1+x{tEt8hk5NgLU05hSj!T^Qme^3C7akT?l$>0_$%&h9Z*w@AZTfhp zj9&D;T&G^{RrBw!b%^wa`g%BNaHkXJwtcOwZW#^RUYmyEx`jw;kP|63^W@S}B+@&y zd1DxKm2$~LX3^9;PTDK36AaUmH)1R>mI|IkmDrdrl}}myXuD`52lYhwgpU3gOD1Tv zE6Igu$!0wA1?s~dP5U+%5mK7+ITKc4w;;_ss)u^swIoKRa&Mn;V+KJ~Sk zLh0ccK&B#x_Cl$3-Tm8cmW!?~v0b5~g)~AcUg*4=MBhNW7};Z6D^LooPfYCHNhYZ2 zHM7IL-*8m8-BZt8YTBTK1#$J)S)m0rk4uf_ASPU%B@;Z(d7A3783D;hsrvF#fGZm7 z0hi%MC+I0oKN$tmOZ>Bh=eWB+Op@32X#R^k8X21)NPI-i%EqRZSvR*EU3E@l|B4&i z2sUcJS6x8B@4A!Ya}1|I}gD1M1&Wm zs@G6iTm7VKzArl><|Jp$5hQy!wvLaxNL1m#N5y*o{r%<3-y+&&Pnr0;!HR~H@(Ri6 zULM(0bnB1vuO8@)$2NXU*%nx}zp1jPol00f#$*e5lg20I$~BTL8K^5e78Dk?mC57( zTamd6Jnuk-H9gty1q9>(w>CP7LuclVyyr-u9HjjwY(iiNG%x|e;<5fdbuO(EA470u zT65NXB^RqIImd}cS91NI$${IT0&?++e&?qjJ0te;NAt_V zub1`?KY#zmncD#RC>R&{&?$dwmm79u>-k;PG+qqga<|GWMmMVz-QzV<6RYL28~H7L zG}tm+MrgF&0$+P(#S_%@fZ6)WI$ljwR8VNsGc$*3Evn{g_guWrlyXOyB)GA`KjHjO zR-2sOPPPV({!N#JC3XhszgfXec)A`=ZtkrhfiJ_jS*ttEw7d}8Lb|22gVlosRRPd3 z@3bwp_wu}F`8|x!wcE(nKrB8UUK0ZgG~foCq0~d_hCPb4G`>b;rR{=Q_I*WoIfrz1i{zEu4N0y}I7MGE?lg%*ZED7>g0F?h0`78%FqDZL|J&V_`e zlQa$7i&V+bm}@f9vVq*qI?3CSx^CQ&fPv=fGVy4^fppe%;1fbk;IxD6gHpq!Xxdc0o;_l}%&aDb=H>kEc-#X9P3Tq3W3srB80Hq&P_3(`0`Kv~=X| zWTZ|LB+1E%cL8ce$np2nqH7j;DtH>RgH<$ znuY-qfcxsjk)J#JZ>9{GeAh>-;>;F$9$RhW*3?uDNX^V>@wz$s?0IwNjsP=BEHU>k z>Bs-7)4=)$Qi_&DGQMjVySp`yLvR$~u~M!agYZ4Y+%)}u1l5__-(OVRffVlvxAnRj zDL0D-p~(WzC4 zM(f2e#0s2>umC)9=hdye0*Z~5m6fHXhzJZ>FBLs0Z{E9%@94MAsoBA@`l+Hk0GU|p z7c7`6pBah>XgzEe3)r15q5ktHR89^w1!pu{-Zv0SZfR{jHHjh-i}QzC?$>!2gxPbu zuqwtMKyf{tth6X*@kt`2erqrr!WnI*#uAKlh=Ocm0gGOWAk!La>nXej>1li8Ju}pU zuI~mDZR%mpcI{tPL7}SP`TkLxSRcli>qe`u53bNY23%k+-|oT#e^m|z-qxDc1M|UBoG33)_$^D4MrmJ zkLUrtvjrq=zv^-%4os;CD%F6AG_=>1*ab9{l%V!5UMS`0Fk%mU{K1Pro*~ABZ?*s_ zd3v zpny~7A4i|;e`89g{7c!c20wWdlAsZgQ3HgTI9LGdVy+NNOAHZ#5eotPK;Tb+1Asp1nHvLMxH#E zy?p%)_z-IUqCN3A4h&)_fd3x;Y3#H&*0-;kAHyw3)Gt~< zpRaCUke!xB==lm16{LBh-6=LG(u945D&2SwHuyO?xl4_ZBR^UW#QxK+#po=6a0!BL zK2Bo(Up?Bt04MS6ppIb9VaE^t@6(hr+>@`^*F=BU@L9B~({ZH5dtUxz< zVeE?4Mmny7qsRa>_)h|T#8S&VrbR1Lh4NczyjnnLTy(e*iWVQC^|Q^*ZkM`2ara;n zV(Wgi!C751uO$P1V(m7+UDLa23yt7iIFp5+n{+8%e~;6VF~}5qlOHh}daA_Os#qVR zbe_uCfa~+Rk&EKPlN-=as}33)ayy%)vPC^5#1VNt@DI{4t$iecNT_zbu-iwemyUc0 zAp7uaik)o9xaRG^%!o<+Y~q0?mJGo-%$1urO~pg_)ucK!%}BPI0qJu{KS@Ef13zp~ z{~hwPX5d%n!SVA4@8geGqsYVE#`fiz+=s;0h@Ie*=&)`7Alr(p$sK6ray2>1!Czs} zk|}Ex=*LpsR@(@F!N40)%G>a1DmnASjF|+*;tP%l2EbRZ$t>agF(puQwi*#{z!UA} zpE8BA_O>}RJz6D3?Qro`f)5d))j0(;<(PO?VAh5a?bth#m?g|ltz*w`cVam21qRoO zjdb5U43D4t)1a~c{fUQ7C@Rv^fbY`)K&(6lC>Wk364=~)VcC?;BE~@Hl!k`JRPXw8 zb94HG$2Y$_L_I6hPiQs1cYh@5FrN6RSvDu~#AO=%wQ$k+jIRy=fI+I#Ph+4Z21AGd z!Iljp#Ef3%3S?`Fc4h2|79S72>5qNk-yea;K)+C-f8L(mp!(a;Nw!!9`~R6ib*@J1J{_He<9b7hl7>5F8%$9!}ILXXAMp zVTF;wK|j-jZ=FAh#{6I!nP?g90w}Zt&K~ea4VieS-aO8RjtRLkda%srKR_ddxQ-4T zEmVgNCa{8e7>X2ge1P+tGfw29)}MD|*)RDOOn3H6kmzOq1C4n%G5u+MJ6e%DQNxS+ zIuc&T&CX0-rhDN;rJ~PeseJXVB~~5n?`Xv^S!mNgZTXR_(nx#Y)WU^1CaQ{mM(&mG z9rHW!>hp%YDH}vjr&rq&o7&NL`*nT#Bte(YIkV7EK05yAg33y;RF>kDpGYWYhd8@1 zy01U|{U^jH=n=@n-YB){uB~+hBO4mD8YTq^N)fv{F~54cfUQN#DQV z1@4N$jKo9v&lhF|qJ0XozqQ}a&#{eXeyK%V{3ueyC|my(q+ac$3cq`%_f_qEqocN+ zsGW-3@2o;bf?P2enooGKp#qQ{Op#!g8+di|PYU<3dl{c~*#t%aA(uS=ZfzZS$a14V z729|U&Tm@Ig^=XAk!vO?O@_h$N7P$DMfHB)!;(q~3=G{c!~hb~jdV%PP(z1^G>CL} z2+|5#8A>ogQOtRAsz3<&-eF#*SgEKT*{!_=Q**@K6@X5NsDe~;xcwJyjDqO zdENf}`0)ew-6Fzh0$QO5A%zZ{)7nJ$Gpmo=ki-SKbgE`0Rf@kVujPCRZY+{2EB%Py zlgyq#xBA(4w#7^(z%+U)97@uAn{a$UsqW`fnHsUecZ!P5Y-&vBjVmGcZkKGjFo08# zb1WliU8WP)dswt`?WEhL;2Z}QQ7Tn-bG%H|=XV%rh6BZY9VhI)3>(DtRGkB<6tU7m z%Q{bI{sQQAZCJmSmKH1exx^h9Ru@#qYf7R7uyNi%edr0w3TF9|=-ZYs3t{~n3Eb`=P3XqHk@b4FM`LR5+=KAPyz;ODw z!rxub+it$W#sI^%bmhZ%<5vqoj&Fc+Nk5st$+M+v$=lF$!Rmo)WGBTw>F_gT^@nXS zadD$Im734hF{uDFW_V09H-|ZTzeaxk#q-1oQ@;DjNeT9$udmpgYC}%9Wnr;{UeiWZjuyX?^%9S^#U%W&jg1z`zRfIKlXcS=%JBx(L2uk zK#y<`_@jcpCMvI^X=o_n_QqbDh;1CfMQ{n?OL_DESO|kxAT2o)f&jG_R9z zuW>YhZM_nV?=V}tTHUta`n`)8%S7a$TwvhSI)5;3M0H0?2 zFhEi>UV<$xRlVj9cwzek+aqiuvyTqx%Kp`pGu$Z2*LELXz~EKs;@lczt(S7wNG+PDVtNaS?N2Cmo z+!WO$!;%V}tFPiD?`DU2#-?b5v`{^N)gTfoKF!#Id0_*vI=$J(h9NG$&xPi%D7MNK zq>8hPO5h$O-c!3VZqcrXBynaq2O9jJu?;FgjaKn_-GDy)_!Iz>w0}ZApCl1rNQtt~ z3+m_cv3ljH`0HyRS{;mJ%VUmY!Dar1wB}m!-Y%&-v{tTS_EkwO21lX&1V3IbFV~4~ zr=~~~Qx>BIAzA>a%*%(;Uc3)s^c3;7liLoXCJU+;)Q%r_yLA9N<_XgadV@?=nsb%IJbHUR35^BX4gc%+wb(;7a;0gF zD~PhrYXSC0;r)Q+_SLUCNki@$KI&`P-x$1lClY{KVTjPm$>kvdN#L8vEWz)J4e_rd zx+{&Eouu{2)o|YdTjJEB^7My?R|YhAG7Ml@8?7hkD!(O{0kPQL_}!DdX4zIkZ11$v z;OdtTF&ubM)*A*aTwItu7y<&X)IaX%6BK?5v0QO-rExZ~3JSkN!O{dG>|M)V<3hIQ zW;(E!a^kUZV%vFUd$@3acW}S9;c!LuTR`nKI=x(0lenxvJlH^rizM=ICilO#y@-UF z;2ho3noZWhVdBq}ySJEelpsnLp8d&Y$?5tS;QyK4a(|>sJ!qxL6&rDA+0fFGUJWsI z0pM0<{e=9_VAshv?Cdjy`bn>`v0nk!bTd=-&s&d$^Z&|%lb#S*1S?{B42$_)6mzXT zBm{bjQJ+6vRnKcOY;UA2HU*nBwbwRR-{32imG*pCRXdxrVe3hTBqZ8BWAFNfF@9Jo zrm8QI>hdKiiIS#C7cErG!gdEI)mSWu!|nUDRSm~HX~WGrJiK~ zOAF3oeZ^`S7c)M{pvoQ7Z-tf~K&^ReUQX6eR#DsUBb$`GiQM(K$BE^Mt^1N|ijZ)( z=&D@fD~a-qk%MoaY+LL)0`k6J(E*s9;Gzqf(~bfy>$wg3ITlqN)M$PBQ=v2Wyz}JR z%?(eS5V*)z$TGPw>~owD2AJ5pLe3U_4SFA_HU^4ZB`Oxdv7Xu7=?_Ahp7>qrebUOh z1v2QRu#68=8(>s@ag7T8#bd%3Cmow>zR&~bh+vgmIPdIiTG{C|YCG2uB>lCr2HMnr zS`+62x!eX0gy)(VPmVhp?k)@t&+CwtkwKGV;dV&03ya8R5s@~Fa&bK{Y@Zk9K?Qv@ zFlgLe5+x`v2%WT6+zTgDxp``wQDElj>A4vga>c~1Q~4Fnsy^staqyF}yn-nC*j3)l z%*|%|tW`vuWLo}+kxtn6K~VJJmIeV@TL6!7V%_2@DABd+^&v~xJX3lWT{0xZBlu+0 z9^3B?^2uS}NYvVzIq%o+sr&o;t*s(_XS;L3ytxl3)TV{+$M0@Wy76R97_JB>Y6x!$ zCrpTL0nQh}lG+0vMh6fTu2w%<&9Un&3Ro$#L1O*ywoJC<{rv94&liEknDm;ps-~Z7 zidarn;*^*JQ$_{`wq;Jhh>e#4IsBA zVFv=A?~KXws1z-r52%&+r-TcGFHyy2@IDx`=IVTT#EX?m;juE!VDvcvN9XOkcgM1I zO2QJVL%I|OkX-nwdFi1}Jd_0H!1iN`Ngl4rkTM^9Hyef?QI5*d_)B^gq#Y_rbRc^j zd48Y;jBbEPj%BF{588KejNazKxdkT4niH@F&W&yoBfOQog&?RxEL9-Eyh0oe^0}~> zUGPv8#$2J(EGREu%3HNjl~b`Uzw~#ta~@z@s_;qM%E0W?yfQ7Ij2;R<{pfsl=jdab z(ilpswZ=XOy;Kfuh|-yCgH)N%gH$kpA+GIO7c09!ECpjs4S|7>+!UL|5-?FH4| z{~wRt*~zkY$gv#Yhv<@P(tEMgqTMrxLBPR5R|yQfD7_RI)}?B$8b-TuxQk(mCepOvvQr>rf z!eU!-F*BcQLra~r$;+4VR&!W2T=7{(8k%)~g7J;DgpuhZvVufa(Bp;r*!e5dy^9x5ucgwQSQ-gwmb1L}D!Jra!sclUD z%suNgi*&Sq%r5vCEl& zDP2&z(eD%g)&0Tyb1j@~db9gR`;11*LcEGX%0@aoNs^K%UQ1#yL!(uMeIT}7U{s?O zA)u1%v&dhIp`r@jPh~2~v-Em~>)ct(=>)L@a2}F99{cE-EbKAg@FCLuk2n5YO)C== zLpIXC04{XpCl3b_D3)w#EvGbCZzHm}n3taX!kUuG({j@ZphEVm3X(XU2b9X<6^^fv!mR*1>d;+MoKs7Vbm&P1 z?tx@!f;l1jiuEb)&(P`?EBMbQ+O)H=vCQ64!hN`wmU;Hh`1DT2BOtuhzq$hq7r7Ve z)*%|g*lhGpc!Ma9N?vBIoxeeiV!uxJj?AY2Q^*aB0hXHIvZ>)drIzflUzX6TiiReo zrWTA(^Gi^K5r+>1MpV4@HRUkrppvnCvc#0%bhh8F1Wv7041Sl%IxuRiX?*u5oc8#y zj95#;*}us)-4ovX@gotIXU=ie9Dy%_B2objn`^~~iseIu4f|XoF)HtmwbiImHA=!q z?#CNS4vdzl>Cn4luKR?hmevQ^_J=2j%X4oYPgppS)!A^3|(9{XOsBUn3B4-+OZlEzP96 zRIy#Ne{1Hut{W+vx376&FhE!z?w6uIR`!tCXFBremzM|U7Ff7rr2PiBk&OlssgG)I z^WK$e-seX^A5Y*JE^Ii%URWM+)T^YH>E1 zP#-2rq<90tig-_JZInp`84jJ=I0==}&7%j@DZ<)H5gjd8_ED6~pIx{05rKRoV&=iE z>)}?n%egr|l;5;ei(1;QVo8DEr}_XI29S5hQt|4<(+L?|yAug9ddEzC@O9!uD8j~{ z@P0j0NqzR~Fw))j&Ci#wrw9H_PLd}wPfUgW%ZovDrjxsA%L7QarGM_EZY-HKv)JFh z-qb{jC-B=&FRrgRJU;K;*iVyPmN;6p3XlX0Snx>c;aCYtA5g+z*f=;3nn?vlfTDg{ z)bh>9a_=J|H6{RKZ@#%V(93TRWrhNI09dRz4~Y9SaD1!Y#7mbyC>;D=trjJ?UcAq2 zt%EvFJYzZI{r$ychp$cdrvIo-y>nD(OMGOVjaqo?!9zI*K4#J8A_&njeghygWV9= zK!hY|HuoS92w@lSM&qc2*Y1`=`u}isT&z8;6&){=-vzHqQgm2dG_HyUNj}|B$MuI^ zJnzb(?9Pn82@UoE@A#c$EZ@9ezQEhrakzisT;NP4=|?4swM!dJO`W>4Qz6Fn(o@Q2 zyE&PiHf;U9P*dD%N<5r>laYOL(#!d-v0<>BraYI@<7E`l7)nY?;gmnc*UU-8&dpx2 z>gt4Oa=phPM3|p*YjX=53Y$x7a~}n+YGVZ6d{f3DD7rg0Njv$~U$Vx#3zFH@(~*Ad zx!Bpv9b_S`jAWg?mJf*%T8sY7SEZ#zEY0Wj(jO&x`T9>Lm$*Oxwn`x^AFbk%XD?X3 zsG+%(&Pv5>J|!V({J`I>u>s>fdEpB!NJ3FimL(fFjloWujTUkEc$*|RBLv2i71Y!V zz3?l1ovX}OmGGvvROzuMu@yp#^Q=1)jMLZJNG5aW7o!ZDN2N+uR4!_67E&p~g)%=z z&A+S1#v~IMobzJ~qAx=QyTC${G`bdfi_8JVs*?;^itswNWZ`e5F=mKbuH|_xbNf1| zW=Bau5Nh)4h99MLp+WFfKk4YYs0FUyfY$XE280477F&fZ8MU;Kl?U2*UcenX5K=ttM1?`4U&D|n@Me=rWu1eJ>OfA9oLY>~UHc+zcYQOIeI1Ny6;nB|vfd zI>l|u+dE2+)-8Xt>3Fx<$?daFxxB)7Vc&Bgbm)0LEcgN~Qu=TVqtoUBucwCG*lWA! zfu|mk6Xa;`&Tn^rcRT99ljE8@@r1j&;qA##GDNSJlFem7;x~S3 zK5Nv&W9s<<6GJCi7;0{u%ld~Sk5!Q>&}2kk-G7xW@Udg(xpyb9g(b3!m;|hh{(Z?% z*4Np(bpYV_R#as1IwT;Yce<)(q1LlPr-}jPjMMk9>+z9?*pAII0Epio;@=a@jAaVD zR+=sD#TdDCcc5gL1>e7lr=z5)4oQ7dWb;~RepXN6vTHb91=#bTf7u&h3=vTPzSYog zjIN71PRe9*cko!c@f(>Y*9iAzm>A5bI`@P1A0O!ihIJNIs`}L~XZK~aIMGa=Pzxjx zb}+3F&C~{#+!Id6CUob7$C?QpEP&5j^6%b3?I8g%K8Lv|z|AREWDFV*f-PX752j?4 zEX3BdT>D{TMM*=`^Y)bYo#mlU;Zwi-wykkA-caf+h0 zJoonYN>$S}_|Tw(l-g{p9M4QX@fGp0@~X~c8(L7lFh?N|FO!88rV4&Y2K zPHNG2dm=GBJ_1LeCXBQQs}>DOda}GdN7nL zhx=8JjD>(hQ0CYSQ=$&K;8maQt0OWQOUT_oj1IA!W|9d3HIZa2t>{^FoS0Tv)upGD zy2-Kv96nN2C7|DX^>;_|?!uylqHob{#^_5BdYpD!EG*@f>QC)WjW=J1$fnP;eb4ka zo>DvU@AgI#>Ei?g&fvXxgS8g2i7Ff!{I-{w!mVXez;yv0a;w2dkGE9fOno+GbaQ2H=nQc_$kQD-UGzmYf zZV4Y0#GYG^YA{DspLgSMt;D~{%Nx+JW94bKPFo{ru5n}I-|$Mleo1!z@des_*^6{j zPAor0z>jR>g`Tuf)NH4Ym)HEx4!cF2@%J=F+*b2nL*YY1ebKHZ5kDD}pX%>FAs(W; zaMUW17{~+x|0ZRv6><;S6M%o!(&0RXZi%UgF(9aqabcS+$j4H(9y05;$D;WNTqq_$ zTZCo8mL-zRK$saraEH>(bx>oU{xS$2-T#6inGyvWpMAR(zyw$w*#g5=}baM}^k5rZvG;D8$} zAq*FxVF+G)-OZH0^?EbWqCe%t&$$U%IV9eQ9Hwk3?!KcDhCLC?6bt>0!*{N^+hzf_ z`KFum3d~%B9reXkekq(y^JCPtPb7(0#5Qz7CSrQrxea?61YjroC zW{4N1kAjGvzBfwK((gdU=kP48#XcF!{wNRpC3(mjSOPgT;FgvbrqOj>vIZ$erpSf@ z31L`V!%QXy+r1hNqy#$ED7H^QzoRESaSnO+N$1R~fzAV4Bup}?+2awI4z^+(lnU~d z;B^(i%zVqL{MW_owA07ATJ2fj`!oUnr%-*j)+!BRxh=cPbQ6XZTwz@M$;j`rl8nd5 z5n4bK1lW*FqJ?FPwH*A`R1VI>`Yo$k&z5+6d<>LE&GtdhF)&+{by!&mHbfZNTnNwK zj-lKBYVExCGaUfL`gJSyR;$C{Iy#M?Kg*#zRW}1%ii;uYsVRWjnrYIVVun@~umMu! zkw(pavG~UgJ`!2}Um(XFGfDE;c;7!wiSBf0-1crS1dHgCA;*I#IwM<@hzhH+#3Sp- z;^JZy|9VCzjC;SazrF#alY5c>O9U4k%M)|y!YJ9z&g&<$OZ+Z2kf&4AG}0LA^6^PT z#so}XgIBXe-H(45Ro9E%9QJ6}<+wD|+k9u9qkG4wD@GG;5&5LneXTo`D2WzmnXQl3 z+}6q()lUT`2(^GaEzfw1Sv~gAAc#?+Cbg}|D%TyM?s3867Q=Egz4?uJK^~^$>pZ4X zVtZ(p=6N+lq+PZ4Ln*U^4g;1seyzi<4cY%}V#namK0zOabS~29djAA!;&t8M_T=`v!eVp9Drz|AnK@SGTX;t%0{N4Q^l@1)sQs^Xq~FW8pr}>EFnm?i zy0nnp_x5PE%pl*LO_MU5EtYc?cHt1hI8zV5GXDt>m<}`!^kYIo)B`!0;g2r!cc{UL zbAWT3sPME1Hb2S&^2r`4*@@w4MAn14N%jd5>K9AmzHh(q7P++WtX>M?yG{ZYaxRY$ z5tW=~Fp)N|(sw51=NTW5Oez_~LWdRohN&%-zCt@RTD%_Tbw}+{XT3cm%0K^o4CbPT zyToiLRbyk69X{@?3LZUR^2#xox2tiE#yFLzxQOM<)=+wq%$|xU+eXXBFRfzig8HG9YR4gc zWe*jCBUJvY1)_MNQlBCuFM=g6-ZA^1D)=|No?rmc{h-4rc&H^pBHt5|qrc=E5ha;J z)y6GkEf~)Do{goZ<-{UO{x8sDuu+IS&w`L}b+})hw(y}|7}^Cae;J~MIXiW3@y3XBC5)&}HjM#*~M zw0$X|EnWNk*}cL4Mro_0&A?#cq7b$^a1JQxpy-8WM8|#dNQXMzG*3>>9}QN=s!P~A z9`s(`~WY`IHj)SeR*Ow-)zJm{1PSL{9-=rrwJ~MHz^`}_LvJ1~UTJp#27KNUpC@9!gVdl}mN%VdwYQ(_+%4)Hg%=);)cslrigy#I|v3T>0&}RMm`c-9x3*{X20}z+=*MmbkH(MmAoHl=k;>1hobgbsw?pp8a`EBJs#NJkS z70tJc^0=4Bo|?pNDH=a!_5k-?pOwJJzx%qr)3@UNSJP-Fb#!!yd!Kt{v*@yKjv%BN z737e%pFf9d23quxb{t~(jqhAb#9p86d0+1}IlryXh-~EO+^BMg7#5m6l-m6RXfo$ zqJeu;cp)cUICjR0N`W5oBO}~kL1dK;rQomt7XK8pI?5Vu8u5Wr5!r9-(|dRD`*%0V z2_;;q8OmC%90dPxS&1kQapa+=hXd!*gR7zO9UZ5PSiIRM_z{|yBziS=U?@ipDE;wD!Qu_VB=!5tw-UIUo3m_umd#L zT{Oq^t4C^q_dz9s)p@GV$nDbFWf{UYKv`M3std7VCtHjbk;85CYNu%VDXaIkA~VS% z-nu}QEh|4{s#SNP){>&r9abmkCPCix7gon|>#^AHf0XSa5l5?;%hCHDJx?lBC?jOa zipBuB1XIgapX_@=0QF)2vWPv`WbKcuv--`ajx7g1{+d<4abO{T6bY9e)L12Tp;Sg_ z;5M3tV$+7phF*ukC&fYXp_D21)^b$q9pBAk_DD--cW(8>lA=aD&0RV45OnLYJZ8}c zvkaB>AR!7wCF_FuvtU#LsAdVW5Og*P*6sv!Hv+KBvSa zj$d1Of()n4h8e%S>?#4&iNMirz^0arfF{sO1G6F=5{|FX@qlj%dZJK)B=qhX^c*(+ z=KGADyQ1KH*_G_@_v77vmIErxxH@l+f3|z?{Q1LRBVaeHk-a~TUta#@t-!*nwVe$c zR;#y{@!h^V!oYyl5hxuW4o%VunA?}8{2@`s2-IeV3{Xw`GKk$IEa3d_Oi7P_ZofVo z6tlSzbF=)e?1bSkJSKTBHX}ZEy<0y<(0c*!m%hgHc2V7>TW9Bq#yrS@AsUC(Ji}r1 zyy}Xs4=n}$R%E@b(qI~ZEYUU_e*awfd_n<1DzX~H~71+rh73zCOan0%1}yDkL6 zF7O^NxZuE=YxmB~UHhyToKNWsfLI!%MG<)y$;vz`R%?!I{q>DaQfOhexvd-Q4)UFjgD3yug%Ilr`4z3yRwSEmV}h4v7%K zsZvb8-XHUSDfqvV<)Pdi1u2JUVuA(v-qhZKnphj7ypU`kGhY0AD?ZWICUB#rA3tOn zRVRsQiy9kS8_x({((5eNk4Z#l;>YuK9O&Ym8YWsGSM_b;^LjOy$t+mG&HB_A6z6c& zGMTzOMFQsP?CZ{(`2hB%@qmkOp(df7hBRKk>4l;`pqcczEuW8OmO0ql7v7lm#UM{M z2dyu$@@WaD@OzdA_Ak49F#*gkDdMYm&gX;`7Pj8M4Og4#}!itF@sx*Cq*ro=bJQ74GRmhVCwd!XF{Fh zLwlaYe=x&)5f6=&F7qgMiq5mPiiXe+2|*2CRLo{V7i;IBAM%`_M^fO%Pz1*+o>0OF zSsNBOJt`1~toHmlRbq8bLIZU31Z)}oJi&;TOabB=!jgI7^O!I8`r5v9TJzz5%k5th zjA(fB_t}Jv^Q*~=BNLAcv&sn#nw87D>W?3_w?;KTMiQ|+oehX4;cNxAm9cU4B)Z9s z39&~x;%(*FagU!qgFNl3!Rz3iSu$M##H@s^LMTCXfNIr_M?4?E6V2kWz(iT+>Pm+s z60u-A#4&q&seMrwAa!eNi!yu)M4_zJ8RZikk z7?3Up+`vd)Jq#o~5~vW0n6*08(GrNEtg%>UjnYt7dB{M@DW6fIPdmzn7SJ@A0Qo3f%uM zO(p@->a9!vl}RRvH7(?VZ5qbzJ*YfUSML8(B(HJ=?xl{45DndyD9aJ8jgR)1&Z~-h z*)X6l@!eK2SsV0Z8Y$B*0mOM_)9GA(uE$BnD&&} zA`wxW@3e{Ko-ZCZB`=*PDk|)30iIV(z3(jbH`3FpdTT@;^=i4%hMxZ_2^zWXt;J@k zG4+vb|2)5+LISO$17{d@_0_WAY^8HUkR!kxa{K*K$6M|IBeZ$Yn9fm8MQvOZOj^7r zh3SYNt)llid=2d{4ofaKH7BfjIW#I~Vu^#evYQR(g2E%1$p*aUFiQKw0OY93wq7T$_LYUbo*GJNhd>JvWQY&d&b2Xhrc{OOx2QPvq1f zh5mj=NdA<00^AALKkNG*jpx5Yar03LIJ!&x~4={1+V(RG2i6 zEsnMxI225+!F^*fF(Af&sqgK+uZjj=3HpqvsAyYj>teLq20r)!!uWq7oRC5b@Q040 zmCTmh=CZZLFE}Jx?x*p#8_g7Eia?q#G}`xoaIHSQp2%0A@eJ8FT_H#H#}d;lRvpce zj1y>BnxAlP>F5|bSxX|71(qEJZ6-OKH?b%1BfMTmtk_X9h5{E^HyhUf2ET^Q}lAD^%8rrY>`Xf##rfd5sXg&>bIM zDabQ;ki8OamT~}R^K3cOi?Tz-##_)!2)Qzn>JrVIy)rp(t&yw=ZortxsH4nO-XQ?+bg2a z4{!kg?-c~~pQdt|OglM7fgp04_bQ(>KWQ;3Jh^_kPeAOBjycV#r0JtchP@*!;`8sV zc`3`*ziOO)D)IZ0v%A2r(K=2wN!Vdghyuk20ficWre6m36}Btqyw%jytgMRK2v1tJ zvg^~Sl<^#hTTx{$dJmq-`iD zVgXZZO+W5;yS>Tmf(1&wEk?z-c&}69qoliADa3z`N&|^iD!a>_D5q}XN?bCsn`cE^ zG(oNOLV{|&c$W53bvRqvtS0z0?zYV3;;ru9rLi&*sq?9(9wfWfbrQbq4s#+`$vr(Q z!OjU^4uUB;8N@6?eHJ8iA=y>tXtM=DSvzjz(2fxYvlCqO3MXgyg_o^LvGUcOM4lAp zuT5BjL$s$v)6`ceYarC;r%hd&dxJm^$=E!o5`?dXHDNAn7pVkJszgaif*Qs*0-w-_ zu2c6u22{x)|7kDvnJzNc3=_&Tkt}4a4k54KEFn&`i{ABJCN2ZD6?Y?_7FxFIC0mB^ zH6ey2wKAs6XLNy9d+0fyv-}b&rvaiBCy`@&Z+9tUh(_>AvrKiB#`K`V5E?+RB zFk?wPn#8{2+;|AT_4?|a4xGQKaX$GyU?WW>?v=#b6*c~l`|jUU>_!naC1)m{coMj+ z=*qcjnASn*pL~f6KDp!E7x@`r>-##y^JKFHC;R&RK%sRa!n8XC3&@SD8h)c2d)8m2-%bSp{{K+5{d=Qkf@2Pz2sH+wZYyy9x8SIQ&`S#rf`o&Y!xBsP3Mcy(8fKR zcqq%*8SIx<YH+un`n}nM4DL?-t3g&`vG@K1^p?P+Zcv=`h9DkX)ZSw{6 zt!R?A)cm~_*mDuk8{O})Q_&_%*889wLDH7ZxtnbUH?K5@zJR3I#8&_tX2`fuEob@T zpB2zqL$X{@BJ{#RdfHH|(g-S#@lL2PR0^^(fSNK(!Jy{XeA zvM=?rH2Dt=PU+aCAQQDqmM-x!fl#^q3#>TSF60k1A9)4rf03V|m>6{H zE=!4=>*^nMw6U4fo9WirxX3UNN>2R5c79NV^fbUk_hwEjjjo_Xy&jF{@Af4#WL?=g%6w?}^@9Q9 z2*VbaUjQvUpAS&0Xm(m{wmFM0DJ^{q%xqMYH#X~KWDh3oqhFZ<6~X!)30boQU@U6K zyLnI?qAoxfIGhqddu_fw=@{KFeeT>FC*E$Xp0hl+?)H~yUPQa7{kij@-qu{SuWX3g za2lvKYO7ur1fXL~d8hr_O`o9cXk~BDy;#YiMv-U=qGPzF35OO~RL^0uWY<(sUqAO8 zc-O6VQ31QATmFun1#Mf*%S@qo+z!V{=iWqC8m3B4o*97t0k*+`eF^SwL25y3AyqGq zLVl-eK>JirRdT{7t>)j`OLtNUrA(Mty5zM;rYh&aBk^A2R9xtDVxChv@Tj`jp(dWB zUQIrQ%H%R2a2uUEYq9rpzLV^~)x}UKo7_=C7=m#fGtPV9+iq~D4Pf}G?B2J9;RyA$#?M(EA}Ko0fN(l&o0gNN*o>1mNjk$&^#`+!T@#pL>_~kS+Yz?Yjr_F4@n10=X*ow@7ta7-b!VT5>A0-MFU97-+J~hm-yKrClVwq z1!4CDuF)99LsER62f`@}ifTY^r&2WNDT2?Qe%fZHLNv#5_cbGP%_X^{p+~hqo@>Vk zpGMf%eN04w`l-h7+=;b9SLYbcfNXTv5vmj*UipA z#K6FM9{xx7h$g>&t-p+jMWWO5xxkXPUqB`Z&Z4eG(TqYT6J&_Deozb~u>mA4#xnwk zU_O3+Y6+h-^vtsL{kDV6zhl5~?XQ{|-wRXm698&0;KLg8{yU|so`3F05$6E;U*6eF z0$>}UE&RKA>f1>#DdhdQfDauM*S{B_W}O(34(iu@mGb+~A8Z=kSvSEi+2jAdOjd0> z8DCM@fhu>r_CQ)q4bMOL#B~~&V-O=oUVGG)Rll*V0IJt@YrEg!W0>!B28Dt;4jh*| z+Ux2je7{Dn1l6|dX;`xIH48&3+euob8R&DRx=q%9YU^NAnbMsV(eq_}{xLc|?loJb zXhT7%o+Ij>bc_~)1GJkKo|nYV)q$ny4=wCM;EG~h^CQoSL+V}=vmDrG=V6bhhhqz= z>&Bqa^`Vmdfpf1+aG;8A+|1mb^Xr?GSPvEN{1*OqW&B~y2Y*Sci_8bG2jfI@Yn8hEgn)Z~biP(~9ba$>x6l`fE?$qbdyVaoS=FIIvRn44NUOzUD?yftt;33ZIrjE}; zjg$?CZ<{82q$sCwUdO#_1`=i=r(s=VuAxJ;i9@u}8>QrOqAWlg4BzLObFa>e1#|Ic z_y_Fs=+7#rI8AAqHXvv<=YU|sw-g#C`2o8+6u8E0${$tm1Xmx)cVs04u(Hcb9@GF? z1;{->`JHIG0psz6QYEV*UcNh0dG_&Q2ySak283e1bcvRum#C zCE>hRMO^IFHb%MUH53tS{j(sdb1FG;r7R;lC?Ux?o^(L11 zUu%v_rfW?2Y)O7Se$UA%%Fgb6eLWb^^0*_cc70jxQ|p^4=&9YsFsSGGWH-T`#J-?o zUan#QPO)k_YCjqaR0{MqCmaZDy^$+>5J#{pTb3DfV|}6nvS6k z9>L(8QH{!fiFmU>BdP0G5}mYy!eejcW{Exbp*Ly&f*5O*%h8&g-4~0;xc_pm1L@&X zyY+#wko=IMn^OweL<6YC*=l>TC{Fy0%qpn%O%AY8JUxk<9VT(PkvQwGq|6L#Ry~?7 zVNE)lpKb@*D~aBUB<PHHhnn8^&;7LRCM^wVrlGkveCkQDs`N|T z?e(MjoLjqt4&R5W_2KbM)LsL)1JxzychD}}%zuFjGUj}{x(}0lDR-nA>G}#w8zk%J zp&sduOSO49{eZQyDu<}_joGmB0rgzpcb#pw2hS45;`xY;Bw)kQBl)|sDedILThKb)b;S9(%77}x?0MMu+t&o{$IOW;e1bW` z-XtUY+J3dKCqB0Ae`J5jB+vbEb7VPZZ1K$l-sdyQrb+i<5aQQbKu$R#Y#>%5t*G$% zT$A96dJ7@CUZu!j#xO0|l;2y+L)~^s`SEI0;4G_U{Q4|*vprl?h>m@en`(_ZqrUEW z2JV5sOVOF3qk=AKDB4ZQ`p7kF1W(RT)HtEzj;az}rkFyd;}_h#yZZOHv--w4WkJ-J zH+S{0mpME32dcSm85{#XBZ(U^!g3Xpqepmlw_bsha`x?hx^H}p`W)JHSFgO}`2cM8 zkm$rW<|1cPqIIt*DXzyv8cnT*7f|t2a1j(hcOyYr9%PvIzMhduZ;hAj#3H)H3=WUkjm3*;8v zB&CJJt0W67cB@6E=^s#_C3e7vY}nQLCAq2*@V4ianS1AeyT;s2y0(zpq!nv!Z!Kb4 z8gtL}8DtL-$+75B6_b0XI29|5b5D|)0TLKgyRnv?xZ(n{Ar0<%u+Gjh+T5s^Y=`)$ z-M;MK&mF) zIiH;7TLF&@`AOu}1S#MI0PT=I4z7RyzOB4`EfW3D7um2zQw5X=ptaVCPB|tnB>R>fWf^Wpo*dVeSZGx z_#2mN0Ofyh&}b#=Wx6(MHb^hc%H)^m6FE(5EZ|SFR3IR%e-pT00(li}lr|9ax-`QH zDJgym`Zu=t_DfeHT%-&i=Z}FoLgLVnGSdhP%E7+Z*_?I#qZ4+A{unY-P2sTfJzgr>9y#2z(b`)@F|*bM*dSODYRz4S?YzdGimcBUw-f zQC}n~<)U_5=G^Tg(ek=FN^+=^zNhCUAPXwAidHe4DNJN7q{^X11{er zm0h1qgkukRx4;hz;FlN7aET5>q8C;(U6dMTV?;XA?QLUCjWM*6Kka#(rc%lq|0L!C zY0B;ism^6f1#h$8Q5H$C=B%nC#UAPFI&C8{%2VHE5wNL2#FlI3brOQ3QaQ&W`n$Q9 zuQ?(&NG)nMUt!UlrMpqj13cRe5C!d2Siy=BKetHgp+wB8U&VzpLUw&iLmcZQW=Pf} zPovdUfjx^#20N5b$nJ9$_4$;Y@?qZEA%(~D&^VKWlZ3-Lk^=K<$gg@7$4s<-5#gD~ ze$LK1nG+8I&Sg0PLV3`Uag4Tn?mqJ)Q^Y-XayU!0sj)GISDLxV`=DKL=1p4nGlKm$ zvv;@G&P*s=FXlHi8Pg0=>puc8ooq4o+-Glhj>i(s?Cbp8MgW#<1 zcP#a8Yk9$_wTuQ3R=$Twi!2~Bor#Mh8MmQ&-h}z@yfCn$7)N&;oB%vgDq)`sV3oyi zOVMpi>||JR7v*?lqN4PIp1d~l4@_4I%;-xH>RaWBR-eXiPS3l56`-= z$zV8U0LM;^KGbo~4v|8hyhevu!_rZrNbX47Cg~YPALIrTL~VwN`+ z5fe8}A~|^bf^Jn9nvX2R{(3tH35GW#btnc-y8v*Bqetz^HO z?q}mTOseka$Y#NxVll<3IJ|vs*OlSgM|SSFTr$N5cHr43)mbI6KsbGQyPaU6Vt|}a zP#y9!-S4D0hl>K48pXhfOxdJcs6+SVmte@$}7-G^ANX|MnH`tK^IY`cPO1 zXDX%xPZ-<@)SfeEK1zmj_vLGf3^`}mJ~PTb7a~TI>zs3h!UBaerQD?X$Gx)~WrbLp9VNbGg=o9~W9;?iaB5n0Dre z9%cL>wrJwU8?t&pkx}&CIj(@ip^h)4%9YgLgIcxvG2s40Q(-JFF3$AzicD*_drUT# zwXg*7`OQ?exHor7qpt4y4{gA7{H;y1v;&{2xqTto@Xh^^_p-Osy8P+ik(#joI!#vP z!%@8^nq9UdfOtwb$7Mp!K|e87uNjb^{%;^<97}}))bqr0Et8Wj!1@g~o{JTYkdxFi zdpa5Mwd(hV29Z6iU+C=s&z}f)m2{t*qkcfooN0xw#_5m_LSRSQV`18|(Hr-2RiaCD z)??|D~|vC=_j)w+HpR_{%{R9AhTcj0Q^Vx&6eYh#b5Do zb$89z9}yO_Cb87O{Fvf8%~PSHBFJdeX;`Wn^TuOs7_Y+A-%~{he8W|dDdw#WjiAa@ z!SKX&=u1&oi#A(g2DWJQQ~>ads%)=#9Qb8OtL{183<+=^dT<|pIn+0tA!OxWs~>;X>lzH|dw1^PM80xxSar7h3R0iC^Y zQeJm9sEhO6+VK0>x@R8BhpZogDV(47k*_?;!zHAco|}?O7xP*6tsvpdzoAP}+%2zm zc>N|Jz4Do1vlQw}*|3q@LiC_A)M??RsoLPj_~yQmywdqbs+!Hlac8vjE9$WuAeS{~ zz$nqN~64?u<jaOA!JjE2t#9z0q6r*%oKFfS=qDfghyBdXe#7U{k8)V!pe{2QUkeaqSA-BVhszYCp@Z|?68ow~esotYPCp5nC>kb-e?NG}%3{o!ZQer8q zPntH7p7I#+7YLCxCCRz@bO38=_N=QM;zv9qH8ce~)QtoCrqi){p>dO}r#Qu0lO&mz z;01HPglFX7X0vAK?<6+u;#}!mR8F9ptHs_*Rje>HOHS9dk2C;cAuY77d3iE^g=C#F zKhJV~AQQjw9HM2_C)Mr<`~P@4>#!)h@9PVaLl0ddF$e>Qlz^1d3@ABtr%IP}N`rI? zf|PW3cL)fA5=yspN!NSu`TpMP;%^4#KKD6i@4eP%#oFl}1aeGe_SY`dHh`@RrxI3O zQ&WM6M{--qRe~BYTfBtUUcDn=qOiUt$~?Y>AR%b&_1lPw0lh1?udlf#6UW9>{)(!t zP?%_jTUT6n0y9}VnM=eAbdFw=q3fJ}McCXuZQQD+VlE6F2u_)oJ~Y&+&8gc# z_~8pj$D>S%;BqDAz0g%jv=}!KyBFQPtf2a%wy>~IqbyR^nTmNqB%G-cXpAeXK7z11 z8AZ_pwAfd;#(eB@(0^|OiBy#w?u%F0!UH}BJ>=k`1qCm}ox7xtPE)m=)2ZR>8n6QT zEPvpaZC|gNC?s?VJA|J9VY%Y-?CohW|3iE{z!sQQL~W?yi;z9O(!$4|*!=US9g#sB z>{{M8X_!kOW^7L=c9CS={{~0V#LOQn3Ll^`RE=SQ7-6c&X6$VogEQ1Q#YE0OAoS`?&G&HkcTX=gQTG>$`rjQo~b?O?&2gcNC>Jz`+%lN5*XD7 zHit!ZM3Ce92%}cF3y9@@QT%`BteHdZ_K7GSsUR_N1^UsO9H$$w7yhN?ABtC zzaj0`T)MuW95pL&ZE+N1Xl5I$YykObs4JiTdocVt%qT1N7P5Rv$n%N=0_y)=v4#7RR#<( z&kYSd!vnSA+dHwyc!BJqg7fy{Kx6!XBf(2I<$U2(^$u&y5^l#eg`&ehjiFIu57lUN zqPLf%k*-A8nRaDGl~1g3)V}}J9KkN|5C27$U(a#E>ErxhpzZwlTv1HGZIF3N1&*|- z?!l;DJrCXkA?{Bzto_ieV&D`{ntyOzJ>w8RGENw>uJAdwJkmthi=rbRZk+(gZ8AN~ zdE-b(6jwfOR*$Bc?_8VD81V+#Wu4MFhf%mv2PQ`|2MQx4NGZA9=jRsXY&LKt~+$y-HBkzA)$1Ud^WokhjPcTZ)7Gz8~q$ar~N-m67y zX6y$bWS&)%;41+zQHT~6Z_9G}kW$W!KiR&N=_XdOF}>4{SDbB>Mj8h_Pg#gU7tq*0 z`T>Ru`$?aPjK6*4J6a#1y8_Ku@SDL8Zla-LDDeB3yCJU5`owxKsAoG^5cI4A)_-`` zCw5e;r*VWWX@0HG=n<{U-=}-?K7aox^MANm7rS+% z-cO)&bD({6uAE;Ib&(?1ZMbvnWia8kM@2`pX##@LL8Fox<%G(?AODr&{fnSG6{}uIzr7PN&7vUWK}*gJ zoA>$r^@RU{2~Jpe*75)$$y4rH_JoIpPpCTVuM4ryo^EZOG7@d>9?#EtZ{!Jac4b33 z`%cM?%N%mtE@%4|aEl%y&}-GJAhiaH6dG6whg_@)_5x&*kcfd^k4KVOF*lls+`P%l zufgAJ_g?o7R^(F4GsrezlUfFX3T3-kykbr4V!a$4PBf*WMnS7eW=3imt{e(Ru(lnE zv`GgJwdh}k--8*0&spk3q7~^BG?2qyj4HD<9T$M0Yx{3v;jcAyd*LzNW>fx`d7v+Y z9>ev;z>dDrysPj)DYWNh`0=?_xD}V~TO@`F4npm3t5U~xmCb99dA+u!TLCNG;)L=;hIluzn%JAmf05aet{^XoT-`EyP5~=W+n8 zK<`GNvV{(FB6$LdRIhmM!|a|1%`Oa4T*e93N#8HEYH^dv{WF3f2|s0}!xKnycQf8r z#KuDud7JP^t7M#uf4xo)hsy$ws;j%x7*-9C+xz+LH6 z9%A2BWJF7=X)u5oY(q^QJ;GRt&wu8ovPRa5b_5Sk|+kw2f-#uYT#aHoV&j%U#6Ql}qwr&M_P@`LB^ zFp47CwRWy^=>VWMsG|Qd({BOfPIHaUMNT{S(#U*3>Tk}B0MP6|cBv&Y%%hS<&3$7f z?6o_iJU|^5K3JJ<;j@>ZQSS1gw9j!wG_~$u`Tke=rK2Oy;r)fC2gfyR0|xHq7`Df~ zb7qh4VX8ig_y6mrdm^v+^71|T+I|vhEn&wuUq+XDI2NvLS67+-Q~Uxr1V=0I%qIGt zdi6bV7U|U_G5#IkOT@>7`ANzq@C^ePO0256baOpGZaU++yX!4@HN9a z#>xUU3!e5+zGRhJ{S*&7WUQFC>*3!?C8OM|PfuBVV-H?Pcfe*^I;Dtj#0+JSzgmlC&4Eb_-Zw%oi8jTQA;tOv8vhmTgBAs+_p7+lYE#HMHA+8cZ%tv z@HbMaTWfTo^-QT`(DBw(Zx#{AmVSg%OHL(-Iu7k!G$3nL}Y zDMir=B{FemrT*K$>tg+1#}l)oeRtY`PO!Ur4;p+2V-fK}znFg3MF5hz9_Ro1#B3m* z)B7O&U8f-%p#8r)?Pgr!rV%zR7Elm3o&AvOA|v(F@krh-bw7oY$NVAgVjrCk`|W;* z4`^%iJ`@X8WHNSk9_KM-;4wJgq6c%-MVO^l!D5EKQdse z)xr5>(0S?=;L#^dXC>L2@~!BRr_FM_+%k@QI8i8_{XCJzgRj{tF=yYTts|2%ey8l5 z7pNt25p(*i#mAoW$lubYI+up5gqRlPE0)-4+VHfFNVpl6y2RtG`JOoiPBEZZSZZJCh zDW}9*U#Mct1W{GDGa?mB$>g@}<k1XgfpszydK<1< z*x2OWi`CN59>*_9tyk|5fz~gWW-BYX-{3q5s(_phs!}s6rfA}lc3%b~-e6OOO^3mz z(y(?7FU@-6m)v+>hGXAt+V$7aIWn7y8`n+Is$IC>z`R6mE2dcI0fx|Cg$7g_7~IjR zSI=ekA6~2mA-{9N9KUng>eoosQWROXC2)^J+OsQQ|dQ&*Iyi~j_X_y8lee3x0hm0#~0G{>C8CdTe>>8 zt@9`al^&ku+s?O|b2rwJ{3jcWT{2r+tlw6?#vMqlJ+=oq5Cf&RXe;sMeadb4 zy-Y|p7RQ|}iqY$jj#Jsm41{3hkr1E~t#_4iJ|+h3Op@GZ zc$k`BBpk5olYm!hdc1tn=Wn)Bkx|!;4H)u)y7x9uDvbM28no?@t&KqhW{3BsKZhu4b>?exY^fIv$HfsVnu>0RUms;a7y5u~@T(>Bs^MV?CYt~O0j(y}z`#&saLp<8 zirLxQ_>R|)6q0=aWyb5*D_p}u+z8k#DKL9 zjDe2cD=6e0n6nUf+s!sO=IItMhST|6*(W=%LuxcgWfG1A!;A7F?r08R!7^nx4rM2;g&|&7 z_?+tCBz|ivbO69=$_h>C?=nFFGJ6)Jm&51JePQ*H@0B0&7Ec>n$tOZ|jmmyks{Quw zgbSEYK|vF0m)w8A=VB+2jVuDjVD+#|a`N$_IC=Kqsh3&^a^e*`MR8aS`sJRU4p8Xi z0r%fW^~@P~nxG%@W>In19yvu;;IKDlPf%u};~KrD)ImQ;cI0-RYFjF~R|Ro5C~U7o zdyE1kju89@?vQ{h6a@#@&!2F z-3}axUC`|{d5mh#5VzF;LxpN<9@u9cgi3=B-W^@#WEQ;9Kq7@>$_b3X?8S|WF++&a z59200zN6Cn+P(WNy|hBrFV@Z$3IaPB;f8Ji9N8C`yJ$IU&CtdZatir(MF5R{S?rVe zXvz^^cSMBvU5_?DkGXW^TGMrg!DJn9H#2=R#rJww*?|p72yjjJj<#V3o6Uuf@ zrFJHYLL?gWy)oZNR#+8;99tLDcRoYhC&${(mmncaem`Y+MwGgIAh`+hT(0kC$EMvCqEWB;OY5xj;v`|-$iXkYKa&RnOF|Z0ER4i+Jc1Drq%^gJ?OVF4+>N=y_>fTL{vs&F&D-RB$=Q${Hm128F$;IJAU68HhA3 zKoX?M#Q;g)<+#B$a+uYR&FobunCQgb8`+YPh$fP{yW#l<=DlFokNDa#r9%*# zN=|@&M}u#j6Bwqe0#;v;w@w!BbOs4{|8PvET?~!r*zOls#m^8!>bC3Ywhy_vTL_l1 z67+M&+nu)Sy7{wS{^$kLgV+kQ{gIpPk(*_ot0E0A{TY$FDCY`=k`Pn z`x!%o4v))xXitZTdt?_E7X<*fw*XIEA+BjtaBgWVcg1XDem=9a|*w8^wb|WlP{ZySVshI+oXrk{w9r zz(Z#>eKK0Ach{$!Q8%0ymN^ML?ff!M>}KR2%TnNjF~Aalsx&gUMZ5?NZQlRuL`{`Q zUKx!DKf;~it9acdLfmg`^By4gQbgU3;2PMUNTe8xQ`hesIv!{J6}`>NyitNAIcWIU&+FdlLEl_G*wv z3w@fnAyfKpdY}EH2gd*c?nE&~Ml`%kJ_5hK@7uq`8_9Ex5^d$0?I&{ebv+6-A{Cfe zN?|oawHOB3^>$YHU++kv7fpS;tpT0vMAz=!r=OY)QVc zq9|hX=b;%-n7Sbhi{QGgZ%96~eAE&jWhbV|Q#a1OA<(y{$a+0PBX)BTW#Dy;++g)< zaXKUGj%A=>@;>XLYyCSWFJMf5H-oq@IUAi0Z95WbJDM_yih(w^Q3zy!yl1*^I+o8L zunA-d1F1tY5|`nv2_TP73=_%{VDDCJ;9V|yAI4>Tzc<9_9>VfAOiEhn4dZXbPl*)6 zS-SxLvws%7Sdw$ffy&O&gKhC=rrdVcJ;lCb3m%?e=$z~w(JvJI9}(={8`le#^$Ov* zg8ck;-Jc%}{j~6Of(!6R#%G71o*6>#)LHxPMRMl_3~~GY86h^O^-7fI^*6+vp6!NT?uI~SKVvN9|NOO5qa!2*It*{&{KbZ=5rY&pS&>VPkp zsZ`02tf*LDUv#2+Tr(TU1V{G|{nYH33jC7@iTDj|+iXGGNks}M7;VBSC1gSQapo-@ zUIA%ksEGN5oM7jq$4>D)m+6$^JtSQfctGEM9ar+>$Q|V} zn^dbeI2-;BA1YDN)HJnVY4MsX6XsvW6jLlHCsptHi-XJ6lF=x3io;Y4u_*0VXXPu! zu?o*XL(|a=^q^BzC>eNm(;QENm5{H*C8Pc#G4xM6NALArYq{;@Dnetf<-*Mm0;UOn zTz(j<2g0(_bQvUI&OYi!!3?q_N&)-$M#Db{UY%c)uU+|wJ;Nkk*sTFNi}TbEQD=l3 zxKHkG__Of+_>!9;%7()7cRRlwWtXGrx}l+;kVw3jFKdwp_%ViI+#NUGXp&tnADVtM zj?64t8e278vg@zacLDd?Q=_ru8Y*>5%~sEb7HSPb2|{v{kA8H(izL$O&Ub6zH034y z_U+qB^{$ChEn;&%c8COv0q8OSg}L8@@^OeIj%#tsEsq_r0W4s*>MqLUQ(3{BMPU1X z$hI7w>B`&>Gfz|^Nza~9ZdXN(By@10B8%GR0Fr)jtNbMztg{;l$Z?W^x7%wG*iQq; z8o3pSA~yb~@S5QldrTmjhEi8pkdEx|$f2GD)9KGh$Q<)UD2r`M=drb<7g}2VFz?~N zo-ucjxUaRy<;h->*4lv;#URbyfB;!)c)S9nOpk(FJWhYh_>NVPc<1Ec5&@%hC&{RD zNFaHbUf1TIdR+s99k+ukw;MbR zfEIs>?W`Ii9~<@XIy)7$9b>Q$pJ#52*V^Hr`m0p_6gd_BKqiCDZoVc_k$<18N)I#K zm%exjhmRebudUzRrrXa&6dY^6c0r^MsZu)X{c@kq#p)Nj<#jdu}pnJCDs&)#wld02o;1~duW z4Z)n(ZVrZ~e{=w;WFyu}qLunjOKSRBX5JOIanZ13f(`tfqq z0rG$4Mo0YpVW_6&^Bd21vug3vEP0Z?d1$K~cklr~p;LNY9{E&YL^ynJ0Z#}!xZZbU zKf$*7K>D#F_MEEo?e*!h2a$YOFmO4$9p?Ov2N#Rh10WXlaEr=#-_fF;erglVUiR{g z$B_A8tL)9ZcR{f|_s;}{kiW4@%k3I^UAN#5869**_=-J#D=<;gKi6BqQH4Y$%z z;vTuIG&%pfVg#W!Bn>dSr~g?$)JgtPi#m`~*!YqE0~hEsd0uSfRZ#G6@6AXQl$5+M z$4*!F+;z;5c;SZgZ#Z^w3OXflM_K&LA?o}pWqa3FZQ0F2mi*~_lxXoFavV?igZb%?IRXyrKEESCsSQ0UI_TeK7`!t0oo}Ngt%2~;7k#c6riH2 zJ<;kMQ?ggitjWc#eg0aZgRZ%~mN1R0cwp0PmBxmy?=^|p^8~Q`VXz(;*j-&St+-4H z&P3GhLFv#%q!;Btd&fMjmdqEpuJpX2&<#NeT7Oq-;F^|9mhI23Q=F_8DqTT?Ny3K_;zUtSvT(yD7dquL2 z0gyRGBR51YNeh(2_jMuBch(tBpEDht{`SX|yHxBF;L0>mvhD$H<%>Xif|h_pCVfn; zQtuKF*Ao5yW3sNQva+Ej0k=5|z;-yaD$%gfFm%^rw!~c4o@p{+I(&-WI>e2gVW1{8 zyE7@^<0p^Dg4!VUnKPWSRs(r1$s(sCZNs;HDRyOKtw*aDMKQV_dh=15;@`3s9+4oV zoYT)$rifp3d&W9ae+&#k&6Y$*Mopbjvzb!}NYX63BDUnO2Zg7?U~2`=@_`DIK8yno zN}kj`&vl{ObFtg?ThlXwATjQ%%*A=En`5P;`PTmU!U##0NRTm*s4DJn)yDm83vl8iOZ;T#D?CnZOh3rz67G`AC#PShFJ58{ z)h>?vP7P&v9%7pd@=6*~mU7^w&u-4ZGX8b5gm;Px3oGX*HGj90xe1$4HvlV!Bl>w6 z2pm&((J}=Q<7wX%z{GWkL#H;HJ7>XO=)uL8cTo`6!6cDiKYr*N7*K{ED|`D|OoJO| zP{z~Tj;h5;eUA@%GyiIfmu!Asz4=4+MXtktRq%fgZ{P^biNPPhMKzTA<;NQq2Koa+ z;}DZ#Dz)w}mF+`6U}i{iICC1?siM7+FdGQSqErpDR`7CcVV9eymW5HKxK93z#e6{L zF;bY7Wn9#$WJ5|~r$_489XN{p!y;aI|L4>y8xACFMLssA)-J8#D{+`)@>Nce|5Bmh z-prYnBjUl?Og&6KdsMtN)?leN8CgMpyK@{(4A%`nRDbro@sGu`%>i8e=ij zA7^m$HA8O6ee_)g++M(AD!EJsCv3YZsKwrJ>wnDkM0pj9lL{LHM?JD*u)1NoO-tuE3uw03u{UchX$Tz zWKmq*zAI4*qIbRw-FjD|MJN!P8Xqw}pjpLBc%-;1^iBcP&Ah!YE5q~wNCtGVX3u(gNIA zwPWlZrInL>s3S1}tG8P2{b1v-#y&Z)0{x#bBC5{wUOG<*Y6!or%#9A{{VXhWMEewM z&>)pbR>_E>El9=O(mVT_ePT|B%{W1@_HjOd^65WV?RsOlNM?2Y6&OuXq1zc-lv4K6yE__ zU+W5v67wF9f*tC>+g{x$lU-+5i#PEHqMfiAGmTmOAOhiFNa{auhApW$`u8O)*Q~Nf z;C^rTi0PC+*>b6jA7ac72}_aa31%fiSmRHNSJC-ap$u!1q7q%K=5c%Y5UDA&C7)Dt z1TpNU<%$R3r#q34@>Cn*>6&T6j>nuPuXxmrXh`4P+96{r@l`)_zjH^JeVw%%*$?2D zxipxL9W^de*dq^8UyM`!Ydp%HW$|W%JIB;sEsd+UR`Lg9iV9lMXG4EE-bdq{IOHAH z(uE}bin*^V{MiAZ24%aP33+evnwaCE`^UB6p20I~Ssm|l$H@wq;AaRShdQufR8uet za+{Dz`#b3@#YC90o3>Z204;^Zb>d*Qt1CEZAmIKs%cjvqh=GqHbZEi%xugi^4eVKC z(@v)bJK5j`w4)JkDZ;SIJ2?%inGUQD2WvlPVA|hWv*Y2u<#=BF ze9OG5rSZ3UB89p6w~yd-qAf1Y!5!)js@%wqk^Hwi&z};#d*P0F=rQ%}5@1zhDI3$E z6RP4snKpOhb$MduhFDlU%y*yrhxTHb(v6(eP7_MW{d;Qo=5h;YU0 z5G#tD8Pxsnv_HHj#b}P6Z8?tpQ)c{{o=y=Hr9Ykb5qtVfiHd!bepOphQ89Tzgco}E zA^#y*#h*^UpY2Yg{4+a2JU0%Fy5vauSg<9MrC5+Rc{G;fmS(`<+{Gy-Iu3vJse1!Q zC8uj;dK$r@{sLInYjHmOyu=?BZL6C<(jyJ17|C3+C{TKwpea0Re?rqU_r=t#nKSVX z&I=aJp1BDZq;Muw-f40o?v$(t|F~~y64|g-7{)q5Q?!IvJT^(UCuAQRdn+l@cVQA* zOt!4I(Y7+x*%D+r$3Wc!Y_B@ZxmlQWZzOK#Lew zLgcW`vjfUevC;GJ@*X5ggD7Whk3Uk$)^acFM^ngLR_~X9YFKw(EYdSGb|Fgc3*=*d zZq27*E5-{}y~bGCWXsMe@ktH9U|k#3_%p-Fa{joc+L$IU7&D+ha>W*G=eF&EBTqjN zf^Qr_QOAo`-j$wSJYL=$=FzzKXB2*b-xopImAcO4+BNk>aiByC?|oZ9lf(hwl>$2n zBW3{Aiz)Kbz5GI|j`1gG9htoS?++Y6Wg*WS`>zay@;{WN^vPR3nD|{|$vSdJ$~g&X z6of6XR`}d{PpbNZ`ojWywU*JipY;6AQg^5(OA41skUPTe@?jPRH=9vRj5IZZNrrOB z0wN(*rSNb0l?;s;ZYe|16bA`qqxhM*K^W8X-Ln|iku*?Zrp_(_9LqAL{|d;@On4>9 zTl_%uXozPj8jU=h;r$S63|r%aY)0wY2>GAB$DD#Y7KEdO8$v8EO-!sMx_~5NKk2sw zfe4cqNJ5-x*y$o*CDiY1qRsA9nga)3tkc8yB_8P(v-^;j4=_mP7&3lWrpeNZI4UG; zmkhDwU+U?#a9|ca6FvWPn9J5Yn6~)obQJ5MJPH#73H{vqH>kj2NoCl+sqEROPqQ4C z_)eacmk4>b(h(ISba|sMVM&=wnEBOpF15SArfB6R9r{ z8ZqtZ-#YXaE2~g~^3hTuT_H^S;HGz^e7w;Enb5S=_|^1U)?wmB34K=vM`u z&!{H#7J8(jS+dG!?z)Xmxz?wz>{dHJ){)SgtE&PBGE+XPZt~g%1dvOM(5nH0H-RBb>vR8Zlnv|rC8s4W^ zyM2?>Z~)bHCpe)DPdrqprkZfoLjFZTdu2$5lM?dVmV`~GvxzZ%-I;S$34 zcv2PhQH5^TpsvlXQfR3!`nr}G1l<$kvVHAa>iQS$9`z@m(G zx0myDPx1mHM@B>MYG`f{feo78-*+(9N%62-t7ot%ZC-_LZoc)zc>r)VXwB_TJS;O> z&7TFC0#c-fw(=CA*JPt@3>VC!J~DsXh_2ftZ=e5#od&im(-8gp^iZXT$qjtGy!}s{ z_n%Sl+t7SK11)#Jz+UWY*^jrImj?LfyVMkdDp>M|GVPkMcpYr0m!WGteYo*^ywrF_X0PFxtV7t}G&BjTG{vp*shdqZa7JjaWW7B=YPm0>z)j#9F z%}4cj7X#>C9|U^S5%GJa3KIdH9v3xZRv_)tf)Q2r2m>yhb~n7ms{(&&jC%PNGJC0k z+~%?|*v;?$(1zAaQEgLzu(d^?w{)%3CNN=TcJ?SQs(IlxIgP(DxEHmgG(8r$M zZ7DKo5PDvymHUBOWklk#m?l2ia56XgQ{GdVMeecrVD!t#LH<+%Bi6?OPx zWhjNGp|z#)qcqmG;h;92ghMC@qEUXB%iH;H>oZSmudAIk>!U2XBXUIC``1lbix0u7 zEM2UpHQHTE??^(+5?auF@G;XJd%|+foLlCJjxV2pcQO-LLO>Umlnw>PobElgvgW%1 zx4*qkjrq^xJL$hDky_vB1}4 zqn=q(l7k`Ygho_OQ4vr5!`*Zj@fd?340y}<0!wQSS2DPpQvayzb<9%tms1^RwY9ZR zcINlo9^}3#eJ89;ooPjJ15z`7{UPbMSsd;aJ6|C#ZdPJWb{4+9I!aURR54@$BIjpY zh79=JS?Q@-sN{zJbq=co#S>i%F{S9hvNfD8GPL}Ju6^a?uKAS0P-ywq`*1>sDhfz} zV2YLVQ@74O^S=vUvc=ReW<)IslMm;&bKRUroOA6ul6Z>o1is+?s3Lygby%Dyc~Pql z^EQFg^y>FZ20&8VTj@$6Ni*<61VQi2XT+7Xn(;xrRDD!+Ai03@_vkbM@jJMua4`qV z@Pv;ng(hs+ivtNY0s$&YhLL*~Pc^A5!`GE5NJ)x1N!1tG(IOFzJ)V}~dxiUy8a)@b zt|=x%gX%`~e?=AQTM@#JPnzb0PL5Dl2&>@f%8M%;m24&CAJjrI0Xk0{2Dhq+Bs@%d zPC=@uZPAwuY<|5A8i8yMpAn?2aIvlKc zEcCBqr`(VK2Fl$UeBpFy*d`&-pMfBz*!vA({ZqO%t^!S-=ZD1;@=Q=ne46%Gm9osP zUxVhPqlY)>^WXM#j?FrtR6Mk9{R&&O>_0yXr6zC6Gw02P zHU4cW-{qg*amVGYAj5_qQ&VFi6MZ##JvVZbI#=Qsq@HaL1~;Lvay=6fC$Foi$&6Gc z3h!B{+;)3Fc3HpG^`7*3#M@>XuAtH5KQ1$5r+u?5xBnW@pYGEX7k3w8=B99)4g63P z6HzfbzTGTq{g!Y?L_7#La7vN|*0plr0~0J;__YQgGR1y>gE$({(hO%;peLL-{~tGM zlvhxYh=J-;+t2GuAy(FMb8$fY=%38R>xoXB@|C2!N8?KrBgm`Y9HR~vRZ|bWId+8( zYORtYm`M4HVt+_T%FdLBIg?kwZwL#f7>1{OFG%v2bU4mC_u=$l1F~YAFGr-o{4Zg% zl7dK66K03PsW}3pa1KxAV94hEB0^J)JO<35=ClXFkXg8PIe5%D?%S9CL9q_cuhvN0JR&feMVk&b=)kCL!7@jP~Fh#RTC{M$#e zUcUnB3g9Adpl9$;Z5uBM33!o-eM0Lb0*kgK5rmO(fL*Xd5H_XS*;{HCipGsqglRw0 zp~oZOoTNjG2V3d1^zaaREbZg$;=<3zXY^qYn9Q;G@aiz_<5-kYlrveSBw><0EQd*g zG#roho2N|M*$az`a8A2lDs_Awqi6yDP?*EkGOrBF9e7GiO_i}r@UG_VfAEAs5cVGy z#&MXf8IOs7@FNf44J`)K8ArZISwIMnJqGXv2)a#eK*$0-uCJ#Z1FDcyrzw5l%h1y4 zTDM34YT77HB7cTWLRlx;(UdFo+DB_W2eO81+own>hP0!bCx?3@u+iZf2D=BN1WIx% z>J^tgUSh0P_G(a-K&cWs*;fgF2(`gAz?r>?3wM~J5r5K7?!cpOguS6 zq125xJBC7Z`|% zDBQVb&&cQ~c<%qhK$dcs=&`-}qDgt!nKIU|-S?(FpV?8`R`%zh+zj5RY#$_F3u+A-EK9oh#5^D?~Q7R+fRI0a9f-g2cq z9Gn41>g-}bYdLWzz(MozXXG}c3_7}svuC_*JKAk>Am#kWW*rm7)e=hh^z4>`d|f%| zD`hdY#B=eW0I}DkbECrtXA%YV)Md+pYG)L4iQP!j_~!{7)BZo+oRVtv%ni^@krj2i z?7!D$SCXQLoz3x9Ec01X7*TZ5zX`4zzAYRQZ7KnUVG@o`*nh(tBxiNP%RXLUgQVV!Ms&#_ft*F zBGPJ^G|~GWlFG0Q%WRZ%z}@cNCVyW8kCWY<;neXbNtz4?%E<8s`K0aMhc124+C9ed zqA!2xUPb2`0SsWgoQzDL-+j!PpBJmEtAGtG#c%Hrx&yd`RaCvBKL3=9;1pGO6>4x< zWANh+`ZWw4_#{PPz`vg3Xx46N`?15!3agYLSrs)UA$pROIx`DniyUok(tIvVN9<%yLuFqj87&!`@%0aM@%22I^w^dA4zudJDpj)Yw8 zM5r9tKG?VvlW!)TTFLa8F(vIcyXuRKC)zVi|NgCiesju|b!9q6*P=z`RJ|?~mc?d; ze}++)`oUA|4dPi8%HG%E24&F{@Mae29GMg}+9EdlZd}KRrz_o}L=j`YVZdE4uFj;QqbG`#Av9B#O%gBhrU0w_()wJlZ9ie#yR= zf3|4dkq{a7!`QnP(OGy$yk$+OjqE=0D!J_%biUoV6+KS!F*uz#xg)z!eY|kL^eh@1 z{Z#MTaJ%v={S&74{H*hNp3q|--Pw1U4fCzJhNN|;B2n{s8RK^Z`PTJzEh5dH#Itq| zG91C!TnNH9%mk;XTO`lGQ~axvQRa&RrsmHv?8wr@C-6`!(k-mTM?7k-OjTj)I^gl>_?hAk!xBFzEjXst5#P zVc|uJ;p7ca;GN4E+-t-qJ1mR!wJHk4xFVl`yYUTu*zv#0^`ygon)vOLP?GOK(gFY& z>PWxlE3TFB)uigq(RG?4-t2hL^jC888j4)nPDoHqTvBar0m1 zes%++#2>Qv_(Oq@VOx-K~9vL{BELR3B z8*)&T+wg#ZC0wi$f2DLG5?5FF}$k>irCg?;MwJHGRs;^cn z397p+!$avoL9VO1n7X0_+Bu@7Z!h-@N^h&$3Or1hUS3_4Kqu0bu2JPD9tpgvh5ZL#s(aZrXZWDI`Oo=qyv4Jq-|a{TNe_LpUXfP9$aQ z9Dh)Na%dBnn05XIW9<%j0gh%*q-VV5=F&%1y{kMtp{#X+yZ!YfWN)^P(~{3>w$VAB z|L@;pV6L~au>{7j)ux(V;=7nTvnefL(CZAuVI>Z5>436D?!G_7qkcNoW)rQ;5T)K# zYyBU`7@RNvZ60CJppdR_GXv^2tc#Ai_36-l)&n-6iIz`fUktcMqY9kW@OD+>nR@$} zX&Ua8TMwjLDxr)qtTHf<0A* zI>L&B+vCsh{=+qfzr{8}l906C!m4e70Bw@*_mS}Qu!zXc@o_?hrmga2@>-y8)Qk}Y9cv>pcP0Wv z;3dpVzRhLDNh6UXZ7&c>ar63fH#lKv;1x6(118QXa7ryRhx~3#6*=7EPH~$yyRRUW zM5|{`3n5E7|CF|Pd zQ0_dmR&?NXm2G&Lh+5HLr~7a*o6n@gPM3N0%|gP9^Siv5EEWxI?S`hXfB~Q>C%Yz)7mfJgB|W2}q7Q zYggyQelRe$+JQ+Wkba=opd znjcEtu@(n>Q}vYnrN+eU6D>{gq%DYWMy4Mq(-ZT%w9S2a=5*e=d1^-S zeIP9Xe#Y)ao^{fGDY$A%!`>jR@KO56GPb5|e`YulmK6|dmVQbUW&9;)v zu|B@519r$A?6CD^D3*`~hm<7>!oX%5It#ZL6}E$a#-hY4jZ{^9~WU6IJ>Z zLhG>5?q|{$X;ehnNn|c!RG0E)nD;5DKBpL?gc&rt_SNUzPWAqeH9|@Fjr9OvK#IVb z@z1ub8^o+|Q!*^LP#AC;-##qpi8GJ}T@-;i6v!On2GTfOac%}~sC4)I%tjGOzdP3e z++0-^P___nqA4Kykmf!w*K$Faf_CU+KaglF0g}4HFatQ^%9E}^=tWUk*?I_(!|zbN zy(zzdx*hX4!>l0G_tHP93w4RPgD@uszstnSF~ksdY`Sl57P@-~vDzjJx$HJNZyClP z@1AXpc)u&n^aHCh-YDvr`YTGMx`Qyh>Y#sH`4yA0aE6kkH+EAdrSr!91;^PH>3#PL zmE0;!*yyhv$;qK83V7ey~kDP*C*R^*)t9V4S*i*i8#u36m&k0;$S*h(8C zvz)W6I-dh$cgbZ|#T|VZs(Mh>l;Da^tydF0;NoEY;os5&Uy$(CGHY?en`o_+3%ytu_pjtS3em901m)=N=tu>L!_QJud z5k&{0bGk~kSg@RqE$S#BKKf_aMK!DK6~h62@7?x+?5_gIm!`yr*L&_xshLY~hmPuq zP!z$C)6rO}`uOhTuWujuO@A20A^mV2cz~i6FQFhM5G*kTft|OS>E&RuP#E_}ZlPDP zXIY!F^i`?X2LG^9i5Dpa1YHV4^cI-L_amhIGmpa!u24}776kl$;t}0{v?8Og`@sB; z%T4c!*EpVNq>HE1^v=5X?UbTVSO5iM^e9N%0#B}a@^Ag`$z@4O z8%b6k$30RUV4WdW6!x<)=Y_VbW&x6SUc&Q_Si&yx;mrFnQ=nXNK-ByFT^q@WlKIW+ zz(V1QCE2G({M=-DBPfV5p5L&&i<-t`a)s{y(e#x8QGL(fN+>P0bf+{(OG$S(OP3%G z(j^ko-QC@>bax9#cXxL`m+$ZY@QPP^@9sHgX3oqf1Q(r8a%DVL$D1P{-Jf+afW`?m zhlU=WfEO>?G0&tRw}j0DHaN-ONSJt5^qtGf!_y13I$UDeh{Afq=^r^qWU1bGV@A-? zVEPvmgc}JRc_6d{4No(guiFN z%Dxp%$vi2}Wol?->8l@73j#jzsjLr6W;jo3bdZ_0tz-kDkpbMH{~8KcOnS4@4kAU+ zlx#e83Htm6FQ#b1*2qe@1oW5*0yh#_b)S zegag44(25&15}OeKXDN?SaY1aw3L-0ha_oQnCyK?5qEZXbWAS|VCUdC0o3`vV8?n6 zkz~C^iJ>$8=X1ce&)G>1{*lx4B?o`OPM3!09m29P=qLfc2P zY6bMyM>$t>75)3TaNj%9he*i7j|n_ZN;8r6FzI1TDhn-a%v=%^`uH3!D{6=2NYE*U z5-VE&v{(l0(mJAoYygWUV6QzqJoL!#2EN!_5*{lfM9{?pf-bJlfOaQ`&5BI7c=Rt< z>AJdUKu<&NgP(D?DLeYwAXz$3R|T|qBi;Zm^_zCWvG|d;kEacnJ)yXl%Ls-_`mWj4 z$yvq5JjpEd0_rRi0KdwwUXJ?uj4=51G4V00g}x7F7;4X1jdC@{n6>b$Jj}C_>&MPX8OaS}bWb z#_J2NENt2>xtBrDCAqG_zsvLII1w40Re7>nYx)y$vVSv49Xe=(Z7)JhuZI25q&?ns z7L{@RUpXt1eo0AIHF~rC2a!a7UC%uCliL_WlN}WK&w}B zC~+zd>xpF>H;D4Qxd@BECZk9$v#;WQ852+7&KB70(+}{4p?c@CzzGOC(CZ5!rch<6 z0@fV`oAC9?SkQpRWA#0$52W>Ix12RmStr0RLDgIJy8-@r z^lx!-*m2A{I7m=eHbQ{Up^(k2&Op(e@cK2vvTVfEb{c+P#)Y@CueCzA@A#;dE zs~fxh`h{~V3^oZOBUKX6I;h63+zBc;(|)ZiJ{X)XQPxsQv*xy)YdHCVy@3Oz0Oo$V|j++Q6i)bz!#*Ltt)Gjlaw7Nk&Ad7TG^53miGhB*Q>J{IyHkvnJ2 zSXU?zX3T*5;aRLkgKgGMYy)Ud8+nmU^1tW}7DAkWtO=OZw4kgNG7FhgdKn*bK$1Lc zTt3h{Cu&wI`C{I%Wfyvn0aEL0`5WbvO`on)QmTmT@6z3g8mB*b7s%^jPU=C)*L@=V z3KJ2iT{6i6y)AID9R8-i39x_|5>+`Yen_HJ@ZK<1f|ES|k)s7)sO?Bl#Glz|dN0X8 z)H-;V=p+n0jJlS#xv!^ACOI$vLKqXKOv0pPDWq^FGHce1tNr9#(gnHmfe@7WN@+@f zR{k-nK5UwUqbmUeOVflgxU!A=*?L$3K<&e=W$Wg-OkB=+>Klpo0wPn(*>L;QFx~KdbKz01|cPfM0Y^#}* z9H9NR6c0v%4h3|EhvXYsG~&Jjf^-h<0uq$RI;e$Rt?kX#qs0U5BpvGuC$KfcU4>_V zDAj?B{{kq}zR7*Pv^q(-qCg2pXnW03#dJAPio#H3PP0q8P9sBc{y{TDb$ve%h^J{u z{^;YSmtV&MwULMM@sg9BR8@O1g4P;L@36WN5Cxi4#ZX<8O942Sfe15(LyR;Dv#i=} zr!$oNq^tNs_`w0(1jbnc4r5nE0DI=vsISgjyqwTcCHN<-7(o4o=jz&xZRmdOQ#o6N zFWK{TaVf)$&VGlihW4cAdy9><&4WW#08{>_0Okqy4|4%bhWf>5|Gyh9WEqv%Kn5p5 zRExU6n(R(dU`;V8U)!I#rFwvLW~Om|rvY|v0P-^nLBVKH@E@1^L>*M}bS8elh|Y!9 zTyL9*8^m93cY^DO?sXHMR|{ao;94=5M~;m2S8pS=0XK=f7^>0Sr*{^va7gl7nF>1#z75D?I|Zlc6T6;C88`z9WD6I{+ z)xE)JH40^Dblh3T^+)#>8}0WtFZeQqfb5+wwZP@h=p%s1_Sx@T#but(l1T<{ zo+Tu5mFrL5k(ncMY&+uvAL9PW@kjt~4q(6TB{a@HE#j>XTtSX=p|MnfAYq63``P;L@~td}p5q8#4`yh!y!I z8<4HX9pC9@nyiE9mR3|qQh5&H#{+IrfGYZ1n6buKdEFXn>n8MB<-v@29UaqgqJd0Zo#XlQZ-j`C!gj}00 zLIuU55~!f~Rhobsunv!jTNp~C53A{{&JSXA0uN8E-5w9r+aCm8$6qhi+b-hHrj`L4 z3eU@w)u);IHvdqJE!zieo9n?7dT>)7gLwC~v@H+|tgF^oI8iDBnc*!i#C~;F*_O0fPSLu>WrF!GLky8Vw6CHy{y8 zlL{2DG;;6Yp8__@sG}rc+AShK0oFYyPAT|kh+i85F5bbe(sf5#Z|pe8hH3y~%ozF4 zkc5xyc;t`)7!4eiJIVmbXdP=Oo51BHg5PgTrx=^^(K@Lk^tP_9E=o8_FquQCd>~O> zndHeD08G6>%IitrpO;%=(z(cO+>+AH4H1Mqep=ytzl))ZF76l8&w@u9l0ktge+MY& z77-teU8|)XSvH|>>b>;#_VUW3+HT#!lpJx=rl`x;(!x>L7>%$J87t8ik?Z;y9pAU% z71namCUIzijzl6Tqf_)lO6;c~J;+OjF8BG5p$wt~#GK85NxfXgX&LvtV-aQPkXK7edF0{XbAD*`Huj%`H|1Z{wBm)9=ODsGP&vrMk{>#a9& zoWOmIz@XN?sGCoBL9?kmT@qUxbIEPJSD(64ltITz!ZSLsqZIA3rkLbTZ)=9Q#VJMF zEz!vvKl@27-}9d&oB>I5Ddix+g{4Fre~{Pb!ZRzHXz&yfbk)Xl`O|8BoL@_~*smUz zHZl2wx9)?1v>a&n5?#LNpWdD?U4qJB+_GFcu(pk|#Jc2iSmBs(Ubq|k^86zVRd{`l z&g`KXK0EMLA{#ly#SRIK^Uix5UtYHAKRFc0rUdlBHkPVcqdP-797vPa<9XmP+^=9w zQ{JeN#}Th(rKQ?uuQkp@9g5oXD>m7G7s%i%MZ_S{81spB@Q5$AWAmmCW9RPN)JJ8t z+`A+34!F%S9#l1fB$WeLfvNPQq@;r+PhLFr9wj9ej>|a)Y~)X`pr3VaZVw~Ktey`` z7-A8C;%#PsX)QoF#0|Qj;v0o`N-;Hq(tBTO;E@LXQOz;Q(!ke2Svh82d=MT#)gM&| zE~;twtC-L$8KGj^XKJxB*_iq)1=*lRhh0-wS$NEemX?-p#(4CFG8C-xE>eaHb7EAa z)V9g&HO)k)+3sz=IL!LLT<18L0iafw7rsoX$3zg4WyYrSCl_bmn9?po zgV;NsU0&o7?}Y*x11&9}(XZqI?}AmBBYn>eN+XSefL}2bEB)&jWp~CHI={wz+x*PR zy^EmR>&3oGGqr>$_ykkrt@V19a!ArhLi{5zYZ$Hy;*=Wc8X*e!KG`t+7*+*)FSyJIc^D6(s$Nl2j8M@k zR%$>1Kil#Z=rfkZ{pf_|DACR6~ex#j%5>jT_lR`+Ww~d0wGN- z2s%+Na#k|Bh?H?lzQ_%)(F58O*}S;<$j%%uAJJ((@3%JFJ=|PeQcU)}6Zaodb4Ojp zH0#;H80VzAU6w&dL$u8`Z_7J^aa5{Vqd|JYrgMFqjBe{Rk$vxl>}O01@a_yvST1Na z=Ow)QxTC(JuY2aWRLaJ@6wzYj+f1DAok1Xw!0}E1Iu8}1Y`xLpW7QoHcfsVo(0g%q zbG-P8nBU`^5C6vtB570VD5-r#m7ViVTX&P3v@{~<0}7GFwg^eT_j+b35nmHBVQP0B zoEF#W%}i8G+15mVQQB~d(x(>eDPBR(^#x@{F@))+$lsr?I&&C07nK4~hW1yUE0mzf zx1Yd&gq6bkV+a(SH_Bfxqe~V&k=L`U=mz`t-uQIp_pzoa^T95wG^*4 z4aD7fB37l}3K40J3%@5m(HIbR5V9|H^^+*~@kro4IYqRB{;Kb`TCESg5Y;G=<*YjK zGdps0*^WkdKW&Q4eL(qEj}hy>_m|XOyUI&=2uBI(BMRFqM#i0psAw+$)%cByGz2-w zUwEkTsJ4yB<7d3W0U^z;j|=yM$ER$r=D7R(J#%{wSfHtG^P?_ila3_LJ@hsr5UtKf zj4#W!T7w`hCW{*hT@Yxc-)FbIR?=TK4ZRIUoV~gDu%afho=@;;WN;pr>#LWn`i{4N zHME!moLa-!>7}`*CaXOzcQ6X%=J7>(CZWveh5w)|x4PGxcV)ta_fl2M!t-U#6`)(# z7;BfpM%UUo5i=M9rgp&mCJ2cD@eoKaev~e1S~QHEIb)?&Mpm-$TS?D9>wiw>N@{e6 z6L3ejG)ls~Z9-%BWz&JNWOSjxbRX0va~*niN?^)r1%_l?p#b#%w;!Lo1 zSLk&T>-FP}Dhd&Awe#r`2@lEXz`r8p4EGc6%c>eI;1#w!spFFE%s8z7+Fl_$$vyJ< zR2rU(VFsZ{chb2TA<^Wjb!pO?a?s0ha8rdB$OfB-M0NE}%^HdEg-Fd4l`x#=F@F}5 za=Dssie!9PaX&>S_$wLcad(;V+TwQogSWd<@BBSrMRnS+8UB&TrQ^!ZlQrBWv(R$P5H$H z+5P2yw`L5F>c2RwqAUalD-B1gqD=OP=83KVn@H31g_N!u&lC7D$TnRkv>mMh0Ae3* zVGXldqQjG3%bmIN`?)9c4%-@lzpI=_i&So@uIK5Pn+!u2o-Z18>@RxRUq&xzB|FLR zx-akj)#XgTXPlnbiSZB0ac*_b-h`2F>3a(jugItXoT)5Sp}^2RTI)D?ulO*OU%u>g zY<>rdSZmr)y1^QKE{NZSDqvEBe7Z7PS5BN|5Prb#-d#Q~9;PtZbczNYl5Z2Zohyf`)=KF*{*c}lit5DFE6LBMB?=W&3}_5n*kJ@y|eudl7Soj zq;$Gn*1f6r*>Hrw!;|FU659C)3o9dGJXASmJwp_CUuG^N<&q5=P0IJR7?=qsc<#eLt*6HdD!n z%ky6t&oW*Lhy7B5PK^W9Gr>m!KO}^X%WW)u%%*LrU;%Izlo5Zgv^ZnB+ zrSwf}rKV|f^bM|~>3lq>^Ds4Cgd(?rRjTs^=`%B|?zd_joSY(Zz@YBF5C7wMntM&z zvE@6IurSA#dSG;J^$w+_zHvU`0dT*VDSeMm4UM=GwxwXFLkkUj2Tk~u!P2QrX(X8r zlmIwo*I%}<8w4L(!X$6UAl*tM)7muJG2~(h{ZkaZM9vG*=|s|53`={@N=jBCjI%H%^9k?>`4(nSVXc*qw1P6oHi5$~{u||pBo8!1<=Z}MbIR#0o zL(#~^BBTDM`QdX~vvGXJ{t1uyNm=`M&`(I(XV}{Yi}r<9cTUzu2Enyoe^OWRcD(HV zJEtNynaSv8jk%T_R%k+TlztMR>DUH9!PXbGnC3lM9Nfov5X(3&82@pGkCFT>mR1Ke z;NeO7R?%o!9Rsw4(vm7qz_!gBkgqsX%C&t0a2a9WdATP6?=18piGV1w+Q|_wE{yaE z0Ji$?NW1=I8wjjoB@`CD0E=Q-8x7Do)ouDogB|Lz2B6hH;d6whNtnQcWrc9T46?Ga zTb+4x>ROIM4@tYf0b6S(jmlpj&GGw_^Bi$K0b6~r-MJ$$I9Q%2E>^E-e`zZNCv5NR zgyFJ6-lDLGwDeRsVToMY*W`qLjKRRJu8pN7X>vxC22TA4MD#?Nj`hJ`gjVy_CM`*l za+zE+-$p!4v#WbgM|CVe5Ny7cFXkPi&8PJ=jjB|ZhC0kunLEylZNr`wdQx05@$>ac zp(HgTey@?@!R;u%RuvX?ml6i};!;}=@s%Q*a3|){)wt)}*6t&5U2RcaZTsHX;g5?O z`z&L2_#qg^6y!)i9^5Suc&5=cB=X+{$VXzs&wwi-syT`4@AI;s>_0Bw^Ez~}_IH7E zmijV`QgH!(VF(>82#+BuL7V0U?fmf1iA*2Go>UNLOd5o1m3$$(6mu+M-UuuA+n>da z`V2%;KM78%umt>N?3X%mPLjxIv%x_2kroyLenAQ7b-NfTXaP*=vU$|h>piCOcV^V;UyA?Kes=_gGaekE zpJ?d&CNmpADRQFaMLD{vEf%TlpfFY?@U|yjX6Q9uT>OTrook824c<^INKQ`FL4yr4 z$BGZ3iTh&qX8ba(_kAQ$Q9~m!m>tPqe5Ue9{B4_EtX_i01EW1>lhGr8%EJHAU^gQ4 zXPv*vzM3S9X`wO{|$&MB^Viv13j4O)FZaW1AIRZ5-X;Lbp*!xaHOqQhi~{c9%1 z%joKh)!atMQ0i#TYmvMsZFElfJ9taf)BxPyBSneQ4YPknKezCC)P2u*?xd@DqFVnp zvrJ@ZZEa~~1@Tte<-6$oEAYCl_mUT++7Ta5;s@VuT*riZ?y~NWt*~HsggE(W{ELWQ zJ8))RK%Vt5BBH&&8Nl)LL9vMi439Tfz2spoDP`c-*)oMrcq^;jZ~|A)*>XqYE4j}} z%Uz0JzmG!}im9mO)1P)Y+i~0AFyiJ-h+P9;JFiFOB-&`K)6r3WxHbSQ87Y9FB}JXc zLqR!jC%HQMPc{v)=Sqp0)E;%W^7?SL-C~el=o_)u-8vx7{gE^{I5+?a7yaCwC*v3Y zzdh+-pa`O_4rtsatAc-e1^$e*y2;G%W&ym7L4P>G2ps9cSVo17C57?tP>NRfo2RW7 zS2X1hWOx(IT3~e*HKng>Hr{8@LoV~`J^pPmo#RLW4o0y7+;emdg z39WSkYH0wCx=YUd=*?s60ljYsQ*zZ}R{oZN>+GS^m#*IW7?dnzn_m|Pk2T}qG|@oorDt?W4DxClXfd z+0z-|@7dn|Q+a(bG< zb*-U9fVO%Rrl&fxDqXaj=V0u*)t3O;#SXA4B~J?n@+oyb3#A1P>Y2Xuw+2+WPJw7| z7dhs|O-DyUjr7f$#*fd=>;Gn94i685*n7nh76;rpG`cE$8@c8t`qISyd~eWy9O@$-!!8pX_I9}vImlh)!PH?im4%Q08B;>DUN1(K;lVxc9HqsA znteFM*YFt?%7((|*8uukdH1$LmFS^@xg|_8Kw1|-t@5RmpyISy;Z^Y*F-Rk(H%K^Z z{#xr_naWs;ME{m;TADS+Lrx#}#I$C(8AJbJbm-9UDg7_0aDxh)nD?mDY(j*6v-4rv zl>adSx{=>ep`$V~BEBw6ml?#SN3zTO_fU4qNs;~^^-3T9QZ@XSv<6y^-(7yZ$5Hz9 zendhRevCp1Dn)&Wo$@HEJYw&`i1zK-L-{EBJbw{L?MEvO zC&(sbWo6~y;P5ea|WF7wF| zZU>_33hL^mwB-gn09tvFBmN0Df&J)GWv^)Wdk#zL*K*PIT;cM0-rha`?jN~A}cLSH6z>DbU!R6-LO7Vk(@ap9@ zPg$>*zuDP#t!~>eq=4wI<$N_8XFby+;5zsGfZTLcon3jhvm*wHi<6eiC}&T~BKF)u zg9ru!SfsXUTT;15nU+`QDcQ!x#@!_9p#829Z^!$Kfhkl6erRP0I8x(NDNQ+ z@n;*g+=igUO)t%Ko(jF-)qrjeN1B(*=W6Y=&bBS7Ab|(Qs~UGNKrFlH9f4oNdH_Bg znJ5Nai!Gj;{npxB{h7|Y9~`diNP5j3fa&bio3NqFK)8xMZh19cd&gj3UtY>KQiU>o zW$R9Y0c@YOD1mCBuWna+xaXo2`RBKH~q0x1K|LX1Ld;02D|H>(b@Rev)#GL z$ro4G1S*k^@K$&4c74GzmSsOxDjO{XBs@Pm!vtyPyf4b&U$EOxPfu&DfApa3BACUH zZh;n^f(Rkv9Goe(^bH6ET32VOG9=;qxu+1BX}L9E5gcrf5kSu>o}#6N(th5zK*-Zj zokmf=>}DY-C@9h+&D8pHYfn*EG%k(X=mT+IU4UW+j9qmA{9D9o;k1y_0Bf6CNTE)7 z0ra^ZQ{&POiFnBv-WS-_Pnn)pgg*YPCP5V?= zd=?^^2=6CQ2;T6h4E0M&YHC=1iTs{l4}aXH)oeikZB+Z=^YXK4U7+c%P$_bI+x{AF zK4o2Bk~SW@>A-s4dWu8;eqMkPH`cH{Zr>X5E73USNR?dV zMlGc~kfb%cA8t=0*y+*#ef>U`dS-J6kR{64k7mF&3=9lm4P8uHwF5`vsl506^yXuy zuc<}Kbj~NG7G`_ygOpR$vO}YTL8)gxhvkc^%EFaBtRdJ5VYm*mc2%C{H?cIbqoeIE zH}l4=A-0yuz+47#DlJkT8Icr%sqTx;2*4@WqCTP3*J#$5h5;QS?tQo1`Ah29xMkbz zxb6?g2XT8&JmY~0g#eK9?_i7?EM+G$OGgw9i_=m=e|Zb~r^f1w3u&fC3OFB>DINo4 z{4d6EMqd{!kXcvLkhK1b-#+u5AD*)V4RsWSo-Kg_#t#)C9&iwi(t+mu!nwgv#(krr z-1T2L^t0a=4JQ!rN=#?&KZ&LlDW^ZPeTf(}PMaE~5OZ(U3}NI)Ub zaJf4p;uNha`Ytqz{P-CY{w~W&YRjYLeS^f#MUVCqa3-h)N?Hr*>)FfaKJX?kqT3Se zS|a_Vr$g5tjQ8}V8(x{v-v4Vr^I>JLq7RiHqruW$DHIMO2aX>0w8$gLZiUS4G&s^O zL2@UJ2BlaUa!vyR@F)RsqA%$5KEv2axj;Ae2>?_#S^UXATL4Cas$_oT{SyuV2`G%d z-k6tZ9-@&(Y8p{hhtc7L4SwAt?>&yW+ceC3C%$AS31M(*H&P;7b!M(siZT?*TjyE66rv$DIBm!bR zwV90!&LR=hvM5K0m}Y6IV}Vzp zv5OO{PEyb$vt{1Vj1e&%`I~h+o@ij2!lTtVBFrSSxoFcICXFjy!4pu45k4Yn`OAw+(+(-)Zdp08k(pA|hkr2AEvfXVJNnoPT`)uRw{(tr5 zGJ@rD-wt%PcG@d9bf^odoWq+FHyn>6?GYIGk6joGxs)q0U zat2@v$cDRpgk5xz@z`1l&3MIAxy2G?!@U`yqtJ`IvB_#eWV{w#>Fq7vnGyr<#q7Gi zrv?Ut)z!sEt>ck21-HD6)jiKJ4B4x)va%T84~tqVQdBD=P$IhIh$HNhM19~Ekct9sr|_kj?m zQZ)?KPa@M(H>L??(7f&&J^#M*Fd__Ubq~BYbi>CFSSsqhB@9$N9|VJI7<$W@XC{6j zcFMrmw@&hm>EiZ(wWsZcL|$vM$Wt=9y0)EY+$Eip78p;<35J7#kDNWC(>c`@9-yNhkA+R}dkqLbs~_y9cai;i+v4Li@0nFe|2 zlEqNJc30Vc@`g0vf1p-Z5LMHtXf?lVCN&LCdvAnYE^wM0x7v`?nuBTWIjeoHPE%1w z?hhuSlaa8iI7Kj=uHmDZ#oDb}ZYp4Lq02OnYc7rbby2b!3Bm{gTFy^b*`Jx|jFE@= z-_~0N&Uz|e0&j;LYZh)m#l$|!QWpLKUH2>*y(q@eth`0l|2L&yqz{#~EWAZ^kTOsc zufFYBIMQ6=ht6NWg*23uguX0iP9^c&UcSY5J}X>)k2`=={InG#Z-{}^UJK}N0=%FU zX8o2ZOG4=1@yA$c92+y*&a*d#I+LurM)!e8|xMyVL+sHUZaL zk9xox0b6;c1O9}Ei)E9}hBwCanb`gNd&2sv>+=aXr&iM)wly~6KQf-OLrYXNtgIPV zEUc`o?YsRWPwC6bcgeXwH)3h_&4)(Trf+Ap!RgEAQio+mHdBv04k{+iGkUjUX6#ML zNsH<=9)gX#TCE{;yy{fE`&{uxAA76)7|M{r>D7KNH}_G*uiIWDAHOvqc?U+S|J-pa z{Pw#|hL#R1-aUMJRui59u2HHN!jKvpJCn~K4{OoFCvbsLxP+EU^g$lGbh4R3L6R1% zEiTlHu7HLgkkPd=H6Dia87u)yUc)yYa!Rb;FFP#) zWt%5`MgUhq~+RqE> zw4D31FBB?;l=6jNoK&Ox>6>UB!S8gK292YsMVXPh6^jf%2#;2#(qfGlJh}-b9Agrl11E)FuZ`5A(RnmIZw7I@6>0{608~>8ylM| zFTCG9 zfzUaiv>YUJ<@{8hvbVQaURa1N3N6-)jDqZs8#Zcv{Ije;D6IV~wDu>YVq%v)z<>*q zFD^Kms`zhQZ~$@YaxX?&&aA)bt}d>8cPLm1e{mvf1oG2TTB9p|V{O@jL7Mkf=pj;5oU;?{)W zb9w=-x0N=}=7HR*86M-?rky5{OP6Zl6^%JYQX= z4B~Ic@@lYkpFp)$pFxS=AX`O-GcS1!wAUP1#hGFA`3zfCk~93SmR_!Dro(fp+zWlV zGkqu%3phGVuqBC*wPFg8_T$;yZJ){j7Aro!75q^!hr#VwjJ-Y&A7~_i(jplT(+-gcQ4Sbm4JW-!o%^G&tldiO(bM>P5E8o2KoA9 z@rs+Th6E9}FC$2Xcf6a&4N0)unXGt!sm>y;%B+aJb)xbW8KqCGd*H|Oq?mGU-v72{ zQgoGSqoEp3Z@9*1s)u0SGuRpoxtP!N1wAwcslSuZ-SCG63Pe~Uiv6peP-=0Q|KudH z`;X`7>9U635BX%(|5|?ms=e1`a|sHQvAS()D0Z!y-yhp*a86aj0~j(UD(5Tdnj)2k1N+`Z7}Cl*T^sr1Hj*qmvdln<+jmWuQXQa(Z@!-#tN!sZxb0{Nf} z@6+2wy9}XrsP?l5eG}!pG8Wf|^*aF>RkE!~^6aq5p9;-;E~s zCaW5SHb?_hoktRPR*Ym-^+kn#Dt--aSGFmPQVu*d`Fo*W7(|Jtfu_ry#V~JmWa1Cw zsuMR)+r$uWQb@4)VgK}nQK3_sK#9hKoj<@Jku1QARg@r5YT5hsnbkdAlgE?|$y}NS zPYtP-ouhow{S@E25!L_>@16c4z48;hMqk!9Kk*e#GU0e-j&K$5Z#)Ad$Zu=v%*u(HzilEbVn)zIxs??j zDfkOuJlg>k*3_1`BukwF5E+pcrSrktBXFovhlqy(xv1BRg!WXghke68M&@8~+4u$- zICuTEVYFw!BTsiL;cofVD*=QmXb(>hqR-3yPU)FfUpfu8T1>ANNo~naf4>w`xCBf? zZQ7rmSkN98pN*?)bBs)ARY`+Cj4bz(3}{Czk|QXx*~&^{Xcy>nAo7wdXK;xkc;Y5%;hYgWhWq*a#ZCnW2o=ZJ2&<5OKz%#V6Hf_V zQzvShCCEE~ma9}&nMQw@?yqnB^NPc6xrTz*KJ}%-K7u8U4@0gH5xz1h{4&ycav6J7saP$w#}wVOkTBcudKkyIF)v=AhO(s&~X1;$PDcpCKb=_{%3Hga)T9EC}k z5{*1}`u8|m&=eL4G}uF_^Lpbk7u`nM_LzE&g<6nE8LTu|-D_!Nt~6Mot5h5o)o*A; z}n`w$`uXB>V5AeqASi6ieVIjN5@e=cZB^$ zYp8AF)Dp~7EClhR#cMm01&w08rz(KzG7?=NgN|FF1nIfY#yNLcH6| z16d=O(7oC(9)|Uba$0J}T7KGf5_yAC!_Ogr~9i7R` zdPYRL%bO1B(2Jv8q#iTYuAz3zw-RE{AgBG-CN!a8vi9i85%c|B!d2le!ph` z2A;eEy2_(P3Fg<^0JOF`XJ)_k6aYHM02ylsd`wr~07X~yR|HlA_S1BJ)Z-K3=I{3{o2IGL>V054#?kD8bFUR8#czy{$D8f{=t(Zf4X0u*$3iD?Eh*U9xtjZ z$Jg`gniR25~hJgUolo;1IuwW zu*}3y#)c_nTV^@liu3KzfmGK-Fm))oTK^ReN&aCIou5=!PA6MDj)rkXGST*@5VNX^ zWsnQ#FQ#4cd@LqcN&eCLoS6+=l|D175L{?vPI6Zqg*r0GItIaita=8v)tj@(>J6mc z00HI;p$S*2c z!SGUrO4)T=&-&6LtqS;bowr#Vd$gJmxbFBTRXkP;fg)b9MyWy~8L-OBpCA>Ka2q3B zq8ey$tVBFR7hVl)oKkdbu9EsTQMLQBt9ZS=dYA!@*GH{d`Kj>Dy=%%!ezbrtX^;4XlSh7bION7+Um?)O?RdV}g_3(NG2G;aTTLOVjHtV7C?a znL$cl4lc(9Y#6V_S?K^T8t*`|U(`d4TD6}!W)F_$bw)=C4f|_69|_4mF?X7p*`ijI z_u>GK(_}F_J3B<86=E5NZs{yR_m{i77%VnFeta1ZGf3R{LvBt78U{&&(hyqKG%NMr z@5msCo<&tNQ}@lA}qY`*3tm0XKC;hRj)as6s|EZRVzBhVED zyuGBX5((}4aKDpeKIC(@0;9<%>aQ7wWRc%CkI1zSN?Pr}1F=X( zg}Qxw0iTmjSc;U|h2L)Q__T=#phbvm zgd#L~)u(@z>3XO1L4VB1iYr<%Pef=>|P`-7Y*b zj-4ZzK;v)i?5t8#wh((H6X=v-B`pC>vnvxRI?{Z?-~eP46#naf%4idnx}+-=Lw{5> z>HPl52+QYt2mdcKenmoJ-R7qBx~a)nm;C;Hh{i|pjzE&`10bYK+4oK4p?a9{QG@E# zb=>{y*RNNnSF9hZLs-5w!*8LufE!#d_-499Jw*o-#*I0`P{g48 zL@bw`YO!R!O>dz?eeW^eg!BXpyZc8fr%m2wgJJ*FhM